From 4f7dfc2069d1ed2413646f4a0be143b6654b0d07 Mon Sep 17 00:00:00 2001 From: erwincoumans Date: Wed, 29 Aug 2018 21:12:13 -0700 Subject: [PATCH] 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 --- build3/premake4.lua | 7 + examples/SharedMemory/PhysicsClientC_API.cpp | 85 +- examples/SharedMemory/PhysicsClientC_API.h | 3 +- .../PhysicsServerCommandProcessor.cpp | 4 +- .../SharedMemory/grpc/ConvertGRPCBullet.cpp | 98 + .../SharedMemory/grpc/ConvertGRPCBullet.h | 17 + examples/SharedMemory/grpc/main.cpp | 278 ++ examples/SharedMemory/grpc/premake4.lua | 150 + .../grpc/proto/createProtobufs.bat | 19 + .../SharedMemory/grpc/proto/pybullet.proto | 85 + .../SharedMemory/grpc/pybullet.grpc.pb.cpp | 59 + examples/SharedMemory/grpc/pybullet.grpc.pb.h | 130 + examples/SharedMemory/grpc/pybullet.pb.cpp | 3388 +++++++++++++++++ examples/SharedMemory/grpc/pybullet.pb.h | 1676 ++++++++ examples/SharedMemory/grpc/pybullet_client.py | 28 + examples/SharedMemory/grpc/pybullet_pb2.py | 508 +++ .../SharedMemory/grpc/pybullet_pb2_grpc.py | 46 + examples/SharedMemory/premake4.lua | 4 + 18 files changed, 6556 insertions(+), 29 deletions(-) create mode 100644 examples/SharedMemory/grpc/ConvertGRPCBullet.cpp create mode 100644 examples/SharedMemory/grpc/ConvertGRPCBullet.h create mode 100644 examples/SharedMemory/grpc/main.cpp create mode 100644 examples/SharedMemory/grpc/premake4.lua create mode 100644 examples/SharedMemory/grpc/proto/createProtobufs.bat create mode 100644 examples/SharedMemory/grpc/proto/pybullet.proto create mode 100644 examples/SharedMemory/grpc/pybullet.grpc.pb.cpp create mode 100644 examples/SharedMemory/grpc/pybullet.grpc.pb.h create mode 100644 examples/SharedMemory/grpc/pybullet.pb.cpp create mode 100644 examples/SharedMemory/grpc/pybullet.pb.h create mode 100644 examples/SharedMemory/grpc/pybullet_client.py create mode 100644 examples/SharedMemory/grpc/pybullet_pb2.py create mode 100644 examples/SharedMemory/grpc/pybullet_pb2_grpc.py diff --git a/build3/premake4.lua b/build3/premake4.lua index d49b9d440..44cf16114 100644 --- a/build3/premake4.lua +++ b/build3/premake4.lua @@ -69,6 +69,13 @@ trigger = "midi", description = "Use Midi controller to control parameters" } + + newoption + { + trigger = "grpc", + description = "Build GRPC server/client features for PyBullet/BulletRobotics" + } + -- _OPTIONS["midi"] = "1"; diff --git a/examples/SharedMemory/PhysicsClientC_API.cpp b/examples/SharedMemory/PhysicsClientC_API.cpp index 0a3e9824b..94d347318 100644 --- a/examples/SharedMemory/PhysicsClientC_API.cpp +++ b/examples/SharedMemory/PhysicsClientC_API.cpp @@ -53,32 +53,6 @@ B3_SHARED_API b3SharedMemoryCommandHandle b3SaveWorldCommandInit(b3PhysicsClient 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) { @@ -310,6 +284,56 @@ B3_SHARED_API int b3LoadSoftBodySetCollisionMargin(b3SharedMemoryCommandHandle c 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) { struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; @@ -720,11 +744,18 @@ B3_SHARED_API b3SharedMemoryCommandHandle b3InitStepSimulationCommand(b3Physics b3Assert(cl->canSubmitCommand()); struct SharedMemoryCommand* command = cl->getAvailableSharedMemoryCommand(); 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_updateFlags = 0; - return (b3SharedMemoryCommandHandle) command; + return (b3SharedMemoryCommandHandle)command; } + B3_SHARED_API b3SharedMemoryCommandHandle b3InitResetSimulationCommand(b3PhysicsClientHandle physClient) { PhysicsClient* cl = (PhysicsClient* ) physClient; diff --git a/examples/SharedMemory/PhysicsClientC_API.h b/examples/SharedMemory/PhysicsClientC_API.h index b9bea0c83..d32446406 100644 --- a/examples/SharedMemory/PhysicsClientC_API.h +++ b/examples/SharedMemory/PhysicsClientC_API.h @@ -338,13 +338,14 @@ B3_SHARED_API int b3PhysicsParamSetInternalSimFlags(b3SharedMemoryCommandHandle B3_SHARED_API b3SharedMemoryCommandHandle b3InitStepSimulationCommand(b3PhysicsClientHandle physClient); +B3_SHARED_API b3SharedMemoryCommandHandle b3InitStepSimulationCommand2(b3SharedMemoryCommandHandle commandHandle); B3_SHARED_API b3SharedMemoryCommandHandle b3InitResetSimulationCommand(b3PhysicsClientHandle physClient); ///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); 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 b3LoadUrdfCommandSetStartOrientation(b3SharedMemoryCommandHandle commandHandle, double startOrnX,double startOrnY,double startOrnZ, double startOrnW); B3_SHARED_API int b3LoadUrdfCommandSetUseMultiBody(b3SharedMemoryCommandHandle commandHandle, int useMultiBody); diff --git a/examples/SharedMemory/PhysicsServerCommandProcessor.cpp b/examples/SharedMemory/PhysicsServerCommandProcessor.cpp index 7c6be5775..241a80317 100644 --- a/examples/SharedMemory/PhysicsServerCommandProcessor.cpp +++ b/examples/SharedMemory/PhysicsServerCommandProcessor.cpp @@ -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 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(); *bodyUniqueIdPtr = -1; diff --git a/examples/SharedMemory/grpc/ConvertGRPCBullet.cpp b/examples/SharedMemory/grpc/ConvertGRPCBullet.cpp new file mode 100644 index 000000000..213a70863 --- /dev/null +++ b/examples/SharedMemory/grpc/ConvertGRPCBullet.cpp @@ -0,0 +1,98 @@ +#include "ConvertGRPCBullet.h" +#include "PhysicsClientC_API.h" +#include "SharedMemoryCommands.h" +#include +#include +#include +#include +#include +#include +#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; +} diff --git a/examples/SharedMemory/grpc/ConvertGRPCBullet.h b/examples/SharedMemory/grpc/ConvertGRPCBullet.h new file mode 100644 index 000000000..530c462b2 --- /dev/null +++ b/examples/SharedMemory/grpc/ConvertGRPCBullet.h @@ -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 \ No newline at end of file diff --git a/examples/SharedMemory/grpc/main.cpp b/examples/SharedMemory/grpc/main.cpp new file mode 100644 index 000000000..751ef4373 --- /dev/null +++ b/examples/SharedMemory/grpc/main.cpp @@ -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 +#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 +#include +#include +#include + +#include +#include + +#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 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) 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 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 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(tag)->Proceed(); + } + } + } + + + std::unique_ptr cq_; + PyBulletAPI::AsyncService service_; + std::unique_ptr 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; +} + + diff --git a/examples/SharedMemory/grpc/premake4.lua b/examples/SharedMemory/grpc/premake4.lua new file mode 100644 index 000000000..4765d11bc --- /dev/null +++ b/examples/SharedMemory/grpc/premake4.lua @@ -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", +} + diff --git a/examples/SharedMemory/grpc/proto/createProtobufs.bat b/examples/SharedMemory/grpc/proto/createProtobufs.bat new file mode 100644 index 000000000..d21ad645a --- /dev/null +++ b/examples/SharedMemory/grpc/proto/createProtobufs.bat @@ -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 diff --git a/examples/SharedMemory/grpc/proto/pybullet.proto b/examples/SharedMemory/grpc/proto/pybullet.proto new file mode 100644 index 000000000..8c8b15875 --- /dev/null +++ b/examples/SharedMemory/grpc/proto/pybullet.proto @@ -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; + } +} + + diff --git a/examples/SharedMemory/grpc/pybullet.grpc.pb.cpp b/examples/SharedMemory/grpc/pybullet.grpc.pb.cpp new file mode 100644 index 000000000..36ab7c4bc --- /dev/null +++ b/examples/SharedMemory/grpc/pybullet.grpc.pb.cpp @@ -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 +#include +#include +#include +#include +#include +#include +#include +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 + diff --git a/examples/SharedMemory/grpc/pybullet.grpc.pb.h b/examples/SharedMemory/grpc/pybullet.grpc.pb.h new file mode 100644 index 000000000..e7787f82b --- /dev/null +++ b/examples/SharedMemory/grpc/pybullet.grpc.pb.h @@ -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 +#include +#include +#include +#include +#include +#include +#include +#include + +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 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 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 AsyncService; + template + 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 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::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 StreamedUnaryService; + typedef Service SplitStreamedService; + typedef WithStreamedUnaryMethod_SubmitCommand StreamedService; +}; + +} // namespace pybullet_grpc + + +#endif // GRPC_pybullet_2eproto__INCLUDED diff --git a/examples/SharedMemory/grpc/pybullet.pb.cpp b/examples/SharedMemory/grpc/pybullet.pb.cpp new file mode 100644 index 000000000..2a841c7c6 --- /dev/null +++ b/examples/SharedMemory/grpc/pybullet.pb.cpp @@ -0,0 +1,3388 @@ +// Generated by the protocol buffer compiler. DO NOT EDIT! +// source: pybullet.proto + +#define INTERNAL_SUPPRESS_PROTOBUF_FIELD_DEPRECATION +#include "pybullet.pb.h" + +#include + +#include +#include +#include +#include +#include +#include +#include +#include +#include +// @@protoc_insertion_point(includes) + +namespace pybullet_grpc { +class vec3DefaultTypeInternal : public ::google::protobuf::internal::ExplicitlyConstructed { +} _vec3_default_instance_; +class quat4DefaultTypeInternal : public ::google::protobuf::internal::ExplicitlyConstructed { +} _quat4_default_instance_; +class TerminateServerCommandDefaultTypeInternal : public ::google::protobuf::internal::ExplicitlyConstructed { +} _TerminateServerCommand_default_instance_; +class StepSimulationCommandDefaultTypeInternal : public ::google::protobuf::internal::ExplicitlyConstructed { +} _StepSimulationCommand_default_instance_; +class LoadUrdfCommandDefaultTypeInternal : public ::google::protobuf::internal::ExplicitlyConstructed { + public: + ::google::protobuf::int32 usemultibody_; + bool usefixedbase_; + double globalscaling_; +} _LoadUrdfCommand_default_instance_; +class LoadUrdfStatusDefaultTypeInternal : public ::google::protobuf::internal::ExplicitlyConstructed { +} _LoadUrdfStatus_default_instance_; +class PyBulletCommandDefaultTypeInternal : public ::google::protobuf::internal::ExplicitlyConstructed { + public: + const ::pybullet_grpc::LoadUrdfCommand* loadurdfcommand_; + const ::pybullet_grpc::TerminateServerCommand* terminateservercommand_; + const ::pybullet_grpc::StepSimulationCommand* stepsimulationcommand_; +} _PyBulletCommand_default_instance_; +class PyBulletStatusDefaultTypeInternal : public ::google::protobuf::internal::ExplicitlyConstructed { + public: + const ::pybullet_grpc::LoadUrdfStatus* urdfstatus_; +} _PyBulletStatus_default_instance_; + +namespace protobuf_pybullet_2eproto { + + +namespace { + +::google::protobuf::Metadata file_level_metadata[8]; + +} // namespace + +const ::google::protobuf::uint32 TableStruct::offsets[] = { + ~0u, // no _has_bits_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(vec3, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(vec3, x_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(vec3, y_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(vec3, z_), + ~0u, // no _has_bits_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(quat4, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(quat4, x_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(quat4, y_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(quat4, z_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(quat4, w_), + ~0u, // no _has_bits_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(TerminateServerCommand, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(TerminateServerCommand, exitreason_), + ~0u, // no _has_bits_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(StepSimulationCommand, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + ~0u, // no _has_bits_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(LoadUrdfCommand, _internal_metadata_), + ~0u, // no _extensions_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(LoadUrdfCommand, _oneof_case_[0]), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(LoadUrdfCommand, urdffilename_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(LoadUrdfCommand, initialposition_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(LoadUrdfCommand, initialorientation_), + PROTO2_GENERATED_DEFAULT_ONEOF_FIELD_OFFSET((&_LoadUrdfCommand_default_instance_), usemultibody_), + PROTO2_GENERATED_DEFAULT_ONEOF_FIELD_OFFSET((&_LoadUrdfCommand_default_instance_), usefixedbase_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(LoadUrdfCommand, urdfflags_), + PROTO2_GENERATED_DEFAULT_ONEOF_FIELD_OFFSET((&_LoadUrdfCommand_default_instance_), globalscaling_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(LoadUrdfCommand, hasUseMultiBody_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(LoadUrdfCommand, hasUseFixedBase_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(LoadUrdfCommand, hasGlobalScaling_), + ~0u, // no _has_bits_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(LoadUrdfStatus, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(LoadUrdfStatus, objectuniqueid_), + ~0u, // no _has_bits_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(PyBulletCommand, _internal_metadata_), + ~0u, // no _extensions_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(PyBulletCommand, _oneof_case_[0]), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(PyBulletCommand, commandtype_), + PROTO2_GENERATED_DEFAULT_ONEOF_FIELD_OFFSET((&_PyBulletCommand_default_instance_), loadurdfcommand_), + PROTO2_GENERATED_DEFAULT_ONEOF_FIELD_OFFSET((&_PyBulletCommand_default_instance_), terminateservercommand_), + PROTO2_GENERATED_DEFAULT_ONEOF_FIELD_OFFSET((&_PyBulletCommand_default_instance_), stepsimulationcommand_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(PyBulletCommand, commands_), + ~0u, // no _has_bits_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(PyBulletStatus, _internal_metadata_), + ~0u, // no _extensions_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(PyBulletStatus, _oneof_case_[0]), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(PyBulletStatus, statustype_), + PROTO2_GENERATED_DEFAULT_ONEOF_FIELD_OFFSET((&_PyBulletStatus_default_instance_), urdfstatus_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(PyBulletStatus, status_), +}; + +static const ::google::protobuf::internal::MigrationSchema schemas[] = { + { 0, -1, sizeof(vec3)}, + { 7, -1, sizeof(quat4)}, + { 15, -1, sizeof(TerminateServerCommand)}, + { 20, -1, sizeof(StepSimulationCommand)}, + { 24, -1, sizeof(LoadUrdfCommand)}, + { 38, -1, sizeof(LoadUrdfStatus)}, + { 43, -1, sizeof(PyBulletCommand)}, + { 52, -1, sizeof(PyBulletStatus)}, +}; + +static ::google::protobuf::Message const * const file_default_instances[] = { + reinterpret_cast(&_vec3_default_instance_), + reinterpret_cast(&_quat4_default_instance_), + reinterpret_cast(&_TerminateServerCommand_default_instance_), + reinterpret_cast(&_StepSimulationCommand_default_instance_), + reinterpret_cast(&_LoadUrdfCommand_default_instance_), + reinterpret_cast(&_LoadUrdfStatus_default_instance_), + reinterpret_cast(&_PyBulletCommand_default_instance_), + reinterpret_cast(&_PyBulletStatus_default_instance_), +}; + +namespace { + +void protobuf_AssignDescriptors() { + AddDescriptors(); + ::google::protobuf::MessageFactory* factory = NULL; + AssignDescriptors( + "pybullet.proto", schemas, file_default_instances, TableStruct::offsets, factory, + file_level_metadata, NULL, NULL); +} + +void protobuf_AssignDescriptorsOnce() { + static GOOGLE_PROTOBUF_DECLARE_ONCE(once); + ::google::protobuf::GoogleOnceInit(&once, &protobuf_AssignDescriptors); +} + +void protobuf_RegisterTypes(const ::std::string&) GOOGLE_ATTRIBUTE_COLD; +void protobuf_RegisterTypes(const ::std::string&) { + protobuf_AssignDescriptorsOnce(); + ::google::protobuf::internal::RegisterAllTypes(file_level_metadata, 8); +} + +} // namespace + +void TableStruct::Shutdown() { + _vec3_default_instance_.Shutdown(); + delete file_level_metadata[0].reflection; + _quat4_default_instance_.Shutdown(); + delete file_level_metadata[1].reflection; + _TerminateServerCommand_default_instance_.Shutdown(); + delete file_level_metadata[2].reflection; + _StepSimulationCommand_default_instance_.Shutdown(); + delete file_level_metadata[3].reflection; + _LoadUrdfCommand_default_instance_.Shutdown(); + delete file_level_metadata[4].reflection; + _LoadUrdfStatus_default_instance_.Shutdown(); + delete file_level_metadata[5].reflection; + _PyBulletCommand_default_instance_.Shutdown(); + delete file_level_metadata[6].reflection; + _PyBulletStatus_default_instance_.Shutdown(); + delete file_level_metadata[7].reflection; +} + +void TableStruct::InitDefaultsImpl() { + GOOGLE_PROTOBUF_VERIFY_VERSION; + + ::google::protobuf::internal::InitProtobufDefaults(); + _vec3_default_instance_.DefaultConstruct(); + _quat4_default_instance_.DefaultConstruct(); + _TerminateServerCommand_default_instance_.DefaultConstruct(); + _StepSimulationCommand_default_instance_.DefaultConstruct(); + _LoadUrdfCommand_default_instance_.DefaultConstruct(); + _LoadUrdfStatus_default_instance_.DefaultConstruct(); + _PyBulletCommand_default_instance_.DefaultConstruct(); + _PyBulletStatus_default_instance_.DefaultConstruct(); + _LoadUrdfCommand_default_instance_.get_mutable()->initialposition_ = const_cast< ::pybullet_grpc::vec3*>( + ::pybullet_grpc::vec3::internal_default_instance()); + _LoadUrdfCommand_default_instance_.get_mutable()->initialorientation_ = const_cast< ::pybullet_grpc::quat4*>( + ::pybullet_grpc::quat4::internal_default_instance()); + _LoadUrdfCommand_default_instance_.usemultibody_ = 0; + _LoadUrdfCommand_default_instance_.usefixedbase_ = false; + _LoadUrdfCommand_default_instance_.globalscaling_ = 0; + _PyBulletCommand_default_instance_.loadurdfcommand_ = const_cast< ::pybullet_grpc::LoadUrdfCommand*>( + ::pybullet_grpc::LoadUrdfCommand::internal_default_instance()); + _PyBulletCommand_default_instance_.terminateservercommand_ = const_cast< ::pybullet_grpc::TerminateServerCommand*>( + ::pybullet_grpc::TerminateServerCommand::internal_default_instance()); + _PyBulletCommand_default_instance_.stepsimulationcommand_ = const_cast< ::pybullet_grpc::StepSimulationCommand*>( + ::pybullet_grpc::StepSimulationCommand::internal_default_instance()); + _PyBulletStatus_default_instance_.urdfstatus_ = const_cast< ::pybullet_grpc::LoadUrdfStatus*>( + ::pybullet_grpc::LoadUrdfStatus::internal_default_instance()); +} + +void InitDefaults() { + static GOOGLE_PROTOBUF_DECLARE_ONCE(once); + ::google::protobuf::GoogleOnceInit(&once, &TableStruct::InitDefaultsImpl); +} +void AddDescriptorsImpl() { + InitDefaults(); + static const char descriptor[] = { + "\n\016pybullet.proto\022\rpybullet_grpc\"\'\n\004vec3\022" + "\t\n\001x\030\001 \001(\001\022\t\n\001y\030\002 \001(\001\022\t\n\001z\030\003 \001(\001\"3\n\005quat" + "4\022\t\n\001x\030\001 \001(\001\022\t\n\001y\030\002 \001(\001\022\t\n\001z\030\003 \001(\001\022\t\n\001w\030" + "\004 \001(\001\",\n\026TerminateServerCommand\022\022\n\nexitR" + "eason\030\001 \001(\t\"\027\n\025StepSimulationCommand\"\235\002\n" + "\017LoadUrdfCommand\022\024\n\014urdfFileName\030\001 \001(\t\022," + "\n\017initialPosition\030\002 \001(\0132\023.pybullet_grpc." + "vec3\0220\n\022initialOrientation\030\003 \001(\0132\024.pybul" + "let_grpc.quat4\022\026\n\014useMultiBody\030\004 \001(\005H\000\022\026" + "\n\014useFixedBase\030\005 \001(\010H\001\022\021\n\turdfFlags\030\006 \001(" + "\005\022\027\n\rglobalScaling\030\007 \001(\001H\002B\021\n\017hasUseMult" + "iBodyB\021\n\017hasUseFixedBaseB\022\n\020hasGlobalSca" + "ling\"(\n\016LoadUrdfStatus\022\026\n\016objectUniqueId" + "\030\001 \001(\005\"\375\001\n\017PyBulletCommand\022\023\n\013commandTyp" + "e\030\001 \001(\005\0229\n\017loadUrdfCommand\030\003 \001(\0132\036.pybul" + "let_grpc.LoadUrdfCommandH\000\022G\n\026terminateS" + "erverCommand\030\004 \001(\0132%.pybullet_grpc.Termi" + "nateServerCommandH\000\022E\n\025stepSimulationCom" + "mand\030\005 \001(\0132$.pybullet_grpc.StepSimulatio" + "nCommandH\000B\n\n\010commands\"c\n\016PyBulletStatus" + "\022\022\n\nstatusType\030\001 \001(\005\0223\n\nurdfStatus\030\002 \001(\013" + "2\035.pybullet_grpc.LoadUrdfStatusH\000B\010\n\006sta" + "tus2_\n\013PyBulletAPI\022P\n\rSubmitCommand\022\036.py" + "bullet_grpc.PyBulletCommand\032\035.pybullet_g" + "rpc.PyBulletStatus\"\000B.\n\025io.grpc.pybullet" + "_grpcB\rPyBulletProtoP\001\242\002\003PBGb\006proto3" + }; + ::google::protobuf::DescriptorPool::InternalAddGeneratedFile( + descriptor, 1036); + ::google::protobuf::MessageFactory::InternalRegisterGeneratedFile( + "pybullet.proto", &protobuf_RegisterTypes); + ::google::protobuf::internal::OnShutdown(&TableStruct::Shutdown); +} + +void AddDescriptors() { + static GOOGLE_PROTOBUF_DECLARE_ONCE(once); + ::google::protobuf::GoogleOnceInit(&once, &AddDescriptorsImpl); +} +// Force AddDescriptors() to be called at static initialization time. +struct StaticDescriptorInitializer { + StaticDescriptorInitializer() { + AddDescriptors(); + } +} static_descriptor_initializer; + +} // namespace protobuf_pybullet_2eproto + + +// =================================================================== + +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const int vec3::kXFieldNumber; +const int vec3::kYFieldNumber; +const int vec3::kZFieldNumber; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 + +vec3::vec3() + : ::google::protobuf::Message(), _internal_metadata_(NULL) { + if (GOOGLE_PREDICT_TRUE(this != internal_default_instance())) { + protobuf_pybullet_2eproto::InitDefaults(); + } + SharedCtor(); + // @@protoc_insertion_point(constructor:pybullet_grpc.vec3) +} +vec3::vec3(const vec3& from) + : ::google::protobuf::Message(), + _internal_metadata_(NULL), + _cached_size_(0) { + _internal_metadata_.MergeFrom(from._internal_metadata_); + ::memcpy(&x_, &from.x_, + reinterpret_cast(&z_) - + reinterpret_cast(&x_) + sizeof(z_)); + // @@protoc_insertion_point(copy_constructor:pybullet_grpc.vec3) +} + +void vec3::SharedCtor() { + ::memset(&x_, 0, reinterpret_cast(&z_) - + reinterpret_cast(&x_) + sizeof(z_)); + _cached_size_ = 0; +} + +vec3::~vec3() { + // @@protoc_insertion_point(destructor:pybullet_grpc.vec3) + SharedDtor(); +} + +void vec3::SharedDtor() { +} + +void vec3::SetCachedSize(int size) const { + GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN(); + _cached_size_ = size; + GOOGLE_SAFE_CONCURRENT_WRITES_END(); +} +const ::google::protobuf::Descriptor* vec3::descriptor() { + protobuf_pybullet_2eproto::protobuf_AssignDescriptorsOnce(); + return protobuf_pybullet_2eproto::file_level_metadata[0].descriptor; +} + +const vec3& vec3::default_instance() { + protobuf_pybullet_2eproto::InitDefaults(); + return *internal_default_instance(); +} + +vec3* vec3::New(::google::protobuf::Arena* arena) const { + vec3* n = new vec3; + if (arena != NULL) { + arena->Own(n); + } + return n; +} + +void vec3::Clear() { +// @@protoc_insertion_point(message_clear_start:pybullet_grpc.vec3) + ::memset(&x_, 0, reinterpret_cast(&z_) - + reinterpret_cast(&x_) + sizeof(z_)); +} + +bool vec3::MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) { +#define DO_(EXPRESSION) if (!GOOGLE_PREDICT_TRUE(EXPRESSION)) goto failure + ::google::protobuf::uint32 tag; + // @@protoc_insertion_point(parse_start:pybullet_grpc.vec3) + for (;;) { + ::std::pair< ::google::protobuf::uint32, bool> p = input->ReadTagWithCutoffNoLastTag(127u); + tag = p.first; + if (!p.second) goto handle_unusual; + switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { + // double x = 1; + case 1: { + if (tag == 9u) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &x_))); + } else { + goto handle_unusual; + } + break; + } + + // double y = 2; + case 2: { + if (tag == 17u) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &y_))); + } else { + goto handle_unusual; + } + break; + } + + // double z = 3; + case 3: { + if (tag == 25u) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &z_))); + } else { + goto handle_unusual; + } + break; + } + + default: { + handle_unusual: + if (tag == 0 || + ::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == + ::google::protobuf::internal::WireFormatLite::WIRETYPE_END_GROUP) { + goto success; + } + DO_(::google::protobuf::internal::WireFormatLite::SkipField(input, tag)); + break; + } + } + } +success: + // @@protoc_insertion_point(parse_success:pybullet_grpc.vec3) + return true; +failure: + // @@protoc_insertion_point(parse_failure:pybullet_grpc.vec3) + return false; +#undef DO_ +} + +void vec3::SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const { + // @@protoc_insertion_point(serialize_start:pybullet_grpc.vec3) + // double x = 1; + if (this->x() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(1, this->x(), output); + } + + // double y = 2; + if (this->y() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(2, this->y(), output); + } + + // double z = 3; + if (this->z() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(3, this->z(), output); + } + + // @@protoc_insertion_point(serialize_end:pybullet_grpc.vec3) +} + +::google::protobuf::uint8* vec3::InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const { + (void)deterministic; // Unused + // @@protoc_insertion_point(serialize_to_array_start:pybullet_grpc.vec3) + // double x = 1; + if (this->x() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(1, this->x(), target); + } + + // double y = 2; + if (this->y() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(2, this->y(), target); + } + + // double z = 3; + if (this->z() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(3, this->z(), target); + } + + // @@protoc_insertion_point(serialize_to_array_end:pybullet_grpc.vec3) + return target; +} + +size_t vec3::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:pybullet_grpc.vec3) + size_t total_size = 0; + + // double x = 1; + if (this->x() != 0) { + total_size += 1 + 8; + } + + // double y = 2; + if (this->y() != 0) { + total_size += 1 + 8; + } + + // double z = 3; + if (this->z() != 0) { + total_size += 1 + 8; + } + + int cached_size = ::google::protobuf::internal::ToCachedSize(total_size); + GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN(); + _cached_size_ = cached_size; + GOOGLE_SAFE_CONCURRENT_WRITES_END(); + return total_size; +} + +void vec3::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:pybullet_grpc.vec3) + GOOGLE_DCHECK_NE(&from, this); + const vec3* source = + ::google::protobuf::internal::DynamicCastToGenerated( + &from); + if (source == NULL) { + // @@protoc_insertion_point(generalized_merge_from_cast_fail:pybullet_grpc.vec3) + ::google::protobuf::internal::ReflectionOps::Merge(from, this); + } else { + // @@protoc_insertion_point(generalized_merge_from_cast_success:pybullet_grpc.vec3) + MergeFrom(*source); + } +} + +void vec3::MergeFrom(const vec3& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:pybullet_grpc.vec3) + GOOGLE_DCHECK_NE(&from, this); + _internal_metadata_.MergeFrom(from._internal_metadata_); + if (from.x() != 0) { + set_x(from.x()); + } + if (from.y() != 0) { + set_y(from.y()); + } + if (from.z() != 0) { + set_z(from.z()); + } +} + +void vec3::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:pybullet_grpc.vec3) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +void vec3::CopyFrom(const vec3& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:pybullet_grpc.vec3) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool vec3::IsInitialized() const { + return true; +} + +void vec3::Swap(vec3* other) { + if (other == this) return; + InternalSwap(other); +} +void vec3::InternalSwap(vec3* other) { + std::swap(x_, other->x_); + std::swap(y_, other->y_); + std::swap(z_, other->z_); + std::swap(_cached_size_, other->_cached_size_); +} + +::google::protobuf::Metadata vec3::GetMetadata() const { + protobuf_pybullet_2eproto::protobuf_AssignDescriptorsOnce(); + return protobuf_pybullet_2eproto::file_level_metadata[0]; +} + +#if PROTOBUF_INLINE_NOT_IN_HEADERS +// vec3 + +// double x = 1; +void vec3::clear_x() { + x_ = 0; +} +double vec3::x() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.vec3.x) + return x_; +} +void vec3::set_x(double value) { + + x_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.vec3.x) +} + +// double y = 2; +void vec3::clear_y() { + y_ = 0; +} +double vec3::y() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.vec3.y) + return y_; +} +void vec3::set_y(double value) { + + y_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.vec3.y) +} + +// double z = 3; +void vec3::clear_z() { + z_ = 0; +} +double vec3::z() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.vec3.z) + return z_; +} +void vec3::set_z(double value) { + + z_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.vec3.z) +} + +#endif // PROTOBUF_INLINE_NOT_IN_HEADERS + +// =================================================================== + +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const int quat4::kXFieldNumber; +const int quat4::kYFieldNumber; +const int quat4::kZFieldNumber; +const int quat4::kWFieldNumber; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 + +quat4::quat4() + : ::google::protobuf::Message(), _internal_metadata_(NULL) { + if (GOOGLE_PREDICT_TRUE(this != internal_default_instance())) { + protobuf_pybullet_2eproto::InitDefaults(); + } + SharedCtor(); + // @@protoc_insertion_point(constructor:pybullet_grpc.quat4) +} +quat4::quat4(const quat4& from) + : ::google::protobuf::Message(), + _internal_metadata_(NULL), + _cached_size_(0) { + _internal_metadata_.MergeFrom(from._internal_metadata_); + ::memcpy(&x_, &from.x_, + reinterpret_cast(&w_) - + reinterpret_cast(&x_) + sizeof(w_)); + // @@protoc_insertion_point(copy_constructor:pybullet_grpc.quat4) +} + +void quat4::SharedCtor() { + ::memset(&x_, 0, reinterpret_cast(&w_) - + reinterpret_cast(&x_) + sizeof(w_)); + _cached_size_ = 0; +} + +quat4::~quat4() { + // @@protoc_insertion_point(destructor:pybullet_grpc.quat4) + SharedDtor(); +} + +void quat4::SharedDtor() { +} + +void quat4::SetCachedSize(int size) const { + GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN(); + _cached_size_ = size; + GOOGLE_SAFE_CONCURRENT_WRITES_END(); +} +const ::google::protobuf::Descriptor* quat4::descriptor() { + protobuf_pybullet_2eproto::protobuf_AssignDescriptorsOnce(); + return protobuf_pybullet_2eproto::file_level_metadata[1].descriptor; +} + +const quat4& quat4::default_instance() { + protobuf_pybullet_2eproto::InitDefaults(); + return *internal_default_instance(); +} + +quat4* quat4::New(::google::protobuf::Arena* arena) const { + quat4* n = new quat4; + if (arena != NULL) { + arena->Own(n); + } + return n; +} + +void quat4::Clear() { +// @@protoc_insertion_point(message_clear_start:pybullet_grpc.quat4) + ::memset(&x_, 0, reinterpret_cast(&w_) - + reinterpret_cast(&x_) + sizeof(w_)); +} + +bool quat4::MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) { +#define DO_(EXPRESSION) if (!GOOGLE_PREDICT_TRUE(EXPRESSION)) goto failure + ::google::protobuf::uint32 tag; + // @@protoc_insertion_point(parse_start:pybullet_grpc.quat4) + for (;;) { + ::std::pair< ::google::protobuf::uint32, bool> p = input->ReadTagWithCutoffNoLastTag(127u); + tag = p.first; + if (!p.second) goto handle_unusual; + switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { + // double x = 1; + case 1: { + if (tag == 9u) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &x_))); + } else { + goto handle_unusual; + } + break; + } + + // double y = 2; + case 2: { + if (tag == 17u) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &y_))); + } else { + goto handle_unusual; + } + break; + } + + // double z = 3; + case 3: { + if (tag == 25u) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &z_))); + } else { + goto handle_unusual; + } + break; + } + + // double w = 4; + case 4: { + if (tag == 33u) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &w_))); + } else { + goto handle_unusual; + } + break; + } + + default: { + handle_unusual: + if (tag == 0 || + ::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == + ::google::protobuf::internal::WireFormatLite::WIRETYPE_END_GROUP) { + goto success; + } + DO_(::google::protobuf::internal::WireFormatLite::SkipField(input, tag)); + break; + } + } + } +success: + // @@protoc_insertion_point(parse_success:pybullet_grpc.quat4) + return true; +failure: + // @@protoc_insertion_point(parse_failure:pybullet_grpc.quat4) + return false; +#undef DO_ +} + +void quat4::SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const { + // @@protoc_insertion_point(serialize_start:pybullet_grpc.quat4) + // double x = 1; + if (this->x() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(1, this->x(), output); + } + + // double y = 2; + if (this->y() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(2, this->y(), output); + } + + // double z = 3; + if (this->z() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(3, this->z(), output); + } + + // double w = 4; + if (this->w() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(4, this->w(), output); + } + + // @@protoc_insertion_point(serialize_end:pybullet_grpc.quat4) +} + +::google::protobuf::uint8* quat4::InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const { + (void)deterministic; // Unused + // @@protoc_insertion_point(serialize_to_array_start:pybullet_grpc.quat4) + // double x = 1; + if (this->x() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(1, this->x(), target); + } + + // double y = 2; + if (this->y() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(2, this->y(), target); + } + + // double z = 3; + if (this->z() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(3, this->z(), target); + } + + // double w = 4; + if (this->w() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(4, this->w(), target); + } + + // @@protoc_insertion_point(serialize_to_array_end:pybullet_grpc.quat4) + return target; +} + +size_t quat4::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:pybullet_grpc.quat4) + size_t total_size = 0; + + // double x = 1; + if (this->x() != 0) { + total_size += 1 + 8; + } + + // double y = 2; + if (this->y() != 0) { + total_size += 1 + 8; + } + + // double z = 3; + if (this->z() != 0) { + total_size += 1 + 8; + } + + // double w = 4; + if (this->w() != 0) { + total_size += 1 + 8; + } + + int cached_size = ::google::protobuf::internal::ToCachedSize(total_size); + GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN(); + _cached_size_ = cached_size; + GOOGLE_SAFE_CONCURRENT_WRITES_END(); + return total_size; +} + +void quat4::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:pybullet_grpc.quat4) + GOOGLE_DCHECK_NE(&from, this); + const quat4* source = + ::google::protobuf::internal::DynamicCastToGenerated( + &from); + if (source == NULL) { + // @@protoc_insertion_point(generalized_merge_from_cast_fail:pybullet_grpc.quat4) + ::google::protobuf::internal::ReflectionOps::Merge(from, this); + } else { + // @@protoc_insertion_point(generalized_merge_from_cast_success:pybullet_grpc.quat4) + MergeFrom(*source); + } +} + +void quat4::MergeFrom(const quat4& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:pybullet_grpc.quat4) + GOOGLE_DCHECK_NE(&from, this); + _internal_metadata_.MergeFrom(from._internal_metadata_); + if (from.x() != 0) { + set_x(from.x()); + } + if (from.y() != 0) { + set_y(from.y()); + } + if (from.z() != 0) { + set_z(from.z()); + } + if (from.w() != 0) { + set_w(from.w()); + } +} + +void quat4::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:pybullet_grpc.quat4) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +void quat4::CopyFrom(const quat4& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:pybullet_grpc.quat4) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool quat4::IsInitialized() const { + return true; +} + +void quat4::Swap(quat4* other) { + if (other == this) return; + InternalSwap(other); +} +void quat4::InternalSwap(quat4* other) { + std::swap(x_, other->x_); + std::swap(y_, other->y_); + std::swap(z_, other->z_); + std::swap(w_, other->w_); + std::swap(_cached_size_, other->_cached_size_); +} + +::google::protobuf::Metadata quat4::GetMetadata() const { + protobuf_pybullet_2eproto::protobuf_AssignDescriptorsOnce(); + return protobuf_pybullet_2eproto::file_level_metadata[1]; +} + +#if PROTOBUF_INLINE_NOT_IN_HEADERS +// quat4 + +// double x = 1; +void quat4::clear_x() { + x_ = 0; +} +double quat4::x() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.quat4.x) + return x_; +} +void quat4::set_x(double value) { + + x_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.quat4.x) +} + +// double y = 2; +void quat4::clear_y() { + y_ = 0; +} +double quat4::y() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.quat4.y) + return y_; +} +void quat4::set_y(double value) { + + y_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.quat4.y) +} + +// double z = 3; +void quat4::clear_z() { + z_ = 0; +} +double quat4::z() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.quat4.z) + return z_; +} +void quat4::set_z(double value) { + + z_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.quat4.z) +} + +// double w = 4; +void quat4::clear_w() { + w_ = 0; +} +double quat4::w() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.quat4.w) + return w_; +} +void quat4::set_w(double value) { + + w_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.quat4.w) +} + +#endif // PROTOBUF_INLINE_NOT_IN_HEADERS + +// =================================================================== + +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const int TerminateServerCommand::kExitReasonFieldNumber; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 + +TerminateServerCommand::TerminateServerCommand() + : ::google::protobuf::Message(), _internal_metadata_(NULL) { + if (GOOGLE_PREDICT_TRUE(this != internal_default_instance())) { + protobuf_pybullet_2eproto::InitDefaults(); + } + SharedCtor(); + // @@protoc_insertion_point(constructor:pybullet_grpc.TerminateServerCommand) +} +TerminateServerCommand::TerminateServerCommand(const TerminateServerCommand& from) + : ::google::protobuf::Message(), + _internal_metadata_(NULL), + _cached_size_(0) { + _internal_metadata_.MergeFrom(from._internal_metadata_); + exitreason_.UnsafeSetDefault(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); + if (from.exitreason().size() > 0) { + exitreason_.AssignWithDefault(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), from.exitreason_); + } + // @@protoc_insertion_point(copy_constructor:pybullet_grpc.TerminateServerCommand) +} + +void TerminateServerCommand::SharedCtor() { + exitreason_.UnsafeSetDefault(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); + _cached_size_ = 0; +} + +TerminateServerCommand::~TerminateServerCommand() { + // @@protoc_insertion_point(destructor:pybullet_grpc.TerminateServerCommand) + SharedDtor(); +} + +void TerminateServerCommand::SharedDtor() { + exitreason_.DestroyNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); +} + +void TerminateServerCommand::SetCachedSize(int size) const { + GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN(); + _cached_size_ = size; + GOOGLE_SAFE_CONCURRENT_WRITES_END(); +} +const ::google::protobuf::Descriptor* TerminateServerCommand::descriptor() { + protobuf_pybullet_2eproto::protobuf_AssignDescriptorsOnce(); + return protobuf_pybullet_2eproto::file_level_metadata[2].descriptor; +} + +const TerminateServerCommand& TerminateServerCommand::default_instance() { + protobuf_pybullet_2eproto::InitDefaults(); + return *internal_default_instance(); +} + +TerminateServerCommand* TerminateServerCommand::New(::google::protobuf::Arena* arena) const { + TerminateServerCommand* n = new TerminateServerCommand; + if (arena != NULL) { + arena->Own(n); + } + return n; +} + +void TerminateServerCommand::Clear() { +// @@protoc_insertion_point(message_clear_start:pybullet_grpc.TerminateServerCommand) + exitreason_.ClearToEmptyNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); +} + +bool TerminateServerCommand::MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) { +#define DO_(EXPRESSION) if (!GOOGLE_PREDICT_TRUE(EXPRESSION)) goto failure + ::google::protobuf::uint32 tag; + // @@protoc_insertion_point(parse_start:pybullet_grpc.TerminateServerCommand) + for (;;) { + ::std::pair< ::google::protobuf::uint32, bool> p = input->ReadTagWithCutoffNoLastTag(127u); + tag = p.first; + if (!p.second) goto handle_unusual; + switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { + // string exitReason = 1; + case 1: { + if (tag == 10u) { + DO_(::google::protobuf::internal::WireFormatLite::ReadString( + input, this->mutable_exitreason())); + DO_(::google::protobuf::internal::WireFormatLite::VerifyUtf8String( + this->exitreason().data(), this->exitreason().length(), + ::google::protobuf::internal::WireFormatLite::PARSE, + "pybullet_grpc.TerminateServerCommand.exitReason")); + } else { + goto handle_unusual; + } + break; + } + + default: { + handle_unusual: + if (tag == 0 || + ::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == + ::google::protobuf::internal::WireFormatLite::WIRETYPE_END_GROUP) { + goto success; + } + DO_(::google::protobuf::internal::WireFormatLite::SkipField(input, tag)); + break; + } + } + } +success: + // @@protoc_insertion_point(parse_success:pybullet_grpc.TerminateServerCommand) + return true; +failure: + // @@protoc_insertion_point(parse_failure:pybullet_grpc.TerminateServerCommand) + return false; +#undef DO_ +} + +void TerminateServerCommand::SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const { + // @@protoc_insertion_point(serialize_start:pybullet_grpc.TerminateServerCommand) + // string exitReason = 1; + if (this->exitreason().size() > 0) { + ::google::protobuf::internal::WireFormatLite::VerifyUtf8String( + this->exitreason().data(), this->exitreason().length(), + ::google::protobuf::internal::WireFormatLite::SERIALIZE, + "pybullet_grpc.TerminateServerCommand.exitReason"); + ::google::protobuf::internal::WireFormatLite::WriteStringMaybeAliased( + 1, this->exitreason(), output); + } + + // @@protoc_insertion_point(serialize_end:pybullet_grpc.TerminateServerCommand) +} + +::google::protobuf::uint8* TerminateServerCommand::InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const { + (void)deterministic; // Unused + // @@protoc_insertion_point(serialize_to_array_start:pybullet_grpc.TerminateServerCommand) + // string exitReason = 1; + if (this->exitreason().size() > 0) { + ::google::protobuf::internal::WireFormatLite::VerifyUtf8String( + this->exitreason().data(), this->exitreason().length(), + ::google::protobuf::internal::WireFormatLite::SERIALIZE, + "pybullet_grpc.TerminateServerCommand.exitReason"); + target = + ::google::protobuf::internal::WireFormatLite::WriteStringToArray( + 1, this->exitreason(), target); + } + + // @@protoc_insertion_point(serialize_to_array_end:pybullet_grpc.TerminateServerCommand) + return target; +} + +size_t TerminateServerCommand::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:pybullet_grpc.TerminateServerCommand) + size_t total_size = 0; + + // string exitReason = 1; + if (this->exitreason().size() > 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::StringSize( + this->exitreason()); + } + + int cached_size = ::google::protobuf::internal::ToCachedSize(total_size); + GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN(); + _cached_size_ = cached_size; + GOOGLE_SAFE_CONCURRENT_WRITES_END(); + return total_size; +} + +void TerminateServerCommand::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:pybullet_grpc.TerminateServerCommand) + GOOGLE_DCHECK_NE(&from, this); + const TerminateServerCommand* source = + ::google::protobuf::internal::DynamicCastToGenerated( + &from); + if (source == NULL) { + // @@protoc_insertion_point(generalized_merge_from_cast_fail:pybullet_grpc.TerminateServerCommand) + ::google::protobuf::internal::ReflectionOps::Merge(from, this); + } else { + // @@protoc_insertion_point(generalized_merge_from_cast_success:pybullet_grpc.TerminateServerCommand) + MergeFrom(*source); + } +} + +void TerminateServerCommand::MergeFrom(const TerminateServerCommand& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:pybullet_grpc.TerminateServerCommand) + GOOGLE_DCHECK_NE(&from, this); + _internal_metadata_.MergeFrom(from._internal_metadata_); + if (from.exitreason().size() > 0) { + + exitreason_.AssignWithDefault(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), from.exitreason_); + } +} + +void TerminateServerCommand::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:pybullet_grpc.TerminateServerCommand) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +void TerminateServerCommand::CopyFrom(const TerminateServerCommand& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:pybullet_grpc.TerminateServerCommand) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool TerminateServerCommand::IsInitialized() const { + return true; +} + +void TerminateServerCommand::Swap(TerminateServerCommand* other) { + if (other == this) return; + InternalSwap(other); +} +void TerminateServerCommand::InternalSwap(TerminateServerCommand* other) { + exitreason_.Swap(&other->exitreason_); + std::swap(_cached_size_, other->_cached_size_); +} + +::google::protobuf::Metadata TerminateServerCommand::GetMetadata() const { + protobuf_pybullet_2eproto::protobuf_AssignDescriptorsOnce(); + return protobuf_pybullet_2eproto::file_level_metadata[2]; +} + +#if PROTOBUF_INLINE_NOT_IN_HEADERS +// TerminateServerCommand + +// string exitReason = 1; +void TerminateServerCommand::clear_exitreason() { + exitreason_.ClearToEmptyNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); +} +const ::std::string& TerminateServerCommand::exitreason() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.TerminateServerCommand.exitReason) + return exitreason_.GetNoArena(); +} +void TerminateServerCommand::set_exitreason(const ::std::string& value) { + + exitreason_.SetNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), value); + // @@protoc_insertion_point(field_set:pybullet_grpc.TerminateServerCommand.exitReason) +} +#if LANG_CXX11 +void TerminateServerCommand::set_exitreason(::std::string&& value) { + + exitreason_.SetNoArena( + &::google::protobuf::internal::GetEmptyStringAlreadyInited(), std::move(value)); + // @@protoc_insertion_point(field_set_rvalue:pybullet_grpc.TerminateServerCommand.exitReason) +} +#endif +void TerminateServerCommand::set_exitreason(const char* value) { + + exitreason_.SetNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), ::std::string(value)); + // @@protoc_insertion_point(field_set_char:pybullet_grpc.TerminateServerCommand.exitReason) +} +void TerminateServerCommand::set_exitreason(const char* value, size_t size) { + + exitreason_.SetNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), + ::std::string(reinterpret_cast(value), size)); + // @@protoc_insertion_point(field_set_pointer:pybullet_grpc.TerminateServerCommand.exitReason) +} +::std::string* TerminateServerCommand::mutable_exitreason() { + + // @@protoc_insertion_point(field_mutable:pybullet_grpc.TerminateServerCommand.exitReason) + return exitreason_.MutableNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); +} +::std::string* TerminateServerCommand::release_exitreason() { + // @@protoc_insertion_point(field_release:pybullet_grpc.TerminateServerCommand.exitReason) + + return exitreason_.ReleaseNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); +} +void TerminateServerCommand::set_allocated_exitreason(::std::string* exitreason) { + if (exitreason != NULL) { + + } else { + + } + exitreason_.SetAllocatedNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), exitreason); + // @@protoc_insertion_point(field_set_allocated:pybullet_grpc.TerminateServerCommand.exitReason) +} + +#endif // PROTOBUF_INLINE_NOT_IN_HEADERS + +// =================================================================== + +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 + +StepSimulationCommand::StepSimulationCommand() + : ::google::protobuf::Message(), _internal_metadata_(NULL) { + if (GOOGLE_PREDICT_TRUE(this != internal_default_instance())) { + protobuf_pybullet_2eproto::InitDefaults(); + } + SharedCtor(); + // @@protoc_insertion_point(constructor:pybullet_grpc.StepSimulationCommand) +} +StepSimulationCommand::StepSimulationCommand(const StepSimulationCommand& from) + : ::google::protobuf::Message(), + _internal_metadata_(NULL), + _cached_size_(0) { + _internal_metadata_.MergeFrom(from._internal_metadata_); + // @@protoc_insertion_point(copy_constructor:pybullet_grpc.StepSimulationCommand) +} + +void StepSimulationCommand::SharedCtor() { + _cached_size_ = 0; +} + +StepSimulationCommand::~StepSimulationCommand() { + // @@protoc_insertion_point(destructor:pybullet_grpc.StepSimulationCommand) + SharedDtor(); +} + +void StepSimulationCommand::SharedDtor() { +} + +void StepSimulationCommand::SetCachedSize(int size) const { + GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN(); + _cached_size_ = size; + GOOGLE_SAFE_CONCURRENT_WRITES_END(); +} +const ::google::protobuf::Descriptor* StepSimulationCommand::descriptor() { + protobuf_pybullet_2eproto::protobuf_AssignDescriptorsOnce(); + return protobuf_pybullet_2eproto::file_level_metadata[3].descriptor; +} + +const StepSimulationCommand& StepSimulationCommand::default_instance() { + protobuf_pybullet_2eproto::InitDefaults(); + return *internal_default_instance(); +} + +StepSimulationCommand* StepSimulationCommand::New(::google::protobuf::Arena* arena) const { + StepSimulationCommand* n = new StepSimulationCommand; + if (arena != NULL) { + arena->Own(n); + } + return n; +} + +void StepSimulationCommand::Clear() { +// @@protoc_insertion_point(message_clear_start:pybullet_grpc.StepSimulationCommand) +} + +bool StepSimulationCommand::MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) { +#define DO_(EXPRESSION) if (!GOOGLE_PREDICT_TRUE(EXPRESSION)) goto failure + ::google::protobuf::uint32 tag; + // @@protoc_insertion_point(parse_start:pybullet_grpc.StepSimulationCommand) + for (;;) { + ::std::pair< ::google::protobuf::uint32, bool> p = input->ReadTagWithCutoffNoLastTag(127u); + tag = p.first; + if (!p.second) goto handle_unusual; + handle_unusual: + if (tag == 0 || + ::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == + ::google::protobuf::internal::WireFormatLite::WIRETYPE_END_GROUP) { + goto success; + } + DO_(::google::protobuf::internal::WireFormatLite::SkipField(input, tag)); + } +success: + // @@protoc_insertion_point(parse_success:pybullet_grpc.StepSimulationCommand) + return true; +failure: + // @@protoc_insertion_point(parse_failure:pybullet_grpc.StepSimulationCommand) + return false; +#undef DO_ +} + +void StepSimulationCommand::SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const { + // @@protoc_insertion_point(serialize_start:pybullet_grpc.StepSimulationCommand) + // @@protoc_insertion_point(serialize_end:pybullet_grpc.StepSimulationCommand) +} + +::google::protobuf::uint8* StepSimulationCommand::InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const { + (void)deterministic; // Unused + // @@protoc_insertion_point(serialize_to_array_start:pybullet_grpc.StepSimulationCommand) + // @@protoc_insertion_point(serialize_to_array_end:pybullet_grpc.StepSimulationCommand) + return target; +} + +size_t StepSimulationCommand::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:pybullet_grpc.StepSimulationCommand) + size_t total_size = 0; + + int cached_size = ::google::protobuf::internal::ToCachedSize(total_size); + GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN(); + _cached_size_ = cached_size; + GOOGLE_SAFE_CONCURRENT_WRITES_END(); + return total_size; +} + +void StepSimulationCommand::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:pybullet_grpc.StepSimulationCommand) + GOOGLE_DCHECK_NE(&from, this); + const StepSimulationCommand* source = + ::google::protobuf::internal::DynamicCastToGenerated( + &from); + if (source == NULL) { + // @@protoc_insertion_point(generalized_merge_from_cast_fail:pybullet_grpc.StepSimulationCommand) + ::google::protobuf::internal::ReflectionOps::Merge(from, this); + } else { + // @@protoc_insertion_point(generalized_merge_from_cast_success:pybullet_grpc.StepSimulationCommand) + MergeFrom(*source); + } +} + +void StepSimulationCommand::MergeFrom(const StepSimulationCommand& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:pybullet_grpc.StepSimulationCommand) + GOOGLE_DCHECK_NE(&from, this); + _internal_metadata_.MergeFrom(from._internal_metadata_); +} + +void StepSimulationCommand::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:pybullet_grpc.StepSimulationCommand) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +void StepSimulationCommand::CopyFrom(const StepSimulationCommand& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:pybullet_grpc.StepSimulationCommand) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool StepSimulationCommand::IsInitialized() const { + return true; +} + +void StepSimulationCommand::Swap(StepSimulationCommand* other) { + if (other == this) return; + InternalSwap(other); +} +void StepSimulationCommand::InternalSwap(StepSimulationCommand* other) { + std::swap(_cached_size_, other->_cached_size_); +} + +::google::protobuf::Metadata StepSimulationCommand::GetMetadata() const { + protobuf_pybullet_2eproto::protobuf_AssignDescriptorsOnce(); + return protobuf_pybullet_2eproto::file_level_metadata[3]; +} + +#if PROTOBUF_INLINE_NOT_IN_HEADERS +// StepSimulationCommand + +#endif // PROTOBUF_INLINE_NOT_IN_HEADERS + +// =================================================================== + +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const int LoadUrdfCommand::kUrdfFileNameFieldNumber; +const int LoadUrdfCommand::kInitialPositionFieldNumber; +const int LoadUrdfCommand::kInitialOrientationFieldNumber; +const int LoadUrdfCommand::kUseMultiBodyFieldNumber; +const int LoadUrdfCommand::kUseFixedBaseFieldNumber; +const int LoadUrdfCommand::kUrdfFlagsFieldNumber; +const int LoadUrdfCommand::kGlobalScalingFieldNumber; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 + +LoadUrdfCommand::LoadUrdfCommand() + : ::google::protobuf::Message(), _internal_metadata_(NULL) { + if (GOOGLE_PREDICT_TRUE(this != internal_default_instance())) { + protobuf_pybullet_2eproto::InitDefaults(); + } + SharedCtor(); + // @@protoc_insertion_point(constructor:pybullet_grpc.LoadUrdfCommand) +} +LoadUrdfCommand::LoadUrdfCommand(const LoadUrdfCommand& from) + : ::google::protobuf::Message(), + _internal_metadata_(NULL), + _cached_size_(0) { + _internal_metadata_.MergeFrom(from._internal_metadata_); + urdffilename_.UnsafeSetDefault(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); + if (from.urdffilename().size() > 0) { + urdffilename_.AssignWithDefault(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), from.urdffilename_); + } + if (from.has_initialposition()) { + initialposition_ = new ::pybullet_grpc::vec3(*from.initialposition_); + } else { + initialposition_ = NULL; + } + if (from.has_initialorientation()) { + initialorientation_ = new ::pybullet_grpc::quat4(*from.initialorientation_); + } else { + initialorientation_ = NULL; + } + urdfflags_ = from.urdfflags_; + clear_has_hasUseMultiBody(); + switch (from.hasUseMultiBody_case()) { + case kUseMultiBody: { + set_usemultibody(from.usemultibody()); + break; + } + case HASUSEMULTIBODY_NOT_SET: { + break; + } + } + clear_has_hasUseFixedBase(); + switch (from.hasUseFixedBase_case()) { + case kUseFixedBase: { + set_usefixedbase(from.usefixedbase()); + break; + } + case HASUSEFIXEDBASE_NOT_SET: { + break; + } + } + clear_has_hasGlobalScaling(); + switch (from.hasGlobalScaling_case()) { + case kGlobalScaling: { + set_globalscaling(from.globalscaling()); + break; + } + case HASGLOBALSCALING_NOT_SET: { + break; + } + } + // @@protoc_insertion_point(copy_constructor:pybullet_grpc.LoadUrdfCommand) +} + +void LoadUrdfCommand::SharedCtor() { + urdffilename_.UnsafeSetDefault(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); + ::memset(&initialposition_, 0, reinterpret_cast(&urdfflags_) - + reinterpret_cast(&initialposition_) + sizeof(urdfflags_)); + clear_has_hasUseMultiBody(); + clear_has_hasUseFixedBase(); + clear_has_hasGlobalScaling(); + _cached_size_ = 0; +} + +LoadUrdfCommand::~LoadUrdfCommand() { + // @@protoc_insertion_point(destructor:pybullet_grpc.LoadUrdfCommand) + SharedDtor(); +} + +void LoadUrdfCommand::SharedDtor() { + urdffilename_.DestroyNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); + if (this != internal_default_instance()) { + delete initialposition_; + } + if (this != internal_default_instance()) { + delete initialorientation_; + } + if (has_hasUseMultiBody()) { + clear_hasUseMultiBody(); + } + if (has_hasUseFixedBase()) { + clear_hasUseFixedBase(); + } + if (has_hasGlobalScaling()) { + clear_hasGlobalScaling(); + } +} + +void LoadUrdfCommand::SetCachedSize(int size) const { + GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN(); + _cached_size_ = size; + GOOGLE_SAFE_CONCURRENT_WRITES_END(); +} +const ::google::protobuf::Descriptor* LoadUrdfCommand::descriptor() { + protobuf_pybullet_2eproto::protobuf_AssignDescriptorsOnce(); + return protobuf_pybullet_2eproto::file_level_metadata[4].descriptor; +} + +const LoadUrdfCommand& LoadUrdfCommand::default_instance() { + protobuf_pybullet_2eproto::InitDefaults(); + return *internal_default_instance(); +} + +LoadUrdfCommand* LoadUrdfCommand::New(::google::protobuf::Arena* arena) const { + LoadUrdfCommand* n = new LoadUrdfCommand; + if (arena != NULL) { + arena->Own(n); + } + return n; +} + +void LoadUrdfCommand::clear_hasUseMultiBody() { +// @@protoc_insertion_point(one_of_clear_start:pybullet_grpc.LoadUrdfCommand) + switch (hasUseMultiBody_case()) { + case kUseMultiBody: { + // No need to clear + break; + } + case HASUSEMULTIBODY_NOT_SET: { + break; + } + } + _oneof_case_[0] = HASUSEMULTIBODY_NOT_SET; +} + +void LoadUrdfCommand::clear_hasUseFixedBase() { +// @@protoc_insertion_point(one_of_clear_start:pybullet_grpc.LoadUrdfCommand) + switch (hasUseFixedBase_case()) { + case kUseFixedBase: { + // No need to clear + break; + } + case HASUSEFIXEDBASE_NOT_SET: { + break; + } + } + _oneof_case_[1] = HASUSEFIXEDBASE_NOT_SET; +} + +void LoadUrdfCommand::clear_hasGlobalScaling() { +// @@protoc_insertion_point(one_of_clear_start:pybullet_grpc.LoadUrdfCommand) + switch (hasGlobalScaling_case()) { + case kGlobalScaling: { + // No need to clear + break; + } + case HASGLOBALSCALING_NOT_SET: { + break; + } + } + _oneof_case_[2] = HASGLOBALSCALING_NOT_SET; +} + + +void LoadUrdfCommand::Clear() { +// @@protoc_insertion_point(message_clear_start:pybullet_grpc.LoadUrdfCommand) + urdffilename_.ClearToEmptyNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); + if (GetArenaNoVirtual() == NULL && initialposition_ != NULL) { + delete initialposition_; + } + initialposition_ = NULL; + if (GetArenaNoVirtual() == NULL && initialorientation_ != NULL) { + delete initialorientation_; + } + initialorientation_ = NULL; + urdfflags_ = 0; + clear_hasUseMultiBody(); + clear_hasUseFixedBase(); + clear_hasGlobalScaling(); +} + +bool LoadUrdfCommand::MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) { +#define DO_(EXPRESSION) if (!GOOGLE_PREDICT_TRUE(EXPRESSION)) goto failure + ::google::protobuf::uint32 tag; + // @@protoc_insertion_point(parse_start:pybullet_grpc.LoadUrdfCommand) + for (;;) { + ::std::pair< ::google::protobuf::uint32, bool> p = input->ReadTagWithCutoffNoLastTag(127u); + tag = p.first; + if (!p.second) goto handle_unusual; + switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { + // string urdfFileName = 1; + case 1: { + if (tag == 10u) { + DO_(::google::protobuf::internal::WireFormatLite::ReadString( + input, this->mutable_urdffilename())); + DO_(::google::protobuf::internal::WireFormatLite::VerifyUtf8String( + this->urdffilename().data(), this->urdffilename().length(), + ::google::protobuf::internal::WireFormatLite::PARSE, + "pybullet_grpc.LoadUrdfCommand.urdfFileName")); + } else { + goto handle_unusual; + } + break; + } + + // .pybullet_grpc.vec3 initialPosition = 2; + case 2: { + if (tag == 18u) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessageNoVirtual( + input, mutable_initialposition())); + } else { + goto handle_unusual; + } + break; + } + + // .pybullet_grpc.quat4 initialOrientation = 3; + case 3: { + if (tag == 26u) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessageNoVirtual( + input, mutable_initialorientation())); + } else { + goto handle_unusual; + } + break; + } + + // int32 useMultiBody = 4; + case 4: { + if (tag == 32u) { + clear_hasUseMultiBody(); + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>( + input, &hasUseMultiBody_.usemultibody_))); + set_has_usemultibody(); + } else { + goto handle_unusual; + } + break; + } + + // bool useFixedBase = 5; + case 5: { + if (tag == 40u) { + clear_hasUseFixedBase(); + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + bool, ::google::protobuf::internal::WireFormatLite::TYPE_BOOL>( + input, &hasUseFixedBase_.usefixedbase_))); + set_has_usefixedbase(); + } else { + goto handle_unusual; + } + break; + } + + // int32 urdfFlags = 6; + case 6: { + if (tag == 48u) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>( + input, &urdfflags_))); + } else { + goto handle_unusual; + } + break; + } + + // double globalScaling = 7; + case 7: { + if (tag == 57u) { + clear_hasGlobalScaling(); + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &hasGlobalScaling_.globalscaling_))); + set_has_globalscaling(); + } else { + goto handle_unusual; + } + break; + } + + default: { + handle_unusual: + if (tag == 0 || + ::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == + ::google::protobuf::internal::WireFormatLite::WIRETYPE_END_GROUP) { + goto success; + } + DO_(::google::protobuf::internal::WireFormatLite::SkipField(input, tag)); + break; + } + } + } +success: + // @@protoc_insertion_point(parse_success:pybullet_grpc.LoadUrdfCommand) + return true; +failure: + // @@protoc_insertion_point(parse_failure:pybullet_grpc.LoadUrdfCommand) + return false; +#undef DO_ +} + +void LoadUrdfCommand::SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const { + // @@protoc_insertion_point(serialize_start:pybullet_grpc.LoadUrdfCommand) + // string urdfFileName = 1; + if (this->urdffilename().size() > 0) { + ::google::protobuf::internal::WireFormatLite::VerifyUtf8String( + this->urdffilename().data(), this->urdffilename().length(), + ::google::protobuf::internal::WireFormatLite::SERIALIZE, + "pybullet_grpc.LoadUrdfCommand.urdfFileName"); + ::google::protobuf::internal::WireFormatLite::WriteStringMaybeAliased( + 1, this->urdffilename(), output); + } + + // .pybullet_grpc.vec3 initialPosition = 2; + if (this->has_initialposition()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 2, *this->initialposition_, output); + } + + // .pybullet_grpc.quat4 initialOrientation = 3; + if (this->has_initialorientation()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 3, *this->initialorientation_, output); + } + + // int32 useMultiBody = 4; + if (has_usemultibody()) { + ::google::protobuf::internal::WireFormatLite::WriteInt32(4, this->usemultibody(), output); + } + + // bool useFixedBase = 5; + if (has_usefixedbase()) { + ::google::protobuf::internal::WireFormatLite::WriteBool(5, this->usefixedbase(), output); + } + + // int32 urdfFlags = 6; + if (this->urdfflags() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteInt32(6, this->urdfflags(), output); + } + + // double globalScaling = 7; + if (has_globalscaling()) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(7, this->globalscaling(), output); + } + + // @@protoc_insertion_point(serialize_end:pybullet_grpc.LoadUrdfCommand) +} + +::google::protobuf::uint8* LoadUrdfCommand::InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const { + (void)deterministic; // Unused + // @@protoc_insertion_point(serialize_to_array_start:pybullet_grpc.LoadUrdfCommand) + // string urdfFileName = 1; + if (this->urdffilename().size() > 0) { + ::google::protobuf::internal::WireFormatLite::VerifyUtf8String( + this->urdffilename().data(), this->urdffilename().length(), + ::google::protobuf::internal::WireFormatLite::SERIALIZE, + "pybullet_grpc.LoadUrdfCommand.urdfFileName"); + target = + ::google::protobuf::internal::WireFormatLite::WriteStringToArray( + 1, this->urdffilename(), target); + } + + // .pybullet_grpc.vec3 initialPosition = 2; + if (this->has_initialposition()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageNoVirtualToArray( + 2, *this->initialposition_, false, target); + } + + // .pybullet_grpc.quat4 initialOrientation = 3; + if (this->has_initialorientation()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageNoVirtualToArray( + 3, *this->initialorientation_, false, target); + } + + // int32 useMultiBody = 4; + if (has_usemultibody()) { + target = ::google::protobuf::internal::WireFormatLite::WriteInt32ToArray(4, this->usemultibody(), target); + } + + // bool useFixedBase = 5; + if (has_usefixedbase()) { + target = ::google::protobuf::internal::WireFormatLite::WriteBoolToArray(5, this->usefixedbase(), target); + } + + // int32 urdfFlags = 6; + if (this->urdfflags() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteInt32ToArray(6, this->urdfflags(), target); + } + + // double globalScaling = 7; + if (has_globalscaling()) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(7, this->globalscaling(), target); + } + + // @@protoc_insertion_point(serialize_to_array_end:pybullet_grpc.LoadUrdfCommand) + return target; +} + +size_t LoadUrdfCommand::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:pybullet_grpc.LoadUrdfCommand) + size_t total_size = 0; + + // string urdfFileName = 1; + if (this->urdffilename().size() > 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::StringSize( + this->urdffilename()); + } + + // .pybullet_grpc.vec3 initialPosition = 2; + if (this->has_initialposition()) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSizeNoVirtual( + *this->initialposition_); + } + + // .pybullet_grpc.quat4 initialOrientation = 3; + if (this->has_initialorientation()) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSizeNoVirtual( + *this->initialorientation_); + } + + // int32 urdfFlags = 6; + if (this->urdfflags() != 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::Int32Size( + this->urdfflags()); + } + + switch (hasUseMultiBody_case()) { + // int32 useMultiBody = 4; + case kUseMultiBody: { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::Int32Size( + this->usemultibody()); + break; + } + case HASUSEMULTIBODY_NOT_SET: { + break; + } + } + switch (hasUseFixedBase_case()) { + // bool useFixedBase = 5; + case kUseFixedBase: { + total_size += 1 + 1; + break; + } + case HASUSEFIXEDBASE_NOT_SET: { + break; + } + } + switch (hasGlobalScaling_case()) { + // double globalScaling = 7; + case kGlobalScaling: { + total_size += 1 + 8; + break; + } + case HASGLOBALSCALING_NOT_SET: { + break; + } + } + int cached_size = ::google::protobuf::internal::ToCachedSize(total_size); + GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN(); + _cached_size_ = cached_size; + GOOGLE_SAFE_CONCURRENT_WRITES_END(); + return total_size; +} + +void LoadUrdfCommand::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:pybullet_grpc.LoadUrdfCommand) + GOOGLE_DCHECK_NE(&from, this); + const LoadUrdfCommand* source = + ::google::protobuf::internal::DynamicCastToGenerated( + &from); + if (source == NULL) { + // @@protoc_insertion_point(generalized_merge_from_cast_fail:pybullet_grpc.LoadUrdfCommand) + ::google::protobuf::internal::ReflectionOps::Merge(from, this); + } else { + // @@protoc_insertion_point(generalized_merge_from_cast_success:pybullet_grpc.LoadUrdfCommand) + MergeFrom(*source); + } +} + +void LoadUrdfCommand::MergeFrom(const LoadUrdfCommand& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:pybullet_grpc.LoadUrdfCommand) + GOOGLE_DCHECK_NE(&from, this); + _internal_metadata_.MergeFrom(from._internal_metadata_); + if (from.urdffilename().size() > 0) { + + urdffilename_.AssignWithDefault(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), from.urdffilename_); + } + if (from.has_initialposition()) { + mutable_initialposition()->::pybullet_grpc::vec3::MergeFrom(from.initialposition()); + } + if (from.has_initialorientation()) { + mutable_initialorientation()->::pybullet_grpc::quat4::MergeFrom(from.initialorientation()); + } + if (from.urdfflags() != 0) { + set_urdfflags(from.urdfflags()); + } + switch (from.hasUseMultiBody_case()) { + case kUseMultiBody: { + set_usemultibody(from.usemultibody()); + break; + } + case HASUSEMULTIBODY_NOT_SET: { + break; + } + } + switch (from.hasUseFixedBase_case()) { + case kUseFixedBase: { + set_usefixedbase(from.usefixedbase()); + break; + } + case HASUSEFIXEDBASE_NOT_SET: { + break; + } + } + switch (from.hasGlobalScaling_case()) { + case kGlobalScaling: { + set_globalscaling(from.globalscaling()); + break; + } + case HASGLOBALSCALING_NOT_SET: { + break; + } + } +} + +void LoadUrdfCommand::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:pybullet_grpc.LoadUrdfCommand) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +void LoadUrdfCommand::CopyFrom(const LoadUrdfCommand& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:pybullet_grpc.LoadUrdfCommand) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool LoadUrdfCommand::IsInitialized() const { + return true; +} + +void LoadUrdfCommand::Swap(LoadUrdfCommand* other) { + if (other == this) return; + InternalSwap(other); +} +void LoadUrdfCommand::InternalSwap(LoadUrdfCommand* other) { + urdffilename_.Swap(&other->urdffilename_); + std::swap(initialposition_, other->initialposition_); + std::swap(initialorientation_, other->initialorientation_); + std::swap(urdfflags_, other->urdfflags_); + std::swap(hasUseMultiBody_, other->hasUseMultiBody_); + std::swap(_oneof_case_[0], other->_oneof_case_[0]); + std::swap(hasUseFixedBase_, other->hasUseFixedBase_); + std::swap(_oneof_case_[1], other->_oneof_case_[1]); + std::swap(hasGlobalScaling_, other->hasGlobalScaling_); + std::swap(_oneof_case_[2], other->_oneof_case_[2]); + std::swap(_cached_size_, other->_cached_size_); +} + +::google::protobuf::Metadata LoadUrdfCommand::GetMetadata() const { + protobuf_pybullet_2eproto::protobuf_AssignDescriptorsOnce(); + return protobuf_pybullet_2eproto::file_level_metadata[4]; +} + +#if PROTOBUF_INLINE_NOT_IN_HEADERS +// LoadUrdfCommand + +// string urdfFileName = 1; +void LoadUrdfCommand::clear_urdffilename() { + urdffilename_.ClearToEmptyNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); +} +const ::std::string& LoadUrdfCommand::urdffilename() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.LoadUrdfCommand.urdfFileName) + return urdffilename_.GetNoArena(); +} +void LoadUrdfCommand::set_urdffilename(const ::std::string& value) { + + urdffilename_.SetNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), value); + // @@protoc_insertion_point(field_set:pybullet_grpc.LoadUrdfCommand.urdfFileName) +} +#if LANG_CXX11 +void LoadUrdfCommand::set_urdffilename(::std::string&& value) { + + urdffilename_.SetNoArena( + &::google::protobuf::internal::GetEmptyStringAlreadyInited(), std::move(value)); + // @@protoc_insertion_point(field_set_rvalue:pybullet_grpc.LoadUrdfCommand.urdfFileName) +} +#endif +void LoadUrdfCommand::set_urdffilename(const char* value) { + + urdffilename_.SetNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), ::std::string(value)); + // @@protoc_insertion_point(field_set_char:pybullet_grpc.LoadUrdfCommand.urdfFileName) +} +void LoadUrdfCommand::set_urdffilename(const char* value, size_t size) { + + urdffilename_.SetNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), + ::std::string(reinterpret_cast(value), size)); + // @@protoc_insertion_point(field_set_pointer:pybullet_grpc.LoadUrdfCommand.urdfFileName) +} +::std::string* LoadUrdfCommand::mutable_urdffilename() { + + // @@protoc_insertion_point(field_mutable:pybullet_grpc.LoadUrdfCommand.urdfFileName) + return urdffilename_.MutableNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); +} +::std::string* LoadUrdfCommand::release_urdffilename() { + // @@protoc_insertion_point(field_release:pybullet_grpc.LoadUrdfCommand.urdfFileName) + + return urdffilename_.ReleaseNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); +} +void LoadUrdfCommand::set_allocated_urdffilename(::std::string* urdffilename) { + if (urdffilename != NULL) { + + } else { + + } + urdffilename_.SetAllocatedNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), urdffilename); + // @@protoc_insertion_point(field_set_allocated:pybullet_grpc.LoadUrdfCommand.urdfFileName) +} + +// .pybullet_grpc.vec3 initialPosition = 2; +bool LoadUrdfCommand::has_initialposition() const { + return this != internal_default_instance() && initialposition_ != NULL; +} +void LoadUrdfCommand::clear_initialposition() { + if (GetArenaNoVirtual() == NULL && initialposition_ != NULL) delete initialposition_; + initialposition_ = NULL; +} +const ::pybullet_grpc::vec3& LoadUrdfCommand::initialposition() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.LoadUrdfCommand.initialPosition) + return initialposition_ != NULL ? *initialposition_ + : *::pybullet_grpc::vec3::internal_default_instance(); +} +::pybullet_grpc::vec3* LoadUrdfCommand::mutable_initialposition() { + + if (initialposition_ == NULL) { + initialposition_ = new ::pybullet_grpc::vec3; + } + // @@protoc_insertion_point(field_mutable:pybullet_grpc.LoadUrdfCommand.initialPosition) + return initialposition_; +} +::pybullet_grpc::vec3* LoadUrdfCommand::release_initialposition() { + // @@protoc_insertion_point(field_release:pybullet_grpc.LoadUrdfCommand.initialPosition) + + ::pybullet_grpc::vec3* temp = initialposition_; + initialposition_ = NULL; + return temp; +} +void LoadUrdfCommand::set_allocated_initialposition(::pybullet_grpc::vec3* initialposition) { + delete initialposition_; + initialposition_ = initialposition; + if (initialposition) { + + } else { + + } + // @@protoc_insertion_point(field_set_allocated:pybullet_grpc.LoadUrdfCommand.initialPosition) +} + +// .pybullet_grpc.quat4 initialOrientation = 3; +bool LoadUrdfCommand::has_initialorientation() const { + return this != internal_default_instance() && initialorientation_ != NULL; +} +void LoadUrdfCommand::clear_initialorientation() { + if (GetArenaNoVirtual() == NULL && initialorientation_ != NULL) delete initialorientation_; + initialorientation_ = NULL; +} +const ::pybullet_grpc::quat4& LoadUrdfCommand::initialorientation() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.LoadUrdfCommand.initialOrientation) + return initialorientation_ != NULL ? *initialorientation_ + : *::pybullet_grpc::quat4::internal_default_instance(); +} +::pybullet_grpc::quat4* LoadUrdfCommand::mutable_initialorientation() { + + if (initialorientation_ == NULL) { + initialorientation_ = new ::pybullet_grpc::quat4; + } + // @@protoc_insertion_point(field_mutable:pybullet_grpc.LoadUrdfCommand.initialOrientation) + return initialorientation_; +} +::pybullet_grpc::quat4* LoadUrdfCommand::release_initialorientation() { + // @@protoc_insertion_point(field_release:pybullet_grpc.LoadUrdfCommand.initialOrientation) + + ::pybullet_grpc::quat4* temp = initialorientation_; + initialorientation_ = NULL; + return temp; +} +void LoadUrdfCommand::set_allocated_initialorientation(::pybullet_grpc::quat4* initialorientation) { + delete initialorientation_; + initialorientation_ = initialorientation; + if (initialorientation) { + + } else { + + } + // @@protoc_insertion_point(field_set_allocated:pybullet_grpc.LoadUrdfCommand.initialOrientation) +} + +// int32 useMultiBody = 4; +bool LoadUrdfCommand::has_usemultibody() const { + return hasUseMultiBody_case() == kUseMultiBody; +} +void LoadUrdfCommand::set_has_usemultibody() { + _oneof_case_[0] = kUseMultiBody; +} +void LoadUrdfCommand::clear_usemultibody() { + if (has_usemultibody()) { + hasUseMultiBody_.usemultibody_ = 0; + clear_has_hasUseMultiBody(); + } +} +::google::protobuf::int32 LoadUrdfCommand::usemultibody() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.LoadUrdfCommand.useMultiBody) + if (has_usemultibody()) { + return hasUseMultiBody_.usemultibody_; + } + return 0; +} +void LoadUrdfCommand::set_usemultibody(::google::protobuf::int32 value) { + if (!has_usemultibody()) { + clear_hasUseMultiBody(); + set_has_usemultibody(); + } + hasUseMultiBody_.usemultibody_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.LoadUrdfCommand.useMultiBody) +} + +// bool useFixedBase = 5; +bool LoadUrdfCommand::has_usefixedbase() const { + return hasUseFixedBase_case() == kUseFixedBase; +} +void LoadUrdfCommand::set_has_usefixedbase() { + _oneof_case_[1] = kUseFixedBase; +} +void LoadUrdfCommand::clear_usefixedbase() { + if (has_usefixedbase()) { + hasUseFixedBase_.usefixedbase_ = false; + clear_has_hasUseFixedBase(); + } +} +bool LoadUrdfCommand::usefixedbase() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.LoadUrdfCommand.useFixedBase) + if (has_usefixedbase()) { + return hasUseFixedBase_.usefixedbase_; + } + return false; +} +void LoadUrdfCommand::set_usefixedbase(bool value) { + if (!has_usefixedbase()) { + clear_hasUseFixedBase(); + set_has_usefixedbase(); + } + hasUseFixedBase_.usefixedbase_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.LoadUrdfCommand.useFixedBase) +} + +// int32 urdfFlags = 6; +void LoadUrdfCommand::clear_urdfflags() { + urdfflags_ = 0; +} +::google::protobuf::int32 LoadUrdfCommand::urdfflags() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.LoadUrdfCommand.urdfFlags) + return urdfflags_; +} +void LoadUrdfCommand::set_urdfflags(::google::protobuf::int32 value) { + + urdfflags_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.LoadUrdfCommand.urdfFlags) +} + +// double globalScaling = 7; +bool LoadUrdfCommand::has_globalscaling() const { + return hasGlobalScaling_case() == kGlobalScaling; +} +void LoadUrdfCommand::set_has_globalscaling() { + _oneof_case_[2] = kGlobalScaling; +} +void LoadUrdfCommand::clear_globalscaling() { + if (has_globalscaling()) { + hasGlobalScaling_.globalscaling_ = 0; + clear_has_hasGlobalScaling(); + } +} +double LoadUrdfCommand::globalscaling() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.LoadUrdfCommand.globalScaling) + if (has_globalscaling()) { + return hasGlobalScaling_.globalscaling_; + } + return 0; +} +void LoadUrdfCommand::set_globalscaling(double value) { + if (!has_globalscaling()) { + clear_hasGlobalScaling(); + set_has_globalscaling(); + } + hasGlobalScaling_.globalscaling_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.LoadUrdfCommand.globalScaling) +} + +bool LoadUrdfCommand::has_hasUseMultiBody() const { + return hasUseMultiBody_case() != HASUSEMULTIBODY_NOT_SET; +} +void LoadUrdfCommand::clear_has_hasUseMultiBody() { + _oneof_case_[0] = HASUSEMULTIBODY_NOT_SET; +} +bool LoadUrdfCommand::has_hasUseFixedBase() const { + return hasUseFixedBase_case() != HASUSEFIXEDBASE_NOT_SET; +} +void LoadUrdfCommand::clear_has_hasUseFixedBase() { + _oneof_case_[1] = HASUSEFIXEDBASE_NOT_SET; +} +bool LoadUrdfCommand::has_hasGlobalScaling() const { + return hasGlobalScaling_case() != HASGLOBALSCALING_NOT_SET; +} +void LoadUrdfCommand::clear_has_hasGlobalScaling() { + _oneof_case_[2] = HASGLOBALSCALING_NOT_SET; +} +LoadUrdfCommand::HasUseMultiBodyCase LoadUrdfCommand::hasUseMultiBody_case() const { + return LoadUrdfCommand::HasUseMultiBodyCase(_oneof_case_[0]); +} +LoadUrdfCommand::HasUseFixedBaseCase LoadUrdfCommand::hasUseFixedBase_case() const { + return LoadUrdfCommand::HasUseFixedBaseCase(_oneof_case_[1]); +} +LoadUrdfCommand::HasGlobalScalingCase LoadUrdfCommand::hasGlobalScaling_case() const { + return LoadUrdfCommand::HasGlobalScalingCase(_oneof_case_[2]); +} +#endif // PROTOBUF_INLINE_NOT_IN_HEADERS + +// =================================================================== + +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const int LoadUrdfStatus::kObjectUniqueIdFieldNumber; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 + +LoadUrdfStatus::LoadUrdfStatus() + : ::google::protobuf::Message(), _internal_metadata_(NULL) { + if (GOOGLE_PREDICT_TRUE(this != internal_default_instance())) { + protobuf_pybullet_2eproto::InitDefaults(); + } + SharedCtor(); + // @@protoc_insertion_point(constructor:pybullet_grpc.LoadUrdfStatus) +} +LoadUrdfStatus::LoadUrdfStatus(const LoadUrdfStatus& from) + : ::google::protobuf::Message(), + _internal_metadata_(NULL), + _cached_size_(0) { + _internal_metadata_.MergeFrom(from._internal_metadata_); + objectuniqueid_ = from.objectuniqueid_; + // @@protoc_insertion_point(copy_constructor:pybullet_grpc.LoadUrdfStatus) +} + +void LoadUrdfStatus::SharedCtor() { + objectuniqueid_ = 0; + _cached_size_ = 0; +} + +LoadUrdfStatus::~LoadUrdfStatus() { + // @@protoc_insertion_point(destructor:pybullet_grpc.LoadUrdfStatus) + SharedDtor(); +} + +void LoadUrdfStatus::SharedDtor() { +} + +void LoadUrdfStatus::SetCachedSize(int size) const { + GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN(); + _cached_size_ = size; + GOOGLE_SAFE_CONCURRENT_WRITES_END(); +} +const ::google::protobuf::Descriptor* LoadUrdfStatus::descriptor() { + protobuf_pybullet_2eproto::protobuf_AssignDescriptorsOnce(); + return protobuf_pybullet_2eproto::file_level_metadata[5].descriptor; +} + +const LoadUrdfStatus& LoadUrdfStatus::default_instance() { + protobuf_pybullet_2eproto::InitDefaults(); + return *internal_default_instance(); +} + +LoadUrdfStatus* LoadUrdfStatus::New(::google::protobuf::Arena* arena) const { + LoadUrdfStatus* n = new LoadUrdfStatus; + if (arena != NULL) { + arena->Own(n); + } + return n; +} + +void LoadUrdfStatus::Clear() { +// @@protoc_insertion_point(message_clear_start:pybullet_grpc.LoadUrdfStatus) + objectuniqueid_ = 0; +} + +bool LoadUrdfStatus::MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) { +#define DO_(EXPRESSION) if (!GOOGLE_PREDICT_TRUE(EXPRESSION)) goto failure + ::google::protobuf::uint32 tag; + // @@protoc_insertion_point(parse_start:pybullet_grpc.LoadUrdfStatus) + for (;;) { + ::std::pair< ::google::protobuf::uint32, bool> p = input->ReadTagWithCutoffNoLastTag(127u); + tag = p.first; + if (!p.second) goto handle_unusual; + switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { + // int32 objectUniqueId = 1; + case 1: { + if (tag == 8u) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>( + input, &objectuniqueid_))); + } else { + goto handle_unusual; + } + break; + } + + default: { + handle_unusual: + if (tag == 0 || + ::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == + ::google::protobuf::internal::WireFormatLite::WIRETYPE_END_GROUP) { + goto success; + } + DO_(::google::protobuf::internal::WireFormatLite::SkipField(input, tag)); + break; + } + } + } +success: + // @@protoc_insertion_point(parse_success:pybullet_grpc.LoadUrdfStatus) + return true; +failure: + // @@protoc_insertion_point(parse_failure:pybullet_grpc.LoadUrdfStatus) + return false; +#undef DO_ +} + +void LoadUrdfStatus::SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const { + // @@protoc_insertion_point(serialize_start:pybullet_grpc.LoadUrdfStatus) + // int32 objectUniqueId = 1; + if (this->objectuniqueid() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteInt32(1, this->objectuniqueid(), output); + } + + // @@protoc_insertion_point(serialize_end:pybullet_grpc.LoadUrdfStatus) +} + +::google::protobuf::uint8* LoadUrdfStatus::InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const { + (void)deterministic; // Unused + // @@protoc_insertion_point(serialize_to_array_start:pybullet_grpc.LoadUrdfStatus) + // int32 objectUniqueId = 1; + if (this->objectuniqueid() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteInt32ToArray(1, this->objectuniqueid(), target); + } + + // @@protoc_insertion_point(serialize_to_array_end:pybullet_grpc.LoadUrdfStatus) + return target; +} + +size_t LoadUrdfStatus::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:pybullet_grpc.LoadUrdfStatus) + size_t total_size = 0; + + // int32 objectUniqueId = 1; + if (this->objectuniqueid() != 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::Int32Size( + this->objectuniqueid()); + } + + int cached_size = ::google::protobuf::internal::ToCachedSize(total_size); + GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN(); + _cached_size_ = cached_size; + GOOGLE_SAFE_CONCURRENT_WRITES_END(); + return total_size; +} + +void LoadUrdfStatus::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:pybullet_grpc.LoadUrdfStatus) + GOOGLE_DCHECK_NE(&from, this); + const LoadUrdfStatus* source = + ::google::protobuf::internal::DynamicCastToGenerated( + &from); + if (source == NULL) { + // @@protoc_insertion_point(generalized_merge_from_cast_fail:pybullet_grpc.LoadUrdfStatus) + ::google::protobuf::internal::ReflectionOps::Merge(from, this); + } else { + // @@protoc_insertion_point(generalized_merge_from_cast_success:pybullet_grpc.LoadUrdfStatus) + MergeFrom(*source); + } +} + +void LoadUrdfStatus::MergeFrom(const LoadUrdfStatus& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:pybullet_grpc.LoadUrdfStatus) + GOOGLE_DCHECK_NE(&from, this); + _internal_metadata_.MergeFrom(from._internal_metadata_); + if (from.objectuniqueid() != 0) { + set_objectuniqueid(from.objectuniqueid()); + } +} + +void LoadUrdfStatus::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:pybullet_grpc.LoadUrdfStatus) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +void LoadUrdfStatus::CopyFrom(const LoadUrdfStatus& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:pybullet_grpc.LoadUrdfStatus) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool LoadUrdfStatus::IsInitialized() const { + return true; +} + +void LoadUrdfStatus::Swap(LoadUrdfStatus* other) { + if (other == this) return; + InternalSwap(other); +} +void LoadUrdfStatus::InternalSwap(LoadUrdfStatus* other) { + std::swap(objectuniqueid_, other->objectuniqueid_); + std::swap(_cached_size_, other->_cached_size_); +} + +::google::protobuf::Metadata LoadUrdfStatus::GetMetadata() const { + protobuf_pybullet_2eproto::protobuf_AssignDescriptorsOnce(); + return protobuf_pybullet_2eproto::file_level_metadata[5]; +} + +#if PROTOBUF_INLINE_NOT_IN_HEADERS +// LoadUrdfStatus + +// int32 objectUniqueId = 1; +void LoadUrdfStatus::clear_objectuniqueid() { + objectuniqueid_ = 0; +} +::google::protobuf::int32 LoadUrdfStatus::objectuniqueid() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.LoadUrdfStatus.objectUniqueId) + return objectuniqueid_; +} +void LoadUrdfStatus::set_objectuniqueid(::google::protobuf::int32 value) { + + objectuniqueid_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.LoadUrdfStatus.objectUniqueId) +} + +#endif // PROTOBUF_INLINE_NOT_IN_HEADERS + +// =================================================================== + +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const int PyBulletCommand::kCommandTypeFieldNumber; +const int PyBulletCommand::kLoadUrdfCommandFieldNumber; +const int PyBulletCommand::kTerminateServerCommandFieldNumber; +const int PyBulletCommand::kStepSimulationCommandFieldNumber; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 + +PyBulletCommand::PyBulletCommand() + : ::google::protobuf::Message(), _internal_metadata_(NULL) { + if (GOOGLE_PREDICT_TRUE(this != internal_default_instance())) { + protobuf_pybullet_2eproto::InitDefaults(); + } + SharedCtor(); + // @@protoc_insertion_point(constructor:pybullet_grpc.PyBulletCommand) +} +PyBulletCommand::PyBulletCommand(const PyBulletCommand& from) + : ::google::protobuf::Message(), + _internal_metadata_(NULL), + _cached_size_(0) { + _internal_metadata_.MergeFrom(from._internal_metadata_); + commandtype_ = from.commandtype_; + clear_has_commands(); + switch (from.commands_case()) { + case kLoadUrdfCommand: { + mutable_loadurdfcommand()->::pybullet_grpc::LoadUrdfCommand::MergeFrom(from.loadurdfcommand()); + break; + } + case kTerminateServerCommand: { + mutable_terminateservercommand()->::pybullet_grpc::TerminateServerCommand::MergeFrom(from.terminateservercommand()); + break; + } + case kStepSimulationCommand: { + mutable_stepsimulationcommand()->::pybullet_grpc::StepSimulationCommand::MergeFrom(from.stepsimulationcommand()); + break; + } + case COMMANDS_NOT_SET: { + break; + } + } + // @@protoc_insertion_point(copy_constructor:pybullet_grpc.PyBulletCommand) +} + +void PyBulletCommand::SharedCtor() { + commandtype_ = 0; + clear_has_commands(); + _cached_size_ = 0; +} + +PyBulletCommand::~PyBulletCommand() { + // @@protoc_insertion_point(destructor:pybullet_grpc.PyBulletCommand) + SharedDtor(); +} + +void PyBulletCommand::SharedDtor() { + if (has_commands()) { + clear_commands(); + } +} + +void PyBulletCommand::SetCachedSize(int size) const { + GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN(); + _cached_size_ = size; + GOOGLE_SAFE_CONCURRENT_WRITES_END(); +} +const ::google::protobuf::Descriptor* PyBulletCommand::descriptor() { + protobuf_pybullet_2eproto::protobuf_AssignDescriptorsOnce(); + return protobuf_pybullet_2eproto::file_level_metadata[6].descriptor; +} + +const PyBulletCommand& PyBulletCommand::default_instance() { + protobuf_pybullet_2eproto::InitDefaults(); + return *internal_default_instance(); +} + +PyBulletCommand* PyBulletCommand::New(::google::protobuf::Arena* arena) const { + PyBulletCommand* n = new PyBulletCommand; + if (arena != NULL) { + arena->Own(n); + } + return n; +} + +void PyBulletCommand::clear_commands() { +// @@protoc_insertion_point(one_of_clear_start:pybullet_grpc.PyBulletCommand) + switch (commands_case()) { + case kLoadUrdfCommand: { + delete commands_.loadurdfcommand_; + break; + } + case kTerminateServerCommand: { + delete commands_.terminateservercommand_; + break; + } + case kStepSimulationCommand: { + delete commands_.stepsimulationcommand_; + break; + } + case COMMANDS_NOT_SET: { + break; + } + } + _oneof_case_[0] = COMMANDS_NOT_SET; +} + + +void PyBulletCommand::Clear() { +// @@protoc_insertion_point(message_clear_start:pybullet_grpc.PyBulletCommand) + commandtype_ = 0; + clear_commands(); +} + +bool PyBulletCommand::MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) { +#define DO_(EXPRESSION) if (!GOOGLE_PREDICT_TRUE(EXPRESSION)) goto failure + ::google::protobuf::uint32 tag; + // @@protoc_insertion_point(parse_start:pybullet_grpc.PyBulletCommand) + for (;;) { + ::std::pair< ::google::protobuf::uint32, bool> p = input->ReadTagWithCutoffNoLastTag(127u); + tag = p.first; + if (!p.second) goto handle_unusual; + switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { + // int32 commandType = 1; + case 1: { + if (tag == 8u) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>( + input, &commandtype_))); + } else { + goto handle_unusual; + } + break; + } + + // .pybullet_grpc.LoadUrdfCommand loadUrdfCommand = 3; + case 3: { + if (tag == 26u) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessageNoVirtual( + input, mutable_loadurdfcommand())); + } else { + goto handle_unusual; + } + break; + } + + // .pybullet_grpc.TerminateServerCommand terminateServerCommand = 4; + case 4: { + if (tag == 34u) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessageNoVirtual( + input, mutable_terminateservercommand())); + } else { + goto handle_unusual; + } + break; + } + + // .pybullet_grpc.StepSimulationCommand stepSimulationCommand = 5; + case 5: { + if (tag == 42u) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessageNoVirtual( + input, mutable_stepsimulationcommand())); + } else { + goto handle_unusual; + } + break; + } + + default: { + handle_unusual: + if (tag == 0 || + ::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == + ::google::protobuf::internal::WireFormatLite::WIRETYPE_END_GROUP) { + goto success; + } + DO_(::google::protobuf::internal::WireFormatLite::SkipField(input, tag)); + break; + } + } + } +success: + // @@protoc_insertion_point(parse_success:pybullet_grpc.PyBulletCommand) + return true; +failure: + // @@protoc_insertion_point(parse_failure:pybullet_grpc.PyBulletCommand) + return false; +#undef DO_ +} + +void PyBulletCommand::SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const { + // @@protoc_insertion_point(serialize_start:pybullet_grpc.PyBulletCommand) + // int32 commandType = 1; + if (this->commandtype() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteInt32(1, this->commandtype(), output); + } + + // .pybullet_grpc.LoadUrdfCommand loadUrdfCommand = 3; + if (has_loadurdfcommand()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 3, *commands_.loadurdfcommand_, output); + } + + // .pybullet_grpc.TerminateServerCommand terminateServerCommand = 4; + if (has_terminateservercommand()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 4, *commands_.terminateservercommand_, output); + } + + // .pybullet_grpc.StepSimulationCommand stepSimulationCommand = 5; + if (has_stepsimulationcommand()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 5, *commands_.stepsimulationcommand_, output); + } + + // @@protoc_insertion_point(serialize_end:pybullet_grpc.PyBulletCommand) +} + +::google::protobuf::uint8* PyBulletCommand::InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const { + (void)deterministic; // Unused + // @@protoc_insertion_point(serialize_to_array_start:pybullet_grpc.PyBulletCommand) + // int32 commandType = 1; + if (this->commandtype() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteInt32ToArray(1, this->commandtype(), target); + } + + // .pybullet_grpc.LoadUrdfCommand loadUrdfCommand = 3; + if (has_loadurdfcommand()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageNoVirtualToArray( + 3, *commands_.loadurdfcommand_, false, target); + } + + // .pybullet_grpc.TerminateServerCommand terminateServerCommand = 4; + if (has_terminateservercommand()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageNoVirtualToArray( + 4, *commands_.terminateservercommand_, false, target); + } + + // .pybullet_grpc.StepSimulationCommand stepSimulationCommand = 5; + if (has_stepsimulationcommand()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageNoVirtualToArray( + 5, *commands_.stepsimulationcommand_, false, target); + } + + // @@protoc_insertion_point(serialize_to_array_end:pybullet_grpc.PyBulletCommand) + return target; +} + +size_t PyBulletCommand::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:pybullet_grpc.PyBulletCommand) + size_t total_size = 0; + + // int32 commandType = 1; + if (this->commandtype() != 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::Int32Size( + this->commandtype()); + } + + switch (commands_case()) { + // .pybullet_grpc.LoadUrdfCommand loadUrdfCommand = 3; + case kLoadUrdfCommand: { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSizeNoVirtual( + *commands_.loadurdfcommand_); + break; + } + // .pybullet_grpc.TerminateServerCommand terminateServerCommand = 4; + case kTerminateServerCommand: { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSizeNoVirtual( + *commands_.terminateservercommand_); + break; + } + // .pybullet_grpc.StepSimulationCommand stepSimulationCommand = 5; + case kStepSimulationCommand: { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSizeNoVirtual( + *commands_.stepsimulationcommand_); + break; + } + case COMMANDS_NOT_SET: { + break; + } + } + int cached_size = ::google::protobuf::internal::ToCachedSize(total_size); + GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN(); + _cached_size_ = cached_size; + GOOGLE_SAFE_CONCURRENT_WRITES_END(); + return total_size; +} + +void PyBulletCommand::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:pybullet_grpc.PyBulletCommand) + GOOGLE_DCHECK_NE(&from, this); + const PyBulletCommand* source = + ::google::protobuf::internal::DynamicCastToGenerated( + &from); + if (source == NULL) { + // @@protoc_insertion_point(generalized_merge_from_cast_fail:pybullet_grpc.PyBulletCommand) + ::google::protobuf::internal::ReflectionOps::Merge(from, this); + } else { + // @@protoc_insertion_point(generalized_merge_from_cast_success:pybullet_grpc.PyBulletCommand) + MergeFrom(*source); + } +} + +void PyBulletCommand::MergeFrom(const PyBulletCommand& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:pybullet_grpc.PyBulletCommand) + GOOGLE_DCHECK_NE(&from, this); + _internal_metadata_.MergeFrom(from._internal_metadata_); + if (from.commandtype() != 0) { + set_commandtype(from.commandtype()); + } + switch (from.commands_case()) { + case kLoadUrdfCommand: { + mutable_loadurdfcommand()->::pybullet_grpc::LoadUrdfCommand::MergeFrom(from.loadurdfcommand()); + break; + } + case kTerminateServerCommand: { + mutable_terminateservercommand()->::pybullet_grpc::TerminateServerCommand::MergeFrom(from.terminateservercommand()); + break; + } + case kStepSimulationCommand: { + mutable_stepsimulationcommand()->::pybullet_grpc::StepSimulationCommand::MergeFrom(from.stepsimulationcommand()); + break; + } + case COMMANDS_NOT_SET: { + break; + } + } +} + +void PyBulletCommand::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:pybullet_grpc.PyBulletCommand) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +void PyBulletCommand::CopyFrom(const PyBulletCommand& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:pybullet_grpc.PyBulletCommand) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool PyBulletCommand::IsInitialized() const { + return true; +} + +void PyBulletCommand::Swap(PyBulletCommand* other) { + if (other == this) return; + InternalSwap(other); +} +void PyBulletCommand::InternalSwap(PyBulletCommand* other) { + std::swap(commandtype_, other->commandtype_); + std::swap(commands_, other->commands_); + std::swap(_oneof_case_[0], other->_oneof_case_[0]); + std::swap(_cached_size_, other->_cached_size_); +} + +::google::protobuf::Metadata PyBulletCommand::GetMetadata() const { + protobuf_pybullet_2eproto::protobuf_AssignDescriptorsOnce(); + return protobuf_pybullet_2eproto::file_level_metadata[6]; +} + +#if PROTOBUF_INLINE_NOT_IN_HEADERS +// PyBulletCommand + +// int32 commandType = 1; +void PyBulletCommand::clear_commandtype() { + commandtype_ = 0; +} +::google::protobuf::int32 PyBulletCommand::commandtype() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.PyBulletCommand.commandType) + return commandtype_; +} +void PyBulletCommand::set_commandtype(::google::protobuf::int32 value) { + + commandtype_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.PyBulletCommand.commandType) +} + +// .pybullet_grpc.LoadUrdfCommand loadUrdfCommand = 3; +bool PyBulletCommand::has_loadurdfcommand() const { + return commands_case() == kLoadUrdfCommand; +} +void PyBulletCommand::set_has_loadurdfcommand() { + _oneof_case_[0] = kLoadUrdfCommand; +} +void PyBulletCommand::clear_loadurdfcommand() { + if (has_loadurdfcommand()) { + delete commands_.loadurdfcommand_; + clear_has_commands(); + } +} + const ::pybullet_grpc::LoadUrdfCommand& PyBulletCommand::loadurdfcommand() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.PyBulletCommand.loadUrdfCommand) + return has_loadurdfcommand() + ? *commands_.loadurdfcommand_ + : ::pybullet_grpc::LoadUrdfCommand::default_instance(); +} +::pybullet_grpc::LoadUrdfCommand* PyBulletCommand::mutable_loadurdfcommand() { + if (!has_loadurdfcommand()) { + clear_commands(); + set_has_loadurdfcommand(); + commands_.loadurdfcommand_ = new ::pybullet_grpc::LoadUrdfCommand; + } + // @@protoc_insertion_point(field_mutable:pybullet_grpc.PyBulletCommand.loadUrdfCommand) + return commands_.loadurdfcommand_; +} +::pybullet_grpc::LoadUrdfCommand* PyBulletCommand::release_loadurdfcommand() { + // @@protoc_insertion_point(field_release:pybullet_grpc.PyBulletCommand.loadUrdfCommand) + if (has_loadurdfcommand()) { + clear_has_commands(); + ::pybullet_grpc::LoadUrdfCommand* temp = commands_.loadurdfcommand_; + commands_.loadurdfcommand_ = NULL; + return temp; + } else { + return NULL; + } +} +void PyBulletCommand::set_allocated_loadurdfcommand(::pybullet_grpc::LoadUrdfCommand* loadurdfcommand) { + clear_commands(); + if (loadurdfcommand) { + set_has_loadurdfcommand(); + commands_.loadurdfcommand_ = loadurdfcommand; + } + // @@protoc_insertion_point(field_set_allocated:pybullet_grpc.PyBulletCommand.loadUrdfCommand) +} + +// .pybullet_grpc.TerminateServerCommand terminateServerCommand = 4; +bool PyBulletCommand::has_terminateservercommand() const { + return commands_case() == kTerminateServerCommand; +} +void PyBulletCommand::set_has_terminateservercommand() { + _oneof_case_[0] = kTerminateServerCommand; +} +void PyBulletCommand::clear_terminateservercommand() { + if (has_terminateservercommand()) { + delete commands_.terminateservercommand_; + clear_has_commands(); + } +} + const ::pybullet_grpc::TerminateServerCommand& PyBulletCommand::terminateservercommand() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.PyBulletCommand.terminateServerCommand) + return has_terminateservercommand() + ? *commands_.terminateservercommand_ + : ::pybullet_grpc::TerminateServerCommand::default_instance(); +} +::pybullet_grpc::TerminateServerCommand* PyBulletCommand::mutable_terminateservercommand() { + if (!has_terminateservercommand()) { + clear_commands(); + set_has_terminateservercommand(); + commands_.terminateservercommand_ = new ::pybullet_grpc::TerminateServerCommand; + } + // @@protoc_insertion_point(field_mutable:pybullet_grpc.PyBulletCommand.terminateServerCommand) + return commands_.terminateservercommand_; +} +::pybullet_grpc::TerminateServerCommand* PyBulletCommand::release_terminateservercommand() { + // @@protoc_insertion_point(field_release:pybullet_grpc.PyBulletCommand.terminateServerCommand) + if (has_terminateservercommand()) { + clear_has_commands(); + ::pybullet_grpc::TerminateServerCommand* temp = commands_.terminateservercommand_; + commands_.terminateservercommand_ = NULL; + return temp; + } else { + return NULL; + } +} +void PyBulletCommand::set_allocated_terminateservercommand(::pybullet_grpc::TerminateServerCommand* terminateservercommand) { + clear_commands(); + if (terminateservercommand) { + set_has_terminateservercommand(); + commands_.terminateservercommand_ = terminateservercommand; + } + // @@protoc_insertion_point(field_set_allocated:pybullet_grpc.PyBulletCommand.terminateServerCommand) +} + +// .pybullet_grpc.StepSimulationCommand stepSimulationCommand = 5; +bool PyBulletCommand::has_stepsimulationcommand() const { + return commands_case() == kStepSimulationCommand; +} +void PyBulletCommand::set_has_stepsimulationcommand() { + _oneof_case_[0] = kStepSimulationCommand; +} +void PyBulletCommand::clear_stepsimulationcommand() { + if (has_stepsimulationcommand()) { + delete commands_.stepsimulationcommand_; + clear_has_commands(); + } +} + const ::pybullet_grpc::StepSimulationCommand& PyBulletCommand::stepsimulationcommand() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.PyBulletCommand.stepSimulationCommand) + return has_stepsimulationcommand() + ? *commands_.stepsimulationcommand_ + : ::pybullet_grpc::StepSimulationCommand::default_instance(); +} +::pybullet_grpc::StepSimulationCommand* PyBulletCommand::mutable_stepsimulationcommand() { + if (!has_stepsimulationcommand()) { + clear_commands(); + set_has_stepsimulationcommand(); + commands_.stepsimulationcommand_ = new ::pybullet_grpc::StepSimulationCommand; + } + // @@protoc_insertion_point(field_mutable:pybullet_grpc.PyBulletCommand.stepSimulationCommand) + return commands_.stepsimulationcommand_; +} +::pybullet_grpc::StepSimulationCommand* PyBulletCommand::release_stepsimulationcommand() { + // @@protoc_insertion_point(field_release:pybullet_grpc.PyBulletCommand.stepSimulationCommand) + if (has_stepsimulationcommand()) { + clear_has_commands(); + ::pybullet_grpc::StepSimulationCommand* temp = commands_.stepsimulationcommand_; + commands_.stepsimulationcommand_ = NULL; + return temp; + } else { + return NULL; + } +} +void PyBulletCommand::set_allocated_stepsimulationcommand(::pybullet_grpc::StepSimulationCommand* stepsimulationcommand) { + clear_commands(); + if (stepsimulationcommand) { + set_has_stepsimulationcommand(); + commands_.stepsimulationcommand_ = stepsimulationcommand; + } + // @@protoc_insertion_point(field_set_allocated:pybullet_grpc.PyBulletCommand.stepSimulationCommand) +} + +bool PyBulletCommand::has_commands() const { + return commands_case() != COMMANDS_NOT_SET; +} +void PyBulletCommand::clear_has_commands() { + _oneof_case_[0] = COMMANDS_NOT_SET; +} +PyBulletCommand::CommandsCase PyBulletCommand::commands_case() const { + return PyBulletCommand::CommandsCase(_oneof_case_[0]); +} +#endif // PROTOBUF_INLINE_NOT_IN_HEADERS + +// =================================================================== + +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const int PyBulletStatus::kStatusTypeFieldNumber; +const int PyBulletStatus::kUrdfStatusFieldNumber; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 + +PyBulletStatus::PyBulletStatus() + : ::google::protobuf::Message(), _internal_metadata_(NULL) { + if (GOOGLE_PREDICT_TRUE(this != internal_default_instance())) { + protobuf_pybullet_2eproto::InitDefaults(); + } + SharedCtor(); + // @@protoc_insertion_point(constructor:pybullet_grpc.PyBulletStatus) +} +PyBulletStatus::PyBulletStatus(const PyBulletStatus& from) + : ::google::protobuf::Message(), + _internal_metadata_(NULL), + _cached_size_(0) { + _internal_metadata_.MergeFrom(from._internal_metadata_); + statustype_ = from.statustype_; + clear_has_status(); + switch (from.status_case()) { + case kUrdfStatus: { + mutable_urdfstatus()->::pybullet_grpc::LoadUrdfStatus::MergeFrom(from.urdfstatus()); + break; + } + case STATUS_NOT_SET: { + break; + } + } + // @@protoc_insertion_point(copy_constructor:pybullet_grpc.PyBulletStatus) +} + +void PyBulletStatus::SharedCtor() { + statustype_ = 0; + clear_has_status(); + _cached_size_ = 0; +} + +PyBulletStatus::~PyBulletStatus() { + // @@protoc_insertion_point(destructor:pybullet_grpc.PyBulletStatus) + SharedDtor(); +} + +void PyBulletStatus::SharedDtor() { + if (has_status()) { + clear_status(); + } +} + +void PyBulletStatus::SetCachedSize(int size) const { + GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN(); + _cached_size_ = size; + GOOGLE_SAFE_CONCURRENT_WRITES_END(); +} +const ::google::protobuf::Descriptor* PyBulletStatus::descriptor() { + protobuf_pybullet_2eproto::protobuf_AssignDescriptorsOnce(); + return protobuf_pybullet_2eproto::file_level_metadata[7].descriptor; +} + +const PyBulletStatus& PyBulletStatus::default_instance() { + protobuf_pybullet_2eproto::InitDefaults(); + return *internal_default_instance(); +} + +PyBulletStatus* PyBulletStatus::New(::google::protobuf::Arena* arena) const { + PyBulletStatus* n = new PyBulletStatus; + if (arena != NULL) { + arena->Own(n); + } + return n; +} + +void PyBulletStatus::clear_status() { +// @@protoc_insertion_point(one_of_clear_start:pybullet_grpc.PyBulletStatus) + switch (status_case()) { + case kUrdfStatus: { + delete status_.urdfstatus_; + break; + } + case STATUS_NOT_SET: { + break; + } + } + _oneof_case_[0] = STATUS_NOT_SET; +} + + +void PyBulletStatus::Clear() { +// @@protoc_insertion_point(message_clear_start:pybullet_grpc.PyBulletStatus) + statustype_ = 0; + clear_status(); +} + +bool PyBulletStatus::MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) { +#define DO_(EXPRESSION) if (!GOOGLE_PREDICT_TRUE(EXPRESSION)) goto failure + ::google::protobuf::uint32 tag; + // @@protoc_insertion_point(parse_start:pybullet_grpc.PyBulletStatus) + for (;;) { + ::std::pair< ::google::protobuf::uint32, bool> p = input->ReadTagWithCutoffNoLastTag(127u); + tag = p.first; + if (!p.second) goto handle_unusual; + switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { + // int32 statusType = 1; + case 1: { + if (tag == 8u) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>( + input, &statustype_))); + } else { + goto handle_unusual; + } + break; + } + + // .pybullet_grpc.LoadUrdfStatus urdfStatus = 2; + case 2: { + if (tag == 18u) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessageNoVirtual( + input, mutable_urdfstatus())); + } else { + goto handle_unusual; + } + break; + } + + default: { + handle_unusual: + if (tag == 0 || + ::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == + ::google::protobuf::internal::WireFormatLite::WIRETYPE_END_GROUP) { + goto success; + } + DO_(::google::protobuf::internal::WireFormatLite::SkipField(input, tag)); + break; + } + } + } +success: + // @@protoc_insertion_point(parse_success:pybullet_grpc.PyBulletStatus) + return true; +failure: + // @@protoc_insertion_point(parse_failure:pybullet_grpc.PyBulletStatus) + return false; +#undef DO_ +} + +void PyBulletStatus::SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const { + // @@protoc_insertion_point(serialize_start:pybullet_grpc.PyBulletStatus) + // int32 statusType = 1; + if (this->statustype() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteInt32(1, this->statustype(), output); + } + + // .pybullet_grpc.LoadUrdfStatus urdfStatus = 2; + if (has_urdfstatus()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 2, *status_.urdfstatus_, output); + } + + // @@protoc_insertion_point(serialize_end:pybullet_grpc.PyBulletStatus) +} + +::google::protobuf::uint8* PyBulletStatus::InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const { + (void)deterministic; // Unused + // @@protoc_insertion_point(serialize_to_array_start:pybullet_grpc.PyBulletStatus) + // int32 statusType = 1; + if (this->statustype() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteInt32ToArray(1, this->statustype(), target); + } + + // .pybullet_grpc.LoadUrdfStatus urdfStatus = 2; + if (has_urdfstatus()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageNoVirtualToArray( + 2, *status_.urdfstatus_, false, target); + } + + // @@protoc_insertion_point(serialize_to_array_end:pybullet_grpc.PyBulletStatus) + return target; +} + +size_t PyBulletStatus::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:pybullet_grpc.PyBulletStatus) + size_t total_size = 0; + + // int32 statusType = 1; + if (this->statustype() != 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::Int32Size( + this->statustype()); + } + + switch (status_case()) { + // .pybullet_grpc.LoadUrdfStatus urdfStatus = 2; + case kUrdfStatus: { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSizeNoVirtual( + *status_.urdfstatus_); + break; + } + case STATUS_NOT_SET: { + break; + } + } + int cached_size = ::google::protobuf::internal::ToCachedSize(total_size); + GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN(); + _cached_size_ = cached_size; + GOOGLE_SAFE_CONCURRENT_WRITES_END(); + return total_size; +} + +void PyBulletStatus::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:pybullet_grpc.PyBulletStatus) + GOOGLE_DCHECK_NE(&from, this); + const PyBulletStatus* source = + ::google::protobuf::internal::DynamicCastToGenerated( + &from); + if (source == NULL) { + // @@protoc_insertion_point(generalized_merge_from_cast_fail:pybullet_grpc.PyBulletStatus) + ::google::protobuf::internal::ReflectionOps::Merge(from, this); + } else { + // @@protoc_insertion_point(generalized_merge_from_cast_success:pybullet_grpc.PyBulletStatus) + MergeFrom(*source); + } +} + +void PyBulletStatus::MergeFrom(const PyBulletStatus& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:pybullet_grpc.PyBulletStatus) + GOOGLE_DCHECK_NE(&from, this); + _internal_metadata_.MergeFrom(from._internal_metadata_); + if (from.statustype() != 0) { + set_statustype(from.statustype()); + } + switch (from.status_case()) { + case kUrdfStatus: { + mutable_urdfstatus()->::pybullet_grpc::LoadUrdfStatus::MergeFrom(from.urdfstatus()); + break; + } + case STATUS_NOT_SET: { + break; + } + } +} + +void PyBulletStatus::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:pybullet_grpc.PyBulletStatus) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +void PyBulletStatus::CopyFrom(const PyBulletStatus& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:pybullet_grpc.PyBulletStatus) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool PyBulletStatus::IsInitialized() const { + return true; +} + +void PyBulletStatus::Swap(PyBulletStatus* other) { + if (other == this) return; + InternalSwap(other); +} +void PyBulletStatus::InternalSwap(PyBulletStatus* other) { + std::swap(statustype_, other->statustype_); + std::swap(status_, other->status_); + std::swap(_oneof_case_[0], other->_oneof_case_[0]); + std::swap(_cached_size_, other->_cached_size_); +} + +::google::protobuf::Metadata PyBulletStatus::GetMetadata() const { + protobuf_pybullet_2eproto::protobuf_AssignDescriptorsOnce(); + return protobuf_pybullet_2eproto::file_level_metadata[7]; +} + +#if PROTOBUF_INLINE_NOT_IN_HEADERS +// PyBulletStatus + +// int32 statusType = 1; +void PyBulletStatus::clear_statustype() { + statustype_ = 0; +} +::google::protobuf::int32 PyBulletStatus::statustype() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.PyBulletStatus.statusType) + return statustype_; +} +void PyBulletStatus::set_statustype(::google::protobuf::int32 value) { + + statustype_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.PyBulletStatus.statusType) +} + +// .pybullet_grpc.LoadUrdfStatus urdfStatus = 2; +bool PyBulletStatus::has_urdfstatus() const { + return status_case() == kUrdfStatus; +} +void PyBulletStatus::set_has_urdfstatus() { + _oneof_case_[0] = kUrdfStatus; +} +void PyBulletStatus::clear_urdfstatus() { + if (has_urdfstatus()) { + delete status_.urdfstatus_; + clear_has_status(); + } +} + const ::pybullet_grpc::LoadUrdfStatus& PyBulletStatus::urdfstatus() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.PyBulletStatus.urdfStatus) + return has_urdfstatus() + ? *status_.urdfstatus_ + : ::pybullet_grpc::LoadUrdfStatus::default_instance(); +} +::pybullet_grpc::LoadUrdfStatus* PyBulletStatus::mutable_urdfstatus() { + if (!has_urdfstatus()) { + clear_status(); + set_has_urdfstatus(); + status_.urdfstatus_ = new ::pybullet_grpc::LoadUrdfStatus; + } + // @@protoc_insertion_point(field_mutable:pybullet_grpc.PyBulletStatus.urdfStatus) + return status_.urdfstatus_; +} +::pybullet_grpc::LoadUrdfStatus* PyBulletStatus::release_urdfstatus() { + // @@protoc_insertion_point(field_release:pybullet_grpc.PyBulletStatus.urdfStatus) + if (has_urdfstatus()) { + clear_has_status(); + ::pybullet_grpc::LoadUrdfStatus* temp = status_.urdfstatus_; + status_.urdfstatus_ = NULL; + return temp; + } else { + return NULL; + } +} +void PyBulletStatus::set_allocated_urdfstatus(::pybullet_grpc::LoadUrdfStatus* urdfstatus) { + clear_status(); + if (urdfstatus) { + set_has_urdfstatus(); + status_.urdfstatus_ = urdfstatus; + } + // @@protoc_insertion_point(field_set_allocated:pybullet_grpc.PyBulletStatus.urdfStatus) +} + +bool PyBulletStatus::has_status() const { + return status_case() != STATUS_NOT_SET; +} +void PyBulletStatus::clear_has_status() { + _oneof_case_[0] = STATUS_NOT_SET; +} +PyBulletStatus::StatusCase PyBulletStatus::status_case() const { + return PyBulletStatus::StatusCase(_oneof_case_[0]); +} +#endif // PROTOBUF_INLINE_NOT_IN_HEADERS + +// @@protoc_insertion_point(namespace_scope) + +} // namespace pybullet_grpc + +// @@protoc_insertion_point(global_scope) diff --git a/examples/SharedMemory/grpc/pybullet.pb.h b/examples/SharedMemory/grpc/pybullet.pb.h new file mode 100644 index 000000000..41ebe4126 --- /dev/null +++ b/examples/SharedMemory/grpc/pybullet.pb.h @@ -0,0 +1,1676 @@ +// Generated by the protocol buffer compiler. DO NOT EDIT! +// source: pybullet.proto + +#ifndef PROTOBUF_pybullet_2eproto__INCLUDED +#define PROTOBUF_pybullet_2eproto__INCLUDED + +#include + +#include + +#if GOOGLE_PROTOBUF_VERSION < 3002000 +#error This file was generated by a newer version of protoc which is +#error incompatible with your Protocol Buffer headers. Please update +#error your headers. +#endif +#if 3002000 < GOOGLE_PROTOBUF_MIN_PROTOC_VERSION +#error This file was generated by an older version of protoc which is +#error incompatible with your Protocol Buffer headers. Please +#error regenerate this file with a newer version of protoc. +#endif + +#include +#include +#include +#include +#include +#include +#include // IWYU pragma: export +#include // IWYU pragma: export +#include +// @@protoc_insertion_point(includes) +namespace pybullet_grpc { +class LoadUrdfCommand; +class LoadUrdfCommandDefaultTypeInternal; +extern LoadUrdfCommandDefaultTypeInternal _LoadUrdfCommand_default_instance_; +class LoadUrdfStatus; +class LoadUrdfStatusDefaultTypeInternal; +extern LoadUrdfStatusDefaultTypeInternal _LoadUrdfStatus_default_instance_; +class PyBulletCommand; +class PyBulletCommandDefaultTypeInternal; +extern PyBulletCommandDefaultTypeInternal _PyBulletCommand_default_instance_; +class PyBulletStatus; +class PyBulletStatusDefaultTypeInternal; +extern PyBulletStatusDefaultTypeInternal _PyBulletStatus_default_instance_; +class StepSimulationCommand; +class StepSimulationCommandDefaultTypeInternal; +extern StepSimulationCommandDefaultTypeInternal _StepSimulationCommand_default_instance_; +class TerminateServerCommand; +class TerminateServerCommandDefaultTypeInternal; +extern TerminateServerCommandDefaultTypeInternal _TerminateServerCommand_default_instance_; +class quat4; +class quat4DefaultTypeInternal; +extern quat4DefaultTypeInternal _quat4_default_instance_; +class vec3; +class vec3DefaultTypeInternal; +extern vec3DefaultTypeInternal _vec3_default_instance_; +} // namespace pybullet_grpc + +namespace pybullet_grpc { + +namespace protobuf_pybullet_2eproto { +// Internal implementation detail -- do not call these. +struct TableStruct { + static const ::google::protobuf::uint32 offsets[]; + static void InitDefaultsImpl(); + static void Shutdown(); +}; +void AddDescriptors(); +void InitDefaults(); +} // namespace protobuf_pybullet_2eproto + +// =================================================================== + +class vec3 : public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:pybullet_grpc.vec3) */ { + public: + vec3(); + virtual ~vec3(); + + vec3(const vec3& from); + + inline vec3& operator=(const vec3& from) { + CopyFrom(from); + return *this; + } + + static const ::google::protobuf::Descriptor* descriptor(); + static const vec3& default_instance(); + + static inline const vec3* internal_default_instance() { + return reinterpret_cast( + &_vec3_default_instance_); + } + + void Swap(vec3* other); + + // implements Message ---------------------------------------------- + + inline vec3* New() const PROTOBUF_FINAL { return New(NULL); } + + vec3* New(::google::protobuf::Arena* arena) const PROTOBUF_FINAL; + void CopyFrom(const ::google::protobuf::Message& from) PROTOBUF_FINAL; + void MergeFrom(const ::google::protobuf::Message& from) PROTOBUF_FINAL; + void CopyFrom(const vec3& from); + void MergeFrom(const vec3& from); + void Clear() PROTOBUF_FINAL; + bool IsInitialized() const PROTOBUF_FINAL; + + size_t ByteSizeLong() const PROTOBUF_FINAL; + bool MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) PROTOBUF_FINAL; + void SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const PROTOBUF_FINAL; + ::google::protobuf::uint8* InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const PROTOBUF_FINAL; + ::google::protobuf::uint8* SerializeWithCachedSizesToArray(::google::protobuf::uint8* output) + const PROTOBUF_FINAL { + return InternalSerializeWithCachedSizesToArray( + ::google::protobuf::io::CodedOutputStream::IsDefaultSerializationDeterministic(), output); + } + int GetCachedSize() const PROTOBUF_FINAL { return _cached_size_; } + private: + void SharedCtor(); + void SharedDtor(); + void SetCachedSize(int size) const PROTOBUF_FINAL; + void InternalSwap(vec3* other); + private: + inline ::google::protobuf::Arena* GetArenaNoVirtual() const { + return NULL; + } + inline void* MaybeArenaPtr() const { + return NULL; + } + public: + + ::google::protobuf::Metadata GetMetadata() const PROTOBUF_FINAL; + + // nested types ---------------------------------------------------- + + // accessors ------------------------------------------------------- + + // double x = 1; + void clear_x(); + static const int kXFieldNumber = 1; + double x() const; + void set_x(double value); + + // double y = 2; + void clear_y(); + static const int kYFieldNumber = 2; + double y() const; + void set_y(double value); + + // double z = 3; + void clear_z(); + static const int kZFieldNumber = 3; + double z() const; + void set_z(double value); + + // @@protoc_insertion_point(class_scope:pybullet_grpc.vec3) + private: + + ::google::protobuf::internal::InternalMetadataWithArena _internal_metadata_; + double x_; + double y_; + double z_; + mutable int _cached_size_; + friend struct protobuf_pybullet_2eproto::TableStruct; +}; +// ------------------------------------------------------------------- + +class quat4 : public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:pybullet_grpc.quat4) */ { + public: + quat4(); + virtual ~quat4(); + + quat4(const quat4& from); + + inline quat4& operator=(const quat4& from) { + CopyFrom(from); + return *this; + } + + static const ::google::protobuf::Descriptor* descriptor(); + static const quat4& default_instance(); + + static inline const quat4* internal_default_instance() { + return reinterpret_cast( + &_quat4_default_instance_); + } + + void Swap(quat4* other); + + // implements Message ---------------------------------------------- + + inline quat4* New() const PROTOBUF_FINAL { return New(NULL); } + + quat4* New(::google::protobuf::Arena* arena) const PROTOBUF_FINAL; + void CopyFrom(const ::google::protobuf::Message& from) PROTOBUF_FINAL; + void MergeFrom(const ::google::protobuf::Message& from) PROTOBUF_FINAL; + void CopyFrom(const quat4& from); + void MergeFrom(const quat4& from); + void Clear() PROTOBUF_FINAL; + bool IsInitialized() const PROTOBUF_FINAL; + + size_t ByteSizeLong() const PROTOBUF_FINAL; + bool MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) PROTOBUF_FINAL; + void SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const PROTOBUF_FINAL; + ::google::protobuf::uint8* InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const PROTOBUF_FINAL; + ::google::protobuf::uint8* SerializeWithCachedSizesToArray(::google::protobuf::uint8* output) + const PROTOBUF_FINAL { + return InternalSerializeWithCachedSizesToArray( + ::google::protobuf::io::CodedOutputStream::IsDefaultSerializationDeterministic(), output); + } + int GetCachedSize() const PROTOBUF_FINAL { return _cached_size_; } + private: + void SharedCtor(); + void SharedDtor(); + void SetCachedSize(int size) const PROTOBUF_FINAL; + void InternalSwap(quat4* other); + private: + inline ::google::protobuf::Arena* GetArenaNoVirtual() const { + return NULL; + } + inline void* MaybeArenaPtr() const { + return NULL; + } + public: + + ::google::protobuf::Metadata GetMetadata() const PROTOBUF_FINAL; + + // nested types ---------------------------------------------------- + + // accessors ------------------------------------------------------- + + // double x = 1; + void clear_x(); + static const int kXFieldNumber = 1; + double x() const; + void set_x(double value); + + // double y = 2; + void clear_y(); + static const int kYFieldNumber = 2; + double y() const; + void set_y(double value); + + // double z = 3; + void clear_z(); + static const int kZFieldNumber = 3; + double z() const; + void set_z(double value); + + // double w = 4; + void clear_w(); + static const int kWFieldNumber = 4; + double w() const; + void set_w(double value); + + // @@protoc_insertion_point(class_scope:pybullet_grpc.quat4) + private: + + ::google::protobuf::internal::InternalMetadataWithArena _internal_metadata_; + double x_; + double y_; + double z_; + double w_; + mutable int _cached_size_; + friend struct protobuf_pybullet_2eproto::TableStruct; +}; +// ------------------------------------------------------------------- + +class TerminateServerCommand : public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:pybullet_grpc.TerminateServerCommand) */ { + public: + TerminateServerCommand(); + virtual ~TerminateServerCommand(); + + TerminateServerCommand(const TerminateServerCommand& from); + + inline TerminateServerCommand& operator=(const TerminateServerCommand& from) { + CopyFrom(from); + return *this; + } + + static const ::google::protobuf::Descriptor* descriptor(); + static const TerminateServerCommand& default_instance(); + + static inline const TerminateServerCommand* internal_default_instance() { + return reinterpret_cast( + &_TerminateServerCommand_default_instance_); + } + + void Swap(TerminateServerCommand* other); + + // implements Message ---------------------------------------------- + + inline TerminateServerCommand* New() const PROTOBUF_FINAL { return New(NULL); } + + TerminateServerCommand* New(::google::protobuf::Arena* arena) const PROTOBUF_FINAL; + void CopyFrom(const ::google::protobuf::Message& from) PROTOBUF_FINAL; + void MergeFrom(const ::google::protobuf::Message& from) PROTOBUF_FINAL; + void CopyFrom(const TerminateServerCommand& from); + void MergeFrom(const TerminateServerCommand& from); + void Clear() PROTOBUF_FINAL; + bool IsInitialized() const PROTOBUF_FINAL; + + size_t ByteSizeLong() const PROTOBUF_FINAL; + bool MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) PROTOBUF_FINAL; + void SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const PROTOBUF_FINAL; + ::google::protobuf::uint8* InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const PROTOBUF_FINAL; + ::google::protobuf::uint8* SerializeWithCachedSizesToArray(::google::protobuf::uint8* output) + const PROTOBUF_FINAL { + return InternalSerializeWithCachedSizesToArray( + ::google::protobuf::io::CodedOutputStream::IsDefaultSerializationDeterministic(), output); + } + int GetCachedSize() const PROTOBUF_FINAL { return _cached_size_; } + private: + void SharedCtor(); + void SharedDtor(); + void SetCachedSize(int size) const PROTOBUF_FINAL; + void InternalSwap(TerminateServerCommand* other); + private: + inline ::google::protobuf::Arena* GetArenaNoVirtual() const { + return NULL; + } + inline void* MaybeArenaPtr() const { + return NULL; + } + public: + + ::google::protobuf::Metadata GetMetadata() const PROTOBUF_FINAL; + + // nested types ---------------------------------------------------- + + // accessors ------------------------------------------------------- + + // string exitReason = 1; + void clear_exitreason(); + static const int kExitReasonFieldNumber = 1; + const ::std::string& exitreason() const; + void set_exitreason(const ::std::string& value); + #if LANG_CXX11 + void set_exitreason(::std::string&& value); + #endif + void set_exitreason(const char* value); + void set_exitreason(const char* value, size_t size); + ::std::string* mutable_exitreason(); + ::std::string* release_exitreason(); + void set_allocated_exitreason(::std::string* exitreason); + + // @@protoc_insertion_point(class_scope:pybullet_grpc.TerminateServerCommand) + private: + + ::google::protobuf::internal::InternalMetadataWithArena _internal_metadata_; + ::google::protobuf::internal::ArenaStringPtr exitreason_; + mutable int _cached_size_; + friend struct protobuf_pybullet_2eproto::TableStruct; +}; +// ------------------------------------------------------------------- + +class StepSimulationCommand : public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:pybullet_grpc.StepSimulationCommand) */ { + public: + StepSimulationCommand(); + virtual ~StepSimulationCommand(); + + StepSimulationCommand(const StepSimulationCommand& from); + + inline StepSimulationCommand& operator=(const StepSimulationCommand& from) { + CopyFrom(from); + return *this; + } + + static const ::google::protobuf::Descriptor* descriptor(); + static const StepSimulationCommand& default_instance(); + + static inline const StepSimulationCommand* internal_default_instance() { + return reinterpret_cast( + &_StepSimulationCommand_default_instance_); + } + + void Swap(StepSimulationCommand* other); + + // implements Message ---------------------------------------------- + + inline StepSimulationCommand* New() const PROTOBUF_FINAL { return New(NULL); } + + StepSimulationCommand* New(::google::protobuf::Arena* arena) const PROTOBUF_FINAL; + void CopyFrom(const ::google::protobuf::Message& from) PROTOBUF_FINAL; + void MergeFrom(const ::google::protobuf::Message& from) PROTOBUF_FINAL; + void CopyFrom(const StepSimulationCommand& from); + void MergeFrom(const StepSimulationCommand& from); + void Clear() PROTOBUF_FINAL; + bool IsInitialized() const PROTOBUF_FINAL; + + size_t ByteSizeLong() const PROTOBUF_FINAL; + bool MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) PROTOBUF_FINAL; + void SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const PROTOBUF_FINAL; + ::google::protobuf::uint8* InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const PROTOBUF_FINAL; + ::google::protobuf::uint8* SerializeWithCachedSizesToArray(::google::protobuf::uint8* output) + const PROTOBUF_FINAL { + return InternalSerializeWithCachedSizesToArray( + ::google::protobuf::io::CodedOutputStream::IsDefaultSerializationDeterministic(), output); + } + int GetCachedSize() const PROTOBUF_FINAL { return _cached_size_; } + private: + void SharedCtor(); + void SharedDtor(); + void SetCachedSize(int size) const PROTOBUF_FINAL; + void InternalSwap(StepSimulationCommand* other); + private: + inline ::google::protobuf::Arena* GetArenaNoVirtual() const { + return NULL; + } + inline void* MaybeArenaPtr() const { + return NULL; + } + public: + + ::google::protobuf::Metadata GetMetadata() const PROTOBUF_FINAL; + + // nested types ---------------------------------------------------- + + // accessors ------------------------------------------------------- + + // @@protoc_insertion_point(class_scope:pybullet_grpc.StepSimulationCommand) + private: + + ::google::protobuf::internal::InternalMetadataWithArena _internal_metadata_; + mutable int _cached_size_; + friend struct protobuf_pybullet_2eproto::TableStruct; +}; +// ------------------------------------------------------------------- + +class LoadUrdfCommand : public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:pybullet_grpc.LoadUrdfCommand) */ { + public: + LoadUrdfCommand(); + virtual ~LoadUrdfCommand(); + + LoadUrdfCommand(const LoadUrdfCommand& from); + + inline LoadUrdfCommand& operator=(const LoadUrdfCommand& from) { + CopyFrom(from); + return *this; + } + + static const ::google::protobuf::Descriptor* descriptor(); + static const LoadUrdfCommand& default_instance(); + + enum HasUseMultiBodyCase { + kUseMultiBody = 4, + HASUSEMULTIBODY_NOT_SET = 0, + }; + + enum HasUseFixedBaseCase { + kUseFixedBase = 5, + HASUSEFIXEDBASE_NOT_SET = 0, + }; + + enum HasGlobalScalingCase { + kGlobalScaling = 7, + HASGLOBALSCALING_NOT_SET = 0, + }; + + static inline const LoadUrdfCommand* internal_default_instance() { + return reinterpret_cast( + &_LoadUrdfCommand_default_instance_); + } + + void Swap(LoadUrdfCommand* other); + + // implements Message ---------------------------------------------- + + inline LoadUrdfCommand* New() const PROTOBUF_FINAL { return New(NULL); } + + LoadUrdfCommand* New(::google::protobuf::Arena* arena) const PROTOBUF_FINAL; + void CopyFrom(const ::google::protobuf::Message& from) PROTOBUF_FINAL; + void MergeFrom(const ::google::protobuf::Message& from) PROTOBUF_FINAL; + void CopyFrom(const LoadUrdfCommand& from); + void MergeFrom(const LoadUrdfCommand& from); + void Clear() PROTOBUF_FINAL; + bool IsInitialized() const PROTOBUF_FINAL; + + size_t ByteSizeLong() const PROTOBUF_FINAL; + bool MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) PROTOBUF_FINAL; + void SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const PROTOBUF_FINAL; + ::google::protobuf::uint8* InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const PROTOBUF_FINAL; + ::google::protobuf::uint8* SerializeWithCachedSizesToArray(::google::protobuf::uint8* output) + const PROTOBUF_FINAL { + return InternalSerializeWithCachedSizesToArray( + ::google::protobuf::io::CodedOutputStream::IsDefaultSerializationDeterministic(), output); + } + int GetCachedSize() const PROTOBUF_FINAL { return _cached_size_; } + private: + void SharedCtor(); + void SharedDtor(); + void SetCachedSize(int size) const PROTOBUF_FINAL; + void InternalSwap(LoadUrdfCommand* other); + private: + inline ::google::protobuf::Arena* GetArenaNoVirtual() const { + return NULL; + } + inline void* MaybeArenaPtr() const { + return NULL; + } + public: + + ::google::protobuf::Metadata GetMetadata() const PROTOBUF_FINAL; + + // nested types ---------------------------------------------------- + + // accessors ------------------------------------------------------- + + // string urdfFileName = 1; + void clear_urdffilename(); + static const int kUrdfFileNameFieldNumber = 1; + const ::std::string& urdffilename() const; + void set_urdffilename(const ::std::string& value); + #if LANG_CXX11 + void set_urdffilename(::std::string&& value); + #endif + void set_urdffilename(const char* value); + void set_urdffilename(const char* value, size_t size); + ::std::string* mutable_urdffilename(); + ::std::string* release_urdffilename(); + void set_allocated_urdffilename(::std::string* urdffilename); + + // .pybullet_grpc.vec3 initialPosition = 2; + bool has_initialposition() const; + void clear_initialposition(); + static const int kInitialPositionFieldNumber = 2; + const ::pybullet_grpc::vec3& initialposition() const; + ::pybullet_grpc::vec3* mutable_initialposition(); + ::pybullet_grpc::vec3* release_initialposition(); + void set_allocated_initialposition(::pybullet_grpc::vec3* initialposition); + + // .pybullet_grpc.quat4 initialOrientation = 3; + bool has_initialorientation() const; + void clear_initialorientation(); + static const int kInitialOrientationFieldNumber = 3; + const ::pybullet_grpc::quat4& initialorientation() const; + ::pybullet_grpc::quat4* mutable_initialorientation(); + ::pybullet_grpc::quat4* release_initialorientation(); + void set_allocated_initialorientation(::pybullet_grpc::quat4* initialorientation); + + // int32 urdfFlags = 6; + void clear_urdfflags(); + static const int kUrdfFlagsFieldNumber = 6; + ::google::protobuf::int32 urdfflags() const; + void set_urdfflags(::google::protobuf::int32 value); + + // int32 useMultiBody = 4; + private: + bool has_usemultibody() const; + public: + void clear_usemultibody(); + static const int kUseMultiBodyFieldNumber = 4; + ::google::protobuf::int32 usemultibody() const; + void set_usemultibody(::google::protobuf::int32 value); + + // bool useFixedBase = 5; + private: + bool has_usefixedbase() const; + public: + void clear_usefixedbase(); + static const int kUseFixedBaseFieldNumber = 5; + bool usefixedbase() const; + void set_usefixedbase(bool value); + + // double globalScaling = 7; + private: + bool has_globalscaling() const; + public: + void clear_globalscaling(); + static const int kGlobalScalingFieldNumber = 7; + double globalscaling() const; + void set_globalscaling(double value); + + HasUseMultiBodyCase hasUseMultiBody_case() const; + HasUseFixedBaseCase hasUseFixedBase_case() const; + HasGlobalScalingCase hasGlobalScaling_case() const; + // @@protoc_insertion_point(class_scope:pybullet_grpc.LoadUrdfCommand) + private: + void set_has_usemultibody(); + void set_has_usefixedbase(); + void set_has_globalscaling(); + + inline bool has_hasUseMultiBody() const; + void clear_hasUseMultiBody(); + inline void clear_has_hasUseMultiBody(); + + inline bool has_hasUseFixedBase() const; + void clear_hasUseFixedBase(); + inline void clear_has_hasUseFixedBase(); + + inline bool has_hasGlobalScaling() const; + void clear_hasGlobalScaling(); + inline void clear_has_hasGlobalScaling(); + + ::google::protobuf::internal::InternalMetadataWithArena _internal_metadata_; + ::google::protobuf::internal::ArenaStringPtr urdffilename_; + ::pybullet_grpc::vec3* initialposition_; + ::pybullet_grpc::quat4* initialorientation_; + ::google::protobuf::int32 urdfflags_; + union HasUseMultiBodyUnion { + HasUseMultiBodyUnion() {} + ::google::protobuf::int32 usemultibody_; + } hasUseMultiBody_; + union HasUseFixedBaseUnion { + HasUseFixedBaseUnion() {} + bool usefixedbase_; + } hasUseFixedBase_; + union HasGlobalScalingUnion { + HasGlobalScalingUnion() {} + double globalscaling_; + } hasGlobalScaling_; + mutable int _cached_size_; + ::google::protobuf::uint32 _oneof_case_[3]; + + friend struct protobuf_pybullet_2eproto::TableStruct; +}; +// ------------------------------------------------------------------- + +class LoadUrdfStatus : public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:pybullet_grpc.LoadUrdfStatus) */ { + public: + LoadUrdfStatus(); + virtual ~LoadUrdfStatus(); + + LoadUrdfStatus(const LoadUrdfStatus& from); + + inline LoadUrdfStatus& operator=(const LoadUrdfStatus& from) { + CopyFrom(from); + return *this; + } + + static const ::google::protobuf::Descriptor* descriptor(); + static const LoadUrdfStatus& default_instance(); + + static inline const LoadUrdfStatus* internal_default_instance() { + return reinterpret_cast( + &_LoadUrdfStatus_default_instance_); + } + + void Swap(LoadUrdfStatus* other); + + // implements Message ---------------------------------------------- + + inline LoadUrdfStatus* New() const PROTOBUF_FINAL { return New(NULL); } + + LoadUrdfStatus* New(::google::protobuf::Arena* arena) const PROTOBUF_FINAL; + void CopyFrom(const ::google::protobuf::Message& from) PROTOBUF_FINAL; + void MergeFrom(const ::google::protobuf::Message& from) PROTOBUF_FINAL; + void CopyFrom(const LoadUrdfStatus& from); + void MergeFrom(const LoadUrdfStatus& from); + void Clear() PROTOBUF_FINAL; + bool IsInitialized() const PROTOBUF_FINAL; + + size_t ByteSizeLong() const PROTOBUF_FINAL; + bool MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) PROTOBUF_FINAL; + void SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const PROTOBUF_FINAL; + ::google::protobuf::uint8* InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const PROTOBUF_FINAL; + ::google::protobuf::uint8* SerializeWithCachedSizesToArray(::google::protobuf::uint8* output) + const PROTOBUF_FINAL { + return InternalSerializeWithCachedSizesToArray( + ::google::protobuf::io::CodedOutputStream::IsDefaultSerializationDeterministic(), output); + } + int GetCachedSize() const PROTOBUF_FINAL { return _cached_size_; } + private: + void SharedCtor(); + void SharedDtor(); + void SetCachedSize(int size) const PROTOBUF_FINAL; + void InternalSwap(LoadUrdfStatus* other); + private: + inline ::google::protobuf::Arena* GetArenaNoVirtual() const { + return NULL; + } + inline void* MaybeArenaPtr() const { + return NULL; + } + public: + + ::google::protobuf::Metadata GetMetadata() const PROTOBUF_FINAL; + + // nested types ---------------------------------------------------- + + // accessors ------------------------------------------------------- + + // int32 objectUniqueId = 1; + void clear_objectuniqueid(); + static const int kObjectUniqueIdFieldNumber = 1; + ::google::protobuf::int32 objectuniqueid() const; + void set_objectuniqueid(::google::protobuf::int32 value); + + // @@protoc_insertion_point(class_scope:pybullet_grpc.LoadUrdfStatus) + private: + + ::google::protobuf::internal::InternalMetadataWithArena _internal_metadata_; + ::google::protobuf::int32 objectuniqueid_; + mutable int _cached_size_; + friend struct protobuf_pybullet_2eproto::TableStruct; +}; +// ------------------------------------------------------------------- + +class PyBulletCommand : public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:pybullet_grpc.PyBulletCommand) */ { + public: + PyBulletCommand(); + virtual ~PyBulletCommand(); + + PyBulletCommand(const PyBulletCommand& from); + + inline PyBulletCommand& operator=(const PyBulletCommand& from) { + CopyFrom(from); + return *this; + } + + static const ::google::protobuf::Descriptor* descriptor(); + static const PyBulletCommand& default_instance(); + + enum CommandsCase { + kLoadUrdfCommand = 3, + kTerminateServerCommand = 4, + kStepSimulationCommand = 5, + COMMANDS_NOT_SET = 0, + }; + + static inline const PyBulletCommand* internal_default_instance() { + return reinterpret_cast( + &_PyBulletCommand_default_instance_); + } + + void Swap(PyBulletCommand* other); + + // implements Message ---------------------------------------------- + + inline PyBulletCommand* New() const PROTOBUF_FINAL { return New(NULL); } + + PyBulletCommand* New(::google::protobuf::Arena* arena) const PROTOBUF_FINAL; + void CopyFrom(const ::google::protobuf::Message& from) PROTOBUF_FINAL; + void MergeFrom(const ::google::protobuf::Message& from) PROTOBUF_FINAL; + void CopyFrom(const PyBulletCommand& from); + void MergeFrom(const PyBulletCommand& from); + void Clear() PROTOBUF_FINAL; + bool IsInitialized() const PROTOBUF_FINAL; + + size_t ByteSizeLong() const PROTOBUF_FINAL; + bool MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) PROTOBUF_FINAL; + void SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const PROTOBUF_FINAL; + ::google::protobuf::uint8* InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const PROTOBUF_FINAL; + ::google::protobuf::uint8* SerializeWithCachedSizesToArray(::google::protobuf::uint8* output) + const PROTOBUF_FINAL { + return InternalSerializeWithCachedSizesToArray( + ::google::protobuf::io::CodedOutputStream::IsDefaultSerializationDeterministic(), output); + } + int GetCachedSize() const PROTOBUF_FINAL { return _cached_size_; } + private: + void SharedCtor(); + void SharedDtor(); + void SetCachedSize(int size) const PROTOBUF_FINAL; + void InternalSwap(PyBulletCommand* other); + private: + inline ::google::protobuf::Arena* GetArenaNoVirtual() const { + return NULL; + } + inline void* MaybeArenaPtr() const { + return NULL; + } + public: + + ::google::protobuf::Metadata GetMetadata() const PROTOBUF_FINAL; + + // nested types ---------------------------------------------------- + + // accessors ------------------------------------------------------- + + // int32 commandType = 1; + void clear_commandtype(); + static const int kCommandTypeFieldNumber = 1; + ::google::protobuf::int32 commandtype() const; + void set_commandtype(::google::protobuf::int32 value); + + // .pybullet_grpc.LoadUrdfCommand loadUrdfCommand = 3; + bool has_loadurdfcommand() const; + void clear_loadurdfcommand(); + static const int kLoadUrdfCommandFieldNumber = 3; + const ::pybullet_grpc::LoadUrdfCommand& loadurdfcommand() const; + ::pybullet_grpc::LoadUrdfCommand* mutable_loadurdfcommand(); + ::pybullet_grpc::LoadUrdfCommand* release_loadurdfcommand(); + void set_allocated_loadurdfcommand(::pybullet_grpc::LoadUrdfCommand* loadurdfcommand); + + // .pybullet_grpc.TerminateServerCommand terminateServerCommand = 4; + bool has_terminateservercommand() const; + void clear_terminateservercommand(); + static const int kTerminateServerCommandFieldNumber = 4; + const ::pybullet_grpc::TerminateServerCommand& terminateservercommand() const; + ::pybullet_grpc::TerminateServerCommand* mutable_terminateservercommand(); + ::pybullet_grpc::TerminateServerCommand* release_terminateservercommand(); + void set_allocated_terminateservercommand(::pybullet_grpc::TerminateServerCommand* terminateservercommand); + + // .pybullet_grpc.StepSimulationCommand stepSimulationCommand = 5; + bool has_stepsimulationcommand() const; + void clear_stepsimulationcommand(); + static const int kStepSimulationCommandFieldNumber = 5; + const ::pybullet_grpc::StepSimulationCommand& stepsimulationcommand() const; + ::pybullet_grpc::StepSimulationCommand* mutable_stepsimulationcommand(); + ::pybullet_grpc::StepSimulationCommand* release_stepsimulationcommand(); + void set_allocated_stepsimulationcommand(::pybullet_grpc::StepSimulationCommand* stepsimulationcommand); + + CommandsCase commands_case() const; + // @@protoc_insertion_point(class_scope:pybullet_grpc.PyBulletCommand) + private: + void set_has_loadurdfcommand(); + void set_has_terminateservercommand(); + void set_has_stepsimulationcommand(); + + inline bool has_commands() const; + void clear_commands(); + inline void clear_has_commands(); + + ::google::protobuf::internal::InternalMetadataWithArena _internal_metadata_; + ::google::protobuf::int32 commandtype_; + union CommandsUnion { + CommandsUnion() {} + ::pybullet_grpc::LoadUrdfCommand* loadurdfcommand_; + ::pybullet_grpc::TerminateServerCommand* terminateservercommand_; + ::pybullet_grpc::StepSimulationCommand* stepsimulationcommand_; + } commands_; + mutable int _cached_size_; + ::google::protobuf::uint32 _oneof_case_[1]; + + friend struct protobuf_pybullet_2eproto::TableStruct; +}; +// ------------------------------------------------------------------- + +class PyBulletStatus : public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:pybullet_grpc.PyBulletStatus) */ { + public: + PyBulletStatus(); + virtual ~PyBulletStatus(); + + PyBulletStatus(const PyBulletStatus& from); + + inline PyBulletStatus& operator=(const PyBulletStatus& from) { + CopyFrom(from); + return *this; + } + + static const ::google::protobuf::Descriptor* descriptor(); + static const PyBulletStatus& default_instance(); + + enum StatusCase { + kUrdfStatus = 2, + STATUS_NOT_SET = 0, + }; + + static inline const PyBulletStatus* internal_default_instance() { + return reinterpret_cast( + &_PyBulletStatus_default_instance_); + } + + void Swap(PyBulletStatus* other); + + // implements Message ---------------------------------------------- + + inline PyBulletStatus* New() const PROTOBUF_FINAL { return New(NULL); } + + PyBulletStatus* New(::google::protobuf::Arena* arena) const PROTOBUF_FINAL; + void CopyFrom(const ::google::protobuf::Message& from) PROTOBUF_FINAL; + void MergeFrom(const ::google::protobuf::Message& from) PROTOBUF_FINAL; + void CopyFrom(const PyBulletStatus& from); + void MergeFrom(const PyBulletStatus& from); + void Clear() PROTOBUF_FINAL; + bool IsInitialized() const PROTOBUF_FINAL; + + size_t ByteSizeLong() const PROTOBUF_FINAL; + bool MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) PROTOBUF_FINAL; + void SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const PROTOBUF_FINAL; + ::google::protobuf::uint8* InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const PROTOBUF_FINAL; + ::google::protobuf::uint8* SerializeWithCachedSizesToArray(::google::protobuf::uint8* output) + const PROTOBUF_FINAL { + return InternalSerializeWithCachedSizesToArray( + ::google::protobuf::io::CodedOutputStream::IsDefaultSerializationDeterministic(), output); + } + int GetCachedSize() const PROTOBUF_FINAL { return _cached_size_; } + private: + void SharedCtor(); + void SharedDtor(); + void SetCachedSize(int size) const PROTOBUF_FINAL; + void InternalSwap(PyBulletStatus* other); + private: + inline ::google::protobuf::Arena* GetArenaNoVirtual() const { + return NULL; + } + inline void* MaybeArenaPtr() const { + return NULL; + } + public: + + ::google::protobuf::Metadata GetMetadata() const PROTOBUF_FINAL; + + // nested types ---------------------------------------------------- + + // accessors ------------------------------------------------------- + + // int32 statusType = 1; + void clear_statustype(); + static const int kStatusTypeFieldNumber = 1; + ::google::protobuf::int32 statustype() const; + void set_statustype(::google::protobuf::int32 value); + + // .pybullet_grpc.LoadUrdfStatus urdfStatus = 2; + bool has_urdfstatus() const; + void clear_urdfstatus(); + static const int kUrdfStatusFieldNumber = 2; + const ::pybullet_grpc::LoadUrdfStatus& urdfstatus() const; + ::pybullet_grpc::LoadUrdfStatus* mutable_urdfstatus(); + ::pybullet_grpc::LoadUrdfStatus* release_urdfstatus(); + void set_allocated_urdfstatus(::pybullet_grpc::LoadUrdfStatus* urdfstatus); + + StatusCase status_case() const; + // @@protoc_insertion_point(class_scope:pybullet_grpc.PyBulletStatus) + private: + void set_has_urdfstatus(); + + inline bool has_status() const; + void clear_status(); + inline void clear_has_status(); + + ::google::protobuf::internal::InternalMetadataWithArena _internal_metadata_; + ::google::protobuf::int32 statustype_; + union StatusUnion { + StatusUnion() {} + ::pybullet_grpc::LoadUrdfStatus* urdfstatus_; + } status_; + mutable int _cached_size_; + ::google::protobuf::uint32 _oneof_case_[1]; + + friend struct protobuf_pybullet_2eproto::TableStruct; +}; +// =================================================================== + + +// =================================================================== + +#if !PROTOBUF_INLINE_NOT_IN_HEADERS +// vec3 + +// double x = 1; +inline void vec3::clear_x() { + x_ = 0; +} +inline double vec3::x() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.vec3.x) + return x_; +} +inline void vec3::set_x(double value) { + + x_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.vec3.x) +} + +// double y = 2; +inline void vec3::clear_y() { + y_ = 0; +} +inline double vec3::y() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.vec3.y) + return y_; +} +inline void vec3::set_y(double value) { + + y_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.vec3.y) +} + +// double z = 3; +inline void vec3::clear_z() { + z_ = 0; +} +inline double vec3::z() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.vec3.z) + return z_; +} +inline void vec3::set_z(double value) { + + z_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.vec3.z) +} + +// ------------------------------------------------------------------- + +// quat4 + +// double x = 1; +inline void quat4::clear_x() { + x_ = 0; +} +inline double quat4::x() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.quat4.x) + return x_; +} +inline void quat4::set_x(double value) { + + x_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.quat4.x) +} + +// double y = 2; +inline void quat4::clear_y() { + y_ = 0; +} +inline double quat4::y() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.quat4.y) + return y_; +} +inline void quat4::set_y(double value) { + + y_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.quat4.y) +} + +// double z = 3; +inline void quat4::clear_z() { + z_ = 0; +} +inline double quat4::z() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.quat4.z) + return z_; +} +inline void quat4::set_z(double value) { + + z_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.quat4.z) +} + +// double w = 4; +inline void quat4::clear_w() { + w_ = 0; +} +inline double quat4::w() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.quat4.w) + return w_; +} +inline void quat4::set_w(double value) { + + w_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.quat4.w) +} + +// ------------------------------------------------------------------- + +// TerminateServerCommand + +// string exitReason = 1; +inline void TerminateServerCommand::clear_exitreason() { + exitreason_.ClearToEmptyNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); +} +inline const ::std::string& TerminateServerCommand::exitreason() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.TerminateServerCommand.exitReason) + return exitreason_.GetNoArena(); +} +inline void TerminateServerCommand::set_exitreason(const ::std::string& value) { + + exitreason_.SetNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), value); + // @@protoc_insertion_point(field_set:pybullet_grpc.TerminateServerCommand.exitReason) +} +#if LANG_CXX11 +inline void TerminateServerCommand::set_exitreason(::std::string&& value) { + + exitreason_.SetNoArena( + &::google::protobuf::internal::GetEmptyStringAlreadyInited(), std::move(value)); + // @@protoc_insertion_point(field_set_rvalue:pybullet_grpc.TerminateServerCommand.exitReason) +} +#endif +inline void TerminateServerCommand::set_exitreason(const char* value) { + + exitreason_.SetNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), ::std::string(value)); + // @@protoc_insertion_point(field_set_char:pybullet_grpc.TerminateServerCommand.exitReason) +} +inline void TerminateServerCommand::set_exitreason(const char* value, size_t size) { + + exitreason_.SetNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), + ::std::string(reinterpret_cast(value), size)); + // @@protoc_insertion_point(field_set_pointer:pybullet_grpc.TerminateServerCommand.exitReason) +} +inline ::std::string* TerminateServerCommand::mutable_exitreason() { + + // @@protoc_insertion_point(field_mutable:pybullet_grpc.TerminateServerCommand.exitReason) + return exitreason_.MutableNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); +} +inline ::std::string* TerminateServerCommand::release_exitreason() { + // @@protoc_insertion_point(field_release:pybullet_grpc.TerminateServerCommand.exitReason) + + return exitreason_.ReleaseNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); +} +inline void TerminateServerCommand::set_allocated_exitreason(::std::string* exitreason) { + if (exitreason != NULL) { + + } else { + + } + exitreason_.SetAllocatedNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), exitreason); + // @@protoc_insertion_point(field_set_allocated:pybullet_grpc.TerminateServerCommand.exitReason) +} + +// ------------------------------------------------------------------- + +// StepSimulationCommand + +// ------------------------------------------------------------------- + +// LoadUrdfCommand + +// string urdfFileName = 1; +inline void LoadUrdfCommand::clear_urdffilename() { + urdffilename_.ClearToEmptyNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); +} +inline const ::std::string& LoadUrdfCommand::urdffilename() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.LoadUrdfCommand.urdfFileName) + return urdffilename_.GetNoArena(); +} +inline void LoadUrdfCommand::set_urdffilename(const ::std::string& value) { + + urdffilename_.SetNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), value); + // @@protoc_insertion_point(field_set:pybullet_grpc.LoadUrdfCommand.urdfFileName) +} +#if LANG_CXX11 +inline void LoadUrdfCommand::set_urdffilename(::std::string&& value) { + + urdffilename_.SetNoArena( + &::google::protobuf::internal::GetEmptyStringAlreadyInited(), std::move(value)); + // @@protoc_insertion_point(field_set_rvalue:pybullet_grpc.LoadUrdfCommand.urdfFileName) +} +#endif +inline void LoadUrdfCommand::set_urdffilename(const char* value) { + + urdffilename_.SetNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), ::std::string(value)); + // @@protoc_insertion_point(field_set_char:pybullet_grpc.LoadUrdfCommand.urdfFileName) +} +inline void LoadUrdfCommand::set_urdffilename(const char* value, size_t size) { + + urdffilename_.SetNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), + ::std::string(reinterpret_cast(value), size)); + // @@protoc_insertion_point(field_set_pointer:pybullet_grpc.LoadUrdfCommand.urdfFileName) +} +inline ::std::string* LoadUrdfCommand::mutable_urdffilename() { + + // @@protoc_insertion_point(field_mutable:pybullet_grpc.LoadUrdfCommand.urdfFileName) + return urdffilename_.MutableNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); +} +inline ::std::string* LoadUrdfCommand::release_urdffilename() { + // @@protoc_insertion_point(field_release:pybullet_grpc.LoadUrdfCommand.urdfFileName) + + return urdffilename_.ReleaseNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); +} +inline void LoadUrdfCommand::set_allocated_urdffilename(::std::string* urdffilename) { + if (urdffilename != NULL) { + + } else { + + } + urdffilename_.SetAllocatedNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), urdffilename); + // @@protoc_insertion_point(field_set_allocated:pybullet_grpc.LoadUrdfCommand.urdfFileName) +} + +// .pybullet_grpc.vec3 initialPosition = 2; +inline bool LoadUrdfCommand::has_initialposition() const { + return this != internal_default_instance() && initialposition_ != NULL; +} +inline void LoadUrdfCommand::clear_initialposition() { + if (GetArenaNoVirtual() == NULL && initialposition_ != NULL) delete initialposition_; + initialposition_ = NULL; +} +inline const ::pybullet_grpc::vec3& LoadUrdfCommand::initialposition() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.LoadUrdfCommand.initialPosition) + return initialposition_ != NULL ? *initialposition_ + : *::pybullet_grpc::vec3::internal_default_instance(); +} +inline ::pybullet_grpc::vec3* LoadUrdfCommand::mutable_initialposition() { + + if (initialposition_ == NULL) { + initialposition_ = new ::pybullet_grpc::vec3; + } + // @@protoc_insertion_point(field_mutable:pybullet_grpc.LoadUrdfCommand.initialPosition) + return initialposition_; +} +inline ::pybullet_grpc::vec3* LoadUrdfCommand::release_initialposition() { + // @@protoc_insertion_point(field_release:pybullet_grpc.LoadUrdfCommand.initialPosition) + + ::pybullet_grpc::vec3* temp = initialposition_; + initialposition_ = NULL; + return temp; +} +inline void LoadUrdfCommand::set_allocated_initialposition(::pybullet_grpc::vec3* initialposition) { + delete initialposition_; + initialposition_ = initialposition; + if (initialposition) { + + } else { + + } + // @@protoc_insertion_point(field_set_allocated:pybullet_grpc.LoadUrdfCommand.initialPosition) +} + +// .pybullet_grpc.quat4 initialOrientation = 3; +inline bool LoadUrdfCommand::has_initialorientation() const { + return this != internal_default_instance() && initialorientation_ != NULL; +} +inline void LoadUrdfCommand::clear_initialorientation() { + if (GetArenaNoVirtual() == NULL && initialorientation_ != NULL) delete initialorientation_; + initialorientation_ = NULL; +} +inline const ::pybullet_grpc::quat4& LoadUrdfCommand::initialorientation() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.LoadUrdfCommand.initialOrientation) + return initialorientation_ != NULL ? *initialorientation_ + : *::pybullet_grpc::quat4::internal_default_instance(); +} +inline ::pybullet_grpc::quat4* LoadUrdfCommand::mutable_initialorientation() { + + if (initialorientation_ == NULL) { + initialorientation_ = new ::pybullet_grpc::quat4; + } + // @@protoc_insertion_point(field_mutable:pybullet_grpc.LoadUrdfCommand.initialOrientation) + return initialorientation_; +} +inline ::pybullet_grpc::quat4* LoadUrdfCommand::release_initialorientation() { + // @@protoc_insertion_point(field_release:pybullet_grpc.LoadUrdfCommand.initialOrientation) + + ::pybullet_grpc::quat4* temp = initialorientation_; + initialorientation_ = NULL; + return temp; +} +inline void LoadUrdfCommand::set_allocated_initialorientation(::pybullet_grpc::quat4* initialorientation) { + delete initialorientation_; + initialorientation_ = initialorientation; + if (initialorientation) { + + } else { + + } + // @@protoc_insertion_point(field_set_allocated:pybullet_grpc.LoadUrdfCommand.initialOrientation) +} + +// int32 useMultiBody = 4; +inline bool LoadUrdfCommand::has_usemultibody() const { + return hasUseMultiBody_case() == kUseMultiBody; +} +inline void LoadUrdfCommand::set_has_usemultibody() { + _oneof_case_[0] = kUseMultiBody; +} +inline void LoadUrdfCommand::clear_usemultibody() { + if (has_usemultibody()) { + hasUseMultiBody_.usemultibody_ = 0; + clear_has_hasUseMultiBody(); + } +} +inline ::google::protobuf::int32 LoadUrdfCommand::usemultibody() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.LoadUrdfCommand.useMultiBody) + if (has_usemultibody()) { + return hasUseMultiBody_.usemultibody_; + } + return 0; +} +inline void LoadUrdfCommand::set_usemultibody(::google::protobuf::int32 value) { + if (!has_usemultibody()) { + clear_hasUseMultiBody(); + set_has_usemultibody(); + } + hasUseMultiBody_.usemultibody_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.LoadUrdfCommand.useMultiBody) +} + +// bool useFixedBase = 5; +inline bool LoadUrdfCommand::has_usefixedbase() const { + return hasUseFixedBase_case() == kUseFixedBase; +} +inline void LoadUrdfCommand::set_has_usefixedbase() { + _oneof_case_[1] = kUseFixedBase; +} +inline void LoadUrdfCommand::clear_usefixedbase() { + if (has_usefixedbase()) { + hasUseFixedBase_.usefixedbase_ = false; + clear_has_hasUseFixedBase(); + } +} +inline bool LoadUrdfCommand::usefixedbase() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.LoadUrdfCommand.useFixedBase) + if (has_usefixedbase()) { + return hasUseFixedBase_.usefixedbase_; + } + return false; +} +inline void LoadUrdfCommand::set_usefixedbase(bool value) { + if (!has_usefixedbase()) { + clear_hasUseFixedBase(); + set_has_usefixedbase(); + } + hasUseFixedBase_.usefixedbase_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.LoadUrdfCommand.useFixedBase) +} + +// int32 urdfFlags = 6; +inline void LoadUrdfCommand::clear_urdfflags() { + urdfflags_ = 0; +} +inline ::google::protobuf::int32 LoadUrdfCommand::urdfflags() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.LoadUrdfCommand.urdfFlags) + return urdfflags_; +} +inline void LoadUrdfCommand::set_urdfflags(::google::protobuf::int32 value) { + + urdfflags_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.LoadUrdfCommand.urdfFlags) +} + +// double globalScaling = 7; +inline bool LoadUrdfCommand::has_globalscaling() const { + return hasGlobalScaling_case() == kGlobalScaling; +} +inline void LoadUrdfCommand::set_has_globalscaling() { + _oneof_case_[2] = kGlobalScaling; +} +inline void LoadUrdfCommand::clear_globalscaling() { + if (has_globalscaling()) { + hasGlobalScaling_.globalscaling_ = 0; + clear_has_hasGlobalScaling(); + } +} +inline double LoadUrdfCommand::globalscaling() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.LoadUrdfCommand.globalScaling) + if (has_globalscaling()) { + return hasGlobalScaling_.globalscaling_; + } + return 0; +} +inline void LoadUrdfCommand::set_globalscaling(double value) { + if (!has_globalscaling()) { + clear_hasGlobalScaling(); + set_has_globalscaling(); + } + hasGlobalScaling_.globalscaling_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.LoadUrdfCommand.globalScaling) +} + +inline bool LoadUrdfCommand::has_hasUseMultiBody() const { + return hasUseMultiBody_case() != HASUSEMULTIBODY_NOT_SET; +} +inline void LoadUrdfCommand::clear_has_hasUseMultiBody() { + _oneof_case_[0] = HASUSEMULTIBODY_NOT_SET; +} +inline bool LoadUrdfCommand::has_hasUseFixedBase() const { + return hasUseFixedBase_case() != HASUSEFIXEDBASE_NOT_SET; +} +inline void LoadUrdfCommand::clear_has_hasUseFixedBase() { + _oneof_case_[1] = HASUSEFIXEDBASE_NOT_SET; +} +inline bool LoadUrdfCommand::has_hasGlobalScaling() const { + return hasGlobalScaling_case() != HASGLOBALSCALING_NOT_SET; +} +inline void LoadUrdfCommand::clear_has_hasGlobalScaling() { + _oneof_case_[2] = HASGLOBALSCALING_NOT_SET; +} +inline LoadUrdfCommand::HasUseMultiBodyCase LoadUrdfCommand::hasUseMultiBody_case() const { + return LoadUrdfCommand::HasUseMultiBodyCase(_oneof_case_[0]); +} +inline LoadUrdfCommand::HasUseFixedBaseCase LoadUrdfCommand::hasUseFixedBase_case() const { + return LoadUrdfCommand::HasUseFixedBaseCase(_oneof_case_[1]); +} +inline LoadUrdfCommand::HasGlobalScalingCase LoadUrdfCommand::hasGlobalScaling_case() const { + return LoadUrdfCommand::HasGlobalScalingCase(_oneof_case_[2]); +} +// ------------------------------------------------------------------- + +// LoadUrdfStatus + +// int32 objectUniqueId = 1; +inline void LoadUrdfStatus::clear_objectuniqueid() { + objectuniqueid_ = 0; +} +inline ::google::protobuf::int32 LoadUrdfStatus::objectuniqueid() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.LoadUrdfStatus.objectUniqueId) + return objectuniqueid_; +} +inline void LoadUrdfStatus::set_objectuniqueid(::google::protobuf::int32 value) { + + objectuniqueid_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.LoadUrdfStatus.objectUniqueId) +} + +// ------------------------------------------------------------------- + +// PyBulletCommand + +// int32 commandType = 1; +inline void PyBulletCommand::clear_commandtype() { + commandtype_ = 0; +} +inline ::google::protobuf::int32 PyBulletCommand::commandtype() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.PyBulletCommand.commandType) + return commandtype_; +} +inline void PyBulletCommand::set_commandtype(::google::protobuf::int32 value) { + + commandtype_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.PyBulletCommand.commandType) +} + +// .pybullet_grpc.LoadUrdfCommand loadUrdfCommand = 3; +inline bool PyBulletCommand::has_loadurdfcommand() const { + return commands_case() == kLoadUrdfCommand; +} +inline void PyBulletCommand::set_has_loadurdfcommand() { + _oneof_case_[0] = kLoadUrdfCommand; +} +inline void PyBulletCommand::clear_loadurdfcommand() { + if (has_loadurdfcommand()) { + delete commands_.loadurdfcommand_; + clear_has_commands(); + } +} +inline const ::pybullet_grpc::LoadUrdfCommand& PyBulletCommand::loadurdfcommand() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.PyBulletCommand.loadUrdfCommand) + return has_loadurdfcommand() + ? *commands_.loadurdfcommand_ + : ::pybullet_grpc::LoadUrdfCommand::default_instance(); +} +inline ::pybullet_grpc::LoadUrdfCommand* PyBulletCommand::mutable_loadurdfcommand() { + if (!has_loadurdfcommand()) { + clear_commands(); + set_has_loadurdfcommand(); + commands_.loadurdfcommand_ = new ::pybullet_grpc::LoadUrdfCommand; + } + // @@protoc_insertion_point(field_mutable:pybullet_grpc.PyBulletCommand.loadUrdfCommand) + return commands_.loadurdfcommand_; +} +inline ::pybullet_grpc::LoadUrdfCommand* PyBulletCommand::release_loadurdfcommand() { + // @@protoc_insertion_point(field_release:pybullet_grpc.PyBulletCommand.loadUrdfCommand) + if (has_loadurdfcommand()) { + clear_has_commands(); + ::pybullet_grpc::LoadUrdfCommand* temp = commands_.loadurdfcommand_; + commands_.loadurdfcommand_ = NULL; + return temp; + } else { + return NULL; + } +} +inline void PyBulletCommand::set_allocated_loadurdfcommand(::pybullet_grpc::LoadUrdfCommand* loadurdfcommand) { + clear_commands(); + if (loadurdfcommand) { + set_has_loadurdfcommand(); + commands_.loadurdfcommand_ = loadurdfcommand; + } + // @@protoc_insertion_point(field_set_allocated:pybullet_grpc.PyBulletCommand.loadUrdfCommand) +} + +// .pybullet_grpc.TerminateServerCommand terminateServerCommand = 4; +inline bool PyBulletCommand::has_terminateservercommand() const { + return commands_case() == kTerminateServerCommand; +} +inline void PyBulletCommand::set_has_terminateservercommand() { + _oneof_case_[0] = kTerminateServerCommand; +} +inline void PyBulletCommand::clear_terminateservercommand() { + if (has_terminateservercommand()) { + delete commands_.terminateservercommand_; + clear_has_commands(); + } +} +inline const ::pybullet_grpc::TerminateServerCommand& PyBulletCommand::terminateservercommand() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.PyBulletCommand.terminateServerCommand) + return has_terminateservercommand() + ? *commands_.terminateservercommand_ + : ::pybullet_grpc::TerminateServerCommand::default_instance(); +} +inline ::pybullet_grpc::TerminateServerCommand* PyBulletCommand::mutable_terminateservercommand() { + if (!has_terminateservercommand()) { + clear_commands(); + set_has_terminateservercommand(); + commands_.terminateservercommand_ = new ::pybullet_grpc::TerminateServerCommand; + } + // @@protoc_insertion_point(field_mutable:pybullet_grpc.PyBulletCommand.terminateServerCommand) + return commands_.terminateservercommand_; +} +inline ::pybullet_grpc::TerminateServerCommand* PyBulletCommand::release_terminateservercommand() { + // @@protoc_insertion_point(field_release:pybullet_grpc.PyBulletCommand.terminateServerCommand) + if (has_terminateservercommand()) { + clear_has_commands(); + ::pybullet_grpc::TerminateServerCommand* temp = commands_.terminateservercommand_; + commands_.terminateservercommand_ = NULL; + return temp; + } else { + return NULL; + } +} +inline void PyBulletCommand::set_allocated_terminateservercommand(::pybullet_grpc::TerminateServerCommand* terminateservercommand) { + clear_commands(); + if (terminateservercommand) { + set_has_terminateservercommand(); + commands_.terminateservercommand_ = terminateservercommand; + } + // @@protoc_insertion_point(field_set_allocated:pybullet_grpc.PyBulletCommand.terminateServerCommand) +} + +// .pybullet_grpc.StepSimulationCommand stepSimulationCommand = 5; +inline bool PyBulletCommand::has_stepsimulationcommand() const { + return commands_case() == kStepSimulationCommand; +} +inline void PyBulletCommand::set_has_stepsimulationcommand() { + _oneof_case_[0] = kStepSimulationCommand; +} +inline void PyBulletCommand::clear_stepsimulationcommand() { + if (has_stepsimulationcommand()) { + delete commands_.stepsimulationcommand_; + clear_has_commands(); + } +} +inline const ::pybullet_grpc::StepSimulationCommand& PyBulletCommand::stepsimulationcommand() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.PyBulletCommand.stepSimulationCommand) + return has_stepsimulationcommand() + ? *commands_.stepsimulationcommand_ + : ::pybullet_grpc::StepSimulationCommand::default_instance(); +} +inline ::pybullet_grpc::StepSimulationCommand* PyBulletCommand::mutable_stepsimulationcommand() { + if (!has_stepsimulationcommand()) { + clear_commands(); + set_has_stepsimulationcommand(); + commands_.stepsimulationcommand_ = new ::pybullet_grpc::StepSimulationCommand; + } + // @@protoc_insertion_point(field_mutable:pybullet_grpc.PyBulletCommand.stepSimulationCommand) + return commands_.stepsimulationcommand_; +} +inline ::pybullet_grpc::StepSimulationCommand* PyBulletCommand::release_stepsimulationcommand() { + // @@protoc_insertion_point(field_release:pybullet_grpc.PyBulletCommand.stepSimulationCommand) + if (has_stepsimulationcommand()) { + clear_has_commands(); + ::pybullet_grpc::StepSimulationCommand* temp = commands_.stepsimulationcommand_; + commands_.stepsimulationcommand_ = NULL; + return temp; + } else { + return NULL; + } +} +inline void PyBulletCommand::set_allocated_stepsimulationcommand(::pybullet_grpc::StepSimulationCommand* stepsimulationcommand) { + clear_commands(); + if (stepsimulationcommand) { + set_has_stepsimulationcommand(); + commands_.stepsimulationcommand_ = stepsimulationcommand; + } + // @@protoc_insertion_point(field_set_allocated:pybullet_grpc.PyBulletCommand.stepSimulationCommand) +} + +inline bool PyBulletCommand::has_commands() const { + return commands_case() != COMMANDS_NOT_SET; +} +inline void PyBulletCommand::clear_has_commands() { + _oneof_case_[0] = COMMANDS_NOT_SET; +} +inline PyBulletCommand::CommandsCase PyBulletCommand::commands_case() const { + return PyBulletCommand::CommandsCase(_oneof_case_[0]); +} +// ------------------------------------------------------------------- + +// PyBulletStatus + +// int32 statusType = 1; +inline void PyBulletStatus::clear_statustype() { + statustype_ = 0; +} +inline ::google::protobuf::int32 PyBulletStatus::statustype() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.PyBulletStatus.statusType) + return statustype_; +} +inline void PyBulletStatus::set_statustype(::google::protobuf::int32 value) { + + statustype_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.PyBulletStatus.statusType) +} + +// .pybullet_grpc.LoadUrdfStatus urdfStatus = 2; +inline bool PyBulletStatus::has_urdfstatus() const { + return status_case() == kUrdfStatus; +} +inline void PyBulletStatus::set_has_urdfstatus() { + _oneof_case_[0] = kUrdfStatus; +} +inline void PyBulletStatus::clear_urdfstatus() { + if (has_urdfstatus()) { + delete status_.urdfstatus_; + clear_has_status(); + } +} +inline const ::pybullet_grpc::LoadUrdfStatus& PyBulletStatus::urdfstatus() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.PyBulletStatus.urdfStatus) + return has_urdfstatus() + ? *status_.urdfstatus_ + : ::pybullet_grpc::LoadUrdfStatus::default_instance(); +} +inline ::pybullet_grpc::LoadUrdfStatus* PyBulletStatus::mutable_urdfstatus() { + if (!has_urdfstatus()) { + clear_status(); + set_has_urdfstatus(); + status_.urdfstatus_ = new ::pybullet_grpc::LoadUrdfStatus; + } + // @@protoc_insertion_point(field_mutable:pybullet_grpc.PyBulletStatus.urdfStatus) + return status_.urdfstatus_; +} +inline ::pybullet_grpc::LoadUrdfStatus* PyBulletStatus::release_urdfstatus() { + // @@protoc_insertion_point(field_release:pybullet_grpc.PyBulletStatus.urdfStatus) + if (has_urdfstatus()) { + clear_has_status(); + ::pybullet_grpc::LoadUrdfStatus* temp = status_.urdfstatus_; + status_.urdfstatus_ = NULL; + return temp; + } else { + return NULL; + } +} +inline void PyBulletStatus::set_allocated_urdfstatus(::pybullet_grpc::LoadUrdfStatus* urdfstatus) { + clear_status(); + if (urdfstatus) { + set_has_urdfstatus(); + status_.urdfstatus_ = urdfstatus; + } + // @@protoc_insertion_point(field_set_allocated:pybullet_grpc.PyBulletStatus.urdfStatus) +} + +inline bool PyBulletStatus::has_status() const { + return status_case() != STATUS_NOT_SET; +} +inline void PyBulletStatus::clear_has_status() { + _oneof_case_[0] = STATUS_NOT_SET; +} +inline PyBulletStatus::StatusCase PyBulletStatus::status_case() const { + return PyBulletStatus::StatusCase(_oneof_case_[0]); +} +#endif // !PROTOBUF_INLINE_NOT_IN_HEADERS +// ------------------------------------------------------------------- + +// ------------------------------------------------------------------- + +// ------------------------------------------------------------------- + +// ------------------------------------------------------------------- + +// ------------------------------------------------------------------- + +// ------------------------------------------------------------------- + +// ------------------------------------------------------------------- + + +// @@protoc_insertion_point(namespace_scope) + + +} // namespace pybullet_grpc + +// @@protoc_insertion_point(global_scope) + +#endif // PROTOBUF_pybullet_2eproto__INCLUDED diff --git a/examples/SharedMemory/grpc/pybullet_client.py b/examples/SharedMemory/grpc/pybullet_client.py new file mode 100644 index 000000000..205113bc9 --- /dev/null +++ b/examples/SharedMemory/grpc/pybullet_client.py @@ -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() diff --git a/examples/SharedMemory/grpc/pybullet_pb2.py b/examples/SharedMemory/grpc/pybullet_pb2.py new file mode 100644 index 000000000..7bbea2282 --- /dev/null +++ b/examples/SharedMemory/grpc/pybullet_pb2.py @@ -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) diff --git a/examples/SharedMemory/grpc/pybullet_pb2_grpc.py b/examples/SharedMemory/grpc/pybullet_pb2_grpc.py new file mode 100644 index 000000000..3d2724010 --- /dev/null +++ b/examples/SharedMemory/grpc/pybullet_pb2_grpc.py @@ -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,)) diff --git a/examples/SharedMemory/premake4.lua b/examples/SharedMemory/premake4.lua index 6330786cf..82dfe1996 100644 --- a/examples/SharedMemory/premake4.lua +++ b/examples/SharedMemory/premake4.lua @@ -466,6 +466,7 @@ end include "udp" include "tcp" + include "plugins/testPlugin" include "plugins/vrSyncPlugin" include "plugins/tinyRendererPlugin" @@ -473,3 +474,6 @@ include "plugins/tinyRendererPlugin" include "plugins/pdControlPlugin" include "plugins/collisionFilterPlugin" +if _OPTIONS["grpc"] then + include "grpc" +end \ No newline at end of file