Add preliminary GRPC server for PyBullet and BulletRobotics.

Will add GRPC client and PyBullet GRPC server plugin.
Will cover most/all SharedMemoryCommand/SharedMemoryStatus messages.
Run the server, then test using the pybullet_client.py
This commit is contained in:
erwincoumans
2018-08-29 21:12:13 -07:00
parent 65175425b0
commit 4f7dfc2069
18 changed files with 6556 additions and 29 deletions

View File

@@ -69,6 +69,13 @@
trigger = "midi", trigger = "midi",
description = "Use Midi controller to control parameters" description = "Use Midi controller to control parameters"
} }
newoption
{
trigger = "grpc",
description = "Build GRPC server/client features for PyBullet/BulletRobotics"
}
-- _OPTIONS["midi"] = "1"; -- _OPTIONS["midi"] = "1";

View File

@@ -53,32 +53,6 @@ B3_SHARED_API b3SharedMemoryCommandHandle b3SaveWorldCommandInit(b3PhysicsClient
return (b3SharedMemoryCommandHandle) command; return (b3SharedMemoryCommandHandle) command;
} }
B3_SHARED_API b3SharedMemoryCommandHandle b3LoadUrdfCommandInit(b3PhysicsClientHandle physClient, const char* urdfFileName)
{
PhysicsClient* cl = (PhysicsClient* ) physClient;
b3Assert(cl);
b3Assert(cl->canSubmitCommand());
if (cl->canSubmitCommand())
{
struct SharedMemoryCommand* command = cl->getAvailableSharedMemoryCommand();
b3Assert(command);
command->m_type = CMD_LOAD_URDF;
int len = strlen(urdfFileName);
if (len < MAX_URDF_FILENAME_LENGTH)
{
strcpy(command->m_urdfArguments.m_urdfFileName, urdfFileName);
}
else
{
command->m_urdfArguments.m_urdfFileName[0] = 0;
}
command->m_updateFlags = URDF_ARGS_FILE_NAME;
return (b3SharedMemoryCommandHandle)command;
}
return 0;
}
B3_SHARED_API b3SharedMemoryCommandHandle b3LoadBulletCommandInit(b3PhysicsClientHandle physClient, const char* fileName) B3_SHARED_API b3SharedMemoryCommandHandle b3LoadBulletCommandInit(b3PhysicsClientHandle physClient, const char* fileName)
{ {
@@ -310,6 +284,56 @@ B3_SHARED_API int b3LoadSoftBodySetCollisionMargin(b3SharedMemoryCommandHandle c
return 0; return 0;
} }
B3_SHARED_API b3SharedMemoryCommandHandle b3LoadUrdfCommandInit(b3PhysicsClientHandle physClient, const char* urdfFileName)
{
PhysicsClient* cl = (PhysicsClient*)physClient;
b3Assert(cl);
b3Assert(cl->canSubmitCommand());
if (cl->canSubmitCommand())
{
struct SharedMemoryCommand* command = cl->getAvailableSharedMemoryCommand();
b3Assert(command);
command->m_type = CMD_LOAD_URDF;
int len = strlen(urdfFileName);
if (len < MAX_URDF_FILENAME_LENGTH)
{
strcpy(command->m_urdfArguments.m_urdfFileName, urdfFileName);
}
else
{
command->m_urdfArguments.m_urdfFileName[0] = 0;
}
command->m_updateFlags = URDF_ARGS_FILE_NAME;
return (b3SharedMemoryCommandHandle)command;
}
return 0;
}
B3_SHARED_API b3SharedMemoryCommandHandle b3LoadUrdfCommandInit2(b3SharedMemoryCommandHandle commandHandle, const char* urdfFileName)
{
struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
b3Assert(command);
command->m_type = CMD_LOAD_URDF;
int len = strlen(urdfFileName);
if (len < MAX_URDF_FILENAME_LENGTH)
{
strcpy(command->m_urdfArguments.m_urdfFileName, urdfFileName);
}
else
{
command->m_urdfArguments.m_urdfFileName[0] = 0;
}
command->m_updateFlags = URDF_ARGS_FILE_NAME;
return (b3SharedMemoryCommandHandle)command;
}
B3_SHARED_API int b3LoadUrdfCommandSetUseMultiBody(b3SharedMemoryCommandHandle commandHandle, int useMultiBody) B3_SHARED_API int b3LoadUrdfCommandSetUseMultiBody(b3SharedMemoryCommandHandle commandHandle, int useMultiBody)
{ {
struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
@@ -720,11 +744,18 @@ B3_SHARED_API b3SharedMemoryCommandHandle b3InitStepSimulationCommand(b3Physics
b3Assert(cl->canSubmitCommand()); b3Assert(cl->canSubmitCommand());
struct SharedMemoryCommand* command = cl->getAvailableSharedMemoryCommand(); struct SharedMemoryCommand* command = cl->getAvailableSharedMemoryCommand();
b3Assert(command); b3Assert(command);
return b3InitStepSimulationCommand2((b3SharedMemoryCommandHandle)command);
}
B3_SHARED_API b3SharedMemoryCommandHandle b3InitStepSimulationCommand2(b3SharedMemoryCommandHandle commandHandle)
{
struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
command->m_type = CMD_STEP_FORWARD_SIMULATION; command->m_type = CMD_STEP_FORWARD_SIMULATION;
command->m_updateFlags = 0; command->m_updateFlags = 0;
return (b3SharedMemoryCommandHandle) command; return (b3SharedMemoryCommandHandle)command;
} }
B3_SHARED_API b3SharedMemoryCommandHandle b3InitResetSimulationCommand(b3PhysicsClientHandle physClient) B3_SHARED_API b3SharedMemoryCommandHandle b3InitResetSimulationCommand(b3PhysicsClientHandle physClient)
{ {
PhysicsClient* cl = (PhysicsClient* ) physClient; PhysicsClient* cl = (PhysicsClient* ) physClient;

View File

@@ -338,13 +338,14 @@ B3_SHARED_API int b3PhysicsParamSetInternalSimFlags(b3SharedMemoryCommandHandle
B3_SHARED_API b3SharedMemoryCommandHandle b3InitStepSimulationCommand(b3PhysicsClientHandle physClient); B3_SHARED_API b3SharedMemoryCommandHandle b3InitStepSimulationCommand(b3PhysicsClientHandle physClient);
B3_SHARED_API b3SharedMemoryCommandHandle b3InitStepSimulationCommand2(b3SharedMemoryCommandHandle commandHandle);
B3_SHARED_API b3SharedMemoryCommandHandle b3InitResetSimulationCommand(b3PhysicsClientHandle physClient); B3_SHARED_API b3SharedMemoryCommandHandle b3InitResetSimulationCommand(b3PhysicsClientHandle physClient);
///Load a robot from a URDF file. Status type will CMD_URDF_LOADING_COMPLETED. ///Load a robot from a URDF file. Status type will CMD_URDF_LOADING_COMPLETED.
///Access the robot from the unique body index, through b3GetStatusBodyIndex(statusHandle); ///Access the robot from the unique body index, through b3GetStatusBodyIndex(statusHandle);
B3_SHARED_API b3SharedMemoryCommandHandle b3LoadUrdfCommandInit(b3PhysicsClientHandle physClient, const char* urdfFileName); B3_SHARED_API b3SharedMemoryCommandHandle b3LoadUrdfCommandInit(b3PhysicsClientHandle physClient, const char* urdfFileName);
B3_SHARED_API b3SharedMemoryCommandHandle b3LoadUrdfCommandInit2(b3SharedMemoryCommandHandle commandHandle, const char* urdfFileName);
B3_SHARED_API int b3LoadUrdfCommandSetStartPosition(b3SharedMemoryCommandHandle commandHandle, double startPosX,double startPosY,double startPosZ); B3_SHARED_API int b3LoadUrdfCommandSetStartPosition(b3SharedMemoryCommandHandle commandHandle, double startPosX,double startPosY,double startPosZ);
B3_SHARED_API int b3LoadUrdfCommandSetStartOrientation(b3SharedMemoryCommandHandle commandHandle, double startOrnX,double startOrnY,double startOrnZ, double startOrnW); B3_SHARED_API int b3LoadUrdfCommandSetStartOrientation(b3SharedMemoryCommandHandle commandHandle, double startOrnX,double startOrnY,double startOrnZ, double startOrnW);
B3_SHARED_API int b3LoadUrdfCommandSetUseMultiBody(b3SharedMemoryCommandHandle commandHandle, int useMultiBody); B3_SHARED_API int b3LoadUrdfCommandSetUseMultiBody(b3SharedMemoryCommandHandle commandHandle, int useMultiBody);

View File

@@ -3008,8 +3008,10 @@ bool PhysicsServerCommandProcessor::loadSdf(const char* fileName, char* bufferSe
bool PhysicsServerCommandProcessor::loadUrdf(const char* fileName, const btVector3& pos, const btQuaternion& orn, bool PhysicsServerCommandProcessor::loadUrdf(const char* fileName, const btVector3& pos, const btQuaternion& orn,
bool useMultiBody, bool useFixedBase, int* bodyUniqueIdPtr, char* bufferServerToClient, int bufferSizeInBytes, int flags, btScalar globalScaling) bool useMultiBody, bool useFixedBase, int* bodyUniqueIdPtr, char* bufferServerToClient, int bufferSizeInBytes, int orgFlags, btScalar globalScaling)
{ {
//clear the LOAD_SDF_FILE=1 bit, which is reserved for internal use of loadSDF command.
int flags = orgFlags & ~1;
m_data->m_sdfRecentLoadedBodies.clear(); m_data->m_sdfRecentLoadedBodies.clear();
*bodyUniqueIdPtr = -1; *bodyUniqueIdPtr = -1;

View File

@@ -0,0 +1,98 @@
#include "ConvertGRPCBullet.h"
#include "PhysicsClientC_API.h"
#include "SharedMemoryCommands.h"
#include <memory>
#include <iostream>
#include <string>
#include <thread>
#include <grpc++/grpc++.h>
#include <grpc/support/log.h>
#include "pybullet.grpc.pb.h"
using grpc::Server;
using grpc::ServerAsyncResponseWriter;
using grpc::ServerBuilder;
using grpc::ServerContext;
using grpc::ServerCompletionQueue;
using grpc::Status;
using pybullet_grpc::PyBulletCommand;
using pybullet_grpc::PyBulletStatus;
using pybullet_grpc::PyBulletAPI;
SharedMemoryCommand* convertGRPCAndSubmitCommand(PyBulletCommand& grpcCommand, SharedMemoryCommand& cmd)
{
SharedMemoryCommand* cmdPtr = 0;
if (grpcCommand.has_loadurdfcommand())
{
auto grpcCmd = grpcCommand.loadurdfcommand();
std::string fileName = grpcCmd.urdffilename();
if (fileName.length())
{
cmdPtr = &cmd;
b3SharedMemoryCommandHandle commandHandle = (b3SharedMemoryCommandHandle)cmdPtr;
b3LoadUrdfCommandInit2(commandHandle, fileName.c_str());
if (grpcCmd.has_initialposition())
{
const ::pybullet_grpc::vec3& pos = grpcCmd.initialposition();
b3LoadUrdfCommandSetStartPosition(commandHandle, pos.x(), pos.y(), pos.z());
}
if (grpcCmd.has_initialorientation())
{
const ::pybullet_grpc::quat4& orn = grpcCmd.initialorientation();
b3LoadUrdfCommandSetStartOrientation(commandHandle, orn.x(), orn.y(), orn.z(), orn.w());
}
if (grpcCmd.hasUseMultiBody_case()== ::pybullet_grpc::LoadUrdfCommand::HasUseMultiBodyCase::kUseMultiBody)
{
b3LoadUrdfCommandSetUseMultiBody( commandHandle, grpcCmd.usemultibody());
}
if (grpcCmd.hasGlobalScaling_case() == ::pybullet_grpc::LoadUrdfCommand::HasGlobalScalingCase::kGlobalScaling)
{
b3LoadUrdfCommandSetGlobalScaling(commandHandle, grpcCmd.globalscaling());
}
if (grpcCmd.hasUseFixedBase_case() == ::pybullet_grpc::LoadUrdfCommand::HasUseFixedBaseCase::kUseFixedBase)
{
b3LoadUrdfCommandSetUseFixedBase(commandHandle, grpcCmd.usefixedbase());
}
if (grpcCmd.urdfflags())
{
b3LoadUrdfCommandSetFlags(commandHandle, grpcCmd.urdfflags());
}
}
}
if (grpcCommand.has_stepsimulationcommand())
{
cmdPtr = &cmd;
b3SharedMemoryCommandHandle commandHandle = (b3SharedMemoryCommandHandle)cmdPtr;
b3InitStepSimulationCommand2(commandHandle);
}
return cmdPtr;
}
bool convertStatusToGRPC(const SharedMemoryStatus& serverStatus, char* bufferServerToClient, int bufferSizeInBytes, PyBulletStatus& grpcReply)
{
bool converted = false;
grpcReply.set_statustype(serverStatus.m_type);
switch (serverStatus.m_type)
{
case CMD_URDF_LOADING_COMPLETED:
{
::pybullet_grpc::LoadUrdfStatus* stat = grpcReply.mutable_urdfstatus();
b3SharedMemoryStatusHandle statusHandle = (b3SharedMemoryStatusHandle)&serverStatus;
int objectUniqueId = b3GetStatusBodyIndex(statusHandle);
stat->set_objectuniqueid(objectUniqueId);
}
break;
}
return converted;
}

View File

@@ -0,0 +1,17 @@
#ifndef BT_CONVERT_GRPC_BULLET_H
#define BT_CONVERT_GRPC_BULLET_H
#include "../PhysicsClientC_API.h"
namespace pybullet_grpc
{
class PyBulletCommand;
class PyBulletStatus;
};
struct SharedMemoryCommand* convertGRPCAndSubmitCommand(pybullet_grpc::PyBulletCommand& grpcCommand, struct SharedMemoryCommand& cmd);
bool convertStatusToGRPC(const struct SharedMemoryStatus& serverStatus, char* bufferServerToClient, int bufferSizeInBytes, pybullet_grpc::PyBulletStatus& grpcReply);
#endif //BT_CONVERT_GRPC_BULLET_H

View File

@@ -0,0 +1,278 @@
///PyBullet / BulletRobotics GRPC server.
///works as standalone GRPC server as as a GRPC server bridge,
///connecting to a local physics server using shared memory
#include <stdio.h>
#include "../../CommonInterfaces/CommonGUIHelperInterface.h"
#include "Bullet3Common/b3CommandLineArgs.h"
#include "PhysicsClientC_API.h"
#ifdef NO_SHARED_MEMORY
#include "PhysicsServerCommandProcessor.h"
typedef PhysicsServerCommandProcessor MyCommandProcessor;
#else
#include "SharedMemoryCommandProcessor.h"
typedef SharedMemoryCommandProcessor MyCommandProcessor;
#endif //NO_SHARED_MEMORY
#include "SharedMemoryCommands.h"
#include "Bullet3Common/b3AlignedObjectArray.h"
#include "PhysicsServerCommandProcessor.h"
#include "../Utils/b3Clock.h"
#include <memory>
#include <iostream>
#include <string>
#include <thread>
#include <grpc++/grpc++.h>
#include <grpc/support/log.h>
#include "pybullet.grpc.pb.h"
using grpc::Server;
using grpc::ServerAsyncResponseWriter;
using grpc::ServerBuilder;
using grpc::ServerContext;
using grpc::ServerCompletionQueue;
using grpc::Status;
using pybullet_grpc::PyBulletCommand;
using pybullet_grpc::PyBulletStatus;
using pybullet_grpc::PyBulletAPI;
bool gVerboseNetworkMessagesServer = true;
#include "ConvertGRPCBullet.h"
class ServerImpl final {
public:
~ServerImpl() {
server_->Shutdown();
// Always shutdown the completion queue after the server.
cq_->Shutdown();
}
void Run(MyCommandProcessor* comProc) {
std::string server_address("0.0.0.0:50051");
ServerBuilder builder;
// Listen on the given address without any authentication mechanism.
builder.AddListeningPort(server_address, grpc::InsecureServerCredentials());
// Register "service_" as the instance through which we'll communicate with
// clients. In this case it corresponds to an *asynchronous* service.
builder.RegisterService(&service_);
// Get hold of the completion queue used for the asynchronous communication
// with the gRPC runtime.
cq_ = builder.AddCompletionQueue();
// Finally assemble the server.
server_ = builder.BuildAndStart();
std::cout << "Server listening on " << server_address << std::endl;
// Proceed to the server's main loop.
HandleRpcs(comProc);
}
private:
// Class encompasing the state and logic needed to serve a request.
class CallData {
public:
// Take in the "service" instance (in this case representing an asynchronous
// server) and the completion queue "cq" used for asynchronous communication
// with the gRPC runtime.
CallData(PyBulletAPI::AsyncService* service, ServerCompletionQueue* cq, MyCommandProcessor* comProc)
: service_(service), cq_(cq), responder_(&ctx_), status_(CREATE) , m_finished(false), m_comProc(comProc){
// Invoke the serving logic right away.
Proceed();
}
enum CallStatus { CREATE, PROCESS, FINISH, TERMINATE };
CallStatus Proceed() {
if (status_ == CREATE) {
// Make this instance progress to the PROCESS state.
status_ = PROCESS;
// As part of the initial CREATE state, we *request* that the system
// start processing SayHello requests. In this request, "this" acts are
// the tag uniquely identifying the request (so that different CallData
// instances can serve different requests concurrently), in this case
// the memory address of this CallData instance.
service_->RequestSubmitCommand(&ctx_, &m_command, &responder_, cq_, cq_,
this);
}
else if (status_ == PROCESS) {
// Spawn a new CallData instance to serve new clients while we process
// the one for this CallData. The instance will deallocate itself as
// part of its FINISH state.
new CallData(service_, cq_, m_comProc);
status_ = FINISH;
std::string replyString;
// The actual processing.
SharedMemoryStatus serverStatus;
b3AlignedObjectArray<char> buffer;
buffer.resize(SHARED_MEMORY_MAX_STREAM_CHUNK_SIZE);
SharedMemoryCommand cmd;
SharedMemoryCommand* cmdPtr = 0;
m_status.set_statustype(CMD_UNKNOWN_COMMAND_FLUSHED);
cmdPtr = convertGRPCAndSubmitCommand(m_command, cmd);
if (cmdPtr)
{
bool hasStatus = m_comProc->processCommand(*cmdPtr, serverStatus, &buffer[0], buffer.size());
double timeOutInSeconds = 10;
b3Clock clock;
double startTimeSeconds = clock.getTimeInSeconds();
double curTimeSeconds = clock.getTimeInSeconds();
while ((!hasStatus) && ((curTimeSeconds - startTimeSeconds) <timeOutInSeconds))
{
hasStatus = m_comProc->receiveStatus(serverStatus, &buffer[0], buffer.size());
curTimeSeconds = clock.getTimeInSeconds();
}
if (gVerboseNetworkMessagesServer)
{
//printf("buffer.size = %d\n", buffer.size());
printf("serverStatus.m_numDataStreamBytes = %d\n", serverStatus.m_numDataStreamBytes);
}
if (hasStatus)
{
b3AlignedObjectArray<unsigned char> packetData;
unsigned char* statBytes = (unsigned char*)&serverStatus;
convertStatusToGRPC(serverStatus, &buffer[0], buffer.size(), m_status);
}
}
if (m_command.has_terminateservercommand())
{
status_ = TERMINATE;
}
// And we are done! Let the gRPC runtime know we've finished, using the
// memory address of this instance as the uniquely identifying tag for
// the event.
responder_.Finish(m_status, Status::OK, this);
}
else {
GPR_ASSERT(status_ == FINISH);
// Once in the FINISH state, deallocate ourselves (CallData).
delete this;
}
return status_;
}
private:
// The means of communication with the gRPC runtime for an asynchronous
// server.
PyBulletAPI::AsyncService* service_;
// The producer-consumer queue where for asynchronous server notifications.
ServerCompletionQueue* cq_;
// Context for the rpc, allowing to tweak aspects of it such as the use
// of compression, authentication, as well as to send metadata back to the
// client.
ServerContext ctx_;
// What we get from the client.
PyBulletCommand m_command;
// What we send back to the client.
PyBulletStatus m_status;
// The means to get back to the client.
ServerAsyncResponseWriter<PyBulletStatus> responder_;
// Let's implement a tiny state machine with the following states.
CallStatus status_; // The current serving state.
bool m_finished;
MyCommandProcessor* m_comProc; //physics server command processor
};
// This can be run in multiple threads if needed.
void HandleRpcs(MyCommandProcessor* comProc) {
// Spawn a new CallData instance to serve new clients.
new CallData(&service_, cq_.get(), comProc);
void* tag; // uniquely identifies a request.
bool ok;
bool finished = false;
CallData::CallStatus status = CallData::CallStatus::CREATE;
while (status!= CallData::CallStatus::TERMINATE) {
// Block waiting to read the next event from the completion queue. The
// event is uniquely identified by its tag, which in this case is the
// memory address of a CallData instance.
// The return value of Next should always be checked. This return value
// tells us whether there is any kind of event or cq_ is shutting down.
grpc::CompletionQueue::NextStatus nextStatus = cq_->AsyncNext(&tag, &ok, gpr_now(GPR_CLOCK_MONOTONIC));
if (nextStatus == grpc::CompletionQueue::NextStatus::GOT_EVENT)
{
//GPR_ASSERT(cq_->Next(&tag, &ok));
GPR_ASSERT(ok);
status = static_cast<CallData*>(tag)->Proceed();
}
}
}
std::unique_ptr<ServerCompletionQueue> cq_;
PyBulletAPI::AsyncService service_;
std::unique_ptr<Server> server_;
};
int main(int argc, char** argv)
{
b3CommandLineArgs parseArgs(argc, argv);
b3Clock clock;
double timeOutInSeconds = 10;
DummyGUIHelper guiHelper;
MyCommandProcessor* sm = new MyCommandProcessor;
sm->setGuiHelper(&guiHelper);
int port = 6667;
parseArgs.GetCmdLineArgument("port", port);
gVerboseNetworkMessagesServer = parseArgs.CheckCmdLineFlag("verbose");
#ifndef NO_SHARED_MEMORY
int key = 0;
if (parseArgs.GetCmdLineArgument("sharedMemoryKey", key))
{
sm->setSharedMemoryKey(key);
}
#endif//NO_SHARED_MEMORY
bool isPhysicsClientConnected = sm->connect();
bool exitRequested = false;
if (isPhysicsClientConnected)
{
ServerImpl server;
server.Run(sm);
}
else
{
printf("Couldn't connect to physics server\n");
}
delete sm;
return 0;
}

View File

@@ -0,0 +1,150 @@
project ("App_PhysicsServerSharedMemoryBridgeGRPC")
language "C++"
kind "ConsoleApp"
includedirs {"../../ThirdPartyLibs/clsocket/src","../../../src",".."}
if os.is("Windows") then
defines { "WIN32", "_WIN32_WINNT=0x0600" }
links {"grpc","grpc++","grpc++_reflection","gpr",
"libprotobuf","crypto","ssl","zlibstaticd","Ws2_32","Winmm" }
end
if os.is("Linux") then
defines {"_LINUX"}
end
if os.is("MacOSX") then
defines {"_DARWIN"}
end
links {
"BulletFileLoader",
"Bullet3Common",
"LinearMath"
}
files {
"main.cpp",
"../PhysicsClient.cpp",
"../PhysicsClient.h",
"../PhysicsDirect.cpp",
"../PhysicsDirect.h",
"../PhysicsCommandProcessorInterface.h",
"../SharedMemoryCommandProcessor.cpp",
"../SharedMemoryCommandProcessor.h",
"../PhysicsClientC_API.cpp",
"../PhysicsClientC_API.h",
"../Win32SharedMemory.cpp",
"../Win32SharedMemory.h",
"../PosixSharedMemory.cpp",
"../PosixSharedMemory.h",
"../../Utils/b3ResourcePath.cpp",
"../../Utils/b3ResourcePath.h",
"../../Utils/b3Clock.cpp",
"../../Utils/b3Clock.h",
}
project "App_PhysicsServerGRPC"
if _OPTIONS["ios"] then
kind "WindowedApp"
else
kind "ConsoleApp"
end
defines { "NO_SHARED_MEMORY" }
includedirs {"..","../../../src", "../../ThirdPartyLibs","../../ThirdPartyLibs/clsocket/src"}
links {
"clsocket","Bullet3Common","BulletInverseDynamicsUtils", "BulletInverseDynamics", "BulletSoftBody", "BulletDynamics","BulletCollision", "LinearMath", "BussIK"
}
if os.is("Windows") then
defines { "WIN32", "_WIN32_WINNT=0x0600" }
links {"grpc","grpc++","grpc++_reflection","gpr",
"libprotobuf","crypto","ssl","zlibstaticd","Ws2_32","Winmm" }
end
if os.is("Linux") then
defines {"_LINUX"}
links{"dl"}
end
if os.is("MacOSX") then
defines {"_DARWIN"}
end
language "C++"
myfiles =
{
"../IKTrajectoryHelper.cpp",
"../IKTrajectoryHelper.h",
"../SharedMemoryCommands.h",
"../SharedMemoryPublic.h",
"../PhysicsServerCommandProcessor.cpp",
"../PhysicsServerCommandProcessor.h",
"../b3PluginManager.cpp",
"../PhysicsDirect.cpp",
"../PhysicsClientC_API.cpp",
"../PhysicsClient.cpp",
"../plugins/collisionFilterPlugin/collisionFilterPlugin.cpp",
"../plugins/pdControlPlugin/pdControlPlugin.cpp",
"../plugins/pdControlPlugin/pdControlPlugin.h",
"../b3RobotSimulatorClientAPI_NoDirect.cpp",
"../b3RobotSimulatorClientAPI_NoDirect.h",
"../plugins/tinyRendererPlugin/tinyRendererPlugin.cpp",
"../plugins/tinyRendererPlugin/TinyRendererVisualShapeConverter.cpp",
"../../TinyRenderer/geometry.cpp",
"../../TinyRenderer/model.cpp",
"../../TinyRenderer/tgaimage.cpp",
"../../TinyRenderer/our_gl.cpp",
"../../TinyRenderer/TinyRenderer.cpp",
"../../OpenGLWindow/SimpleCamera.cpp",
"../../OpenGLWindow/SimpleCamera.h",
"../../Importers/ImportURDFDemo/ConvertRigidBodies2MultiBody.h",
"../../Importers/ImportURDFDemo/MultiBodyCreationInterface.h",
"../../Importers/ImportURDFDemo/MyMultiBodyCreator.cpp",
"../../Importers/ImportURDFDemo/MyMultiBodyCreator.h",
"../../Importers/ImportMJCFDemo/BulletMJCFImporter.cpp",
"../../Importers/ImportMJCFDemo/BulletMJCFImporter.h",
"../../Importers/ImportURDFDemo/BulletUrdfImporter.cpp",
"../../Importers/ImportURDFDemo/BulletUrdfImporter.h",
"../../Importers/ImportURDFDemo/UrdfParser.cpp",
"../../Importers/ImportURDFDemo/urdfStringSplit.cpp",
"../../Importers/ImportURDFDemo/UrdfParser.cpp",
"../../Importers/ImportURDFDemo/UrdfParser.h",
"../../Importers/ImportURDFDemo/URDF2Bullet.cpp",
"../../Importers/ImportURDFDemo/URDF2Bullet.h",
"../../Utils/b3ResourcePath.cpp",
"../../Utils/b3Clock.cpp",
"../../Utils/ChromeTraceUtil.cpp",
"../../Utils/ChromeTraceUtil.h",
"../../Utils/RobotLoggingUtil.cpp",
"../../Utils/RobotLoggingUtil.h",
"../../../Extras/Serialize/BulletWorldImporter/*",
"../../../Extras/Serialize/BulletFileLoader/*",
"../../Importers/ImportURDFDemo/URDFImporterInterface.h",
"../../Importers/ImportURDFDemo/URDFJointTypes.h",
"../../Importers/ImportObjDemo/Wavefront2GLInstanceGraphicsShape.cpp",
"../../Importers/ImportObjDemo/LoadMeshFromObj.cpp",
"../../Importers/ImportSTLDemo/ImportSTLSetup.h",
"../../Importers/ImportSTLDemo/LoadMeshFromSTL.h",
"../../Importers/ImportColladaDemo/LoadMeshFromCollada.cpp",
"../../Importers/ImportColladaDemo/ColladaGraphicsInstance.h",
"../../ThirdPartyLibs/Wavefront/tiny_obj_loader.cpp",
"../../ThirdPartyLibs/tinyxml2/tinyxml2.cpp",
"../../Importers/ImportMeshUtility/b3ImportMeshUtility.cpp",
"../../ThirdPartyLibs/stb_image/stb_image.cpp",
}
files {
myfiles,
"main.cpp",
}

View File

@@ -0,0 +1,19 @@
del ..\pybullet.pb.cpp
del ..\pybullet.pb.h
del ..\pybullet.grpc.pb.cpp
del ..\pybullet.grpc.pb.h
..\..\..\ThirdPartyLibs\grpc\lib\win32\protoc --proto_path=. --cpp_out=. pybullet.proto
..\..\..\ThirdPartyLibs\grpc\lib\win32\protoc.exe --plugin=protoc-gen-grpc="..\..\..\ThirdPartyLibs\grpc\lib\win32\grpc_cpp_plugin.exe" --grpc_out=. pybullet.proto
move pybullet.grpc.pb.cc ..\pybullet.grpc.pb.cpp
move pybullet.grpc.pb.h ..\pybullet.grpc.pb.h
move pybullet.pb.cc ..\pybullet.pb.cpp
move pybullet.pb.h ..\pybullet.pb.h
del ..\pybullet_pb2.py
del ..\pybullet_pb2_grpc.py
..\..\..\ThirdPartyLibs\grpc\lib\win32\protoc --proto_path=. --python_out=. pybullet.proto
python -m grpc_tools.protoc -I. --python_out=. --grpc_python_out=. pybullet.proto
move pybullet_pb2.py ..\pybullet_pb2.py
move pybullet_pb2_grpc.py ..\pybullet_pb2_grpc.py

View File

@@ -0,0 +1,85 @@
syntax = "proto3";
option java_multiple_files = true;
option java_package = "io.grpc.pybullet_grpc";
option java_outer_classname = "PyBulletProto";
option objc_class_prefix = "PBG";
package pybullet_grpc;
service PyBulletAPI {
// Sends a greeting
rpc SubmitCommand (PyBulletCommand) returns (PyBulletStatus) {}
}
message vec3
{
double x=1;
double y=2;
double z=3;
};
message quat4
{
double x=1;
double y=2;
double z=3;
double w=4;
};
message TerminateServerCommand
{
string exitReason=1;
};
message StepSimulationCommand
{
};
message LoadUrdfCommand {
string urdfFileName=1;
vec3 initialPosition=2;
quat4 initialOrientation=3;
//for why oneof here, see the sad decision here:
//https://github.com/protocolbuffers/protobuf/issues/1606
oneof hasUseMultiBody { int32 useMultiBody=4; }
oneof hasUseFixedBase{ bool useFixedBase=5; }
int32 urdfFlags=6;
oneof hasGlobalScaling { double globalScaling=7;
}
};
message LoadUrdfStatus {
int32 objectUniqueId=1;
}
// The request message containing the command
message PyBulletCommand {
int32 commandType=1;
oneof commands {
LoadUrdfCommand loadUrdfCommand = 3;
TerminateServerCommand terminateServerCommand=4;
StepSimulationCommand stepSimulationCommand= 5;
}
}
// The response message containing the status
message PyBulletStatus {
int32 statusType=1;
oneof status
{
LoadUrdfStatus urdfStatus = 2;
}
}

View File

@@ -0,0 +1,59 @@
// Generated by the gRPC C++ plugin.
// If you make any local change, they will be lost.
// source: pybullet.proto
#include "pybullet.pb.h"
#include "pybullet.grpc.pb.h"
#include <grpc++/impl/codegen/async_stream.h>
#include <grpc++/impl/codegen/async_unary_call.h>
#include <grpc++/impl/codegen/channel_interface.h>
#include <grpc++/impl/codegen/client_unary_call.h>
#include <grpc++/impl/codegen/method_handler_impl.h>
#include <grpc++/impl/codegen/rpc_service_method.h>
#include <grpc++/impl/codegen/service_type.h>
#include <grpc++/impl/codegen/sync_stream.h>
namespace pybullet_grpc {
static const char* PyBulletAPI_method_names[] = {
"/pybullet_grpc.PyBulletAPI/SubmitCommand",
};
std::unique_ptr< PyBulletAPI::Stub> PyBulletAPI::NewStub(const std::shared_ptr< ::grpc::ChannelInterface>& channel, const ::grpc::StubOptions& options) {
std::unique_ptr< PyBulletAPI::Stub> stub(new PyBulletAPI::Stub(channel));
return stub;
}
PyBulletAPI::Stub::Stub(const std::shared_ptr< ::grpc::ChannelInterface>& channel)
: channel_(channel), rpcmethod_SubmitCommand_(PyBulletAPI_method_names[0], ::grpc::RpcMethod::NORMAL_RPC, channel)
{}
::grpc::Status PyBulletAPI::Stub::SubmitCommand(::grpc::ClientContext* context, const ::pybullet_grpc::PyBulletCommand& request, ::pybullet_grpc::PyBulletStatus* response) {
return ::grpc::BlockingUnaryCall(channel_.get(), rpcmethod_SubmitCommand_, context, request, response);
}
::grpc::ClientAsyncResponseReader< ::pybullet_grpc::PyBulletStatus>* PyBulletAPI::Stub::AsyncSubmitCommandRaw(::grpc::ClientContext* context, const ::pybullet_grpc::PyBulletCommand& request, ::grpc::CompletionQueue* cq) {
return new ::grpc::ClientAsyncResponseReader< ::pybullet_grpc::PyBulletStatus>(channel_.get(), cq, rpcmethod_SubmitCommand_, context, request);
}
PyBulletAPI::Service::Service() {
AddMethod(new ::grpc::RpcServiceMethod(
PyBulletAPI_method_names[0],
::grpc::RpcMethod::NORMAL_RPC,
new ::grpc::RpcMethodHandler< PyBulletAPI::Service, ::pybullet_grpc::PyBulletCommand, ::pybullet_grpc::PyBulletStatus>(
std::mem_fn(&PyBulletAPI::Service::SubmitCommand), this)));
}
PyBulletAPI::Service::~Service() {
}
::grpc::Status PyBulletAPI::Service::SubmitCommand(::grpc::ServerContext* context, const ::pybullet_grpc::PyBulletCommand* request, ::pybullet_grpc::PyBulletStatus* response) {
(void) context;
(void) request;
(void) response;
return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, "");
}
} // namespace pybullet_grpc

View File

@@ -0,0 +1,130 @@
// Generated by the gRPC C++ plugin.
// If you make any local change, they will be lost.
// source: pybullet.proto
#ifndef GRPC_pybullet_2eproto__INCLUDED
#define GRPC_pybullet_2eproto__INCLUDED
#include "pybullet.pb.h"
#include <grpc++/impl/codegen/async_stream.h>
#include <grpc++/impl/codegen/async_unary_call.h>
#include <grpc++/impl/codegen/method_handler_impl.h>
#include <grpc++/impl/codegen/proto_utils.h>
#include <grpc++/impl/codegen/rpc_method.h>
#include <grpc++/impl/codegen/service_type.h>
#include <grpc++/impl/codegen/status.h>
#include <grpc++/impl/codegen/stub_options.h>
#include <grpc++/impl/codegen/sync_stream.h>
namespace grpc {
class CompletionQueue;
class Channel;
class RpcService;
class ServerCompletionQueue;
class ServerContext;
} // namespace grpc
namespace pybullet_grpc {
class PyBulletAPI final {
public:
class StubInterface {
public:
virtual ~StubInterface() {}
// Sends a greeting
virtual ::grpc::Status SubmitCommand(::grpc::ClientContext* context, const ::pybullet_grpc::PyBulletCommand& request, ::pybullet_grpc::PyBulletStatus* response) = 0;
std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::pybullet_grpc::PyBulletStatus>> AsyncSubmitCommand(::grpc::ClientContext* context, const ::pybullet_grpc::PyBulletCommand& request, ::grpc::CompletionQueue* cq) {
return std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::pybullet_grpc::PyBulletStatus>>(AsyncSubmitCommandRaw(context, request, cq));
}
private:
virtual ::grpc::ClientAsyncResponseReaderInterface< ::pybullet_grpc::PyBulletStatus>* AsyncSubmitCommandRaw(::grpc::ClientContext* context, const ::pybullet_grpc::PyBulletCommand& request, ::grpc::CompletionQueue* cq) = 0;
};
class Stub final : public StubInterface {
public:
Stub(const std::shared_ptr< ::grpc::ChannelInterface>& channel);
::grpc::Status SubmitCommand(::grpc::ClientContext* context, const ::pybullet_grpc::PyBulletCommand& request, ::pybullet_grpc::PyBulletStatus* response) override;
std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::pybullet_grpc::PyBulletStatus>> AsyncSubmitCommand(::grpc::ClientContext* context, const ::pybullet_grpc::PyBulletCommand& request, ::grpc::CompletionQueue* cq) {
return std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::pybullet_grpc::PyBulletStatus>>(AsyncSubmitCommandRaw(context, request, cq));
}
private:
std::shared_ptr< ::grpc::ChannelInterface> channel_;
::grpc::ClientAsyncResponseReader< ::pybullet_grpc::PyBulletStatus>* AsyncSubmitCommandRaw(::grpc::ClientContext* context, const ::pybullet_grpc::PyBulletCommand& request, ::grpc::CompletionQueue* cq) override;
const ::grpc::RpcMethod rpcmethod_SubmitCommand_;
};
static std::unique_ptr<Stub> NewStub(const std::shared_ptr< ::grpc::ChannelInterface>& channel, const ::grpc::StubOptions& options = ::grpc::StubOptions());
class Service : public ::grpc::Service {
public:
Service();
virtual ~Service();
// Sends a greeting
virtual ::grpc::Status SubmitCommand(::grpc::ServerContext* context, const ::pybullet_grpc::PyBulletCommand* request, ::pybullet_grpc::PyBulletStatus* response);
};
template <class BaseClass>
class WithAsyncMethod_SubmitCommand : public BaseClass {
private:
void BaseClassMustBeDerivedFromService(const Service *service) {}
public:
WithAsyncMethod_SubmitCommand() {
::grpc::Service::MarkMethodAsync(0);
}
~WithAsyncMethod_SubmitCommand() override {
BaseClassMustBeDerivedFromService(this);
}
// disable synchronous version of this method
::grpc::Status SubmitCommand(::grpc::ServerContext* context, const ::pybullet_grpc::PyBulletCommand* request, ::pybullet_grpc::PyBulletStatus* response) final override {
abort();
return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, "");
}
void RequestSubmitCommand(::grpc::ServerContext* context, ::pybullet_grpc::PyBulletCommand* request, ::grpc::ServerAsyncResponseWriter< ::pybullet_grpc::PyBulletStatus>* response, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) {
::grpc::Service::RequestAsyncUnary(0, context, request, response, new_call_cq, notification_cq, tag);
}
};
typedef WithAsyncMethod_SubmitCommand<Service > AsyncService;
template <class BaseClass>
class WithGenericMethod_SubmitCommand : public BaseClass {
private:
void BaseClassMustBeDerivedFromService(const Service *service) {}
public:
WithGenericMethod_SubmitCommand() {
::grpc::Service::MarkMethodGeneric(0);
}
~WithGenericMethod_SubmitCommand() override {
BaseClassMustBeDerivedFromService(this);
}
// disable synchronous version of this method
::grpc::Status SubmitCommand(::grpc::ServerContext* context, const ::pybullet_grpc::PyBulletCommand* request, ::pybullet_grpc::PyBulletStatus* response) final override {
abort();
return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, "");
}
};
template <class BaseClass>
class WithStreamedUnaryMethod_SubmitCommand : public BaseClass {
private:
void BaseClassMustBeDerivedFromService(const Service *service) {}
public:
WithStreamedUnaryMethod_SubmitCommand() {
::grpc::Service::MarkMethodStreamed(0,
new ::grpc::StreamedUnaryHandler< ::pybullet_grpc::PyBulletCommand, ::pybullet_grpc::PyBulletStatus>(std::bind(&WithStreamedUnaryMethod_SubmitCommand<BaseClass>::StreamedSubmitCommand, this, std::placeholders::_1, std::placeholders::_2)));
}
~WithStreamedUnaryMethod_SubmitCommand() override {
BaseClassMustBeDerivedFromService(this);
}
// disable regular version of this method
::grpc::Status SubmitCommand(::grpc::ServerContext* context, const ::pybullet_grpc::PyBulletCommand* request, ::pybullet_grpc::PyBulletStatus* response) final override {
abort();
return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, "");
}
// replace default version of method with streamed unary
virtual ::grpc::Status StreamedSubmitCommand(::grpc::ServerContext* context, ::grpc::ServerUnaryStreamer< ::pybullet_grpc::PyBulletCommand,::pybullet_grpc::PyBulletStatus>* server_unary_streamer) = 0;
};
typedef WithStreamedUnaryMethod_SubmitCommand<Service > StreamedUnaryService;
typedef Service SplitStreamedService;
typedef WithStreamedUnaryMethod_SubmitCommand<Service > StreamedService;
};
} // namespace pybullet_grpc
#endif // GRPC_pybullet_2eproto__INCLUDED

File diff suppressed because it is too large Load Diff

File diff suppressed because it is too large Load Diff

View File

@@ -0,0 +1,28 @@
"""The Python implementation of the PyBullet GRPC client."""
from __future__ import print_function
import grpc
import pybullet_pb2
import pybullet_pb2_grpc
def run():
channel = grpc.insecure_channel('localhost:50051')
stub = pybullet_pb2_grpc.PyBulletAPIStub(channel)
response = stub.SubmitCommand(pybullet_pb2.PyBulletCommand(loadUrdfCommand=pybullet_pb2.LoadUrdfCommand(urdfFileName="plane.urdf", initialPosition=pybullet_pb2.vec3(x=0,y=0,z=0), useMultiBody=False, useFixedBase=True, globalScaling=2, urdfFlags = 1)))
print("PyBullet client received: " , response.statusType)
print("URDF objectid =", response.urdfStatus.objectUniqueId)
response = stub.SubmitCommand(pybullet_pb2.PyBulletCommand(stepSimulationCommand=pybullet_pb2.StepSimulationCommand()))
print("PyBullet client received: " , response.statusType)
#response = stub.SubmitCommand(pybullet_pb2.PyBulletCommand(terminateServerCommand=pybullet_pb2.TerminateServerCommand()))
#print("PyBullet client received: " , response.statusType)
if __name__ == '__main__':
run()

View File

@@ -0,0 +1,508 @@
# Generated by the protocol buffer compiler. DO NOT EDIT!
# source: pybullet.proto
import sys
_b=sys.version_info[0]<3 and (lambda x:x) or (lambda x:x.encode('latin1'))
from google.protobuf import descriptor as _descriptor
from google.protobuf import message as _message
from google.protobuf import reflection as _reflection
from google.protobuf import symbol_database as _symbol_database
from google.protobuf import descriptor_pb2
# @@protoc_insertion_point(imports)
_sym_db = _symbol_database.Default()
DESCRIPTOR = _descriptor.FileDescriptor(
name='pybullet.proto',
package='pybullet_grpc',
syntax='proto3',
serialized_pb=_b('\n\x0epybullet.proto\x12\rpybullet_grpc\"\'\n\x04vec3\x12\t\n\x01x\x18\x01 \x01(\x01\x12\t\n\x01y\x18\x02 \x01(\x01\x12\t\n\x01z\x18\x03 \x01(\x01\"3\n\x05quat4\x12\t\n\x01x\x18\x01 \x01(\x01\x12\t\n\x01y\x18\x02 \x01(\x01\x12\t\n\x01z\x18\x03 \x01(\x01\x12\t\n\x01w\x18\x04 \x01(\x01\",\n\x16TerminateServerCommand\x12\x12\n\nexitReason\x18\x01 \x01(\t\"\x17\n\x15StepSimulationCommand\"\x9d\x02\n\x0fLoadUrdfCommand\x12\x14\n\x0curdfFileName\x18\x01 \x01(\t\x12,\n\x0finitialPosition\x18\x02 \x01(\x0b\x32\x13.pybullet_grpc.vec3\x12\x30\n\x12initialOrientation\x18\x03 \x01(\x0b\x32\x14.pybullet_grpc.quat4\x12\x16\n\x0cuseMultiBody\x18\x04 \x01(\x05H\x00\x12\x16\n\x0cuseFixedBase\x18\x05 \x01(\x08H\x01\x12\x11\n\turdfFlags\x18\x06 \x01(\x05\x12\x17\n\rglobalScaling\x18\x07 \x01(\x01H\x02\x42\x11\n\x0fhasUseMultiBodyB\x11\n\x0fhasUseFixedBaseB\x12\n\x10hasGlobalScaling\"(\n\x0eLoadUrdfStatus\x12\x16\n\x0eobjectUniqueId\x18\x01 \x01(\x05\"\xfd\x01\n\x0fPyBulletCommand\x12\x13\n\x0b\x63ommandType\x18\x01 \x01(\x05\x12\x39\n\x0floadUrdfCommand\x18\x03 \x01(\x0b\x32\x1e.pybullet_grpc.LoadUrdfCommandH\x00\x12G\n\x16terminateServerCommand\x18\x04 \x01(\x0b\x32%.pybullet_grpc.TerminateServerCommandH\x00\x12\x45\n\x15stepSimulationCommand\x18\x05 \x01(\x0b\x32$.pybullet_grpc.StepSimulationCommandH\x00\x42\n\n\x08\x63ommands\"c\n\x0ePyBulletStatus\x12\x12\n\nstatusType\x18\x01 \x01(\x05\x12\x33\n\nurdfStatus\x18\x02 \x01(\x0b\x32\x1d.pybullet_grpc.LoadUrdfStatusH\x00\x42\x08\n\x06status2_\n\x0bPyBulletAPI\x12P\n\rSubmitCommand\x12\x1e.pybullet_grpc.PyBulletCommand\x1a\x1d.pybullet_grpc.PyBulletStatus\"\x00\x42.\n\x15io.grpc.pybullet_grpcB\rPyBulletProtoP\x01\xa2\x02\x03PBGb\x06proto3')
)
_VEC3 = _descriptor.Descriptor(
name='vec3',
full_name='pybullet_grpc.vec3',
filename=None,
file=DESCRIPTOR,
containing_type=None,
fields=[
_descriptor.FieldDescriptor(
name='x', full_name='pybullet_grpc.vec3.x', index=0,
number=1, type=1, cpp_type=5, label=1,
has_default_value=False, default_value=float(0),
message_type=None, enum_type=None, containing_type=None,
is_extension=False, extension_scope=None,
options=None, file=DESCRIPTOR),
_descriptor.FieldDescriptor(
name='y', full_name='pybullet_grpc.vec3.y', index=1,
number=2, type=1, cpp_type=5, label=1,
has_default_value=False, default_value=float(0),
message_type=None, enum_type=None, containing_type=None,
is_extension=False, extension_scope=None,
options=None, file=DESCRIPTOR),
_descriptor.FieldDescriptor(
name='z', full_name='pybullet_grpc.vec3.z', index=2,
number=3, type=1, cpp_type=5, label=1,
has_default_value=False, default_value=float(0),
message_type=None, enum_type=None, containing_type=None,
is_extension=False, extension_scope=None,
options=None, file=DESCRIPTOR),
],
extensions=[
],
nested_types=[],
enum_types=[
],
options=None,
is_extendable=False,
syntax='proto3',
extension_ranges=[],
oneofs=[
],
serialized_start=33,
serialized_end=72,
)
_QUAT4 = _descriptor.Descriptor(
name='quat4',
full_name='pybullet_grpc.quat4',
filename=None,
file=DESCRIPTOR,
containing_type=None,
fields=[
_descriptor.FieldDescriptor(
name='x', full_name='pybullet_grpc.quat4.x', index=0,
number=1, type=1, cpp_type=5, label=1,
has_default_value=False, default_value=float(0),
message_type=None, enum_type=None, containing_type=None,
is_extension=False, extension_scope=None,
options=None, file=DESCRIPTOR),
_descriptor.FieldDescriptor(
name='y', full_name='pybullet_grpc.quat4.y', index=1,
number=2, type=1, cpp_type=5, label=1,
has_default_value=False, default_value=float(0),
message_type=None, enum_type=None, containing_type=None,
is_extension=False, extension_scope=None,
options=None, file=DESCRIPTOR),
_descriptor.FieldDescriptor(
name='z', full_name='pybullet_grpc.quat4.z', index=2,
number=3, type=1, cpp_type=5, label=1,
has_default_value=False, default_value=float(0),
message_type=None, enum_type=None, containing_type=None,
is_extension=False, extension_scope=None,
options=None, file=DESCRIPTOR),
_descriptor.FieldDescriptor(
name='w', full_name='pybullet_grpc.quat4.w', index=3,
number=4, type=1, cpp_type=5, label=1,
has_default_value=False, default_value=float(0),
message_type=None, enum_type=None, containing_type=None,
is_extension=False, extension_scope=None,
options=None, file=DESCRIPTOR),
],
extensions=[
],
nested_types=[],
enum_types=[
],
options=None,
is_extendable=False,
syntax='proto3',
extension_ranges=[],
oneofs=[
],
serialized_start=74,
serialized_end=125,
)
_TERMINATESERVERCOMMAND = _descriptor.Descriptor(
name='TerminateServerCommand',
full_name='pybullet_grpc.TerminateServerCommand',
filename=None,
file=DESCRIPTOR,
containing_type=None,
fields=[
_descriptor.FieldDescriptor(
name='exitReason', full_name='pybullet_grpc.TerminateServerCommand.exitReason', index=0,
number=1, type=9, cpp_type=9, label=1,
has_default_value=False, default_value=_b("").decode('utf-8'),
message_type=None, enum_type=None, containing_type=None,
is_extension=False, extension_scope=None,
options=None, file=DESCRIPTOR),
],
extensions=[
],
nested_types=[],
enum_types=[
],
options=None,
is_extendable=False,
syntax='proto3',
extension_ranges=[],
oneofs=[
],
serialized_start=127,
serialized_end=171,
)
_STEPSIMULATIONCOMMAND = _descriptor.Descriptor(
name='StepSimulationCommand',
full_name='pybullet_grpc.StepSimulationCommand',
filename=None,
file=DESCRIPTOR,
containing_type=None,
fields=[
],
extensions=[
],
nested_types=[],
enum_types=[
],
options=None,
is_extendable=False,
syntax='proto3',
extension_ranges=[],
oneofs=[
],
serialized_start=173,
serialized_end=196,
)
_LOADURDFCOMMAND = _descriptor.Descriptor(
name='LoadUrdfCommand',
full_name='pybullet_grpc.LoadUrdfCommand',
filename=None,
file=DESCRIPTOR,
containing_type=None,
fields=[
_descriptor.FieldDescriptor(
name='urdfFileName', full_name='pybullet_grpc.LoadUrdfCommand.urdfFileName', index=0,
number=1, type=9, cpp_type=9, label=1,
has_default_value=False, default_value=_b("").decode('utf-8'),
message_type=None, enum_type=None, containing_type=None,
is_extension=False, extension_scope=None,
options=None, file=DESCRIPTOR),
_descriptor.FieldDescriptor(
name='initialPosition', full_name='pybullet_grpc.LoadUrdfCommand.initialPosition', index=1,
number=2, type=11, cpp_type=10, label=1,
has_default_value=False, default_value=None,
message_type=None, enum_type=None, containing_type=None,
is_extension=False, extension_scope=None,
options=None, file=DESCRIPTOR),
_descriptor.FieldDescriptor(
name='initialOrientation', full_name='pybullet_grpc.LoadUrdfCommand.initialOrientation', index=2,
number=3, type=11, cpp_type=10, label=1,
has_default_value=False, default_value=None,
message_type=None, enum_type=None, containing_type=None,
is_extension=False, extension_scope=None,
options=None, file=DESCRIPTOR),
_descriptor.FieldDescriptor(
name='useMultiBody', full_name='pybullet_grpc.LoadUrdfCommand.useMultiBody', index=3,
number=4, type=5, cpp_type=1, label=1,
has_default_value=False, default_value=0,
message_type=None, enum_type=None, containing_type=None,
is_extension=False, extension_scope=None,
options=None, file=DESCRIPTOR),
_descriptor.FieldDescriptor(
name='useFixedBase', full_name='pybullet_grpc.LoadUrdfCommand.useFixedBase', index=4,
number=5, type=8, cpp_type=7, label=1,
has_default_value=False, default_value=False,
message_type=None, enum_type=None, containing_type=None,
is_extension=False, extension_scope=None,
options=None, file=DESCRIPTOR),
_descriptor.FieldDescriptor(
name='urdfFlags', full_name='pybullet_grpc.LoadUrdfCommand.urdfFlags', index=5,
number=6, type=5, cpp_type=1, label=1,
has_default_value=False, default_value=0,
message_type=None, enum_type=None, containing_type=None,
is_extension=False, extension_scope=None,
options=None, file=DESCRIPTOR),
_descriptor.FieldDescriptor(
name='globalScaling', full_name='pybullet_grpc.LoadUrdfCommand.globalScaling', index=6,
number=7, type=1, cpp_type=5, label=1,
has_default_value=False, default_value=float(0),
message_type=None, enum_type=None, containing_type=None,
is_extension=False, extension_scope=None,
options=None, file=DESCRIPTOR),
],
extensions=[
],
nested_types=[],
enum_types=[
],
options=None,
is_extendable=False,
syntax='proto3',
extension_ranges=[],
oneofs=[
_descriptor.OneofDescriptor(
name='hasUseMultiBody', full_name='pybullet_grpc.LoadUrdfCommand.hasUseMultiBody',
index=0, containing_type=None, fields=[]),
_descriptor.OneofDescriptor(
name='hasUseFixedBase', full_name='pybullet_grpc.LoadUrdfCommand.hasUseFixedBase',
index=1, containing_type=None, fields=[]),
_descriptor.OneofDescriptor(
name='hasGlobalScaling', full_name='pybullet_grpc.LoadUrdfCommand.hasGlobalScaling',
index=2, containing_type=None, fields=[]),
],
serialized_start=199,
serialized_end=484,
)
_LOADURDFSTATUS = _descriptor.Descriptor(
name='LoadUrdfStatus',
full_name='pybullet_grpc.LoadUrdfStatus',
filename=None,
file=DESCRIPTOR,
containing_type=None,
fields=[
_descriptor.FieldDescriptor(
name='objectUniqueId', full_name='pybullet_grpc.LoadUrdfStatus.objectUniqueId', index=0,
number=1, type=5, cpp_type=1, label=1,
has_default_value=False, default_value=0,
message_type=None, enum_type=None, containing_type=None,
is_extension=False, extension_scope=None,
options=None, file=DESCRIPTOR),
],
extensions=[
],
nested_types=[],
enum_types=[
],
options=None,
is_extendable=False,
syntax='proto3',
extension_ranges=[],
oneofs=[
],
serialized_start=486,
serialized_end=526,
)
_PYBULLETCOMMAND = _descriptor.Descriptor(
name='PyBulletCommand',
full_name='pybullet_grpc.PyBulletCommand',
filename=None,
file=DESCRIPTOR,
containing_type=None,
fields=[
_descriptor.FieldDescriptor(
name='commandType', full_name='pybullet_grpc.PyBulletCommand.commandType', index=0,
number=1, type=5, cpp_type=1, label=1,
has_default_value=False, default_value=0,
message_type=None, enum_type=None, containing_type=None,
is_extension=False, extension_scope=None,
options=None, file=DESCRIPTOR),
_descriptor.FieldDescriptor(
name='loadUrdfCommand', full_name='pybullet_grpc.PyBulletCommand.loadUrdfCommand', index=1,
number=3, type=11, cpp_type=10, label=1,
has_default_value=False, default_value=None,
message_type=None, enum_type=None, containing_type=None,
is_extension=False, extension_scope=None,
options=None, file=DESCRIPTOR),
_descriptor.FieldDescriptor(
name='terminateServerCommand', full_name='pybullet_grpc.PyBulletCommand.terminateServerCommand', index=2,
number=4, type=11, cpp_type=10, label=1,
has_default_value=False, default_value=None,
message_type=None, enum_type=None, containing_type=None,
is_extension=False, extension_scope=None,
options=None, file=DESCRIPTOR),
_descriptor.FieldDescriptor(
name='stepSimulationCommand', full_name='pybullet_grpc.PyBulletCommand.stepSimulationCommand', index=3,
number=5, type=11, cpp_type=10, label=1,
has_default_value=False, default_value=None,
message_type=None, enum_type=None, containing_type=None,
is_extension=False, extension_scope=None,
options=None, file=DESCRIPTOR),
],
extensions=[
],
nested_types=[],
enum_types=[
],
options=None,
is_extendable=False,
syntax='proto3',
extension_ranges=[],
oneofs=[
_descriptor.OneofDescriptor(
name='commands', full_name='pybullet_grpc.PyBulletCommand.commands',
index=0, containing_type=None, fields=[]),
],
serialized_start=529,
serialized_end=782,
)
_PYBULLETSTATUS = _descriptor.Descriptor(
name='PyBulletStatus',
full_name='pybullet_grpc.PyBulletStatus',
filename=None,
file=DESCRIPTOR,
containing_type=None,
fields=[
_descriptor.FieldDescriptor(
name='statusType', full_name='pybullet_grpc.PyBulletStatus.statusType', index=0,
number=1, type=5, cpp_type=1, label=1,
has_default_value=False, default_value=0,
message_type=None, enum_type=None, containing_type=None,
is_extension=False, extension_scope=None,
options=None, file=DESCRIPTOR),
_descriptor.FieldDescriptor(
name='urdfStatus', full_name='pybullet_grpc.PyBulletStatus.urdfStatus', index=1,
number=2, type=11, cpp_type=10, label=1,
has_default_value=False, default_value=None,
message_type=None, enum_type=None, containing_type=None,
is_extension=False, extension_scope=None,
options=None, file=DESCRIPTOR),
],
extensions=[
],
nested_types=[],
enum_types=[
],
options=None,
is_extendable=False,
syntax='proto3',
extension_ranges=[],
oneofs=[
_descriptor.OneofDescriptor(
name='status', full_name='pybullet_grpc.PyBulletStatus.status',
index=0, containing_type=None, fields=[]),
],
serialized_start=784,
serialized_end=883,
)
_LOADURDFCOMMAND.fields_by_name['initialPosition'].message_type = _VEC3
_LOADURDFCOMMAND.fields_by_name['initialOrientation'].message_type = _QUAT4
_LOADURDFCOMMAND.oneofs_by_name['hasUseMultiBody'].fields.append(
_LOADURDFCOMMAND.fields_by_name['useMultiBody'])
_LOADURDFCOMMAND.fields_by_name['useMultiBody'].containing_oneof = _LOADURDFCOMMAND.oneofs_by_name['hasUseMultiBody']
_LOADURDFCOMMAND.oneofs_by_name['hasUseFixedBase'].fields.append(
_LOADURDFCOMMAND.fields_by_name['useFixedBase'])
_LOADURDFCOMMAND.fields_by_name['useFixedBase'].containing_oneof = _LOADURDFCOMMAND.oneofs_by_name['hasUseFixedBase']
_LOADURDFCOMMAND.oneofs_by_name['hasGlobalScaling'].fields.append(
_LOADURDFCOMMAND.fields_by_name['globalScaling'])
_LOADURDFCOMMAND.fields_by_name['globalScaling'].containing_oneof = _LOADURDFCOMMAND.oneofs_by_name['hasGlobalScaling']
_PYBULLETCOMMAND.fields_by_name['loadUrdfCommand'].message_type = _LOADURDFCOMMAND
_PYBULLETCOMMAND.fields_by_name['terminateServerCommand'].message_type = _TERMINATESERVERCOMMAND
_PYBULLETCOMMAND.fields_by_name['stepSimulationCommand'].message_type = _STEPSIMULATIONCOMMAND
_PYBULLETCOMMAND.oneofs_by_name['commands'].fields.append(
_PYBULLETCOMMAND.fields_by_name['loadUrdfCommand'])
_PYBULLETCOMMAND.fields_by_name['loadUrdfCommand'].containing_oneof = _PYBULLETCOMMAND.oneofs_by_name['commands']
_PYBULLETCOMMAND.oneofs_by_name['commands'].fields.append(
_PYBULLETCOMMAND.fields_by_name['terminateServerCommand'])
_PYBULLETCOMMAND.fields_by_name['terminateServerCommand'].containing_oneof = _PYBULLETCOMMAND.oneofs_by_name['commands']
_PYBULLETCOMMAND.oneofs_by_name['commands'].fields.append(
_PYBULLETCOMMAND.fields_by_name['stepSimulationCommand'])
_PYBULLETCOMMAND.fields_by_name['stepSimulationCommand'].containing_oneof = _PYBULLETCOMMAND.oneofs_by_name['commands']
_PYBULLETSTATUS.fields_by_name['urdfStatus'].message_type = _LOADURDFSTATUS
_PYBULLETSTATUS.oneofs_by_name['status'].fields.append(
_PYBULLETSTATUS.fields_by_name['urdfStatus'])
_PYBULLETSTATUS.fields_by_name['urdfStatus'].containing_oneof = _PYBULLETSTATUS.oneofs_by_name['status']
DESCRIPTOR.message_types_by_name['vec3'] = _VEC3
DESCRIPTOR.message_types_by_name['quat4'] = _QUAT4
DESCRIPTOR.message_types_by_name['TerminateServerCommand'] = _TERMINATESERVERCOMMAND
DESCRIPTOR.message_types_by_name['StepSimulationCommand'] = _STEPSIMULATIONCOMMAND
DESCRIPTOR.message_types_by_name['LoadUrdfCommand'] = _LOADURDFCOMMAND
DESCRIPTOR.message_types_by_name['LoadUrdfStatus'] = _LOADURDFSTATUS
DESCRIPTOR.message_types_by_name['PyBulletCommand'] = _PYBULLETCOMMAND
DESCRIPTOR.message_types_by_name['PyBulletStatus'] = _PYBULLETSTATUS
_sym_db.RegisterFileDescriptor(DESCRIPTOR)
vec3 = _reflection.GeneratedProtocolMessageType('vec3', (_message.Message,), dict(
DESCRIPTOR = _VEC3,
__module__ = 'pybullet_pb2'
# @@protoc_insertion_point(class_scope:pybullet_grpc.vec3)
))
_sym_db.RegisterMessage(vec3)
quat4 = _reflection.GeneratedProtocolMessageType('quat4', (_message.Message,), dict(
DESCRIPTOR = _QUAT4,
__module__ = 'pybullet_pb2'
# @@protoc_insertion_point(class_scope:pybullet_grpc.quat4)
))
_sym_db.RegisterMessage(quat4)
TerminateServerCommand = _reflection.GeneratedProtocolMessageType('TerminateServerCommand', (_message.Message,), dict(
DESCRIPTOR = _TERMINATESERVERCOMMAND,
__module__ = 'pybullet_pb2'
# @@protoc_insertion_point(class_scope:pybullet_grpc.TerminateServerCommand)
))
_sym_db.RegisterMessage(TerminateServerCommand)
StepSimulationCommand = _reflection.GeneratedProtocolMessageType('StepSimulationCommand', (_message.Message,), dict(
DESCRIPTOR = _STEPSIMULATIONCOMMAND,
__module__ = 'pybullet_pb2'
# @@protoc_insertion_point(class_scope:pybullet_grpc.StepSimulationCommand)
))
_sym_db.RegisterMessage(StepSimulationCommand)
LoadUrdfCommand = _reflection.GeneratedProtocolMessageType('LoadUrdfCommand', (_message.Message,), dict(
DESCRIPTOR = _LOADURDFCOMMAND,
__module__ = 'pybullet_pb2'
# @@protoc_insertion_point(class_scope:pybullet_grpc.LoadUrdfCommand)
))
_sym_db.RegisterMessage(LoadUrdfCommand)
LoadUrdfStatus = _reflection.GeneratedProtocolMessageType('LoadUrdfStatus', (_message.Message,), dict(
DESCRIPTOR = _LOADURDFSTATUS,
__module__ = 'pybullet_pb2'
# @@protoc_insertion_point(class_scope:pybullet_grpc.LoadUrdfStatus)
))
_sym_db.RegisterMessage(LoadUrdfStatus)
PyBulletCommand = _reflection.GeneratedProtocolMessageType('PyBulletCommand', (_message.Message,), dict(
DESCRIPTOR = _PYBULLETCOMMAND,
__module__ = 'pybullet_pb2'
# @@protoc_insertion_point(class_scope:pybullet_grpc.PyBulletCommand)
))
_sym_db.RegisterMessage(PyBulletCommand)
PyBulletStatus = _reflection.GeneratedProtocolMessageType('PyBulletStatus', (_message.Message,), dict(
DESCRIPTOR = _PYBULLETSTATUS,
__module__ = 'pybullet_pb2'
# @@protoc_insertion_point(class_scope:pybullet_grpc.PyBulletStatus)
))
_sym_db.RegisterMessage(PyBulletStatus)
DESCRIPTOR.has_options = True
DESCRIPTOR._options = _descriptor._ParseOptions(descriptor_pb2.FileOptions(), _b('\n\025io.grpc.pybullet_grpcB\rPyBulletProtoP\001\242\002\003PBG'))
_PYBULLETAPI = _descriptor.ServiceDescriptor(
name='PyBulletAPI',
full_name='pybullet_grpc.PyBulletAPI',
file=DESCRIPTOR,
index=0,
options=None,
serialized_start=885,
serialized_end=980,
methods=[
_descriptor.MethodDescriptor(
name='SubmitCommand',
full_name='pybullet_grpc.PyBulletAPI.SubmitCommand',
index=0,
containing_service=None,
input_type=_PYBULLETCOMMAND,
output_type=_PYBULLETSTATUS,
options=None,
),
])
_sym_db.RegisterServiceDescriptor(_PYBULLETAPI)
DESCRIPTOR.services_by_name['PyBulletAPI'] = _PYBULLETAPI
# @@protoc_insertion_point(module_scope)

View File

@@ -0,0 +1,46 @@
# Generated by the gRPC Python protocol compiler plugin. DO NOT EDIT!
import grpc
import pybullet_pb2 as pybullet__pb2
class PyBulletAPIStub(object):
# missing associated documentation comment in .proto file
pass
def __init__(self, channel):
"""Constructor.
Args:
channel: A grpc.Channel.
"""
self.SubmitCommand = channel.unary_unary(
'/pybullet_grpc.PyBulletAPI/SubmitCommand',
request_serializer=pybullet__pb2.PyBulletCommand.SerializeToString,
response_deserializer=pybullet__pb2.PyBulletStatus.FromString,
)
class PyBulletAPIServicer(object):
# missing associated documentation comment in .proto file
pass
def SubmitCommand(self, request, context):
"""Sends a greeting
"""
context.set_code(grpc.StatusCode.UNIMPLEMENTED)
context.set_details('Method not implemented!')
raise NotImplementedError('Method not implemented!')
def add_PyBulletAPIServicer_to_server(servicer, server):
rpc_method_handlers = {
'SubmitCommand': grpc.unary_unary_rpc_method_handler(
servicer.SubmitCommand,
request_deserializer=pybullet__pb2.PyBulletCommand.FromString,
response_serializer=pybullet__pb2.PyBulletStatus.SerializeToString,
),
}
generic_handler = grpc.method_handlers_generic_handler(
'pybullet_grpc.PyBulletAPI', rpc_method_handlers)
server.add_generic_rpc_handlers((generic_handler,))

View File

@@ -466,6 +466,7 @@ end
include "udp" include "udp"
include "tcp" include "tcp"
include "plugins/testPlugin" include "plugins/testPlugin"
include "plugins/vrSyncPlugin" include "plugins/vrSyncPlugin"
include "plugins/tinyRendererPlugin" include "plugins/tinyRendererPlugin"
@@ -473,3 +474,6 @@ include "plugins/tinyRendererPlugin"
include "plugins/pdControlPlugin" include "plugins/pdControlPlugin"
include "plugins/collisionFilterPlugin" include "plugins/collisionFilterPlugin"
if _OPTIONS["grpc"] then
include "grpc"
end