From 23e84ca9b6827cb4c77ffce93ec9952bb4b02d68 Mon Sep 17 00:00:00 2001 From: erwincoumans Date: Sat, 1 Sep 2018 13:49:56 -0700 Subject: [PATCH 1/3] more work on proto/pybullet.proto --- examples/SharedMemory/PhysicsClientC_API.cpp | 180 +- examples/SharedMemory/PhysicsClientC_API.h | 28 + .../PhysicsServerCommandProcessor.cpp | 37 + examples/SharedMemory/SharedMemoryPublic.h | 7 + .../SharedMemory/grpc/ConvertGRPCBullet.cpp | 350 +- examples/SharedMemory/grpc/premake4.lua | 20 +- .../SharedMemory/grpc/proto/pybullet.proto | 132 +- examples/SharedMemory/grpc/pybullet.pb.cpp | 7941 ++++++++++++++++- examples/SharedMemory/grpc/pybullet.pb.h | 3950 +++++++- examples/SharedMemory/grpc/pybullet_client.py | 60 +- examples/SharedMemory/grpc/pybullet_pb2.py | 967 +- 11 files changed, 13387 insertions(+), 285 deletions(-) diff --git a/examples/SharedMemory/PhysicsClientC_API.cpp b/examples/SharedMemory/PhysicsClientC_API.cpp index 94d347318..454a2bfc6 100644 --- a/examples/SharedMemory/PhysicsClientC_API.cpp +++ b/examples/SharedMemory/PhysicsClientC_API.cpp @@ -17,18 +17,26 @@ B3_SHARED_API b3SharedMemoryCommandHandle b3LoadSdfCommandInit(b3PhysicsClientHa struct SharedMemoryCommand* command = cl->getAvailableSharedMemoryCommand(); b3Assert(command); + + return b3LoadSdfCommandInit2((b3SharedMemoryCommandHandle)command, sdfFileName); +} + +B3_SHARED_API b3SharedMemoryCommandHandle b3LoadSdfCommandInit2(b3SharedMemoryCommandHandle commandHandle, const char* sdfFileName) +{ + struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; command->m_type = CMD_LOAD_SDF; int len = strlen(sdfFileName); if (lenm_sdfArguments.m_sdfFileName,sdfFileName); - } else + strcpy(command->m_sdfArguments.m_sdfFileName, sdfFileName); + } + else { command->m_sdfArguments.m_sdfFileName[0] = 0; } command->m_updateFlags = SDF_ARGS_FILE_NAME; - - return (b3SharedMemoryCommandHandle) command; + + return (b3SharedMemoryCommandHandle)command; } B3_SHARED_API b3SharedMemoryCommandHandle b3SaveWorldCommandInit(b3PhysicsClientHandle physClient, const char* sdfFileName) @@ -202,23 +210,30 @@ B3_SHARED_API b3SharedMemoryCommandHandle b3LoadMJCFCommandInit(b3PhysicsClientH { struct SharedMemoryCommand* command = cl->getAvailableSharedMemoryCommand(); b3Assert(command); - command->m_type = CMD_LOAD_MJCF; - int len = strlen(fileName); - if (len < MAX_URDF_FILENAME_LENGTH) - { - strcpy(command->m_mjcfArguments.m_mjcfFileName, fileName); - } - else - { - command->m_mjcfArguments.m_mjcfFileName[0] = 0; - } - command->m_updateFlags = 0; - - return (b3SharedMemoryCommandHandle)command; + return b3LoadMJCFCommandInit2((b3SharedMemoryCommandHandle)command, fileName); } return 0; } +B3_SHARED_API b3SharedMemoryCommandHandle b3LoadMJCFCommandInit2(b3SharedMemoryCommandHandle commandHandle, const char* fileName) +{ + struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; + command->m_type = CMD_LOAD_MJCF; + int len = strlen(fileName); + if (len < MAX_URDF_FILENAME_LENGTH) + { + strcpy(command->m_mjcfArguments.m_mjcfFileName, fileName); + } + else + { + command->m_mjcfArguments.m_mjcfFileName[0] = 0; + } + command->m_updateFlags = 0; + + return (b3SharedMemoryCommandHandle)command; + +} + B3_SHARED_API void b3LoadMJCFCommandSetFlags(b3SharedMemoryCommandHandle commandHandle, int flags) { struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; @@ -893,10 +908,17 @@ B3_SHARED_API b3SharedMemoryCommandHandle b3RequestActualStateCommandInit(b3Phys b3Assert(cl->canSubmitCommand()); struct SharedMemoryCommand* command = cl->getAvailableSharedMemoryCommand(); b3Assert(command); - command->m_type =CMD_REQUEST_ACTUAL_STATE; + return b3RequestActualStateCommandInit2((b3SharedMemoryCommandHandle)command, bodyUniqueId); + +} + +B3_SHARED_API b3SharedMemoryCommandHandle b3RequestActualStateCommandInit2(b3SharedMemoryCommandHandle commandHandle, int bodyUniqueId) +{ + struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; + command->m_type = CMD_REQUEST_ACTUAL_STATE; command->m_updateFlags = 0; command->m_requestActualStateInformationCommandArgument.m_bodyUniqueId = bodyUniqueId; - return (b3SharedMemoryCommandHandle) command; + return (b3SharedMemoryCommandHandle)command; } B3_SHARED_API int b3RequestActualStateCommandComputeLinkVelocity(b3SharedMemoryCommandHandle commandHandle, int computeLinkVelocity) @@ -1594,16 +1616,23 @@ B3_SHARED_API b3SharedMemoryCommandHandle b3CreatePoseCommandInit(b3PhysicsClien b3Assert(cl->canSubmitCommand()); struct SharedMemoryCommand* command = cl->getAvailableSharedMemoryCommand(); b3Assert(command); - command->m_type = CMD_INIT_POSE; - command->m_updateFlags =0; + return b3CreatePoseCommandInit2((b3SharedMemoryCommandHandle)command, bodyUniqueId); + +} + +B3_SHARED_API b3SharedMemoryCommandHandle b3CreatePoseCommandInit2(b3SharedMemoryCommandHandle commandHandle, int bodyUniqueId) +{ + struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; + command->m_type = CMD_INIT_POSE; + command->m_updateFlags = 0; command->m_initPoseArgs.m_bodyUniqueId = bodyUniqueId; //a bit slow, initialing the full range to zero... - for (int i=0;im_initPoseArgs.m_hasInitialStateQ[i] = 0; + for (int i = 0; im_initPoseArgs.m_hasInitialStateQ[i] = 0; command->m_initPoseArgs.m_hasInitialStateQdot[i] = 0; - } - return (b3SharedMemoryCommandHandle) command; + } + return commandHandle; } B3_SHARED_API int b3CreatePoseCommandSetBasePosition(b3SharedMemoryCommandHandle commandHandle, double startPosX,double startPosY,double startPosZ) @@ -1693,6 +1722,23 @@ B3_SHARED_API int b3CreatePoseCommandSetJointPositions(b3SharedMemoryCommandHand return 0; } +B3_SHARED_API int b3CreatePoseCommandSetQ(b3SharedMemoryCommandHandle commandHandle, int numJointPositions, const double* q, const int* hasQ) +{ + struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; + b3Assert(command); + b3Assert(command->m_type == CMD_INIT_POSE); + command->m_updateFlags |= INIT_POSE_HAS_JOINT_STATE; + for (int i = 0; im_initPoseArgs.m_initialStateQ[i] = q[i]; + command->m_initPoseArgs.m_hasInitialStateQ[i] = hasQ[i]; + } + } + return 0; +} + B3_SHARED_API int b3CreatePoseCommandSetJointPosition(b3PhysicsClientHandle physClient, b3SharedMemoryCommandHandle commandHandle, int jointIndex, double jointPosition) @@ -1730,6 +1776,24 @@ B3_SHARED_API int b3CreatePoseCommandSetJointVelocities(b3PhysicsClientHandle ph return 0; } +B3_SHARED_API int b3CreatePoseCommandSetQdots(b3SharedMemoryCommandHandle commandHandle, int numJointVelocities, const double* qDots, const int* hasQdots) +{ + struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; + b3Assert(command); + b3Assert(command->m_type == CMD_INIT_POSE); + + command->m_updateFlags |= INIT_POSE_HAS_JOINT_VELOCITY; + for (int i = 0; im_initPoseArgs.m_initialStateQdot[i] = qDots[i]; + command->m_initPoseArgs.m_hasInitialStateQdot[i] = hasQdots[i]; + } + } + return 0; +} + B3_SHARED_API int b3CreatePoseCommandSetJointVelocity(b3PhysicsClientHandle physClient, b3SharedMemoryCommandHandle commandHandle, int jointIndex, double jointVelocity) { struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; @@ -1948,6 +2012,52 @@ B3_SHARED_API int b3GetStatusAABB(b3SharedMemoryStatusHandle statusHandle, int l return 0; } +B3_SHARED_API int b3GetStatusActualState2(b3SharedMemoryStatusHandle statusHandle, + int* bodyUniqueId, + int* numLinks, + int* numDegreeOfFreedomQ, + int* numDegreeOfFreedomU, + const double* rootLocalInertialFrame[], + const double* actualStateQ[], + const double* actualStateQdot[], + const double* jointReactionForces[], + const double* linkLocalInertialFrames[], + const double* jointMotorForces[], + const double* linkStates[], + const double* linkWorldVelocities[] ) +{ + const SharedMemoryStatus* status = (const SharedMemoryStatus*)statusHandle; + btAssert(status); + if (status == 0) + return 0; + + b3GetStatusActualState(statusHandle, bodyUniqueId, numDegreeOfFreedomQ, numDegreeOfFreedomU, + rootLocalInertialFrame, actualStateQ, actualStateQdot, jointReactionForces); + + const SendActualStateArgs &args = status->m_sendActualStateArgs; + if (numLinks) + { + *numLinks = args.m_numLinks; + } + if (linkLocalInertialFrames) + { + *linkLocalInertialFrames = args.m_linkLocalInertialFrames; + } + if (jointMotorForces) + { + *jointMotorForces = args.m_jointMotorForce; + } + if (linkStates) + { + *linkStates = args.m_linkState; + } + if (linkWorldVelocities) + { + *linkWorldVelocities = args.m_linkWorldVelocities; + } + +} + B3_SHARED_API int b3GetStatusActualState(b3SharedMemoryStatusHandle statusHandle, int* bodyUniqueId, int* numDegreeOfFreedomQ, @@ -2317,10 +2427,16 @@ B3_SHARED_API b3SharedMemoryCommandHandle b3GetDynamicsInfoCommandInit(b3Physics b3Assert(cl->canSubmitCommand()); struct SharedMemoryCommand* command = cl->getAvailableSharedMemoryCommand(); b3Assert(command); + return b3GetDynamicsInfoCommandInit2((b3SharedMemoryCommandHandle)command, bodyUniqueId, linkIndex); +} + +B3_SHARED_API b3SharedMemoryCommandHandle b3GetDynamicsInfoCommandInit2(b3SharedMemoryCommandHandle commandHandle, int bodyUniqueId, int linkIndex) +{ + struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; command->m_type = CMD_GET_DYNAMICS_INFO; command->m_getDynamicsInfoArgs.m_bodyUniqueId = bodyUniqueId; command->m_getDynamicsInfoArgs.m_linkIndex = linkIndex; - return (b3SharedMemoryCommandHandle) command; + return (b3SharedMemoryCommandHandle)command; } B3_SHARED_API int b3GetDynamicsInfo(b3SharedMemoryStatusHandle statusHandle, struct b3DynamicsInfo* info) @@ -2346,12 +2462,18 @@ B3_SHARED_API b3SharedMemoryCommandHandle b3InitChangeDynamicsInfo(b3PhysicsClie b3Assert(cl->canSubmitCommand()); struct SharedMemoryCommand* command = cl->getAvailableSharedMemoryCommand(); b3Assert(command); + return b3InitChangeDynamicsInfo2((b3SharedMemoryCommandHandle)command); + +} + +B3_SHARED_API b3SharedMemoryCommandHandle b3InitChangeDynamicsInfo2(b3SharedMemoryCommandHandle commandHandle) +{ + struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; command->m_type = CMD_CHANGE_DYNAMICS_INFO; command->m_changeDynamicsInfoArgs.m_bodyUniqueId = -1; command->m_changeDynamicsInfoArgs.m_linkIndex = -2; command->m_updateFlags = 0; - - return (b3SharedMemoryCommandHandle) command; + return commandHandle; } B3_SHARED_API int b3ChangeDynamicsInfoSetMass(b3SharedMemoryCommandHandle commandHandle, int bodyUniqueId, int linkIndex, double mass) diff --git a/examples/SharedMemory/PhysicsClientC_API.h b/examples/SharedMemory/PhysicsClientC_API.h index d32446406..48b00990e 100644 --- a/examples/SharedMemory/PhysicsClientC_API.h +++ b/examples/SharedMemory/PhysicsClientC_API.h @@ -85,6 +85,20 @@ B3_SHARED_API int b3GetStatusActualState(b3SharedMemoryStatusHandle statusHandle const double* actualStateQdot[], const double* jointReactionForces[]); +B3_SHARED_API int b3GetStatusActualState2(b3SharedMemoryStatusHandle statusHandle, + int* bodyUniqueId, + int* numLinks, + int* numDegreeOfFreedomQ, + int* numDegreeOfFreedomU, + const double* rootLocalInertialFrame[], + const double* actualStateQ[], + const double* actualStateQdot[], + const double* jointReactionForces[], + const double* linkLocalInertialFrames[], + const double* jointMotorForces[], + const double* linkStates[], + const double* linkWorldVelocities[]); + B3_SHARED_API b3SharedMemoryCommandHandle b3RequestCollisionInfoCommandInit(b3PhysicsClientHandle physClient, int bodyUniqueId); B3_SHARED_API int b3GetStatusAABB(b3SharedMemoryStatusHandle statusHandle, int linkIndex, double aabbMin[/*3*/], double aabbMax[/*3*/]); @@ -125,10 +139,14 @@ B3_SHARED_API int b3GetNumUserData(b3PhysicsClientHandle physClient, int bodyUni B3_SHARED_API void b3GetUserDataInfo(b3PhysicsClientHandle physClient, int bodyUniqueId, int userDataIndex, const char **keyOut, int *userDataIdOut, int *linkIndexOut, int *visualShapeIndexOut); B3_SHARED_API b3SharedMemoryCommandHandle b3GetDynamicsInfoCommandInit(b3PhysicsClientHandle physClient, int bodyUniqueId, int linkIndex); +B3_SHARED_API b3SharedMemoryCommandHandle b3GetDynamicsInfoCommandInit2(b3SharedMemoryCommandHandle commandHandle, int bodyUniqueId, int linkIndex); + ///given a body unique id and link index, return the dynamics information. See b3DynamicsInfo in SharedMemoryPublic.h B3_SHARED_API int b3GetDynamicsInfo(b3SharedMemoryStatusHandle statusHandle, struct b3DynamicsInfo* info); B3_SHARED_API b3SharedMemoryCommandHandle b3InitChangeDynamicsInfo(b3PhysicsClientHandle physClient); +B3_SHARED_API b3SharedMemoryCommandHandle b3InitChangeDynamicsInfo2(b3SharedMemoryCommandHandle commandHandle); + B3_SHARED_API int b3ChangeDynamicsInfoSetMass(b3SharedMemoryCommandHandle commandHandle, int bodyUniqueId, int linkIndex, double mass); B3_SHARED_API int b3ChangeDynamicsInfoSetLocalInertiaDiagonal(b3SharedMemoryCommandHandle commandHandle, int bodyUniqueId, int linkIndex, double localInertiaDiagonal[]); @@ -367,6 +385,7 @@ B3_SHARED_API b3SharedMemoryCommandHandle b3LoadBulletCommandInit(b3PhysicsClien B3_SHARED_API b3SharedMemoryCommandHandle b3SaveBulletCommandInit(b3PhysicsClientHandle physClient, const char* fileName); B3_SHARED_API b3SharedMemoryCommandHandle b3LoadMJCFCommandInit(b3PhysicsClientHandle physClient, const char* fileName); +B3_SHARED_API b3SharedMemoryCommandHandle b3LoadMJCFCommandInit2(b3SharedMemoryCommandHandle commandHandle, const char* fileName); B3_SHARED_API void b3LoadMJCFCommandSetFlags(b3SharedMemoryCommandHandle commandHandle, int flags); @@ -408,6 +427,8 @@ B3_SHARED_API void b3CalculateInverseKinematicsSetResidualThreshold(b3SharedMemo B3_SHARED_API b3SharedMemoryCommandHandle b3LoadSdfCommandInit(b3PhysicsClientHandle physClient, const char* sdfFileName); +B3_SHARED_API b3SharedMemoryCommandHandle b3LoadSdfCommandInit2(b3SharedMemoryCommandHandle commandHandle, const char* sdfFileName); + B3_SHARED_API int b3LoadSdfCommandSetUseMultiBody(b3SharedMemoryCommandHandle commandHandle, int useMultiBody); B3_SHARED_API int b3LoadSdfCommandSetUseGlobalScaling(b3SharedMemoryCommandHandle commandHandle, double globalScaling); @@ -505,6 +526,8 @@ B3_SHARED_API int b3CreateBoxCommandSetColorRGBA(b3SharedMemoryCommandHandle com ///base orientation and joint angles. This will set all velocities of base and joints to zero. ///This is not a robot control command using actuators/joint motors, but manual repositioning the robot. B3_SHARED_API b3SharedMemoryCommandHandle b3CreatePoseCommandInit(b3PhysicsClientHandle physClient, int bodyUniqueId); +B3_SHARED_API b3SharedMemoryCommandHandle b3CreatePoseCommandInit2(b3SharedMemoryCommandHandle commandHandle, int bodyUniqueId); + B3_SHARED_API int b3CreatePoseCommandSetBasePosition(b3SharedMemoryCommandHandle commandHandle, double startPosX,double startPosY,double startPosZ); B3_SHARED_API int b3CreatePoseCommandSetBaseOrientation(b3SharedMemoryCommandHandle commandHandle, double startOrnX,double startOrnY,double startOrnZ, double startOrnW); B3_SHARED_API int b3CreatePoseCommandSetBaseLinearVelocity(b3SharedMemoryCommandHandle commandHandle, double linVel[/*3*/]); @@ -513,6 +536,9 @@ B3_SHARED_API int b3CreatePoseCommandSetBaseAngularVelocity(b3SharedMemoryComman B3_SHARED_API int b3CreatePoseCommandSetJointPositions(b3SharedMemoryCommandHandle commandHandle, int numJointPositions, const double* jointPositions); B3_SHARED_API int b3CreatePoseCommandSetJointPosition(b3PhysicsClientHandle physClient, b3SharedMemoryCommandHandle commandHandle, int jointIndex, double jointPosition); +B3_SHARED_API int b3CreatePoseCommandSetQ(b3SharedMemoryCommandHandle commandHandle, int numJointPositions, const double* q, const int* hasQ); +B3_SHARED_API int b3CreatePoseCommandSetQdots(b3SharedMemoryCommandHandle commandHandle, int numJointVelocities, const double* qDots, const int* hasQdots); + B3_SHARED_API int b3CreatePoseCommandSetJointVelocities(b3PhysicsClientHandle physClient, b3SharedMemoryCommandHandle commandHandle, int numJointVelocities, const double* jointVelocities); B3_SHARED_API int b3CreatePoseCommandSetJointVelocity(b3PhysicsClientHandle physClient, b3SharedMemoryCommandHandle commandHandle, int jointIndex, double jointVelocity); @@ -525,6 +551,8 @@ B3_SHARED_API int b3CreateSensorEnable6DofJointForceTorqueSensor(b3SharedMemoryC B3_SHARED_API int b3CreateSensorEnableIMUForLink(b3SharedMemoryCommandHandle commandHandle, int linkIndex, int enable); B3_SHARED_API b3SharedMemoryCommandHandle b3RequestActualStateCommandInit(b3PhysicsClientHandle physClient,int bodyUniqueId); +B3_SHARED_API b3SharedMemoryCommandHandle b3RequestActualStateCommandInit2(b3SharedMemoryCommandHandle commandHandle, int bodyUniqueId); + B3_SHARED_API int b3RequestActualStateCommandComputeLinkVelocity(b3SharedMemoryCommandHandle commandHandle, int computeLinkVelocity); B3_SHARED_API int b3RequestActualStateCommandComputeForwardKinematics(b3SharedMemoryCommandHandle commandHandle, int computeForwardKinematics); diff --git a/examples/SharedMemory/PhysicsServerCommandProcessor.cpp b/examples/SharedMemory/PhysicsServerCommandProcessor.cpp index 241a80317..197bf7536 100644 --- a/examples/SharedMemory/PhysicsServerCommandProcessor.cpp +++ b/examples/SharedMemory/PhysicsServerCommandProcessor.cpp @@ -7148,6 +7148,21 @@ bool PhysicsServerCommandProcessor::processGetDynamicsInfoCommand(const struct S if (linkIndex == -1) { serverCmd.m_dynamicsInfo.m_mass = mb->getBaseMass(); + if (mb->getBaseCollider()) + { + serverCmd.m_dynamicsInfo.m_activationState = mb->getBaseCollider()->getActivationState(); + serverCmd.m_dynamicsInfo.m_contactProcessingThreshold = mb->getBaseCollider()->getContactProcessingThreshold(); + serverCmd.m_dynamicsInfo.m_ccdSweptSphereRadius = mb->getBaseCollider()->getCcdSweptSphereRadius(); + serverCmd.m_dynamicsInfo.m_frictionAnchor = mb->getBaseCollider()->getCollisionFlags()&btCollisionObject::CF_HAS_FRICTION_ANCHOR; + + } + else + { + serverCmd.m_dynamicsInfo.m_activationState = 0; + serverCmd.m_dynamicsInfo.m_contactProcessingThreshold = 0; + serverCmd.m_dynamicsInfo.m_ccdSweptSphereRadius = 0; + serverCmd.m_dynamicsInfo.m_frictionAnchor = 0; + } serverCmd.m_dynamicsInfo.m_localInertialDiagonal[0] = mb->getBaseInertia()[0]; serverCmd.m_dynamicsInfo.m_localInertialDiagonal[1] = mb->getBaseInertia()[1]; serverCmd.m_dynamicsInfo.m_localInertialDiagonal[2] = mb->getBaseInertia()[2]; @@ -7161,6 +7176,9 @@ bool PhysicsServerCommandProcessor::processGetDynamicsInfoCommand(const struct S serverCmd.m_dynamicsInfo.m_localInertialFrame[5] = body->m_rootLocalInertialFrame.getRotation()[2]; serverCmd.m_dynamicsInfo.m_localInertialFrame[6] = body->m_rootLocalInertialFrame.getRotation()[3]; + serverCmd.m_dynamicsInfo.m_angularDamping = body->m_multiBody->getAngularDamping(); + serverCmd.m_dynamicsInfo.m_linearDamping = body->m_multiBody->getLinearDamping(); + serverCmd.m_dynamicsInfo.m_restitution = mb->getBaseCollider()->getRestitution(); serverCmd.m_dynamicsInfo.m_rollingFrictionCoeff = mb->getBaseCollider()->getRollingFriction(); serverCmd.m_dynamicsInfo.m_spinningFrictionCoeff = mb->getBaseCollider()->getSpinningFriction(); @@ -7179,6 +7197,22 @@ bool PhysicsServerCommandProcessor::processGetDynamicsInfoCommand(const struct S else { serverCmd.m_dynamicsInfo.m_mass = mb->getLinkMass(linkIndex); + + if (mb->getLinkCollider(linkIndex)) + { + serverCmd.m_dynamicsInfo.m_activationState = mb->getLinkCollider(linkIndex)->getActivationState(); + serverCmd.m_dynamicsInfo.m_contactProcessingThreshold = mb->getLinkCollider(linkIndex)->getContactProcessingThreshold(); + serverCmd.m_dynamicsInfo.m_ccdSweptSphereRadius = mb->getLinkCollider(linkIndex)->getCcdSweptSphereRadius(); + serverCmd.m_dynamicsInfo.m_frictionAnchor = mb->getLinkCollider(linkIndex)->getCollisionFlags()&btCollisionObject::CF_HAS_FRICTION_ANCHOR; + } + else + { + serverCmd.m_dynamicsInfo.m_activationState = 0; + serverCmd.m_dynamicsInfo.m_contactProcessingThreshold = 0; + serverCmd.m_dynamicsInfo.m_ccdSweptSphereRadius = 0; + serverCmd.m_dynamicsInfo.m_frictionAnchor = 0; + } + serverCmd.m_dynamicsInfo.m_localInertialDiagonal[0] = mb->getLinkInertia(linkIndex)[0]; serverCmd.m_dynamicsInfo.m_localInertialDiagonal[1] = mb->getLinkInertia(linkIndex)[1]; serverCmd.m_dynamicsInfo.m_localInertialDiagonal[2] = mb->getLinkInertia(linkIndex)[2]; @@ -7191,6 +7225,9 @@ bool PhysicsServerCommandProcessor::processGetDynamicsInfoCommand(const struct S serverCmd.m_dynamicsInfo.m_localInertialFrame[5] = body->m_linkLocalInertialFrames[linkIndex].getRotation()[2]; serverCmd.m_dynamicsInfo.m_localInertialFrame[6] = body->m_linkLocalInertialFrames[linkIndex].getRotation()[3]; + serverCmd.m_dynamicsInfo.m_angularDamping = body->m_multiBody->getAngularDamping(); + serverCmd.m_dynamicsInfo.m_linearDamping = body->m_multiBody->getLinearDamping(); + if (mb->getLinkCollider(linkIndex)) { serverCmd.m_dynamicsInfo.m_lateralFrictionCoeff = mb->getLinkCollider(linkIndex)->getFriction(); diff --git a/examples/SharedMemory/SharedMemoryPublic.h b/examples/SharedMemory/SharedMemoryPublic.h index 794265306..5e7cc31d0 100644 --- a/examples/SharedMemory/SharedMemoryPublic.h +++ b/examples/SharedMemory/SharedMemoryPublic.h @@ -334,6 +334,13 @@ struct b3DynamicsInfo double m_restitution; double m_contactStiffness; double m_contactDamping; + int m_activationState; + double m_angularDamping; + double m_linearDamping; + double m_ccdSweptSphereRadius; + double m_contactProcessingThreshold; + int m_frictionAnchor; + }; // copied from btMultiBodyLink.h diff --git a/examples/SharedMemory/grpc/ConvertGRPCBullet.cpp b/examples/SharedMemory/grpc/ConvertGRPCBullet.cpp index 213a70863..c6f4daabe 100644 --- a/examples/SharedMemory/grpc/ConvertGRPCBullet.cpp +++ b/examples/SharedMemory/grpc/ConvertGRPCBullet.cpp @@ -8,6 +8,7 @@ #include #include #include "pybullet.grpc.pb.h" +#include "LinearMath/btMinMax.h" using grpc::Server; using grpc::ServerAsyncResponseWriter; @@ -26,9 +27,9 @@ SharedMemoryCommand* convertGRPCAndSubmitCommand(PyBulletCommand& grpcCommand, S if (grpcCommand.has_loadurdfcommand()) { - auto grpcCmd = grpcCommand.loadurdfcommand(); + const ::pybullet_grpc::LoadUrdfCommand& grpcCmd = grpcCommand.loadurdfcommand(); - std::string fileName = grpcCmd.urdffilename(); + std::string fileName = grpcCmd.filename(); if (fileName.length()) { cmdPtr = &cmd; @@ -45,9 +46,9 @@ SharedMemoryCommand* convertGRPCAndSubmitCommand(PyBulletCommand& grpcCommand, S 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) + if (grpcCmd.hasUseMultiBody_case() == ::pybullet_grpc::LoadUrdfCommand::HasUseMultiBodyCase::kUseMultiBody) { - b3LoadUrdfCommandSetUseMultiBody( commandHandle, grpcCmd.usemultibody()); + b3LoadUrdfCommandSetUseMultiBody(commandHandle, grpcCmd.usemultibody()); } if (grpcCmd.hasGlobalScaling_case() == ::pybullet_grpc::LoadUrdfCommand::HasGlobalScalingCase::kGlobalScaling) { @@ -57,14 +58,200 @@ SharedMemoryCommand* convertGRPCAndSubmitCommand(PyBulletCommand& grpcCommand, S { b3LoadUrdfCommandSetUseFixedBase(commandHandle, grpcCmd.usefixedbase()); } - if (grpcCmd.urdfflags()) + if (grpcCmd.flags()) { - b3LoadUrdfCommandSetFlags(commandHandle, grpcCmd.urdfflags()); + b3LoadUrdfCommandSetFlags(commandHandle, grpcCmd.flags()); } } } + if (grpcCommand.has_loadsdfcommand()) + { + const ::pybullet_grpc::LoadSdfCommand& grpcCmd = grpcCommand.loadsdfcommand(); + + std::string fileName = grpcCmd.filename(); + if (fileName.length()) + { + cmdPtr = &cmd; + b3SharedMemoryCommandHandle commandHandle = (b3SharedMemoryCommandHandle)cmdPtr; + b3LoadSdfCommandInit2(commandHandle, fileName.c_str()); + + + if (grpcCmd.hasUseMultiBody_case() == ::pybullet_grpc::LoadSdfCommand::HasUseMultiBodyCase::kUseMultiBody) + { + b3LoadSdfCommandSetUseMultiBody(commandHandle, grpcCmd.usemultibody()); + } + if (grpcCmd.hasGlobalScaling_case() == ::pybullet_grpc::LoadSdfCommand::HasGlobalScalingCase::kGlobalScaling) + { + b3LoadSdfCommandSetUseGlobalScaling(commandHandle, grpcCmd.globalscaling()); + } + } + } + + if (grpcCommand.has_loadmjcfcommand()) + { + const pybullet_grpc::LoadMjcfCommand& grpcCmd = grpcCommand.loadmjcfcommand(); + + std::string fileName = grpcCmd.filename(); + if (fileName.length()) + { + cmdPtr = &cmd; + b3SharedMemoryCommandHandle commandHandle = (b3SharedMemoryCommandHandle)cmdPtr; + b3LoadMJCFCommandInit2(commandHandle, fileName.c_str()); + + if (grpcCmd.flags()) + { + b3LoadMJCFCommandSetFlags(commandHandle, grpcCmd.flags()); + } + } + } + + if (grpcCommand.has_changedynamicscommand()) + { + cmdPtr = &cmd; + b3SharedMemoryCommandHandle commandHandle = (b3SharedMemoryCommandHandle)cmdPtr; + const ::pybullet_grpc::ChangeDynamicsCommand& grpcCmd = grpcCommand.changedynamicscommand(); + int bodyUniqueId = grpcCmd.bodyuniqueid(); + int linkIndex = grpcCmd.linkindex(); + b3InitChangeDynamicsInfo2(commandHandle); + if (grpcCmd.hasMass_case() == ::pybullet_grpc::ChangeDynamicsCommand::HasMassCase::kMass) + { + b3ChangeDynamicsInfoSetMass(commandHandle, bodyUniqueId, linkIndex, grpcCmd.mass()); + } + if (grpcCmd.hasLateralFriction_case() == ::pybullet_grpc::ChangeDynamicsCommand::HasLateralFrictionCase::kLateralFriction) + { + b3ChangeDynamicsInfoSetLateralFriction(commandHandle, bodyUniqueId, linkIndex, grpcCmd.lateralfriction()); + } + if (grpcCmd.hasSpinningFriction_case() == ::pybullet_grpc::ChangeDynamicsCommand::HasSpinningFrictionCase::kSpinningFriction) + { + b3ChangeDynamicsInfoSetSpinningFriction(commandHandle, bodyUniqueId, linkIndex, grpcCmd.spinningfriction()); + } + if (grpcCmd.hasRollingFriction_case() == ::pybullet_grpc::ChangeDynamicsCommand::HasRollingFrictionCase::kRollingFriction) + { + b3ChangeDynamicsInfoSetRollingFriction(commandHandle, bodyUniqueId, linkIndex, grpcCmd.rollingfriction()); + } + + if (grpcCmd.hasRestitution_case() == ::pybullet_grpc::ChangeDynamicsCommand::HasRestitutionCase::kRestitution) + { + b3ChangeDynamicsInfoSetRestitution(commandHandle, bodyUniqueId, linkIndex, grpcCmd.restitution()); + } + if (grpcCmd.haslinearDamping_case() == ::pybullet_grpc::ChangeDynamicsCommand::HaslinearDampingCase::kLinearDamping) + { + b3ChangeDynamicsInfoSetLinearDamping(commandHandle, bodyUniqueId, grpcCmd.lineardamping()); + } + + if (grpcCmd.hasangularDamping_case() == ::pybullet_grpc::ChangeDynamicsCommand::HasangularDampingCase::kAngularDamping) + { + b3ChangeDynamicsInfoSetAngularDamping(commandHandle, bodyUniqueId, grpcCmd.angulardamping()); + } + + bool hasContactDamping = grpcCmd.hasContactDamping_case() == ::pybullet_grpc::ChangeDynamicsCommand::HasContactDampingCase::kContactDamping; + bool hasContactStiffness = grpcCmd.hasContactStiffness_case() == ::pybullet_grpc::ChangeDynamicsCommand::HasContactStiffnessCase::kContactStiffness; + if (hasContactDamping && hasContactStiffness) + { + b3ChangeDynamicsInfoSetContactStiffnessAndDamping(commandHandle, bodyUniqueId, linkIndex, grpcCmd.contactstiffness(), grpcCmd.contactdamping()); + } + if (grpcCmd.hasLocalInertiaDiagonal_case() == ::pybullet_grpc::ChangeDynamicsCommand::HasLocalInertiaDiagonalCase::kLocalInertiaDiagonal) + { + double localInertiaDiag[3] = { grpcCmd.localinertiadiagonal().x(), grpcCmd.localinertiadiagonal().y(), grpcCmd.localinertiadiagonal().z() }; + b3ChangeDynamicsInfoSetLocalInertiaDiagonal(commandHandle, bodyUniqueId, linkIndex, localInertiaDiag); + } + + if (grpcCmd.hasFrictionAnchor_case() == ::pybullet_grpc::ChangeDynamicsCommand::HasFrictionAnchorCase::kFrictionAnchor) + { + b3ChangeDynamicsInfoSetFrictionAnchor(commandHandle, bodyUniqueId, linkIndex, grpcCmd.frictionanchor()); + } + if (grpcCmd.hasccdSweptSphereRadius_case() == ::pybullet_grpc::ChangeDynamicsCommand::HasccdSweptSphereRadiusCase::kCcdSweptSphereRadius) + { + b3ChangeDynamicsInfoSetCcdSweptSphereRadius(commandHandle, bodyUniqueId, linkIndex, grpcCmd.ccdsweptsphereradius()); + } + + + if (grpcCmd.hasContactProcessingThreshold_case() == ::pybullet_grpc::ChangeDynamicsCommand::HasContactProcessingThresholdCase::kContactProcessingThreshold) + { + b3ChangeDynamicsInfoSetContactProcessingThreshold(commandHandle, bodyUniqueId, linkIndex, grpcCmd.contactprocessingthreshold()); + } + + if (grpcCmd.hasActivationState_case() == ::pybullet_grpc::ChangeDynamicsCommand::HasActivationStateCase::kActivationState) + { + b3ChangeDynamicsInfoSetActivationState(commandHandle, bodyUniqueId, grpcCmd.activationstate()); + } + + + } + if (grpcCommand.has_getdynamicscommand()) + { + cmdPtr = &cmd; + b3SharedMemoryCommandHandle commandHandle = (b3SharedMemoryCommandHandle)cmdPtr; + const ::pybullet_grpc::GetDynamicsCommand& grpcCmd = grpcCommand.getdynamicscommand(); + b3GetDynamicsInfoCommandInit2(commandHandle, grpcCmd.bodyuniqueid(), grpcCmd.linkindex()); + } + + if (grpcCommand.has_initposecommand()) + { + cmdPtr = &cmd; + b3SharedMemoryCommandHandle commandHandle = (b3SharedMemoryCommandHandle)cmdPtr; + + const ::pybullet_grpc::InitPoseCommand& grpcCmd = grpcCommand.initposecommand(); + b3CreatePoseCommandInit2(commandHandle, grpcCmd.bodyuniqueid()); + double initialQ[MAX_DEGREE_OF_FREEDOM] = { 0 }; + double initialQdot[MAX_DEGREE_OF_FREEDOM] = { 0 }; + int hasInitialQ[MAX_DEGREE_OF_FREEDOM] = { 0 }; + int hasInitialQdot[MAX_DEGREE_OF_FREEDOM] = { 0 }; + + if (grpcCmd.initialstateq_size() == grpcCmd.hasinitialstateq_size()) + { + int numInitial = btMin(grpcCmd.initialstateq_size(), MAX_DEGREE_OF_FREEDOM); + for (int i = 0; i < numInitial; i++) + { + initialQ[i] = grpcCmd.initialstateq(i); + hasInitialQ[i] = grpcCmd.hasinitialstateq(i); + } + if (numInitial) + { + b3CreatePoseCommandSetQ(commandHandle, numInitial, initialQ, hasInitialQ); + } + } + else + { + printf("Error: if (grpcCmd.initialstateq_size() != grpcCmd.hasinitialstateq_size())\n"); + } + if (grpcCmd.initialstateqdot_size() == grpcCmd.hasinitialstateqdot_size()) + { + int numInitial = btMin(grpcCmd.initialstateqdot_size(), MAX_DEGREE_OF_FREEDOM); + for (int i = 0; i < numInitial; i++) + { + initialQdot[i] = grpcCmd.initialstateqdot(i); + hasInitialQdot[i] = grpcCmd.hasinitialstateqdot(i); + } + if (numInitial) + { + b3CreatePoseCommandSetQdots(commandHandle, numInitial, initialQdot, hasInitialQdot); + } + } + else + { + printf("Error: (grpcCmd.initialstateqdot_size() != grpcCmd.hasinitialstateqdot_size())\n"); + } + } + + if (grpcCommand.has_requestactualstatecommand()) + { + cmdPtr = &cmd; + b3SharedMemoryCommandHandle commandHandle = (b3SharedMemoryCommandHandle)cmdPtr; + const ::pybullet_grpc::RequestActualStateCommand& grpcCmd = grpcCommand.requestactualstatecommand(); + b3RequestActualStateCommandInit2(commandHandle, grpcCmd.bodyuniqueid()); + if (grpcCmd.computeforwardkinematics()) + { + b3RequestActualStateCommandComputeForwardKinematics(commandHandle, grpcCmd.computeforwardkinematics()); + } + if (grpcCmd.computelinkvelocities()) + { + b3RequestActualStateCommandComputeLinkVelocity(commandHandle, grpcCmd.computelinkvelocities()); + } + } + if (grpcCommand.has_stepsimulationcommand()) { cmdPtr = &cmd; @@ -87,10 +274,157 @@ bool convertStatusToGRPC(const SharedMemoryStatus& serverStatus, char* bufferSer ::pybullet_grpc::LoadUrdfStatus* stat = grpcReply.mutable_urdfstatus(); b3SharedMemoryStatusHandle statusHandle = (b3SharedMemoryStatusHandle)&serverStatus; int objectUniqueId = b3GetStatusBodyIndex(statusHandle); - stat->set_objectuniqueid(objectUniqueId); + stat->set_bodyuniqueid(objectUniqueId); + break; } + case CMD_SDF_LOADING_COMPLETED: + { + int bodyIndicesOut[MAX_SDF_BODIES]; + ::pybullet_grpc::SdfLoadedStatus* stat = grpcReply.mutable_sdfstatus(); + b3SharedMemoryStatusHandle statusHandle = (b3SharedMemoryStatusHandle)&serverStatus; + int numBodies = b3GetStatusBodyIndices(statusHandle, bodyIndicesOut, MAX_SDF_BODIES); + if (numBodies > MAX_SDF_BODIES) + { + printf("SDF exceeds body capacity: %d > %d", numBodies, MAX_SDF_BODIES); + } + for (int i = 0; i < numBodies; i++) + { + stat->add_bodyuniqueids(bodyIndicesOut[i]); + } + break; + } + case CMD_MJCF_LOADING_COMPLETED: + { + int bodyIndicesOut[MAX_SDF_BODIES]; + ::pybullet_grpc::MjcfLoadedStatus* stat = grpcReply.mutable_mjcfstatus(); + b3SharedMemoryStatusHandle statusHandle = (b3SharedMemoryStatusHandle)&serverStatus; + int numBodies = b3GetStatusBodyIndices(statusHandle, bodyIndicesOut, MAX_SDF_BODIES); + if (numBodies > MAX_SDF_BODIES) + { + printf("MJCF exceeds body capacity: %d > %d", numBodies, MAX_SDF_BODIES); + } + for (int i = 0; i < numBodies; i++) + { + stat->add_bodyuniqueids(bodyIndicesOut[i]); + } + break; + } + case CMD_GET_DYNAMICS_INFO_COMPLETED: + { + b3DynamicsInfo info; + b3SharedMemoryStatusHandle statusHandle = (b3SharedMemoryStatusHandle)&serverStatus; + if (b3GetDynamicsInfo(statusHandle, &info)) + { + ::pybullet_grpc::GetDynamicsStatus*stat = grpcReply.mutable_getdynamicsstatus(); + + stat->set_mass(info.m_mass); + stat->set_lateralfriction(info.m_lateralFrictionCoeff); + stat->set_spinningfriction(info.m_spinningFrictionCoeff); + stat->set_rollingfriction(info.m_rollingFrictionCoeff); + stat->set_restitution(info.m_restitution); + stat->set_lineardamping(info.m_linearDamping); + stat->set_angulardamping(info.m_angularDamping); + + stat->set_contactstiffness(info.m_contactStiffness); + stat->set_contactdamping(info.m_contactDamping); + + pybullet_grpc::vec3* localInertia = stat->mutable_localinertiadiagonal(); + localInertia->set_x(info.m_localInertialDiagonal[0]); + localInertia->set_y(info.m_localInertialDiagonal[1]); + localInertia->set_z(info.m_localInertialDiagonal[2]); - break; + stat->set_frictionanchor(info.m_frictionAnchor); + stat->set_ccdsweptsphereradius(info.m_ccdSweptSphereRadius); + stat->set_contactprocessingthreshold(info.m_contactProcessingThreshold); + + + stat->set_activationstate(info.m_activationState); + } + break; + } + case CMD_ACTUAL_STATE_UPDATE_COMPLETED: + { + b3SharedMemoryStatusHandle statusHandle = (b3SharedMemoryStatusHandle)&serverStatus; + int bodyUniqueId; + int numLinks; + + int numDegreeOfFreedomQ; + int numDegreeOfFreedomU; + + const double* rootLocalInertialFramePtr=0; + const double* actualStateQptr=0; + const double* actualStateQdotPtr=0; + const double* jointReactionForcesPtr = 0; + + const double* linkLocalInertialFrames = 0; + const double* jointMotorForces = 0; + const double* linkStates = 0; + const double* linkWorldVelocities = 0; + + + if (b3GetStatusActualState2( + statusHandle, &bodyUniqueId,&numLinks, + &numDegreeOfFreedomQ, + &numDegreeOfFreedomU, + &rootLocalInertialFramePtr, + &actualStateQptr, + &actualStateQdotPtr, + &jointReactionForcesPtr, + &linkLocalInertialFrames, + &jointMotorForces, + &linkStates, + &linkWorldVelocities)) + { + ::pybullet_grpc::SendActualStateStatus* stat = grpcReply.mutable_actualstatestatus(); + stat->set_bodyuniqueid(bodyUniqueId); + stat->set_numlinks(numLinks); + + stat->set_numdegreeoffreedomq(numDegreeOfFreedomQ); + stat->set_numdegreeoffreedomu(numDegreeOfFreedomU); + for (int i = 0; i < numDegreeOfFreedomQ; i++) + { + stat->add_actualstateq( actualStateQptr[i]); + } + for (int i = 0; i < numDegreeOfFreedomU; i++) + { + stat->add_actualstateqdot( actualStateQdotPtr[i]); + } + for (int i = 0; i < 7; i++) + { + stat->add_rootlocalinertialframe(rootLocalInertialFramePtr[i]); + } + for (int i = 0; i < numLinks * 6; i++) + { + stat->add_linklocalinertialframes( linkLocalInertialFrames[i]); + } + for (int i = 0; i < numLinks * 6; i++) + { + stat->add_jointreactionforces(jointReactionForcesPtr[i]); + } + for (int i = 0; i < numLinks; i++) + { + stat->add_jointmotorforce(jointMotorForces[i]); + } + for (int i = 0; i < numLinks * 7; i++) + { + stat->add_linkstate(linkStates[i]); + } + for (int i = 0; i < numLinks * 6; i++) + { + stat->add_linkworldvelocities(linkWorldVelocities[i]); + } + } + break; + } + case CMD_CLIENT_COMMAND_COMPLETED: + { + //no action needed? + break; + } + default: + { + printf("convertStatusToGRPC: unknown status"); + } } diff --git a/examples/SharedMemory/grpc/premake4.lua b/examples/SharedMemory/grpc/premake4.lua index 4765d11bc..814fb3e06 100644 --- a/examples/SharedMemory/grpc/premake4.lua +++ b/examples/SharedMemory/grpc/premake4.lua @@ -10,8 +10,10 @@ project ("App_PhysicsServerSharedMemoryBridgeGRPC") if os.is("Windows") then defines { "WIN32", "_WIN32_WINNT=0x0600" } + includedirs {"../../ThirdPartyLibs/grpc/include"} + libdirs {"../../ThirdPartyLibs/grpc/lib/win64"} links {"grpc","grpc++","grpc++_reflection","gpr", - "libprotobuf","crypto","ssl","zlibstaticd","Ws2_32","Winmm" } + "libprotobufd","crypto","ssl","zlibstaticd","Ws2_32","Winmm" } end if os.is("Linux") then defines {"_LINUX"} @@ -28,6 +30,12 @@ project ("App_PhysicsServerSharedMemoryBridgeGRPC") files { "main.cpp", + "ConvertGRPCBullet.cpp", + "ConvertGRPCBullet.h", + "pybullet.grpc.pb.cpp", + "pybullet.grpc.pb.h", + "pybullet.pb.cpp", + "pybullet.pb.h", "../PhysicsClient.cpp", "../PhysicsClient.h", "../PhysicsDirect.cpp", @@ -68,8 +76,10 @@ links { if os.is("Windows") then defines { "WIN32", "_WIN32_WINNT=0x0600" } + includedirs {"../../ThirdPartyLibs/grpc/include"} + libdirs {"../../ThirdPartyLibs/grpc/lib/win64"} links {"grpc","grpc++","grpc++_reflection","gpr", - "libprotobuf","crypto","ssl","zlibstaticd","Ws2_32","Winmm" } + "libprotobufd","crypto","ssl","zlibstaticd","Ws2_32","Winmm" } end if os.is("Linux") then defines {"_LINUX"} @@ -146,5 +156,11 @@ myfiles = files { myfiles, "main.cpp", + "ConvertGRPCBullet.cpp", + "ConvertGRPCBullet.h", + "pybullet.grpc.pb.cpp", + "pybullet.grpc.pb.h", + "pybullet.pb.cpp", + "pybullet.pb.h", } diff --git a/examples/SharedMemory/grpc/proto/pybullet.proto b/examples/SharedMemory/grpc/proto/pybullet.proto index 8c8b15875..cdedcfca0 100644 --- a/examples/SharedMemory/grpc/proto/pybullet.proto +++ b/examples/SharedMemory/grpc/proto/pybullet.proto @@ -1,5 +1,8 @@ syntax = "proto3"; +//for why oneof everywhere, see the sad decision here: +//https://github.com/protocolbuffers/protobuf/issues/1606 + option java_multiple_files = true; option java_package = "io.grpc.pybullet_grpc"; option java_outer_classname = "PyBulletProto"; @@ -40,24 +43,134 @@ message StepSimulationCommand }; message LoadUrdfCommand { - string urdfFileName=1; + string fileName=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; + int32 flags=6; oneof hasGlobalScaling { double globalScaling=7; } }; - message LoadUrdfStatus { - int32 objectUniqueId=1; + int32 bodyUniqueId=1; } +message LoadSdfCommand { + string fileName=1; + oneof hasUseMultiBody { int32 useMultiBody=2; } + oneof hasGlobalScaling { double globalScaling=3; + } +}; + +message SdfLoadedStatus +{ + repeated int32 bodyUniqueIds=2; +} + +message LoadMjcfCommand { + string fileName=1; + int32 flags=2; + +}; + +message MjcfLoadedStatus +{ + repeated int32 bodyUniqueIds=2; +} + + +message ChangeDynamicsCommand +{ + int32 bodyUniqueId=1; + int32 linkIndex=2; + + oneof hasMass { double mass=3;} + oneof hasLateralFriction { double lateralFriction=5;} + oneof hasSpinningFriction {double spinningFriction=6;} + oneof hasRollingFriction {double rollingFriction=7;} + oneof hasRestitution { double restitution=8;} + oneof haslinearDamping { double linearDamping=9;} + oneof hasangularDamping { double angularDamping=10;} + oneof hasContactStiffness { double contactStiffness=11;} + oneof hasContactDamping { double contactDamping=12;} + oneof hasLocalInertiaDiagonal { vec3 localInertiaDiagonal=13;} + oneof hasFrictionAnchor { int32 frictionAnchor=14;} + oneof hasccdSweptSphereRadius { double ccdSweptSphereRadius=15;} + oneof hasContactProcessingThreshold { double contactProcessingThreshold=16;} + oneof hasActivationState { int32 activationState=17;} +}; + +message GetDynamicsCommand +{ + int32 bodyUniqueId=1; + int32 linkIndex=2; +}; + +message GetDynamicsStatus +{ + double mass=3; + double lateralFriction=5; + double spinningFriction=6; + double rollingFriction=7; + double restitution=8; + double linearDamping=9; + double angularDamping=10; + double contactStiffness=11; + double contactDamping=12; + vec3 localInertiaDiagonal=13; + int32 frictionAnchor=14; + double ccdSweptSphereRadius=15; + double contactProcessingThreshold=16; + int32 activationState=17; +}; + + +message InitPoseCommand +{ + int32 bodyUniqueId=1; + repeated int32 hasInitialStateQ=2; + repeated double initialStateQ=3; + repeated int32 hasInitialStateQdot=4; + repeated double initialStateQdot=5; +}; + + +message RequestActualStateCommand +{ + int32 bodyUniqueId=1; + bool computeForwardKinematics=2; + bool computeLinkVelocities=3; +}; + +message SendActualStateStatus +{ + int32 bodyUniqueId=1; + int32 numLinks=2; + int32 numDegreeOfFreedomQ=3; + int32 numDegreeOfFreedomU=4; + + repeated double rootLocalInertialFrame=5; + + //actual state is only written by the server, read-only access by client is expected + repeated double actualStateQ=6; + repeated double actualStateQdot=7; + + //measured 6DOF force/torque sensors: force[x,y,z] and torque[x,y,z] + repeated double jointReactionForces=8; + + repeated double jointMotorForce=9; + + repeated double linkState=10; + repeated double linkWorldVelocities=11;//linear velocity and angular velocity in world space (x/y/z each). + repeated double linkLocalInertialFrames=12; +}; + + // The request message containing the command message PyBulletCommand { @@ -67,8 +180,13 @@ message PyBulletCommand { LoadUrdfCommand loadUrdfCommand = 3; TerminateServerCommand terminateServerCommand=4; StepSimulationCommand stepSimulationCommand= 5; + LoadSdfCommand loadSdfCommand=6; + LoadMjcfCommand loadMjcfCommand=7; + ChangeDynamicsCommand changeDynamicsCommand=8; + GetDynamicsCommand getDynamicsCommand=9; + InitPoseCommand initPoseCommand=10; + RequestActualStateCommand requestActualStateCommand=11; } - } @@ -79,6 +197,10 @@ message PyBulletStatus { oneof status { LoadUrdfStatus urdfStatus = 2; + SdfLoadedStatus sdfStatus = 3; + MjcfLoadedStatus mjcfStatus = 4; + GetDynamicsStatus getDynamicsStatus = 5; + SendActualStateStatus actualStateStatus = 6; } } diff --git a/examples/SharedMemory/grpc/pybullet.pb.cpp b/examples/SharedMemory/grpc/pybullet.pb.cpp index 2a841c7c6..5a3df827a 100644 --- a/examples/SharedMemory/grpc/pybullet.pb.cpp +++ b/examples/SharedMemory/grpc/pybullet.pb.cpp @@ -34,15 +34,63 @@ class LoadUrdfCommandDefaultTypeInternal : public ::google::protobuf::internal:: } _LoadUrdfCommand_default_instance_; class LoadUrdfStatusDefaultTypeInternal : public ::google::protobuf::internal::ExplicitlyConstructed { } _LoadUrdfStatus_default_instance_; +class LoadSdfCommandDefaultTypeInternal : public ::google::protobuf::internal::ExplicitlyConstructed { + public: + ::google::protobuf::int32 usemultibody_; + double globalscaling_; +} _LoadSdfCommand_default_instance_; +class SdfLoadedStatusDefaultTypeInternal : public ::google::protobuf::internal::ExplicitlyConstructed { +} _SdfLoadedStatus_default_instance_; +class LoadMjcfCommandDefaultTypeInternal : public ::google::protobuf::internal::ExplicitlyConstructed { +} _LoadMjcfCommand_default_instance_; +class MjcfLoadedStatusDefaultTypeInternal : public ::google::protobuf::internal::ExplicitlyConstructed { +} _MjcfLoadedStatus_default_instance_; +class ChangeDynamicsCommandDefaultTypeInternal : public ::google::protobuf::internal::ExplicitlyConstructed { + public: + double mass_; + double lateralfriction_; + double spinningfriction_; + double rollingfriction_; + double restitution_; + double lineardamping_; + double angulardamping_; + double contactstiffness_; + double contactdamping_; + const ::pybullet_grpc::vec3* localinertiadiagonal_; + ::google::protobuf::int32 frictionanchor_; + double ccdsweptsphereradius_; + double contactprocessingthreshold_; + ::google::protobuf::int32 activationstate_; +} _ChangeDynamicsCommand_default_instance_; +class GetDynamicsCommandDefaultTypeInternal : public ::google::protobuf::internal::ExplicitlyConstructed { +} _GetDynamicsCommand_default_instance_; +class GetDynamicsStatusDefaultTypeInternal : public ::google::protobuf::internal::ExplicitlyConstructed { +} _GetDynamicsStatus_default_instance_; +class InitPoseCommandDefaultTypeInternal : public ::google::protobuf::internal::ExplicitlyConstructed { +} _InitPoseCommand_default_instance_; +class RequestActualStateCommandDefaultTypeInternal : public ::google::protobuf::internal::ExplicitlyConstructed { +} _RequestActualStateCommand_default_instance_; +class SendActualStateStatusDefaultTypeInternal : public ::google::protobuf::internal::ExplicitlyConstructed { +} _SendActualStateStatus_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_; + const ::pybullet_grpc::LoadSdfCommand* loadsdfcommand_; + const ::pybullet_grpc::LoadMjcfCommand* loadmjcfcommand_; + const ::pybullet_grpc::ChangeDynamicsCommand* changedynamicscommand_; + const ::pybullet_grpc::GetDynamicsCommand* getdynamicscommand_; + const ::pybullet_grpc::InitPoseCommand* initposecommand_; + const ::pybullet_grpc::RequestActualStateCommand* requestactualstatecommand_; } _PyBulletCommand_default_instance_; class PyBulletStatusDefaultTypeInternal : public ::google::protobuf::internal::ExplicitlyConstructed { public: const ::pybullet_grpc::LoadUrdfStatus* urdfstatus_; + const ::pybullet_grpc::SdfLoadedStatus* sdfstatus_; + const ::pybullet_grpc::MjcfLoadedStatus* mjcfstatus_; + const ::pybullet_grpc::GetDynamicsStatus* getdynamicsstatus_; + const ::pybullet_grpc::SendActualStateStatus* actualstatestatus_; } _PyBulletStatus_default_instance_; namespace protobuf_pybullet_2eproto { @@ -50,7 +98,7 @@ namespace protobuf_pybullet_2eproto { namespace { -::google::protobuf::Metadata file_level_metadata[8]; +::google::protobuf::Metadata file_level_metadata[18]; } // namespace @@ -83,12 +131,12 @@ const ::google::protobuf::uint32 TableStruct::offsets[] = { 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, filename_), 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_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(LoadUrdfCommand, flags_), 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_), @@ -97,7 +145,122 @@ const ::google::protobuf::uint32 TableStruct::offsets[] = { GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(LoadUrdfStatus, _internal_metadata_), ~0u, // no _extensions_ ~0u, // no _oneof_case_ - GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(LoadUrdfStatus, objectuniqueid_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(LoadUrdfStatus, bodyuniqueid_), + ~0u, // no _has_bits_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(LoadSdfCommand, _internal_metadata_), + ~0u, // no _extensions_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(LoadSdfCommand, _oneof_case_[0]), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(LoadSdfCommand, filename_), + PROTO2_GENERATED_DEFAULT_ONEOF_FIELD_OFFSET((&_LoadSdfCommand_default_instance_), usemultibody_), + PROTO2_GENERATED_DEFAULT_ONEOF_FIELD_OFFSET((&_LoadSdfCommand_default_instance_), globalscaling_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(LoadSdfCommand, hasUseMultiBody_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(LoadSdfCommand, hasGlobalScaling_), + ~0u, // no _has_bits_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(SdfLoadedStatus, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(SdfLoadedStatus, bodyuniqueids_), + ~0u, // no _has_bits_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(LoadMjcfCommand, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(LoadMjcfCommand, filename_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(LoadMjcfCommand, flags_), + ~0u, // no _has_bits_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(MjcfLoadedStatus, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(MjcfLoadedStatus, bodyuniqueids_), + ~0u, // no _has_bits_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(ChangeDynamicsCommand, _internal_metadata_), + ~0u, // no _extensions_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(ChangeDynamicsCommand, _oneof_case_[0]), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(ChangeDynamicsCommand, bodyuniqueid_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(ChangeDynamicsCommand, linkindex_), + PROTO2_GENERATED_DEFAULT_ONEOF_FIELD_OFFSET((&_ChangeDynamicsCommand_default_instance_), mass_), + PROTO2_GENERATED_DEFAULT_ONEOF_FIELD_OFFSET((&_ChangeDynamicsCommand_default_instance_), lateralfriction_), + PROTO2_GENERATED_DEFAULT_ONEOF_FIELD_OFFSET((&_ChangeDynamicsCommand_default_instance_), spinningfriction_), + PROTO2_GENERATED_DEFAULT_ONEOF_FIELD_OFFSET((&_ChangeDynamicsCommand_default_instance_), rollingfriction_), + PROTO2_GENERATED_DEFAULT_ONEOF_FIELD_OFFSET((&_ChangeDynamicsCommand_default_instance_), restitution_), + PROTO2_GENERATED_DEFAULT_ONEOF_FIELD_OFFSET((&_ChangeDynamicsCommand_default_instance_), lineardamping_), + PROTO2_GENERATED_DEFAULT_ONEOF_FIELD_OFFSET((&_ChangeDynamicsCommand_default_instance_), angulardamping_), + PROTO2_GENERATED_DEFAULT_ONEOF_FIELD_OFFSET((&_ChangeDynamicsCommand_default_instance_), contactstiffness_), + PROTO2_GENERATED_DEFAULT_ONEOF_FIELD_OFFSET((&_ChangeDynamicsCommand_default_instance_), contactdamping_), + PROTO2_GENERATED_DEFAULT_ONEOF_FIELD_OFFSET((&_ChangeDynamicsCommand_default_instance_), localinertiadiagonal_), + PROTO2_GENERATED_DEFAULT_ONEOF_FIELD_OFFSET((&_ChangeDynamicsCommand_default_instance_), frictionanchor_), + PROTO2_GENERATED_DEFAULT_ONEOF_FIELD_OFFSET((&_ChangeDynamicsCommand_default_instance_), ccdsweptsphereradius_), + PROTO2_GENERATED_DEFAULT_ONEOF_FIELD_OFFSET((&_ChangeDynamicsCommand_default_instance_), contactprocessingthreshold_), + PROTO2_GENERATED_DEFAULT_ONEOF_FIELD_OFFSET((&_ChangeDynamicsCommand_default_instance_), activationstate_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(ChangeDynamicsCommand, hasMass_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(ChangeDynamicsCommand, hasLateralFriction_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(ChangeDynamicsCommand, hasSpinningFriction_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(ChangeDynamicsCommand, hasRollingFriction_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(ChangeDynamicsCommand, hasRestitution_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(ChangeDynamicsCommand, haslinearDamping_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(ChangeDynamicsCommand, hasangularDamping_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(ChangeDynamicsCommand, hasContactStiffness_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(ChangeDynamicsCommand, hasContactDamping_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(ChangeDynamicsCommand, hasLocalInertiaDiagonal_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(ChangeDynamicsCommand, hasFrictionAnchor_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(ChangeDynamicsCommand, hasccdSweptSphereRadius_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(ChangeDynamicsCommand, hasContactProcessingThreshold_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(ChangeDynamicsCommand, hasActivationState_), + ~0u, // no _has_bits_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(GetDynamicsCommand, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(GetDynamicsCommand, bodyuniqueid_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(GetDynamicsCommand, linkindex_), + ~0u, // no _has_bits_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(GetDynamicsStatus, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(GetDynamicsStatus, mass_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(GetDynamicsStatus, lateralfriction_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(GetDynamicsStatus, spinningfriction_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(GetDynamicsStatus, rollingfriction_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(GetDynamicsStatus, restitution_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(GetDynamicsStatus, lineardamping_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(GetDynamicsStatus, angulardamping_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(GetDynamicsStatus, contactstiffness_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(GetDynamicsStatus, contactdamping_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(GetDynamicsStatus, localinertiadiagonal_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(GetDynamicsStatus, frictionanchor_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(GetDynamicsStatus, ccdsweptsphereradius_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(GetDynamicsStatus, contactprocessingthreshold_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(GetDynamicsStatus, activationstate_), + ~0u, // no _has_bits_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(InitPoseCommand, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(InitPoseCommand, bodyuniqueid_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(InitPoseCommand, hasinitialstateq_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(InitPoseCommand, initialstateq_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(InitPoseCommand, hasinitialstateqdot_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(InitPoseCommand, initialstateqdot_), + ~0u, // no _has_bits_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(RequestActualStateCommand, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(RequestActualStateCommand, bodyuniqueid_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(RequestActualStateCommand, computeforwardkinematics_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(RequestActualStateCommand, computelinkvelocities_), + ~0u, // no _has_bits_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(SendActualStateStatus, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(SendActualStateStatus, bodyuniqueid_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(SendActualStateStatus, numlinks_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(SendActualStateStatus, numdegreeoffreedomq_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(SendActualStateStatus, numdegreeoffreedomu_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(SendActualStateStatus, rootlocalinertialframe_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(SendActualStateStatus, actualstateq_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(SendActualStateStatus, actualstateqdot_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(SendActualStateStatus, jointreactionforces_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(SendActualStateStatus, jointmotorforce_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(SendActualStateStatus, linkstate_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(SendActualStateStatus, linkworldvelocities_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(SendActualStateStatus, linklocalinertialframes_), ~0u, // no _has_bits_ GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(PyBulletCommand, _internal_metadata_), ~0u, // no _extensions_ @@ -106,6 +269,12 @@ const ::google::protobuf::uint32 TableStruct::offsets[] = { 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_), + PROTO2_GENERATED_DEFAULT_ONEOF_FIELD_OFFSET((&_PyBulletCommand_default_instance_), loadsdfcommand_), + PROTO2_GENERATED_DEFAULT_ONEOF_FIELD_OFFSET((&_PyBulletCommand_default_instance_), loadmjcfcommand_), + PROTO2_GENERATED_DEFAULT_ONEOF_FIELD_OFFSET((&_PyBulletCommand_default_instance_), changedynamicscommand_), + PROTO2_GENERATED_DEFAULT_ONEOF_FIELD_OFFSET((&_PyBulletCommand_default_instance_), getdynamicscommand_), + PROTO2_GENERATED_DEFAULT_ONEOF_FIELD_OFFSET((&_PyBulletCommand_default_instance_), initposecommand_), + PROTO2_GENERATED_DEFAULT_ONEOF_FIELD_OFFSET((&_PyBulletCommand_default_instance_), requestactualstatecommand_), GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(PyBulletCommand, commands_), ~0u, // no _has_bits_ GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(PyBulletStatus, _internal_metadata_), @@ -113,6 +282,10 @@ const ::google::protobuf::uint32 TableStruct::offsets[] = { 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_), + PROTO2_GENERATED_DEFAULT_ONEOF_FIELD_OFFSET((&_PyBulletStatus_default_instance_), sdfstatus_), + PROTO2_GENERATED_DEFAULT_ONEOF_FIELD_OFFSET((&_PyBulletStatus_default_instance_), mjcfstatus_), + PROTO2_GENERATED_DEFAULT_ONEOF_FIELD_OFFSET((&_PyBulletStatus_default_instance_), getdynamicsstatus_), + PROTO2_GENERATED_DEFAULT_ONEOF_FIELD_OFFSET((&_PyBulletStatus_default_instance_), actualstatestatus_), GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(PyBulletStatus, status_), }; @@ -123,8 +296,18 @@ static const ::google::protobuf::internal::MigrationSchema schemas[] = { { 20, -1, sizeof(StepSimulationCommand)}, { 24, -1, sizeof(LoadUrdfCommand)}, { 38, -1, sizeof(LoadUrdfStatus)}, - { 43, -1, sizeof(PyBulletCommand)}, - { 52, -1, sizeof(PyBulletStatus)}, + { 43, -1, sizeof(LoadSdfCommand)}, + { 52, -1, sizeof(SdfLoadedStatus)}, + { 57, -1, sizeof(LoadMjcfCommand)}, + { 63, -1, sizeof(MjcfLoadedStatus)}, + { 68, -1, sizeof(ChangeDynamicsCommand)}, + { 102, -1, sizeof(GetDynamicsCommand)}, + { 108, -1, sizeof(GetDynamicsStatus)}, + { 126, -1, sizeof(InitPoseCommand)}, + { 135, -1, sizeof(RequestActualStateCommand)}, + { 142, -1, sizeof(SendActualStateStatus)}, + { 158, -1, sizeof(PyBulletCommand)}, + { 173, -1, sizeof(PyBulletStatus)}, }; static ::google::protobuf::Message const * const file_default_instances[] = { @@ -134,6 +317,16 @@ static ::google::protobuf::Message const * const file_default_instances[] = { reinterpret_cast(&_StepSimulationCommand_default_instance_), reinterpret_cast(&_LoadUrdfCommand_default_instance_), reinterpret_cast(&_LoadUrdfStatus_default_instance_), + reinterpret_cast(&_LoadSdfCommand_default_instance_), + reinterpret_cast(&_SdfLoadedStatus_default_instance_), + reinterpret_cast(&_LoadMjcfCommand_default_instance_), + reinterpret_cast(&_MjcfLoadedStatus_default_instance_), + reinterpret_cast(&_ChangeDynamicsCommand_default_instance_), + reinterpret_cast(&_GetDynamicsCommand_default_instance_), + reinterpret_cast(&_GetDynamicsStatus_default_instance_), + reinterpret_cast(&_InitPoseCommand_default_instance_), + reinterpret_cast(&_RequestActualStateCommand_default_instance_), + reinterpret_cast(&_SendActualStateStatus_default_instance_), reinterpret_cast(&_PyBulletCommand_default_instance_), reinterpret_cast(&_PyBulletStatus_default_instance_), }; @@ -156,7 +349,7 @@ void protobuf_AssignDescriptorsOnce() { 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); + ::google::protobuf::internal::RegisterAllTypes(file_level_metadata, 18); } } // namespace @@ -174,10 +367,30 @@ void TableStruct::Shutdown() { delete file_level_metadata[4].reflection; _LoadUrdfStatus_default_instance_.Shutdown(); delete file_level_metadata[5].reflection; - _PyBulletCommand_default_instance_.Shutdown(); + _LoadSdfCommand_default_instance_.Shutdown(); delete file_level_metadata[6].reflection; - _PyBulletStatus_default_instance_.Shutdown(); + _SdfLoadedStatus_default_instance_.Shutdown(); delete file_level_metadata[7].reflection; + _LoadMjcfCommand_default_instance_.Shutdown(); + delete file_level_metadata[8].reflection; + _MjcfLoadedStatus_default_instance_.Shutdown(); + delete file_level_metadata[9].reflection; + _ChangeDynamicsCommand_default_instance_.Shutdown(); + delete file_level_metadata[10].reflection; + _GetDynamicsCommand_default_instance_.Shutdown(); + delete file_level_metadata[11].reflection; + _GetDynamicsStatus_default_instance_.Shutdown(); + delete file_level_metadata[12].reflection; + _InitPoseCommand_default_instance_.Shutdown(); + delete file_level_metadata[13].reflection; + _RequestActualStateCommand_default_instance_.Shutdown(); + delete file_level_metadata[14].reflection; + _SendActualStateStatus_default_instance_.Shutdown(); + delete file_level_metadata[15].reflection; + _PyBulletCommand_default_instance_.Shutdown(); + delete file_level_metadata[16].reflection; + _PyBulletStatus_default_instance_.Shutdown(); + delete file_level_metadata[17].reflection; } void TableStruct::InitDefaultsImpl() { @@ -190,6 +403,16 @@ void TableStruct::InitDefaultsImpl() { _StepSimulationCommand_default_instance_.DefaultConstruct(); _LoadUrdfCommand_default_instance_.DefaultConstruct(); _LoadUrdfStatus_default_instance_.DefaultConstruct(); + _LoadSdfCommand_default_instance_.DefaultConstruct(); + _SdfLoadedStatus_default_instance_.DefaultConstruct(); + _LoadMjcfCommand_default_instance_.DefaultConstruct(); + _MjcfLoadedStatus_default_instance_.DefaultConstruct(); + _ChangeDynamicsCommand_default_instance_.DefaultConstruct(); + _GetDynamicsCommand_default_instance_.DefaultConstruct(); + _GetDynamicsStatus_default_instance_.DefaultConstruct(); + _InitPoseCommand_default_instance_.DefaultConstruct(); + _RequestActualStateCommand_default_instance_.DefaultConstruct(); + _SendActualStateStatus_default_instance_.DefaultConstruct(); _PyBulletCommand_default_instance_.DefaultConstruct(); _PyBulletStatus_default_instance_.DefaultConstruct(); _LoadUrdfCommand_default_instance_.get_mutable()->initialposition_ = const_cast< ::pybullet_grpc::vec3*>( @@ -199,14 +422,53 @@ void TableStruct::InitDefaultsImpl() { _LoadUrdfCommand_default_instance_.usemultibody_ = 0; _LoadUrdfCommand_default_instance_.usefixedbase_ = false; _LoadUrdfCommand_default_instance_.globalscaling_ = 0; + _LoadSdfCommand_default_instance_.usemultibody_ = 0; + _LoadSdfCommand_default_instance_.globalscaling_ = 0; + _ChangeDynamicsCommand_default_instance_.mass_ = 0; + _ChangeDynamicsCommand_default_instance_.lateralfriction_ = 0; + _ChangeDynamicsCommand_default_instance_.spinningfriction_ = 0; + _ChangeDynamicsCommand_default_instance_.rollingfriction_ = 0; + _ChangeDynamicsCommand_default_instance_.restitution_ = 0; + _ChangeDynamicsCommand_default_instance_.lineardamping_ = 0; + _ChangeDynamicsCommand_default_instance_.angulardamping_ = 0; + _ChangeDynamicsCommand_default_instance_.contactstiffness_ = 0; + _ChangeDynamicsCommand_default_instance_.contactdamping_ = 0; + _ChangeDynamicsCommand_default_instance_.localinertiadiagonal_ = const_cast< ::pybullet_grpc::vec3*>( + ::pybullet_grpc::vec3::internal_default_instance()); + _ChangeDynamicsCommand_default_instance_.frictionanchor_ = 0; + _ChangeDynamicsCommand_default_instance_.ccdsweptsphereradius_ = 0; + _ChangeDynamicsCommand_default_instance_.contactprocessingthreshold_ = 0; + _ChangeDynamicsCommand_default_instance_.activationstate_ = 0; + _GetDynamicsStatus_default_instance_.get_mutable()->localinertiadiagonal_ = const_cast< ::pybullet_grpc::vec3*>( + ::pybullet_grpc::vec3::internal_default_instance()); _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()); + _PyBulletCommand_default_instance_.loadsdfcommand_ = const_cast< ::pybullet_grpc::LoadSdfCommand*>( + ::pybullet_grpc::LoadSdfCommand::internal_default_instance()); + _PyBulletCommand_default_instance_.loadmjcfcommand_ = const_cast< ::pybullet_grpc::LoadMjcfCommand*>( + ::pybullet_grpc::LoadMjcfCommand::internal_default_instance()); + _PyBulletCommand_default_instance_.changedynamicscommand_ = const_cast< ::pybullet_grpc::ChangeDynamicsCommand*>( + ::pybullet_grpc::ChangeDynamicsCommand::internal_default_instance()); + _PyBulletCommand_default_instance_.getdynamicscommand_ = const_cast< ::pybullet_grpc::GetDynamicsCommand*>( + ::pybullet_grpc::GetDynamicsCommand::internal_default_instance()); + _PyBulletCommand_default_instance_.initposecommand_ = const_cast< ::pybullet_grpc::InitPoseCommand*>( + ::pybullet_grpc::InitPoseCommand::internal_default_instance()); + _PyBulletCommand_default_instance_.requestactualstatecommand_ = const_cast< ::pybullet_grpc::RequestActualStateCommand*>( + ::pybullet_grpc::RequestActualStateCommand::internal_default_instance()); _PyBulletStatus_default_instance_.urdfstatus_ = const_cast< ::pybullet_grpc::LoadUrdfStatus*>( ::pybullet_grpc::LoadUrdfStatus::internal_default_instance()); + _PyBulletStatus_default_instance_.sdfstatus_ = const_cast< ::pybullet_grpc::SdfLoadedStatus*>( + ::pybullet_grpc::SdfLoadedStatus::internal_default_instance()); + _PyBulletStatus_default_instance_.mjcfstatus_ = const_cast< ::pybullet_grpc::MjcfLoadedStatus*>( + ::pybullet_grpc::MjcfLoadedStatus::internal_default_instance()); + _PyBulletStatus_default_instance_.getdynamicsstatus_ = const_cast< ::pybullet_grpc::GetDynamicsStatus*>( + ::pybullet_grpc::GetDynamicsStatus::internal_default_instance()); + _PyBulletStatus_default_instance_.actualstatestatus_ = const_cast< ::pybullet_grpc::SendActualStateStatus*>( + ::pybullet_grpc::SendActualStateStatus::internal_default_instance()); } void InitDefaults() { @@ -220,31 +482,99 @@ void AddDescriptorsImpl() { "\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" + "eason\030\001 \001(\t\"\027\n\025StepSimulationCommand\"\225\002\n" + "\017LoadUrdfCommand\022\020\n\010fileName\030\001 \001(\t\022,\n\017in" + "itialPosition\030\002 \001(\0132\023.pybullet_grpc.vec3" + "\0220\n\022initialOrientation\030\003 \001(\0132\024.pybullet_" + "grpc.quat4\022\026\n\014useMultiBody\030\004 \001(\005H\000\022\026\n\014us" + "eFixedBase\030\005 \001(\010H\001\022\r\n\005flags\030\006 \001(\005\022\027\n\rglo" + "balScaling\030\007 \001(\001H\002B\021\n\017hasUseMultiBodyB\021\n" + "\017hasUseFixedBaseB\022\n\020hasGlobalScaling\"&\n\016" + "LoadUrdfStatus\022\024\n\014bodyUniqueId\030\001 \001(\005\"z\n\016" + "LoadSdfCommand\022\020\n\010fileName\030\001 \001(\t\022\026\n\014useM" + "ultiBody\030\002 \001(\005H\000\022\027\n\rglobalScaling\030\003 \001(\001H" + "\001B\021\n\017hasUseMultiBodyB\022\n\020hasGlobalScaling" + "\"(\n\017SdfLoadedStatus\022\025\n\rbodyUniqueIds\030\002 \003" + "(\005\"2\n\017LoadMjcfCommand\022\020\n\010fileName\030\001 \001(\t\022" + "\r\n\005flags\030\002 \001(\005\")\n\020MjcfLoadedStatus\022\025\n\rbo" + "dyUniqueIds\030\002 \003(\005\"\211\006\n\025ChangeDynamicsComm" + "and\022\024\n\014bodyUniqueId\030\001 \001(\005\022\021\n\tlinkIndex\030\002" + " \001(\005\022\016\n\004mass\030\003 \001(\001H\000\022\031\n\017lateralFriction\030" + "\005 \001(\001H\001\022\032\n\020spinningFriction\030\006 \001(\001H\002\022\031\n\017r" + "ollingFriction\030\007 \001(\001H\003\022\025\n\013restitution\030\010 " + "\001(\001H\004\022\027\n\rlinearDamping\030\t \001(\001H\005\022\030\n\016angula" + "rDamping\030\n \001(\001H\006\022\032\n\020contactStiffness\030\013 \001" + "(\001H\007\022\030\n\016contactDamping\030\014 \001(\001H\010\0223\n\024localI" + "nertiaDiagonal\030\r \001(\0132\023.pybullet_grpc.vec" + "3H\t\022\030\n\016frictionAnchor\030\016 \001(\005H\n\022\036\n\024ccdSwep" + "tSphereRadius\030\017 \001(\001H\013\022$\n\032contactProcessi" + "ngThreshold\030\020 \001(\001H\014\022\031\n\017activationState\030\021" + " \001(\005H\rB\t\n\007hasMassB\024\n\022hasLateralFrictionB" + "\025\n\023hasSpinningFrictionB\024\n\022hasRollingFric" + "tionB\020\n\016hasRestitutionB\022\n\020haslinearDampi" + "ngB\023\n\021hasangularDampingB\025\n\023hasContactSti" + "ffnessB\023\n\021hasContactDampingB\031\n\027hasLocalI" + "nertiaDiagonalB\023\n\021hasFrictionAnchorB\031\n\027h" + "asccdSweptSphereRadiusB\037\n\035hasContactProc" + "essingThresholdB\024\n\022hasActivationState\"=\n" + "\022GetDynamicsCommand\022\024\n\014bodyUniqueId\030\001 \001(" + "\005\022\021\n\tlinkIndex\030\002 \001(\005\"\211\003\n\021GetDynamicsStat" + "us\022\014\n\004mass\030\003 \001(\001\022\027\n\017lateralFriction\030\005 \001(" + "\001\022\030\n\020spinningFriction\030\006 \001(\001\022\027\n\017rollingFr" + "iction\030\007 \001(\001\022\023\n\013restitution\030\010 \001(\001\022\025\n\rlin" + "earDamping\030\t \001(\001\022\026\n\016angularDamping\030\n \001(\001" + "\022\030\n\020contactStiffness\030\013 \001(\001\022\026\n\016contactDam" + "ping\030\014 \001(\001\0221\n\024localInertiaDiagonal\030\r \001(\013" + "2\023.pybullet_grpc.vec3\022\026\n\016frictionAnchor\030" + "\016 \001(\005\022\034\n\024ccdSweptSphereRadius\030\017 \001(\001\022\"\n\032c" + "ontactProcessingThreshold\030\020 \001(\001\022\027\n\017activ" + "ationState\030\021 \001(\005\"\217\001\n\017InitPoseCommand\022\024\n\014" + "bodyUniqueId\030\001 \001(\005\022\030\n\020hasInitialStateQ\030\002" + " \003(\005\022\025\n\rinitialStateQ\030\003 \003(\001\022\033\n\023hasInitia" + "lStateQdot\030\004 \003(\005\022\030\n\020initialStateQdot\030\005 \003" + "(\001\"r\n\031RequestActualStateCommand\022\024\n\014bodyU" + "niqueId\030\001 \001(\005\022 \n\030computeForwardKinematic" + "s\030\002 \001(\010\022\035\n\025computeLinkVelocities\030\003 \001(\010\"\317" + "\002\n\025SendActualStateStatus\022\024\n\014bodyUniqueId" + "\030\001 \001(\005\022\020\n\010numLinks\030\002 \001(\005\022\033\n\023numDegreeOfF" + "reedomQ\030\003 \001(\005\022\033\n\023numDegreeOfFreedomU\030\004 \001" + "(\005\022\036\n\026rootLocalInertialFrame\030\005 \003(\001\022\024\n\014ac" + "tualStateQ\030\006 \003(\001\022\027\n\017actualStateQdot\030\007 \003(" + "\001\022\033\n\023jointReactionForces\030\010 \003(\001\022\027\n\017jointM" + "otorForce\030\t \003(\001\022\021\n\tlinkState\030\n \003(\001\022\033\n\023li" + "nkWorldVelocities\030\013 \003(\001\022\037\n\027linkLocalIner" + "tialFrames\030\014 \003(\001\"\203\005\n\017PyBulletCommand\022\023\n\013" + "commandType\030\001 \001(\005\0229\n\017loadUrdfCommand\030\003 \001" + "(\0132\036.pybullet_grpc.LoadUrdfCommandH\000\022G\n\026" + "terminateServerCommand\030\004 \001(\0132%.pybullet_" + "grpc.TerminateServerCommandH\000\022E\n\025stepSim" + "ulationCommand\030\005 \001(\0132$.pybullet_grpc.Ste" + "pSimulationCommandH\000\0227\n\016loadSdfCommand\030\006" + " \001(\0132\035.pybullet_grpc.LoadSdfCommandH\000\0229\n" + "\017loadMjcfCommand\030\007 \001(\0132\036.pybullet_grpc.L" + "oadMjcfCommandH\000\022E\n\025changeDynamicsComman" + "d\030\010 \001(\0132$.pybullet_grpc.ChangeDynamicsCo" + "mmandH\000\022\?\n\022getDynamicsCommand\030\t \001(\0132!.py" + "bullet_grpc.GetDynamicsCommandH\000\0229\n\017init" + "PoseCommand\030\n \001(\0132\036.pybullet_grpc.InitPo" + "seCommandH\000\022M\n\031requestActualStateCommand" + "\030\013 \001(\0132(.pybullet_grpc.RequestActualStat" + "eCommandH\000B\n\n\010commands\"\321\002\n\016PyBulletStatu" + "s\022\022\n\nstatusType\030\001 \001(\005\0223\n\nurdfStatus\030\002 \001(" + "\0132\035.pybullet_grpc.LoadUrdfStatusH\000\0223\n\tsd" + "fStatus\030\003 \001(\0132\036.pybullet_grpc.SdfLoadedS" + "tatusH\000\0225\n\nmjcfStatus\030\004 \001(\0132\037.pybullet_g" + "rpc.MjcfLoadedStatusH\000\022=\n\021getDynamicsSta" + "tus\030\005 \001(\0132 .pybullet_grpc.GetDynamicsSta" + "tusH\000\022A\n\021actualStateStatus\030\006 \001(\0132$.pybul" + "let_grpc.SendActualStateStatusH\000B\010\n\006stat" + "us2_\n\013PyBulletAPI\022P\n\rSubmitCommand\022\036.pyb" + "ullet_grpc.PyBulletCommand\032\035.pybullet_gr" + "pc.PyBulletStatus\"\000B.\n\025io.grpc.pybullet_" + "grpcB\rPyBulletProtoP\001\242\002\003PBGb\006proto3" }; ::google::protobuf::DescriptorPool::InternalAddGeneratedFile( - descriptor, 1036); + descriptor, 3755); ::google::protobuf::MessageFactory::InternalRegisterGeneratedFile( "pybullet.proto", &protobuf_RegisterTypes); ::google::protobuf::internal::OnShutdown(&TableStruct::Shutdown); @@ -1405,12 +1735,12 @@ void StepSimulationCommand::InternalSwap(StepSimulationCommand* other) { // =================================================================== #if !defined(_MSC_VER) || _MSC_VER >= 1900 -const int LoadUrdfCommand::kUrdfFileNameFieldNumber; +const int LoadUrdfCommand::kFileNameFieldNumber; const int LoadUrdfCommand::kInitialPositionFieldNumber; const int LoadUrdfCommand::kInitialOrientationFieldNumber; const int LoadUrdfCommand::kUseMultiBodyFieldNumber; const int LoadUrdfCommand::kUseFixedBaseFieldNumber; -const int LoadUrdfCommand::kUrdfFlagsFieldNumber; +const int LoadUrdfCommand::kFlagsFieldNumber; const int LoadUrdfCommand::kGlobalScalingFieldNumber; #endif // !defined(_MSC_VER) || _MSC_VER >= 1900 @@ -1427,9 +1757,9 @@ LoadUrdfCommand::LoadUrdfCommand(const LoadUrdfCommand& from) _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_); + filename_.UnsafeSetDefault(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); + if (from.filename().size() > 0) { + filename_.AssignWithDefault(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), from.filename_); } if (from.has_initialposition()) { initialposition_ = new ::pybullet_grpc::vec3(*from.initialposition_); @@ -1441,7 +1771,7 @@ LoadUrdfCommand::LoadUrdfCommand(const LoadUrdfCommand& from) } else { initialorientation_ = NULL; } - urdfflags_ = from.urdfflags_; + flags_ = from.flags_; clear_has_hasUseMultiBody(); switch (from.hasUseMultiBody_case()) { case kUseMultiBody: { @@ -1476,9 +1806,9 @@ LoadUrdfCommand::LoadUrdfCommand(const LoadUrdfCommand& from) } void LoadUrdfCommand::SharedCtor() { - urdffilename_.UnsafeSetDefault(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); - ::memset(&initialposition_, 0, reinterpret_cast(&urdfflags_) - - reinterpret_cast(&initialposition_) + sizeof(urdfflags_)); + filename_.UnsafeSetDefault(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); + ::memset(&initialposition_, 0, reinterpret_cast(&flags_) - + reinterpret_cast(&initialposition_) + sizeof(flags_)); clear_has_hasUseMultiBody(); clear_has_hasUseFixedBase(); clear_has_hasGlobalScaling(); @@ -1491,7 +1821,7 @@ LoadUrdfCommand::~LoadUrdfCommand() { } void LoadUrdfCommand::SharedDtor() { - urdffilename_.DestroyNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); + filename_.DestroyNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); if (this != internal_default_instance()) { delete initialposition_; } @@ -1577,7 +1907,7 @@ void LoadUrdfCommand::clear_hasGlobalScaling() { void LoadUrdfCommand::Clear() { // @@protoc_insertion_point(message_clear_start:pybullet_grpc.LoadUrdfCommand) - urdffilename_.ClearToEmptyNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); + filename_.ClearToEmptyNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); if (GetArenaNoVirtual() == NULL && initialposition_ != NULL) { delete initialposition_; } @@ -1586,7 +1916,7 @@ void LoadUrdfCommand::Clear() { delete initialorientation_; } initialorientation_ = NULL; - urdfflags_ = 0; + flags_ = 0; clear_hasUseMultiBody(); clear_hasUseFixedBase(); clear_hasGlobalScaling(); @@ -1602,15 +1932,15 @@ bool LoadUrdfCommand::MergePartialFromCodedStream( tag = p.first; if (!p.second) goto handle_unusual; switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { - // string urdfFileName = 1; + // string fileName = 1; case 1: { if (tag == 10u) { DO_(::google::protobuf::internal::WireFormatLite::ReadString( - input, this->mutable_urdffilename())); + input, this->mutable_filename())); DO_(::google::protobuf::internal::WireFormatLite::VerifyUtf8String( - this->urdffilename().data(), this->urdffilename().length(), + this->filename().data(), this->filename().length(), ::google::protobuf::internal::WireFormatLite::PARSE, - "pybullet_grpc.LoadUrdfCommand.urdfFileName")); + "pybullet_grpc.LoadUrdfCommand.fileName")); } else { goto handle_unusual; } @@ -1667,13 +1997,13 @@ bool LoadUrdfCommand::MergePartialFromCodedStream( break; } - // int32 urdfFlags = 6; + // int32 flags = 6; case 6: { if (tag == 48u) { DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>( - input, &urdfflags_))); + input, &flags_))); } else { goto handle_unusual; } @@ -1718,14 +2048,14 @@ failure: 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) { + // string fileName = 1; + if (this->filename().size() > 0) { ::google::protobuf::internal::WireFormatLite::VerifyUtf8String( - this->urdffilename().data(), this->urdffilename().length(), + this->filename().data(), this->filename().length(), ::google::protobuf::internal::WireFormatLite::SERIALIZE, - "pybullet_grpc.LoadUrdfCommand.urdfFileName"); + "pybullet_grpc.LoadUrdfCommand.fileName"); ::google::protobuf::internal::WireFormatLite::WriteStringMaybeAliased( - 1, this->urdffilename(), output); + 1, this->filename(), output); } // .pybullet_grpc.vec3 initialPosition = 2; @@ -1750,9 +2080,9 @@ void LoadUrdfCommand::SerializeWithCachedSizes( ::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); + // int32 flags = 6; + if (this->flags() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteInt32(6, this->flags(), output); } // double globalScaling = 7; @@ -1767,15 +2097,15 @@ void LoadUrdfCommand::SerializeWithCachedSizes( 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) { + // string fileName = 1; + if (this->filename().size() > 0) { ::google::protobuf::internal::WireFormatLite::VerifyUtf8String( - this->urdffilename().data(), this->urdffilename().length(), + this->filename().data(), this->filename().length(), ::google::protobuf::internal::WireFormatLite::SERIALIZE, - "pybullet_grpc.LoadUrdfCommand.urdfFileName"); + "pybullet_grpc.LoadUrdfCommand.fileName"); target = ::google::protobuf::internal::WireFormatLite::WriteStringToArray( - 1, this->urdffilename(), target); + 1, this->filename(), target); } // .pybullet_grpc.vec3 initialPosition = 2; @@ -1802,9 +2132,9 @@ void LoadUrdfCommand::SerializeWithCachedSizes( 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); + // int32 flags = 6; + if (this->flags() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteInt32ToArray(6, this->flags(), target); } // double globalScaling = 7; @@ -1820,11 +2150,11 @@ 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) { + // string fileName = 1; + if (this->filename().size() > 0) { total_size += 1 + ::google::protobuf::internal::WireFormatLite::StringSize( - this->urdffilename()); + this->filename()); } // .pybullet_grpc.vec3 initialPosition = 2; @@ -1841,11 +2171,11 @@ size_t LoadUrdfCommand::ByteSizeLong() const { *this->initialorientation_); } - // int32 urdfFlags = 6; - if (this->urdfflags() != 0) { + // int32 flags = 6; + if (this->flags() != 0) { total_size += 1 + ::google::protobuf::internal::WireFormatLite::Int32Size( - this->urdfflags()); + this->flags()); } switch (hasUseMultiBody_case()) { @@ -1906,9 +2236,9 @@ 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) { + if (from.filename().size() > 0) { - urdffilename_.AssignWithDefault(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), from.urdffilename_); + filename_.AssignWithDefault(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), from.filename_); } if (from.has_initialposition()) { mutable_initialposition()->::pybullet_grpc::vec3::MergeFrom(from.initialposition()); @@ -1916,8 +2246,8 @@ void LoadUrdfCommand::MergeFrom(const LoadUrdfCommand& from) { if (from.has_initialorientation()) { mutable_initialorientation()->::pybullet_grpc::quat4::MergeFrom(from.initialorientation()); } - if (from.urdfflags() != 0) { - set_urdfflags(from.urdfflags()); + if (from.flags() != 0) { + set_flags(from.flags()); } switch (from.hasUseMultiBody_case()) { case kUseMultiBody: { @@ -1971,10 +2301,10 @@ void LoadUrdfCommand::Swap(LoadUrdfCommand* other) { InternalSwap(other); } void LoadUrdfCommand::InternalSwap(LoadUrdfCommand* other) { - urdffilename_.Swap(&other->urdffilename_); + filename_.Swap(&other->filename_); std::swap(initialposition_, other->initialposition_); std::swap(initialorientation_, other->initialorientation_); - std::swap(urdfflags_, other->urdfflags_); + std::swap(flags_, other->flags_); std::swap(hasUseMultiBody_, other->hasUseMultiBody_); std::swap(_oneof_case_[0], other->_oneof_case_[0]); std::swap(hasUseFixedBase_, other->hasUseFixedBase_); @@ -1992,56 +2322,56 @@ void LoadUrdfCommand::InternalSwap(LoadUrdfCommand* other) { #if PROTOBUF_INLINE_NOT_IN_HEADERS // LoadUrdfCommand -// string urdfFileName = 1; -void LoadUrdfCommand::clear_urdffilename() { - urdffilename_.ClearToEmptyNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); +// string fileName = 1; +void LoadUrdfCommand::clear_filename() { + filename_.ClearToEmptyNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); } -const ::std::string& LoadUrdfCommand::urdffilename() const { - // @@protoc_insertion_point(field_get:pybullet_grpc.LoadUrdfCommand.urdfFileName) - return urdffilename_.GetNoArena(); +const ::std::string& LoadUrdfCommand::filename() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.LoadUrdfCommand.fileName) + return filename_.GetNoArena(); } -void LoadUrdfCommand::set_urdffilename(const ::std::string& value) { +void LoadUrdfCommand::set_filename(const ::std::string& value) { - urdffilename_.SetNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), value); - // @@protoc_insertion_point(field_set:pybullet_grpc.LoadUrdfCommand.urdfFileName) + filename_.SetNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), value); + // @@protoc_insertion_point(field_set:pybullet_grpc.LoadUrdfCommand.fileName) } #if LANG_CXX11 -void LoadUrdfCommand::set_urdffilename(::std::string&& value) { +void LoadUrdfCommand::set_filename(::std::string&& value) { - urdffilename_.SetNoArena( + filename_.SetNoArena( &::google::protobuf::internal::GetEmptyStringAlreadyInited(), std::move(value)); - // @@protoc_insertion_point(field_set_rvalue:pybullet_grpc.LoadUrdfCommand.urdfFileName) + // @@protoc_insertion_point(field_set_rvalue:pybullet_grpc.LoadUrdfCommand.fileName) } #endif -void LoadUrdfCommand::set_urdffilename(const char* value) { +void LoadUrdfCommand::set_filename(const char* value) { - urdffilename_.SetNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), ::std::string(value)); - // @@protoc_insertion_point(field_set_char:pybullet_grpc.LoadUrdfCommand.urdfFileName) + filename_.SetNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), ::std::string(value)); + // @@protoc_insertion_point(field_set_char:pybullet_grpc.LoadUrdfCommand.fileName) } -void LoadUrdfCommand::set_urdffilename(const char* value, size_t size) { +void LoadUrdfCommand::set_filename(const char* value, size_t size) { - urdffilename_.SetNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), + filename_.SetNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), ::std::string(reinterpret_cast(value), size)); - // @@protoc_insertion_point(field_set_pointer:pybullet_grpc.LoadUrdfCommand.urdfFileName) + // @@protoc_insertion_point(field_set_pointer:pybullet_grpc.LoadUrdfCommand.fileName) } -::std::string* LoadUrdfCommand::mutable_urdffilename() { +::std::string* LoadUrdfCommand::mutable_filename() { - // @@protoc_insertion_point(field_mutable:pybullet_grpc.LoadUrdfCommand.urdfFileName) - return urdffilename_.MutableNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); + // @@protoc_insertion_point(field_mutable:pybullet_grpc.LoadUrdfCommand.fileName) + return filename_.MutableNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); } -::std::string* LoadUrdfCommand::release_urdffilename() { - // @@protoc_insertion_point(field_release:pybullet_grpc.LoadUrdfCommand.urdfFileName) +::std::string* LoadUrdfCommand::release_filename() { + // @@protoc_insertion_point(field_release:pybullet_grpc.LoadUrdfCommand.fileName) - return urdffilename_.ReleaseNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); + return filename_.ReleaseNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); } -void LoadUrdfCommand::set_allocated_urdffilename(::std::string* urdffilename) { - if (urdffilename != NULL) { +void LoadUrdfCommand::set_allocated_filename(::std::string* filename) { + if (filename != NULL) { } else { } - urdffilename_.SetAllocatedNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), urdffilename); - // @@protoc_insertion_point(field_set_allocated:pybullet_grpc.LoadUrdfCommand.urdfFileName) + filename_.SetAllocatedNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), filename); + // @@protoc_insertion_point(field_set_allocated:pybullet_grpc.LoadUrdfCommand.fileName) } // .pybullet_grpc.vec3 initialPosition = 2; @@ -2180,18 +2510,18 @@ void LoadUrdfCommand::set_usefixedbase(bool value) { // @@protoc_insertion_point(field_set:pybullet_grpc.LoadUrdfCommand.useFixedBase) } -// int32 urdfFlags = 6; -void LoadUrdfCommand::clear_urdfflags() { - urdfflags_ = 0; +// int32 flags = 6; +void LoadUrdfCommand::clear_flags() { + flags_ = 0; } -::google::protobuf::int32 LoadUrdfCommand::urdfflags() const { - // @@protoc_insertion_point(field_get:pybullet_grpc.LoadUrdfCommand.urdfFlags) - return urdfflags_; +::google::protobuf::int32 LoadUrdfCommand::flags() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.LoadUrdfCommand.flags) + return flags_; } -void LoadUrdfCommand::set_urdfflags(::google::protobuf::int32 value) { +void LoadUrdfCommand::set_flags(::google::protobuf::int32 value) { - urdfflags_ = value; - // @@protoc_insertion_point(field_set:pybullet_grpc.LoadUrdfCommand.urdfFlags) + flags_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.LoadUrdfCommand.flags) } // double globalScaling = 7; @@ -2255,7 +2585,7 @@ LoadUrdfCommand::HasGlobalScalingCase LoadUrdfCommand::hasGlobalScaling_case() c // =================================================================== #if !defined(_MSC_VER) || _MSC_VER >= 1900 -const int LoadUrdfStatus::kObjectUniqueIdFieldNumber; +const int LoadUrdfStatus::kBodyUniqueIdFieldNumber; #endif // !defined(_MSC_VER) || _MSC_VER >= 1900 LoadUrdfStatus::LoadUrdfStatus() @@ -2271,12 +2601,12 @@ LoadUrdfStatus::LoadUrdfStatus(const LoadUrdfStatus& from) _internal_metadata_(NULL), _cached_size_(0) { _internal_metadata_.MergeFrom(from._internal_metadata_); - objectuniqueid_ = from.objectuniqueid_; + bodyuniqueid_ = from.bodyuniqueid_; // @@protoc_insertion_point(copy_constructor:pybullet_grpc.LoadUrdfStatus) } void LoadUrdfStatus::SharedCtor() { - objectuniqueid_ = 0; + bodyuniqueid_ = 0; _cached_size_ = 0; } @@ -2313,7 +2643,7 @@ LoadUrdfStatus* LoadUrdfStatus::New(::google::protobuf::Arena* arena) const { void LoadUrdfStatus::Clear() { // @@protoc_insertion_point(message_clear_start:pybullet_grpc.LoadUrdfStatus) - objectuniqueid_ = 0; + bodyuniqueid_ = 0; } bool LoadUrdfStatus::MergePartialFromCodedStream( @@ -2326,13 +2656,13 @@ bool LoadUrdfStatus::MergePartialFromCodedStream( tag = p.first; if (!p.second) goto handle_unusual; switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { - // int32 objectUniqueId = 1; + // int32 bodyUniqueId = 1; case 1: { if (tag == 8u) { DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>( - input, &objectuniqueid_))); + input, &bodyuniqueid_))); } else { goto handle_unusual; } @@ -2363,9 +2693,9 @@ failure: 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); + // int32 bodyUniqueId = 1; + if (this->bodyuniqueid() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteInt32(1, this->bodyuniqueid(), output); } // @@protoc_insertion_point(serialize_end:pybullet_grpc.LoadUrdfStatus) @@ -2375,9 +2705,9 @@ void LoadUrdfStatus::SerializeWithCachedSizes( 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); + // int32 bodyUniqueId = 1; + if (this->bodyuniqueid() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteInt32ToArray(1, this->bodyuniqueid(), target); } // @@protoc_insertion_point(serialize_to_array_end:pybullet_grpc.LoadUrdfStatus) @@ -2388,11 +2718,11 @@ 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) { + // int32 bodyUniqueId = 1; + if (this->bodyuniqueid() != 0) { total_size += 1 + ::google::protobuf::internal::WireFormatLite::Int32Size( - this->objectuniqueid()); + this->bodyuniqueid()); } int cached_size = ::google::protobuf::internal::ToCachedSize(total_size); @@ -2421,8 +2751,8 @@ 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()); + if (from.bodyuniqueid() != 0) { + set_bodyuniqueid(from.bodyuniqueid()); } } @@ -2449,7 +2779,7 @@ void LoadUrdfStatus::Swap(LoadUrdfStatus* other) { InternalSwap(other); } void LoadUrdfStatus::InternalSwap(LoadUrdfStatus* other) { - std::swap(objectuniqueid_, other->objectuniqueid_); + std::swap(bodyuniqueid_, other->bodyuniqueid_); std::swap(_cached_size_, other->_cached_size_); } @@ -2461,18 +2791,6417 @@ void LoadUrdfStatus::InternalSwap(LoadUrdfStatus* other) { #if PROTOBUF_INLINE_NOT_IN_HEADERS // LoadUrdfStatus -// int32 objectUniqueId = 1; -void LoadUrdfStatus::clear_objectuniqueid() { - objectuniqueid_ = 0; +// int32 bodyUniqueId = 1; +void LoadUrdfStatus::clear_bodyuniqueid() { + bodyuniqueid_ = 0; } -::google::protobuf::int32 LoadUrdfStatus::objectuniqueid() const { - // @@protoc_insertion_point(field_get:pybullet_grpc.LoadUrdfStatus.objectUniqueId) - return objectuniqueid_; +::google::protobuf::int32 LoadUrdfStatus::bodyuniqueid() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.LoadUrdfStatus.bodyUniqueId) + return bodyuniqueid_; } -void LoadUrdfStatus::set_objectuniqueid(::google::protobuf::int32 value) { +void LoadUrdfStatus::set_bodyuniqueid(::google::protobuf::int32 value) { - objectuniqueid_ = value; - // @@protoc_insertion_point(field_set:pybullet_grpc.LoadUrdfStatus.objectUniqueId) + bodyuniqueid_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.LoadUrdfStatus.bodyUniqueId) +} + +#endif // PROTOBUF_INLINE_NOT_IN_HEADERS + +// =================================================================== + +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const int LoadSdfCommand::kFileNameFieldNumber; +const int LoadSdfCommand::kUseMultiBodyFieldNumber; +const int LoadSdfCommand::kGlobalScalingFieldNumber; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 + +LoadSdfCommand::LoadSdfCommand() + : ::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.LoadSdfCommand) +} +LoadSdfCommand::LoadSdfCommand(const LoadSdfCommand& from) + : ::google::protobuf::Message(), + _internal_metadata_(NULL), + _cached_size_(0) { + _internal_metadata_.MergeFrom(from._internal_metadata_); + filename_.UnsafeSetDefault(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); + if (from.filename().size() > 0) { + filename_.AssignWithDefault(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), from.filename_); + } + clear_has_hasUseMultiBody(); + switch (from.hasUseMultiBody_case()) { + case kUseMultiBody: { + set_usemultibody(from.usemultibody()); + break; + } + case HASUSEMULTIBODY_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.LoadSdfCommand) +} + +void LoadSdfCommand::SharedCtor() { + filename_.UnsafeSetDefault(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); + clear_has_hasUseMultiBody(); + clear_has_hasGlobalScaling(); + _cached_size_ = 0; +} + +LoadSdfCommand::~LoadSdfCommand() { + // @@protoc_insertion_point(destructor:pybullet_grpc.LoadSdfCommand) + SharedDtor(); +} + +void LoadSdfCommand::SharedDtor() { + filename_.DestroyNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); + if (has_hasUseMultiBody()) { + clear_hasUseMultiBody(); + } + if (has_hasGlobalScaling()) { + clear_hasGlobalScaling(); + } +} + +void LoadSdfCommand::SetCachedSize(int size) const { + GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN(); + _cached_size_ = size; + GOOGLE_SAFE_CONCURRENT_WRITES_END(); +} +const ::google::protobuf::Descriptor* LoadSdfCommand::descriptor() { + protobuf_pybullet_2eproto::protobuf_AssignDescriptorsOnce(); + return protobuf_pybullet_2eproto::file_level_metadata[6].descriptor; +} + +const LoadSdfCommand& LoadSdfCommand::default_instance() { + protobuf_pybullet_2eproto::InitDefaults(); + return *internal_default_instance(); +} + +LoadSdfCommand* LoadSdfCommand::New(::google::protobuf::Arena* arena) const { + LoadSdfCommand* n = new LoadSdfCommand; + if (arena != NULL) { + arena->Own(n); + } + return n; +} + +void LoadSdfCommand::clear_hasUseMultiBody() { +// @@protoc_insertion_point(one_of_clear_start:pybullet_grpc.LoadSdfCommand) + switch (hasUseMultiBody_case()) { + case kUseMultiBody: { + // No need to clear + break; + } + case HASUSEMULTIBODY_NOT_SET: { + break; + } + } + _oneof_case_[0] = HASUSEMULTIBODY_NOT_SET; +} + +void LoadSdfCommand::clear_hasGlobalScaling() { +// @@protoc_insertion_point(one_of_clear_start:pybullet_grpc.LoadSdfCommand) + switch (hasGlobalScaling_case()) { + case kGlobalScaling: { + // No need to clear + break; + } + case HASGLOBALSCALING_NOT_SET: { + break; + } + } + _oneof_case_[1] = HASGLOBALSCALING_NOT_SET; +} + + +void LoadSdfCommand::Clear() { +// @@protoc_insertion_point(message_clear_start:pybullet_grpc.LoadSdfCommand) + filename_.ClearToEmptyNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); + clear_hasUseMultiBody(); + clear_hasGlobalScaling(); +} + +bool LoadSdfCommand::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.LoadSdfCommand) + 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 fileName = 1; + case 1: { + if (tag == 10u) { + DO_(::google::protobuf::internal::WireFormatLite::ReadString( + input, this->mutable_filename())); + DO_(::google::protobuf::internal::WireFormatLite::VerifyUtf8String( + this->filename().data(), this->filename().length(), + ::google::protobuf::internal::WireFormatLite::PARSE, + "pybullet_grpc.LoadSdfCommand.fileName")); + } else { + goto handle_unusual; + } + break; + } + + // int32 useMultiBody = 2; + case 2: { + if (tag == 16u) { + 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; + } + + // double globalScaling = 3; + case 3: { + if (tag == 25u) { + 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.LoadSdfCommand) + return true; +failure: + // @@protoc_insertion_point(parse_failure:pybullet_grpc.LoadSdfCommand) + return false; +#undef DO_ +} + +void LoadSdfCommand::SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const { + // @@protoc_insertion_point(serialize_start:pybullet_grpc.LoadSdfCommand) + // string fileName = 1; + if (this->filename().size() > 0) { + ::google::protobuf::internal::WireFormatLite::VerifyUtf8String( + this->filename().data(), this->filename().length(), + ::google::protobuf::internal::WireFormatLite::SERIALIZE, + "pybullet_grpc.LoadSdfCommand.fileName"); + ::google::protobuf::internal::WireFormatLite::WriteStringMaybeAliased( + 1, this->filename(), output); + } + + // int32 useMultiBody = 2; + if (has_usemultibody()) { + ::google::protobuf::internal::WireFormatLite::WriteInt32(2, this->usemultibody(), output); + } + + // double globalScaling = 3; + if (has_globalscaling()) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(3, this->globalscaling(), output); + } + + // @@protoc_insertion_point(serialize_end:pybullet_grpc.LoadSdfCommand) +} + +::google::protobuf::uint8* LoadSdfCommand::InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const { + (void)deterministic; // Unused + // @@protoc_insertion_point(serialize_to_array_start:pybullet_grpc.LoadSdfCommand) + // string fileName = 1; + if (this->filename().size() > 0) { + ::google::protobuf::internal::WireFormatLite::VerifyUtf8String( + this->filename().data(), this->filename().length(), + ::google::protobuf::internal::WireFormatLite::SERIALIZE, + "pybullet_grpc.LoadSdfCommand.fileName"); + target = + ::google::protobuf::internal::WireFormatLite::WriteStringToArray( + 1, this->filename(), target); + } + + // int32 useMultiBody = 2; + if (has_usemultibody()) { + target = ::google::protobuf::internal::WireFormatLite::WriteInt32ToArray(2, this->usemultibody(), target); + } + + // double globalScaling = 3; + if (has_globalscaling()) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(3, this->globalscaling(), target); + } + + // @@protoc_insertion_point(serialize_to_array_end:pybullet_grpc.LoadSdfCommand) + return target; +} + +size_t LoadSdfCommand::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:pybullet_grpc.LoadSdfCommand) + size_t total_size = 0; + + // string fileName = 1; + if (this->filename().size() > 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::StringSize( + this->filename()); + } + + switch (hasUseMultiBody_case()) { + // int32 useMultiBody = 2; + case kUseMultiBody: { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::Int32Size( + this->usemultibody()); + break; + } + case HASUSEMULTIBODY_NOT_SET: { + break; + } + } + switch (hasGlobalScaling_case()) { + // double globalScaling = 3; + 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 LoadSdfCommand::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:pybullet_grpc.LoadSdfCommand) + GOOGLE_DCHECK_NE(&from, this); + const LoadSdfCommand* source = + ::google::protobuf::internal::DynamicCastToGenerated( + &from); + if (source == NULL) { + // @@protoc_insertion_point(generalized_merge_from_cast_fail:pybullet_grpc.LoadSdfCommand) + ::google::protobuf::internal::ReflectionOps::Merge(from, this); + } else { + // @@protoc_insertion_point(generalized_merge_from_cast_success:pybullet_grpc.LoadSdfCommand) + MergeFrom(*source); + } +} + +void LoadSdfCommand::MergeFrom(const LoadSdfCommand& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:pybullet_grpc.LoadSdfCommand) + GOOGLE_DCHECK_NE(&from, this); + _internal_metadata_.MergeFrom(from._internal_metadata_); + if (from.filename().size() > 0) { + + filename_.AssignWithDefault(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), from.filename_); + } + switch (from.hasUseMultiBody_case()) { + case kUseMultiBody: { + set_usemultibody(from.usemultibody()); + break; + } + case HASUSEMULTIBODY_NOT_SET: { + break; + } + } + switch (from.hasGlobalScaling_case()) { + case kGlobalScaling: { + set_globalscaling(from.globalscaling()); + break; + } + case HASGLOBALSCALING_NOT_SET: { + break; + } + } +} + +void LoadSdfCommand::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:pybullet_grpc.LoadSdfCommand) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +void LoadSdfCommand::CopyFrom(const LoadSdfCommand& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:pybullet_grpc.LoadSdfCommand) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool LoadSdfCommand::IsInitialized() const { + return true; +} + +void LoadSdfCommand::Swap(LoadSdfCommand* other) { + if (other == this) return; + InternalSwap(other); +} +void LoadSdfCommand::InternalSwap(LoadSdfCommand* other) { + filename_.Swap(&other->filename_); + std::swap(hasUseMultiBody_, other->hasUseMultiBody_); + std::swap(_oneof_case_[0], other->_oneof_case_[0]); + std::swap(hasGlobalScaling_, other->hasGlobalScaling_); + std::swap(_oneof_case_[1], other->_oneof_case_[1]); + std::swap(_cached_size_, other->_cached_size_); +} + +::google::protobuf::Metadata LoadSdfCommand::GetMetadata() const { + protobuf_pybullet_2eproto::protobuf_AssignDescriptorsOnce(); + return protobuf_pybullet_2eproto::file_level_metadata[6]; +} + +#if PROTOBUF_INLINE_NOT_IN_HEADERS +// LoadSdfCommand + +// string fileName = 1; +void LoadSdfCommand::clear_filename() { + filename_.ClearToEmptyNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); +} +const ::std::string& LoadSdfCommand::filename() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.LoadSdfCommand.fileName) + return filename_.GetNoArena(); +} +void LoadSdfCommand::set_filename(const ::std::string& value) { + + filename_.SetNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), value); + // @@protoc_insertion_point(field_set:pybullet_grpc.LoadSdfCommand.fileName) +} +#if LANG_CXX11 +void LoadSdfCommand::set_filename(::std::string&& value) { + + filename_.SetNoArena( + &::google::protobuf::internal::GetEmptyStringAlreadyInited(), std::move(value)); + // @@protoc_insertion_point(field_set_rvalue:pybullet_grpc.LoadSdfCommand.fileName) +} +#endif +void LoadSdfCommand::set_filename(const char* value) { + + filename_.SetNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), ::std::string(value)); + // @@protoc_insertion_point(field_set_char:pybullet_grpc.LoadSdfCommand.fileName) +} +void LoadSdfCommand::set_filename(const char* value, size_t size) { + + filename_.SetNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), + ::std::string(reinterpret_cast(value), size)); + // @@protoc_insertion_point(field_set_pointer:pybullet_grpc.LoadSdfCommand.fileName) +} +::std::string* LoadSdfCommand::mutable_filename() { + + // @@protoc_insertion_point(field_mutable:pybullet_grpc.LoadSdfCommand.fileName) + return filename_.MutableNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); +} +::std::string* LoadSdfCommand::release_filename() { + // @@protoc_insertion_point(field_release:pybullet_grpc.LoadSdfCommand.fileName) + + return filename_.ReleaseNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); +} +void LoadSdfCommand::set_allocated_filename(::std::string* filename) { + if (filename != NULL) { + + } else { + + } + filename_.SetAllocatedNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), filename); + // @@protoc_insertion_point(field_set_allocated:pybullet_grpc.LoadSdfCommand.fileName) +} + +// int32 useMultiBody = 2; +bool LoadSdfCommand::has_usemultibody() const { + return hasUseMultiBody_case() == kUseMultiBody; +} +void LoadSdfCommand::set_has_usemultibody() { + _oneof_case_[0] = kUseMultiBody; +} +void LoadSdfCommand::clear_usemultibody() { + if (has_usemultibody()) { + hasUseMultiBody_.usemultibody_ = 0; + clear_has_hasUseMultiBody(); + } +} +::google::protobuf::int32 LoadSdfCommand::usemultibody() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.LoadSdfCommand.useMultiBody) + if (has_usemultibody()) { + return hasUseMultiBody_.usemultibody_; + } + return 0; +} +void LoadSdfCommand::set_usemultibody(::google::protobuf::int32 value) { + if (!has_usemultibody()) { + clear_hasUseMultiBody(); + set_has_usemultibody(); + } + hasUseMultiBody_.usemultibody_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.LoadSdfCommand.useMultiBody) +} + +// double globalScaling = 3; +bool LoadSdfCommand::has_globalscaling() const { + return hasGlobalScaling_case() == kGlobalScaling; +} +void LoadSdfCommand::set_has_globalscaling() { + _oneof_case_[1] = kGlobalScaling; +} +void LoadSdfCommand::clear_globalscaling() { + if (has_globalscaling()) { + hasGlobalScaling_.globalscaling_ = 0; + clear_has_hasGlobalScaling(); + } +} +double LoadSdfCommand::globalscaling() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.LoadSdfCommand.globalScaling) + if (has_globalscaling()) { + return hasGlobalScaling_.globalscaling_; + } + return 0; +} +void LoadSdfCommand::set_globalscaling(double value) { + if (!has_globalscaling()) { + clear_hasGlobalScaling(); + set_has_globalscaling(); + } + hasGlobalScaling_.globalscaling_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.LoadSdfCommand.globalScaling) +} + +bool LoadSdfCommand::has_hasUseMultiBody() const { + return hasUseMultiBody_case() != HASUSEMULTIBODY_NOT_SET; +} +void LoadSdfCommand::clear_has_hasUseMultiBody() { + _oneof_case_[0] = HASUSEMULTIBODY_NOT_SET; +} +bool LoadSdfCommand::has_hasGlobalScaling() const { + return hasGlobalScaling_case() != HASGLOBALSCALING_NOT_SET; +} +void LoadSdfCommand::clear_has_hasGlobalScaling() { + _oneof_case_[1] = HASGLOBALSCALING_NOT_SET; +} +LoadSdfCommand::HasUseMultiBodyCase LoadSdfCommand::hasUseMultiBody_case() const { + return LoadSdfCommand::HasUseMultiBodyCase(_oneof_case_[0]); +} +LoadSdfCommand::HasGlobalScalingCase LoadSdfCommand::hasGlobalScaling_case() const { + return LoadSdfCommand::HasGlobalScalingCase(_oneof_case_[1]); +} +#endif // PROTOBUF_INLINE_NOT_IN_HEADERS + +// =================================================================== + +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const int SdfLoadedStatus::kBodyUniqueIdsFieldNumber; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 + +SdfLoadedStatus::SdfLoadedStatus() + : ::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.SdfLoadedStatus) +} +SdfLoadedStatus::SdfLoadedStatus(const SdfLoadedStatus& from) + : ::google::protobuf::Message(), + _internal_metadata_(NULL), + bodyuniqueids_(from.bodyuniqueids_), + _cached_size_(0) { + _internal_metadata_.MergeFrom(from._internal_metadata_); + // @@protoc_insertion_point(copy_constructor:pybullet_grpc.SdfLoadedStatus) +} + +void SdfLoadedStatus::SharedCtor() { + _cached_size_ = 0; +} + +SdfLoadedStatus::~SdfLoadedStatus() { + // @@protoc_insertion_point(destructor:pybullet_grpc.SdfLoadedStatus) + SharedDtor(); +} + +void SdfLoadedStatus::SharedDtor() { +} + +void SdfLoadedStatus::SetCachedSize(int size) const { + GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN(); + _cached_size_ = size; + GOOGLE_SAFE_CONCURRENT_WRITES_END(); +} +const ::google::protobuf::Descriptor* SdfLoadedStatus::descriptor() { + protobuf_pybullet_2eproto::protobuf_AssignDescriptorsOnce(); + return protobuf_pybullet_2eproto::file_level_metadata[7].descriptor; +} + +const SdfLoadedStatus& SdfLoadedStatus::default_instance() { + protobuf_pybullet_2eproto::InitDefaults(); + return *internal_default_instance(); +} + +SdfLoadedStatus* SdfLoadedStatus::New(::google::protobuf::Arena* arena) const { + SdfLoadedStatus* n = new SdfLoadedStatus; + if (arena != NULL) { + arena->Own(n); + } + return n; +} + +void SdfLoadedStatus::Clear() { +// @@protoc_insertion_point(message_clear_start:pybullet_grpc.SdfLoadedStatus) + bodyuniqueids_.Clear(); +} + +bool SdfLoadedStatus::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.SdfLoadedStatus) + 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)) { + // repeated int32 bodyUniqueIds = 2; + case 2: { + if (tag == 18u) { + DO_((::google::protobuf::internal::WireFormatLite::ReadPackedPrimitive< + ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>( + input, this->mutable_bodyuniqueids()))); + } else if (tag == 16u) { + DO_((::google::protobuf::internal::WireFormatLite::ReadRepeatedPrimitiveNoInline< + ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>( + 1, 18u, input, this->mutable_bodyuniqueids()))); + } 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.SdfLoadedStatus) + return true; +failure: + // @@protoc_insertion_point(parse_failure:pybullet_grpc.SdfLoadedStatus) + return false; +#undef DO_ +} + +void SdfLoadedStatus::SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const { + // @@protoc_insertion_point(serialize_start:pybullet_grpc.SdfLoadedStatus) + // repeated int32 bodyUniqueIds = 2; + if (this->bodyuniqueids_size() > 0) { + ::google::protobuf::internal::WireFormatLite::WriteTag(2, ::google::protobuf::internal::WireFormatLite::WIRETYPE_LENGTH_DELIMITED, output); + output->WriteVarint32(_bodyuniqueids_cached_byte_size_); + } + for (int i = 0; i < this->bodyuniqueids_size(); i++) { + ::google::protobuf::internal::WireFormatLite::WriteInt32NoTag( + this->bodyuniqueids(i), output); + } + + // @@protoc_insertion_point(serialize_end:pybullet_grpc.SdfLoadedStatus) +} + +::google::protobuf::uint8* SdfLoadedStatus::InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const { + (void)deterministic; // Unused + // @@protoc_insertion_point(serialize_to_array_start:pybullet_grpc.SdfLoadedStatus) + // repeated int32 bodyUniqueIds = 2; + if (this->bodyuniqueids_size() > 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteTagToArray( + 2, + ::google::protobuf::internal::WireFormatLite::WIRETYPE_LENGTH_DELIMITED, + target); + target = ::google::protobuf::io::CodedOutputStream::WriteVarint32ToArray( + _bodyuniqueids_cached_byte_size_, target); + } + for (int i = 0; i < this->bodyuniqueids_size(); i++) { + target = ::google::protobuf::internal::WireFormatLite:: + WriteInt32NoTagToArray(this->bodyuniqueids(i), target); + } + + // @@protoc_insertion_point(serialize_to_array_end:pybullet_grpc.SdfLoadedStatus) + return target; +} + +size_t SdfLoadedStatus::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:pybullet_grpc.SdfLoadedStatus) + size_t total_size = 0; + + // repeated int32 bodyUniqueIds = 2; + { + size_t data_size = ::google::protobuf::internal::WireFormatLite:: + Int32Size(this->bodyuniqueids_); + if (data_size > 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::Int32Size(data_size); + } + int cached_size = ::google::protobuf::internal::ToCachedSize(data_size); + GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN(); + _bodyuniqueids_cached_byte_size_ = cached_size; + GOOGLE_SAFE_CONCURRENT_WRITES_END(); + total_size += data_size; + } + + 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 SdfLoadedStatus::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:pybullet_grpc.SdfLoadedStatus) + GOOGLE_DCHECK_NE(&from, this); + const SdfLoadedStatus* source = + ::google::protobuf::internal::DynamicCastToGenerated( + &from); + if (source == NULL) { + // @@protoc_insertion_point(generalized_merge_from_cast_fail:pybullet_grpc.SdfLoadedStatus) + ::google::protobuf::internal::ReflectionOps::Merge(from, this); + } else { + // @@protoc_insertion_point(generalized_merge_from_cast_success:pybullet_grpc.SdfLoadedStatus) + MergeFrom(*source); + } +} + +void SdfLoadedStatus::MergeFrom(const SdfLoadedStatus& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:pybullet_grpc.SdfLoadedStatus) + GOOGLE_DCHECK_NE(&from, this); + _internal_metadata_.MergeFrom(from._internal_metadata_); + bodyuniqueids_.MergeFrom(from.bodyuniqueids_); +} + +void SdfLoadedStatus::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:pybullet_grpc.SdfLoadedStatus) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +void SdfLoadedStatus::CopyFrom(const SdfLoadedStatus& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:pybullet_grpc.SdfLoadedStatus) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool SdfLoadedStatus::IsInitialized() const { + return true; +} + +void SdfLoadedStatus::Swap(SdfLoadedStatus* other) { + if (other == this) return; + InternalSwap(other); +} +void SdfLoadedStatus::InternalSwap(SdfLoadedStatus* other) { + bodyuniqueids_.UnsafeArenaSwap(&other->bodyuniqueids_); + std::swap(_cached_size_, other->_cached_size_); +} + +::google::protobuf::Metadata SdfLoadedStatus::GetMetadata() const { + protobuf_pybullet_2eproto::protobuf_AssignDescriptorsOnce(); + return protobuf_pybullet_2eproto::file_level_metadata[7]; +} + +#if PROTOBUF_INLINE_NOT_IN_HEADERS +// SdfLoadedStatus + +// repeated int32 bodyUniqueIds = 2; +int SdfLoadedStatus::bodyuniqueids_size() const { + return bodyuniqueids_.size(); +} +void SdfLoadedStatus::clear_bodyuniqueids() { + bodyuniqueids_.Clear(); +} +::google::protobuf::int32 SdfLoadedStatus::bodyuniqueids(int index) const { + // @@protoc_insertion_point(field_get:pybullet_grpc.SdfLoadedStatus.bodyUniqueIds) + return bodyuniqueids_.Get(index); +} +void SdfLoadedStatus::set_bodyuniqueids(int index, ::google::protobuf::int32 value) { + bodyuniqueids_.Set(index, value); + // @@protoc_insertion_point(field_set:pybullet_grpc.SdfLoadedStatus.bodyUniqueIds) +} +void SdfLoadedStatus::add_bodyuniqueids(::google::protobuf::int32 value) { + bodyuniqueids_.Add(value); + // @@protoc_insertion_point(field_add:pybullet_grpc.SdfLoadedStatus.bodyUniqueIds) +} +const ::google::protobuf::RepeatedField< ::google::protobuf::int32 >& +SdfLoadedStatus::bodyuniqueids() const { + // @@protoc_insertion_point(field_list:pybullet_grpc.SdfLoadedStatus.bodyUniqueIds) + return bodyuniqueids_; +} +::google::protobuf::RepeatedField< ::google::protobuf::int32 >* +SdfLoadedStatus::mutable_bodyuniqueids() { + // @@protoc_insertion_point(field_mutable_list:pybullet_grpc.SdfLoadedStatus.bodyUniqueIds) + return &bodyuniqueids_; +} + +#endif // PROTOBUF_INLINE_NOT_IN_HEADERS + +// =================================================================== + +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const int LoadMjcfCommand::kFileNameFieldNumber; +const int LoadMjcfCommand::kFlagsFieldNumber; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 + +LoadMjcfCommand::LoadMjcfCommand() + : ::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.LoadMjcfCommand) +} +LoadMjcfCommand::LoadMjcfCommand(const LoadMjcfCommand& from) + : ::google::protobuf::Message(), + _internal_metadata_(NULL), + _cached_size_(0) { + _internal_metadata_.MergeFrom(from._internal_metadata_); + filename_.UnsafeSetDefault(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); + if (from.filename().size() > 0) { + filename_.AssignWithDefault(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), from.filename_); + } + flags_ = from.flags_; + // @@protoc_insertion_point(copy_constructor:pybullet_grpc.LoadMjcfCommand) +} + +void LoadMjcfCommand::SharedCtor() { + filename_.UnsafeSetDefault(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); + flags_ = 0; + _cached_size_ = 0; +} + +LoadMjcfCommand::~LoadMjcfCommand() { + // @@protoc_insertion_point(destructor:pybullet_grpc.LoadMjcfCommand) + SharedDtor(); +} + +void LoadMjcfCommand::SharedDtor() { + filename_.DestroyNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); +} + +void LoadMjcfCommand::SetCachedSize(int size) const { + GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN(); + _cached_size_ = size; + GOOGLE_SAFE_CONCURRENT_WRITES_END(); +} +const ::google::protobuf::Descriptor* LoadMjcfCommand::descriptor() { + protobuf_pybullet_2eproto::protobuf_AssignDescriptorsOnce(); + return protobuf_pybullet_2eproto::file_level_metadata[8].descriptor; +} + +const LoadMjcfCommand& LoadMjcfCommand::default_instance() { + protobuf_pybullet_2eproto::InitDefaults(); + return *internal_default_instance(); +} + +LoadMjcfCommand* LoadMjcfCommand::New(::google::protobuf::Arena* arena) const { + LoadMjcfCommand* n = new LoadMjcfCommand; + if (arena != NULL) { + arena->Own(n); + } + return n; +} + +void LoadMjcfCommand::Clear() { +// @@protoc_insertion_point(message_clear_start:pybullet_grpc.LoadMjcfCommand) + filename_.ClearToEmptyNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); + flags_ = 0; +} + +bool LoadMjcfCommand::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.LoadMjcfCommand) + 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 fileName = 1; + case 1: { + if (tag == 10u) { + DO_(::google::protobuf::internal::WireFormatLite::ReadString( + input, this->mutable_filename())); + DO_(::google::protobuf::internal::WireFormatLite::VerifyUtf8String( + this->filename().data(), this->filename().length(), + ::google::protobuf::internal::WireFormatLite::PARSE, + "pybullet_grpc.LoadMjcfCommand.fileName")); + } else { + goto handle_unusual; + } + break; + } + + // int32 flags = 2; + case 2: { + if (tag == 16u) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>( + input, &flags_))); + } 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.LoadMjcfCommand) + return true; +failure: + // @@protoc_insertion_point(parse_failure:pybullet_grpc.LoadMjcfCommand) + return false; +#undef DO_ +} + +void LoadMjcfCommand::SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const { + // @@protoc_insertion_point(serialize_start:pybullet_grpc.LoadMjcfCommand) + // string fileName = 1; + if (this->filename().size() > 0) { + ::google::protobuf::internal::WireFormatLite::VerifyUtf8String( + this->filename().data(), this->filename().length(), + ::google::protobuf::internal::WireFormatLite::SERIALIZE, + "pybullet_grpc.LoadMjcfCommand.fileName"); + ::google::protobuf::internal::WireFormatLite::WriteStringMaybeAliased( + 1, this->filename(), output); + } + + // int32 flags = 2; + if (this->flags() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteInt32(2, this->flags(), output); + } + + // @@protoc_insertion_point(serialize_end:pybullet_grpc.LoadMjcfCommand) +} + +::google::protobuf::uint8* LoadMjcfCommand::InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const { + (void)deterministic; // Unused + // @@protoc_insertion_point(serialize_to_array_start:pybullet_grpc.LoadMjcfCommand) + // string fileName = 1; + if (this->filename().size() > 0) { + ::google::protobuf::internal::WireFormatLite::VerifyUtf8String( + this->filename().data(), this->filename().length(), + ::google::protobuf::internal::WireFormatLite::SERIALIZE, + "pybullet_grpc.LoadMjcfCommand.fileName"); + target = + ::google::protobuf::internal::WireFormatLite::WriteStringToArray( + 1, this->filename(), target); + } + + // int32 flags = 2; + if (this->flags() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteInt32ToArray(2, this->flags(), target); + } + + // @@protoc_insertion_point(serialize_to_array_end:pybullet_grpc.LoadMjcfCommand) + return target; +} + +size_t LoadMjcfCommand::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:pybullet_grpc.LoadMjcfCommand) + size_t total_size = 0; + + // string fileName = 1; + if (this->filename().size() > 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::StringSize( + this->filename()); + } + + // int32 flags = 2; + if (this->flags() != 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::Int32Size( + this->flags()); + } + + 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 LoadMjcfCommand::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:pybullet_grpc.LoadMjcfCommand) + GOOGLE_DCHECK_NE(&from, this); + const LoadMjcfCommand* source = + ::google::protobuf::internal::DynamicCastToGenerated( + &from); + if (source == NULL) { + // @@protoc_insertion_point(generalized_merge_from_cast_fail:pybullet_grpc.LoadMjcfCommand) + ::google::protobuf::internal::ReflectionOps::Merge(from, this); + } else { + // @@protoc_insertion_point(generalized_merge_from_cast_success:pybullet_grpc.LoadMjcfCommand) + MergeFrom(*source); + } +} + +void LoadMjcfCommand::MergeFrom(const LoadMjcfCommand& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:pybullet_grpc.LoadMjcfCommand) + GOOGLE_DCHECK_NE(&from, this); + _internal_metadata_.MergeFrom(from._internal_metadata_); + if (from.filename().size() > 0) { + + filename_.AssignWithDefault(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), from.filename_); + } + if (from.flags() != 0) { + set_flags(from.flags()); + } +} + +void LoadMjcfCommand::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:pybullet_grpc.LoadMjcfCommand) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +void LoadMjcfCommand::CopyFrom(const LoadMjcfCommand& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:pybullet_grpc.LoadMjcfCommand) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool LoadMjcfCommand::IsInitialized() const { + return true; +} + +void LoadMjcfCommand::Swap(LoadMjcfCommand* other) { + if (other == this) return; + InternalSwap(other); +} +void LoadMjcfCommand::InternalSwap(LoadMjcfCommand* other) { + filename_.Swap(&other->filename_); + std::swap(flags_, other->flags_); + std::swap(_cached_size_, other->_cached_size_); +} + +::google::protobuf::Metadata LoadMjcfCommand::GetMetadata() const { + protobuf_pybullet_2eproto::protobuf_AssignDescriptorsOnce(); + return protobuf_pybullet_2eproto::file_level_metadata[8]; +} + +#if PROTOBUF_INLINE_NOT_IN_HEADERS +// LoadMjcfCommand + +// string fileName = 1; +void LoadMjcfCommand::clear_filename() { + filename_.ClearToEmptyNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); +} +const ::std::string& LoadMjcfCommand::filename() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.LoadMjcfCommand.fileName) + return filename_.GetNoArena(); +} +void LoadMjcfCommand::set_filename(const ::std::string& value) { + + filename_.SetNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), value); + // @@protoc_insertion_point(field_set:pybullet_grpc.LoadMjcfCommand.fileName) +} +#if LANG_CXX11 +void LoadMjcfCommand::set_filename(::std::string&& value) { + + filename_.SetNoArena( + &::google::protobuf::internal::GetEmptyStringAlreadyInited(), std::move(value)); + // @@protoc_insertion_point(field_set_rvalue:pybullet_grpc.LoadMjcfCommand.fileName) +} +#endif +void LoadMjcfCommand::set_filename(const char* value) { + + filename_.SetNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), ::std::string(value)); + // @@protoc_insertion_point(field_set_char:pybullet_grpc.LoadMjcfCommand.fileName) +} +void LoadMjcfCommand::set_filename(const char* value, size_t size) { + + filename_.SetNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), + ::std::string(reinterpret_cast(value), size)); + // @@protoc_insertion_point(field_set_pointer:pybullet_grpc.LoadMjcfCommand.fileName) +} +::std::string* LoadMjcfCommand::mutable_filename() { + + // @@protoc_insertion_point(field_mutable:pybullet_grpc.LoadMjcfCommand.fileName) + return filename_.MutableNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); +} +::std::string* LoadMjcfCommand::release_filename() { + // @@protoc_insertion_point(field_release:pybullet_grpc.LoadMjcfCommand.fileName) + + return filename_.ReleaseNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); +} +void LoadMjcfCommand::set_allocated_filename(::std::string* filename) { + if (filename != NULL) { + + } else { + + } + filename_.SetAllocatedNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), filename); + // @@protoc_insertion_point(field_set_allocated:pybullet_grpc.LoadMjcfCommand.fileName) +} + +// int32 flags = 2; +void LoadMjcfCommand::clear_flags() { + flags_ = 0; +} +::google::protobuf::int32 LoadMjcfCommand::flags() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.LoadMjcfCommand.flags) + return flags_; +} +void LoadMjcfCommand::set_flags(::google::protobuf::int32 value) { + + flags_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.LoadMjcfCommand.flags) +} + +#endif // PROTOBUF_INLINE_NOT_IN_HEADERS + +// =================================================================== + +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const int MjcfLoadedStatus::kBodyUniqueIdsFieldNumber; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 + +MjcfLoadedStatus::MjcfLoadedStatus() + : ::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.MjcfLoadedStatus) +} +MjcfLoadedStatus::MjcfLoadedStatus(const MjcfLoadedStatus& from) + : ::google::protobuf::Message(), + _internal_metadata_(NULL), + bodyuniqueids_(from.bodyuniqueids_), + _cached_size_(0) { + _internal_metadata_.MergeFrom(from._internal_metadata_); + // @@protoc_insertion_point(copy_constructor:pybullet_grpc.MjcfLoadedStatus) +} + +void MjcfLoadedStatus::SharedCtor() { + _cached_size_ = 0; +} + +MjcfLoadedStatus::~MjcfLoadedStatus() { + // @@protoc_insertion_point(destructor:pybullet_grpc.MjcfLoadedStatus) + SharedDtor(); +} + +void MjcfLoadedStatus::SharedDtor() { +} + +void MjcfLoadedStatus::SetCachedSize(int size) const { + GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN(); + _cached_size_ = size; + GOOGLE_SAFE_CONCURRENT_WRITES_END(); +} +const ::google::protobuf::Descriptor* MjcfLoadedStatus::descriptor() { + protobuf_pybullet_2eproto::protobuf_AssignDescriptorsOnce(); + return protobuf_pybullet_2eproto::file_level_metadata[9].descriptor; +} + +const MjcfLoadedStatus& MjcfLoadedStatus::default_instance() { + protobuf_pybullet_2eproto::InitDefaults(); + return *internal_default_instance(); +} + +MjcfLoadedStatus* MjcfLoadedStatus::New(::google::protobuf::Arena* arena) const { + MjcfLoadedStatus* n = new MjcfLoadedStatus; + if (arena != NULL) { + arena->Own(n); + } + return n; +} + +void MjcfLoadedStatus::Clear() { +// @@protoc_insertion_point(message_clear_start:pybullet_grpc.MjcfLoadedStatus) + bodyuniqueids_.Clear(); +} + +bool MjcfLoadedStatus::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.MjcfLoadedStatus) + 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)) { + // repeated int32 bodyUniqueIds = 2; + case 2: { + if (tag == 18u) { + DO_((::google::protobuf::internal::WireFormatLite::ReadPackedPrimitive< + ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>( + input, this->mutable_bodyuniqueids()))); + } else if (tag == 16u) { + DO_((::google::protobuf::internal::WireFormatLite::ReadRepeatedPrimitiveNoInline< + ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>( + 1, 18u, input, this->mutable_bodyuniqueids()))); + } 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.MjcfLoadedStatus) + return true; +failure: + // @@protoc_insertion_point(parse_failure:pybullet_grpc.MjcfLoadedStatus) + return false; +#undef DO_ +} + +void MjcfLoadedStatus::SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const { + // @@protoc_insertion_point(serialize_start:pybullet_grpc.MjcfLoadedStatus) + // repeated int32 bodyUniqueIds = 2; + if (this->bodyuniqueids_size() > 0) { + ::google::protobuf::internal::WireFormatLite::WriteTag(2, ::google::protobuf::internal::WireFormatLite::WIRETYPE_LENGTH_DELIMITED, output); + output->WriteVarint32(_bodyuniqueids_cached_byte_size_); + } + for (int i = 0; i < this->bodyuniqueids_size(); i++) { + ::google::protobuf::internal::WireFormatLite::WriteInt32NoTag( + this->bodyuniqueids(i), output); + } + + // @@protoc_insertion_point(serialize_end:pybullet_grpc.MjcfLoadedStatus) +} + +::google::protobuf::uint8* MjcfLoadedStatus::InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const { + (void)deterministic; // Unused + // @@protoc_insertion_point(serialize_to_array_start:pybullet_grpc.MjcfLoadedStatus) + // repeated int32 bodyUniqueIds = 2; + if (this->bodyuniqueids_size() > 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteTagToArray( + 2, + ::google::protobuf::internal::WireFormatLite::WIRETYPE_LENGTH_DELIMITED, + target); + target = ::google::protobuf::io::CodedOutputStream::WriteVarint32ToArray( + _bodyuniqueids_cached_byte_size_, target); + } + for (int i = 0; i < this->bodyuniqueids_size(); i++) { + target = ::google::protobuf::internal::WireFormatLite:: + WriteInt32NoTagToArray(this->bodyuniqueids(i), target); + } + + // @@protoc_insertion_point(serialize_to_array_end:pybullet_grpc.MjcfLoadedStatus) + return target; +} + +size_t MjcfLoadedStatus::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:pybullet_grpc.MjcfLoadedStatus) + size_t total_size = 0; + + // repeated int32 bodyUniqueIds = 2; + { + size_t data_size = ::google::protobuf::internal::WireFormatLite:: + Int32Size(this->bodyuniqueids_); + if (data_size > 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::Int32Size(data_size); + } + int cached_size = ::google::protobuf::internal::ToCachedSize(data_size); + GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN(); + _bodyuniqueids_cached_byte_size_ = cached_size; + GOOGLE_SAFE_CONCURRENT_WRITES_END(); + total_size += data_size; + } + + 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 MjcfLoadedStatus::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:pybullet_grpc.MjcfLoadedStatus) + GOOGLE_DCHECK_NE(&from, this); + const MjcfLoadedStatus* source = + ::google::protobuf::internal::DynamicCastToGenerated( + &from); + if (source == NULL) { + // @@protoc_insertion_point(generalized_merge_from_cast_fail:pybullet_grpc.MjcfLoadedStatus) + ::google::protobuf::internal::ReflectionOps::Merge(from, this); + } else { + // @@protoc_insertion_point(generalized_merge_from_cast_success:pybullet_grpc.MjcfLoadedStatus) + MergeFrom(*source); + } +} + +void MjcfLoadedStatus::MergeFrom(const MjcfLoadedStatus& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:pybullet_grpc.MjcfLoadedStatus) + GOOGLE_DCHECK_NE(&from, this); + _internal_metadata_.MergeFrom(from._internal_metadata_); + bodyuniqueids_.MergeFrom(from.bodyuniqueids_); +} + +void MjcfLoadedStatus::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:pybullet_grpc.MjcfLoadedStatus) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +void MjcfLoadedStatus::CopyFrom(const MjcfLoadedStatus& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:pybullet_grpc.MjcfLoadedStatus) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool MjcfLoadedStatus::IsInitialized() const { + return true; +} + +void MjcfLoadedStatus::Swap(MjcfLoadedStatus* other) { + if (other == this) return; + InternalSwap(other); +} +void MjcfLoadedStatus::InternalSwap(MjcfLoadedStatus* other) { + bodyuniqueids_.UnsafeArenaSwap(&other->bodyuniqueids_); + std::swap(_cached_size_, other->_cached_size_); +} + +::google::protobuf::Metadata MjcfLoadedStatus::GetMetadata() const { + protobuf_pybullet_2eproto::protobuf_AssignDescriptorsOnce(); + return protobuf_pybullet_2eproto::file_level_metadata[9]; +} + +#if PROTOBUF_INLINE_NOT_IN_HEADERS +// MjcfLoadedStatus + +// repeated int32 bodyUniqueIds = 2; +int MjcfLoadedStatus::bodyuniqueids_size() const { + return bodyuniqueids_.size(); +} +void MjcfLoadedStatus::clear_bodyuniqueids() { + bodyuniqueids_.Clear(); +} +::google::protobuf::int32 MjcfLoadedStatus::bodyuniqueids(int index) const { + // @@protoc_insertion_point(field_get:pybullet_grpc.MjcfLoadedStatus.bodyUniqueIds) + return bodyuniqueids_.Get(index); +} +void MjcfLoadedStatus::set_bodyuniqueids(int index, ::google::protobuf::int32 value) { + bodyuniqueids_.Set(index, value); + // @@protoc_insertion_point(field_set:pybullet_grpc.MjcfLoadedStatus.bodyUniqueIds) +} +void MjcfLoadedStatus::add_bodyuniqueids(::google::protobuf::int32 value) { + bodyuniqueids_.Add(value); + // @@protoc_insertion_point(field_add:pybullet_grpc.MjcfLoadedStatus.bodyUniqueIds) +} +const ::google::protobuf::RepeatedField< ::google::protobuf::int32 >& +MjcfLoadedStatus::bodyuniqueids() const { + // @@protoc_insertion_point(field_list:pybullet_grpc.MjcfLoadedStatus.bodyUniqueIds) + return bodyuniqueids_; +} +::google::protobuf::RepeatedField< ::google::protobuf::int32 >* +MjcfLoadedStatus::mutable_bodyuniqueids() { + // @@protoc_insertion_point(field_mutable_list:pybullet_grpc.MjcfLoadedStatus.bodyUniqueIds) + return &bodyuniqueids_; +} + +#endif // PROTOBUF_INLINE_NOT_IN_HEADERS + +// =================================================================== + +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const int ChangeDynamicsCommand::kBodyUniqueIdFieldNumber; +const int ChangeDynamicsCommand::kLinkIndexFieldNumber; +const int ChangeDynamicsCommand::kMassFieldNumber; +const int ChangeDynamicsCommand::kLateralFrictionFieldNumber; +const int ChangeDynamicsCommand::kSpinningFrictionFieldNumber; +const int ChangeDynamicsCommand::kRollingFrictionFieldNumber; +const int ChangeDynamicsCommand::kRestitutionFieldNumber; +const int ChangeDynamicsCommand::kLinearDampingFieldNumber; +const int ChangeDynamicsCommand::kAngularDampingFieldNumber; +const int ChangeDynamicsCommand::kContactStiffnessFieldNumber; +const int ChangeDynamicsCommand::kContactDampingFieldNumber; +const int ChangeDynamicsCommand::kLocalInertiaDiagonalFieldNumber; +const int ChangeDynamicsCommand::kFrictionAnchorFieldNumber; +const int ChangeDynamicsCommand::kCcdSweptSphereRadiusFieldNumber; +const int ChangeDynamicsCommand::kContactProcessingThresholdFieldNumber; +const int ChangeDynamicsCommand::kActivationStateFieldNumber; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 + +ChangeDynamicsCommand::ChangeDynamicsCommand() + : ::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.ChangeDynamicsCommand) +} +ChangeDynamicsCommand::ChangeDynamicsCommand(const ChangeDynamicsCommand& from) + : ::google::protobuf::Message(), + _internal_metadata_(NULL), + _cached_size_(0) { + _internal_metadata_.MergeFrom(from._internal_metadata_); + ::memcpy(&bodyuniqueid_, &from.bodyuniqueid_, + reinterpret_cast(&linkindex_) - + reinterpret_cast(&bodyuniqueid_) + sizeof(linkindex_)); + clear_has_hasMass(); + switch (from.hasMass_case()) { + case kMass: { + set_mass(from.mass()); + break; + } + case HASMASS_NOT_SET: { + break; + } + } + clear_has_hasLateralFriction(); + switch (from.hasLateralFriction_case()) { + case kLateralFriction: { + set_lateralfriction(from.lateralfriction()); + break; + } + case HASLATERALFRICTION_NOT_SET: { + break; + } + } + clear_has_hasSpinningFriction(); + switch (from.hasSpinningFriction_case()) { + case kSpinningFriction: { + set_spinningfriction(from.spinningfriction()); + break; + } + case HASSPINNINGFRICTION_NOT_SET: { + break; + } + } + clear_has_hasRollingFriction(); + switch (from.hasRollingFriction_case()) { + case kRollingFriction: { + set_rollingfriction(from.rollingfriction()); + break; + } + case HASROLLINGFRICTION_NOT_SET: { + break; + } + } + clear_has_hasRestitution(); + switch (from.hasRestitution_case()) { + case kRestitution: { + set_restitution(from.restitution()); + break; + } + case HASRESTITUTION_NOT_SET: { + break; + } + } + clear_has_haslinearDamping(); + switch (from.haslinearDamping_case()) { + case kLinearDamping: { + set_lineardamping(from.lineardamping()); + break; + } + case HASLINEARDAMPING_NOT_SET: { + break; + } + } + clear_has_hasangularDamping(); + switch (from.hasangularDamping_case()) { + case kAngularDamping: { + set_angulardamping(from.angulardamping()); + break; + } + case HASANGULARDAMPING_NOT_SET: { + break; + } + } + clear_has_hasContactStiffness(); + switch (from.hasContactStiffness_case()) { + case kContactStiffness: { + set_contactstiffness(from.contactstiffness()); + break; + } + case HASCONTACTSTIFFNESS_NOT_SET: { + break; + } + } + clear_has_hasContactDamping(); + switch (from.hasContactDamping_case()) { + case kContactDamping: { + set_contactdamping(from.contactdamping()); + break; + } + case HASCONTACTDAMPING_NOT_SET: { + break; + } + } + clear_has_hasLocalInertiaDiagonal(); + switch (from.hasLocalInertiaDiagonal_case()) { + case kLocalInertiaDiagonal: { + mutable_localinertiadiagonal()->::pybullet_grpc::vec3::MergeFrom(from.localinertiadiagonal()); + break; + } + case HASLOCALINERTIADIAGONAL_NOT_SET: { + break; + } + } + clear_has_hasFrictionAnchor(); + switch (from.hasFrictionAnchor_case()) { + case kFrictionAnchor: { + set_frictionanchor(from.frictionanchor()); + break; + } + case HASFRICTIONANCHOR_NOT_SET: { + break; + } + } + clear_has_hasccdSweptSphereRadius(); + switch (from.hasccdSweptSphereRadius_case()) { + case kCcdSweptSphereRadius: { + set_ccdsweptsphereradius(from.ccdsweptsphereradius()); + break; + } + case HASCCDSWEPTSPHERERADIUS_NOT_SET: { + break; + } + } + clear_has_hasContactProcessingThreshold(); + switch (from.hasContactProcessingThreshold_case()) { + case kContactProcessingThreshold: { + set_contactprocessingthreshold(from.contactprocessingthreshold()); + break; + } + case HASCONTACTPROCESSINGTHRESHOLD_NOT_SET: { + break; + } + } + clear_has_hasActivationState(); + switch (from.hasActivationState_case()) { + case kActivationState: { + set_activationstate(from.activationstate()); + break; + } + case HASACTIVATIONSTATE_NOT_SET: { + break; + } + } + // @@protoc_insertion_point(copy_constructor:pybullet_grpc.ChangeDynamicsCommand) +} + +void ChangeDynamicsCommand::SharedCtor() { + ::memset(&bodyuniqueid_, 0, reinterpret_cast(&linkindex_) - + reinterpret_cast(&bodyuniqueid_) + sizeof(linkindex_)); + clear_has_hasMass(); + clear_has_hasLateralFriction(); + clear_has_hasSpinningFriction(); + clear_has_hasRollingFriction(); + clear_has_hasRestitution(); + clear_has_haslinearDamping(); + clear_has_hasangularDamping(); + clear_has_hasContactStiffness(); + clear_has_hasContactDamping(); + clear_has_hasLocalInertiaDiagonal(); + clear_has_hasFrictionAnchor(); + clear_has_hasccdSweptSphereRadius(); + clear_has_hasContactProcessingThreshold(); + clear_has_hasActivationState(); + _cached_size_ = 0; +} + +ChangeDynamicsCommand::~ChangeDynamicsCommand() { + // @@protoc_insertion_point(destructor:pybullet_grpc.ChangeDynamicsCommand) + SharedDtor(); +} + +void ChangeDynamicsCommand::SharedDtor() { + if (has_hasMass()) { + clear_hasMass(); + } + if (has_hasLateralFriction()) { + clear_hasLateralFriction(); + } + if (has_hasSpinningFriction()) { + clear_hasSpinningFriction(); + } + if (has_hasRollingFriction()) { + clear_hasRollingFriction(); + } + if (has_hasRestitution()) { + clear_hasRestitution(); + } + if (has_haslinearDamping()) { + clear_haslinearDamping(); + } + if (has_hasangularDamping()) { + clear_hasangularDamping(); + } + if (has_hasContactStiffness()) { + clear_hasContactStiffness(); + } + if (has_hasContactDamping()) { + clear_hasContactDamping(); + } + if (has_hasLocalInertiaDiagonal()) { + clear_hasLocalInertiaDiagonal(); + } + if (has_hasFrictionAnchor()) { + clear_hasFrictionAnchor(); + } + if (has_hasccdSweptSphereRadius()) { + clear_hasccdSweptSphereRadius(); + } + if (has_hasContactProcessingThreshold()) { + clear_hasContactProcessingThreshold(); + } + if (has_hasActivationState()) { + clear_hasActivationState(); + } +} + +void ChangeDynamicsCommand::SetCachedSize(int size) const { + GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN(); + _cached_size_ = size; + GOOGLE_SAFE_CONCURRENT_WRITES_END(); +} +const ::google::protobuf::Descriptor* ChangeDynamicsCommand::descriptor() { + protobuf_pybullet_2eproto::protobuf_AssignDescriptorsOnce(); + return protobuf_pybullet_2eproto::file_level_metadata[10].descriptor; +} + +const ChangeDynamicsCommand& ChangeDynamicsCommand::default_instance() { + protobuf_pybullet_2eproto::InitDefaults(); + return *internal_default_instance(); +} + +ChangeDynamicsCommand* ChangeDynamicsCommand::New(::google::protobuf::Arena* arena) const { + ChangeDynamicsCommand* n = new ChangeDynamicsCommand; + if (arena != NULL) { + arena->Own(n); + } + return n; +} + +void ChangeDynamicsCommand::clear_hasMass() { +// @@protoc_insertion_point(one_of_clear_start:pybullet_grpc.ChangeDynamicsCommand) + switch (hasMass_case()) { + case kMass: { + // No need to clear + break; + } + case HASMASS_NOT_SET: { + break; + } + } + _oneof_case_[0] = HASMASS_NOT_SET; +} + +void ChangeDynamicsCommand::clear_hasLateralFriction() { +// @@protoc_insertion_point(one_of_clear_start:pybullet_grpc.ChangeDynamicsCommand) + switch (hasLateralFriction_case()) { + case kLateralFriction: { + // No need to clear + break; + } + case HASLATERALFRICTION_NOT_SET: { + break; + } + } + _oneof_case_[1] = HASLATERALFRICTION_NOT_SET; +} + +void ChangeDynamicsCommand::clear_hasSpinningFriction() { +// @@protoc_insertion_point(one_of_clear_start:pybullet_grpc.ChangeDynamicsCommand) + switch (hasSpinningFriction_case()) { + case kSpinningFriction: { + // No need to clear + break; + } + case HASSPINNINGFRICTION_NOT_SET: { + break; + } + } + _oneof_case_[2] = HASSPINNINGFRICTION_NOT_SET; +} + +void ChangeDynamicsCommand::clear_hasRollingFriction() { +// @@protoc_insertion_point(one_of_clear_start:pybullet_grpc.ChangeDynamicsCommand) + switch (hasRollingFriction_case()) { + case kRollingFriction: { + // No need to clear + break; + } + case HASROLLINGFRICTION_NOT_SET: { + break; + } + } + _oneof_case_[3] = HASROLLINGFRICTION_NOT_SET; +} + +void ChangeDynamicsCommand::clear_hasRestitution() { +// @@protoc_insertion_point(one_of_clear_start:pybullet_grpc.ChangeDynamicsCommand) + switch (hasRestitution_case()) { + case kRestitution: { + // No need to clear + break; + } + case HASRESTITUTION_NOT_SET: { + break; + } + } + _oneof_case_[4] = HASRESTITUTION_NOT_SET; +} + +void ChangeDynamicsCommand::clear_haslinearDamping() { +// @@protoc_insertion_point(one_of_clear_start:pybullet_grpc.ChangeDynamicsCommand) + switch (haslinearDamping_case()) { + case kLinearDamping: { + // No need to clear + break; + } + case HASLINEARDAMPING_NOT_SET: { + break; + } + } + _oneof_case_[5] = HASLINEARDAMPING_NOT_SET; +} + +void ChangeDynamicsCommand::clear_hasangularDamping() { +// @@protoc_insertion_point(one_of_clear_start:pybullet_grpc.ChangeDynamicsCommand) + switch (hasangularDamping_case()) { + case kAngularDamping: { + // No need to clear + break; + } + case HASANGULARDAMPING_NOT_SET: { + break; + } + } + _oneof_case_[6] = HASANGULARDAMPING_NOT_SET; +} + +void ChangeDynamicsCommand::clear_hasContactStiffness() { +// @@protoc_insertion_point(one_of_clear_start:pybullet_grpc.ChangeDynamicsCommand) + switch (hasContactStiffness_case()) { + case kContactStiffness: { + // No need to clear + break; + } + case HASCONTACTSTIFFNESS_NOT_SET: { + break; + } + } + _oneof_case_[7] = HASCONTACTSTIFFNESS_NOT_SET; +} + +void ChangeDynamicsCommand::clear_hasContactDamping() { +// @@protoc_insertion_point(one_of_clear_start:pybullet_grpc.ChangeDynamicsCommand) + switch (hasContactDamping_case()) { + case kContactDamping: { + // No need to clear + break; + } + case HASCONTACTDAMPING_NOT_SET: { + break; + } + } + _oneof_case_[8] = HASCONTACTDAMPING_NOT_SET; +} + +void ChangeDynamicsCommand::clear_hasLocalInertiaDiagonal() { +// @@protoc_insertion_point(one_of_clear_start:pybullet_grpc.ChangeDynamicsCommand) + switch (hasLocalInertiaDiagonal_case()) { + case kLocalInertiaDiagonal: { + delete hasLocalInertiaDiagonal_.localinertiadiagonal_; + break; + } + case HASLOCALINERTIADIAGONAL_NOT_SET: { + break; + } + } + _oneof_case_[9] = HASLOCALINERTIADIAGONAL_NOT_SET; +} + +void ChangeDynamicsCommand::clear_hasFrictionAnchor() { +// @@protoc_insertion_point(one_of_clear_start:pybullet_grpc.ChangeDynamicsCommand) + switch (hasFrictionAnchor_case()) { + case kFrictionAnchor: { + // No need to clear + break; + } + case HASFRICTIONANCHOR_NOT_SET: { + break; + } + } + _oneof_case_[10] = HASFRICTIONANCHOR_NOT_SET; +} + +void ChangeDynamicsCommand::clear_hasccdSweptSphereRadius() { +// @@protoc_insertion_point(one_of_clear_start:pybullet_grpc.ChangeDynamicsCommand) + switch (hasccdSweptSphereRadius_case()) { + case kCcdSweptSphereRadius: { + // No need to clear + break; + } + case HASCCDSWEPTSPHERERADIUS_NOT_SET: { + break; + } + } + _oneof_case_[11] = HASCCDSWEPTSPHERERADIUS_NOT_SET; +} + +void ChangeDynamicsCommand::clear_hasContactProcessingThreshold() { +// @@protoc_insertion_point(one_of_clear_start:pybullet_grpc.ChangeDynamicsCommand) + switch (hasContactProcessingThreshold_case()) { + case kContactProcessingThreshold: { + // No need to clear + break; + } + case HASCONTACTPROCESSINGTHRESHOLD_NOT_SET: { + break; + } + } + _oneof_case_[12] = HASCONTACTPROCESSINGTHRESHOLD_NOT_SET; +} + +void ChangeDynamicsCommand::clear_hasActivationState() { +// @@protoc_insertion_point(one_of_clear_start:pybullet_grpc.ChangeDynamicsCommand) + switch (hasActivationState_case()) { + case kActivationState: { + // No need to clear + break; + } + case HASACTIVATIONSTATE_NOT_SET: { + break; + } + } + _oneof_case_[13] = HASACTIVATIONSTATE_NOT_SET; +} + + +void ChangeDynamicsCommand::Clear() { +// @@protoc_insertion_point(message_clear_start:pybullet_grpc.ChangeDynamicsCommand) + ::memset(&bodyuniqueid_, 0, reinterpret_cast(&linkindex_) - + reinterpret_cast(&bodyuniqueid_) + sizeof(linkindex_)); + clear_hasMass(); + clear_hasLateralFriction(); + clear_hasSpinningFriction(); + clear_hasRollingFriction(); + clear_hasRestitution(); + clear_haslinearDamping(); + clear_hasangularDamping(); + clear_hasContactStiffness(); + clear_hasContactDamping(); + clear_hasLocalInertiaDiagonal(); + clear_hasFrictionAnchor(); + clear_hasccdSweptSphereRadius(); + clear_hasContactProcessingThreshold(); + clear_hasActivationState(); +} + +bool ChangeDynamicsCommand::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.ChangeDynamicsCommand) + for (;;) { + ::std::pair< ::google::protobuf::uint32, bool> p = input->ReadTagWithCutoffNoLastTag(16383u); + tag = p.first; + if (!p.second) goto handle_unusual; + switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { + // int32 bodyUniqueId = 1; + case 1: { + if (tag == 8u) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>( + input, &bodyuniqueid_))); + } else { + goto handle_unusual; + } + break; + } + + // int32 linkIndex = 2; + case 2: { + if (tag == 16u) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>( + input, &linkindex_))); + } else { + goto handle_unusual; + } + break; + } + + // double mass = 3; + case 3: { + if (tag == 25u) { + clear_hasMass(); + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &hasMass_.mass_))); + set_has_mass(); + } else { + goto handle_unusual; + } + break; + } + + // double lateralFriction = 5; + case 5: { + if (tag == 41u) { + clear_hasLateralFriction(); + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &hasLateralFriction_.lateralfriction_))); + set_has_lateralfriction(); + } else { + goto handle_unusual; + } + break; + } + + // double spinningFriction = 6; + case 6: { + if (tag == 49u) { + clear_hasSpinningFriction(); + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &hasSpinningFriction_.spinningfriction_))); + set_has_spinningfriction(); + } else { + goto handle_unusual; + } + break; + } + + // double rollingFriction = 7; + case 7: { + if (tag == 57u) { + clear_hasRollingFriction(); + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &hasRollingFriction_.rollingfriction_))); + set_has_rollingfriction(); + } else { + goto handle_unusual; + } + break; + } + + // double restitution = 8; + case 8: { + if (tag == 65u) { + clear_hasRestitution(); + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &hasRestitution_.restitution_))); + set_has_restitution(); + } else { + goto handle_unusual; + } + break; + } + + // double linearDamping = 9; + case 9: { + if (tag == 73u) { + clear_haslinearDamping(); + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &haslinearDamping_.lineardamping_))); + set_has_lineardamping(); + } else { + goto handle_unusual; + } + break; + } + + // double angularDamping = 10; + case 10: { + if (tag == 81u) { + clear_hasangularDamping(); + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &hasangularDamping_.angulardamping_))); + set_has_angulardamping(); + } else { + goto handle_unusual; + } + break; + } + + // double contactStiffness = 11; + case 11: { + if (tag == 89u) { + clear_hasContactStiffness(); + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &hasContactStiffness_.contactstiffness_))); + set_has_contactstiffness(); + } else { + goto handle_unusual; + } + break; + } + + // double contactDamping = 12; + case 12: { + if (tag == 97u) { + clear_hasContactDamping(); + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &hasContactDamping_.contactdamping_))); + set_has_contactdamping(); + } else { + goto handle_unusual; + } + break; + } + + // .pybullet_grpc.vec3 localInertiaDiagonal = 13; + case 13: { + if (tag == 106u) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessageNoVirtual( + input, mutable_localinertiadiagonal())); + } else { + goto handle_unusual; + } + break; + } + + // int32 frictionAnchor = 14; + case 14: { + if (tag == 112u) { + clear_hasFrictionAnchor(); + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>( + input, &hasFrictionAnchor_.frictionanchor_))); + set_has_frictionanchor(); + } else { + goto handle_unusual; + } + break; + } + + // double ccdSweptSphereRadius = 15; + case 15: { + if (tag == 121u) { + clear_hasccdSweptSphereRadius(); + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &hasccdSweptSphereRadius_.ccdsweptsphereradius_))); + set_has_ccdsweptsphereradius(); + } else { + goto handle_unusual; + } + break; + } + + // double contactProcessingThreshold = 16; + case 16: { + if (tag == 129u) { + clear_hasContactProcessingThreshold(); + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &hasContactProcessingThreshold_.contactprocessingthreshold_))); + set_has_contactprocessingthreshold(); + } else { + goto handle_unusual; + } + break; + } + + // int32 activationState = 17; + case 17: { + if (tag == 136u) { + clear_hasActivationState(); + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>( + input, &hasActivationState_.activationstate_))); + set_has_activationstate(); + } 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.ChangeDynamicsCommand) + return true; +failure: + // @@protoc_insertion_point(parse_failure:pybullet_grpc.ChangeDynamicsCommand) + return false; +#undef DO_ +} + +void ChangeDynamicsCommand::SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const { + // @@protoc_insertion_point(serialize_start:pybullet_grpc.ChangeDynamicsCommand) + // int32 bodyUniqueId = 1; + if (this->bodyuniqueid() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteInt32(1, this->bodyuniqueid(), output); + } + + // int32 linkIndex = 2; + if (this->linkindex() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteInt32(2, this->linkindex(), output); + } + + // double mass = 3; + if (has_mass()) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(3, this->mass(), output); + } + + // double lateralFriction = 5; + if (has_lateralfriction()) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(5, this->lateralfriction(), output); + } + + // double spinningFriction = 6; + if (has_spinningfriction()) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(6, this->spinningfriction(), output); + } + + // double rollingFriction = 7; + if (has_rollingfriction()) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(7, this->rollingfriction(), output); + } + + // double restitution = 8; + if (has_restitution()) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(8, this->restitution(), output); + } + + // double linearDamping = 9; + if (has_lineardamping()) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(9, this->lineardamping(), output); + } + + // double angularDamping = 10; + if (has_angulardamping()) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(10, this->angulardamping(), output); + } + + // double contactStiffness = 11; + if (has_contactstiffness()) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(11, this->contactstiffness(), output); + } + + // double contactDamping = 12; + if (has_contactdamping()) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(12, this->contactdamping(), output); + } + + // .pybullet_grpc.vec3 localInertiaDiagonal = 13; + if (has_localinertiadiagonal()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 13, *hasLocalInertiaDiagonal_.localinertiadiagonal_, output); + } + + // int32 frictionAnchor = 14; + if (has_frictionanchor()) { + ::google::protobuf::internal::WireFormatLite::WriteInt32(14, this->frictionanchor(), output); + } + + // double ccdSweptSphereRadius = 15; + if (has_ccdsweptsphereradius()) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(15, this->ccdsweptsphereradius(), output); + } + + // double contactProcessingThreshold = 16; + if (has_contactprocessingthreshold()) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(16, this->contactprocessingthreshold(), output); + } + + // int32 activationState = 17; + if (has_activationstate()) { + ::google::protobuf::internal::WireFormatLite::WriteInt32(17, this->activationstate(), output); + } + + // @@protoc_insertion_point(serialize_end:pybullet_grpc.ChangeDynamicsCommand) +} + +::google::protobuf::uint8* ChangeDynamicsCommand::InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const { + (void)deterministic; // Unused + // @@protoc_insertion_point(serialize_to_array_start:pybullet_grpc.ChangeDynamicsCommand) + // int32 bodyUniqueId = 1; + if (this->bodyuniqueid() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteInt32ToArray(1, this->bodyuniqueid(), target); + } + + // int32 linkIndex = 2; + if (this->linkindex() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteInt32ToArray(2, this->linkindex(), target); + } + + // double mass = 3; + if (has_mass()) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(3, this->mass(), target); + } + + // double lateralFriction = 5; + if (has_lateralfriction()) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(5, this->lateralfriction(), target); + } + + // double spinningFriction = 6; + if (has_spinningfriction()) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(6, this->spinningfriction(), target); + } + + // double rollingFriction = 7; + if (has_rollingfriction()) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(7, this->rollingfriction(), target); + } + + // double restitution = 8; + if (has_restitution()) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(8, this->restitution(), target); + } + + // double linearDamping = 9; + if (has_lineardamping()) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(9, this->lineardamping(), target); + } + + // double angularDamping = 10; + if (has_angulardamping()) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(10, this->angulardamping(), target); + } + + // double contactStiffness = 11; + if (has_contactstiffness()) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(11, this->contactstiffness(), target); + } + + // double contactDamping = 12; + if (has_contactdamping()) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(12, this->contactdamping(), target); + } + + // .pybullet_grpc.vec3 localInertiaDiagonal = 13; + if (has_localinertiadiagonal()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageNoVirtualToArray( + 13, *hasLocalInertiaDiagonal_.localinertiadiagonal_, false, target); + } + + // int32 frictionAnchor = 14; + if (has_frictionanchor()) { + target = ::google::protobuf::internal::WireFormatLite::WriteInt32ToArray(14, this->frictionanchor(), target); + } + + // double ccdSweptSphereRadius = 15; + if (has_ccdsweptsphereradius()) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(15, this->ccdsweptsphereradius(), target); + } + + // double contactProcessingThreshold = 16; + if (has_contactprocessingthreshold()) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(16, this->contactprocessingthreshold(), target); + } + + // int32 activationState = 17; + if (has_activationstate()) { + target = ::google::protobuf::internal::WireFormatLite::WriteInt32ToArray(17, this->activationstate(), target); + } + + // @@protoc_insertion_point(serialize_to_array_end:pybullet_grpc.ChangeDynamicsCommand) + return target; +} + +size_t ChangeDynamicsCommand::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:pybullet_grpc.ChangeDynamicsCommand) + size_t total_size = 0; + + // int32 bodyUniqueId = 1; + if (this->bodyuniqueid() != 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::Int32Size( + this->bodyuniqueid()); + } + + // int32 linkIndex = 2; + if (this->linkindex() != 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::Int32Size( + this->linkindex()); + } + + switch (hasMass_case()) { + // double mass = 3; + case kMass: { + total_size += 1 + 8; + break; + } + case HASMASS_NOT_SET: { + break; + } + } + switch (hasLateralFriction_case()) { + // double lateralFriction = 5; + case kLateralFriction: { + total_size += 1 + 8; + break; + } + case HASLATERALFRICTION_NOT_SET: { + break; + } + } + switch (hasSpinningFriction_case()) { + // double spinningFriction = 6; + case kSpinningFriction: { + total_size += 1 + 8; + break; + } + case HASSPINNINGFRICTION_NOT_SET: { + break; + } + } + switch (hasRollingFriction_case()) { + // double rollingFriction = 7; + case kRollingFriction: { + total_size += 1 + 8; + break; + } + case HASROLLINGFRICTION_NOT_SET: { + break; + } + } + switch (hasRestitution_case()) { + // double restitution = 8; + case kRestitution: { + total_size += 1 + 8; + break; + } + case HASRESTITUTION_NOT_SET: { + break; + } + } + switch (haslinearDamping_case()) { + // double linearDamping = 9; + case kLinearDamping: { + total_size += 1 + 8; + break; + } + case HASLINEARDAMPING_NOT_SET: { + break; + } + } + switch (hasangularDamping_case()) { + // double angularDamping = 10; + case kAngularDamping: { + total_size += 1 + 8; + break; + } + case HASANGULARDAMPING_NOT_SET: { + break; + } + } + switch (hasContactStiffness_case()) { + // double contactStiffness = 11; + case kContactStiffness: { + total_size += 1 + 8; + break; + } + case HASCONTACTSTIFFNESS_NOT_SET: { + break; + } + } + switch (hasContactDamping_case()) { + // double contactDamping = 12; + case kContactDamping: { + total_size += 1 + 8; + break; + } + case HASCONTACTDAMPING_NOT_SET: { + break; + } + } + switch (hasLocalInertiaDiagonal_case()) { + // .pybullet_grpc.vec3 localInertiaDiagonal = 13; + case kLocalInertiaDiagonal: { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSizeNoVirtual( + *hasLocalInertiaDiagonal_.localinertiadiagonal_); + break; + } + case HASLOCALINERTIADIAGONAL_NOT_SET: { + break; + } + } + switch (hasFrictionAnchor_case()) { + // int32 frictionAnchor = 14; + case kFrictionAnchor: { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::Int32Size( + this->frictionanchor()); + break; + } + case HASFRICTIONANCHOR_NOT_SET: { + break; + } + } + switch (hasccdSweptSphereRadius_case()) { + // double ccdSweptSphereRadius = 15; + case kCcdSweptSphereRadius: { + total_size += 1 + 8; + break; + } + case HASCCDSWEPTSPHERERADIUS_NOT_SET: { + break; + } + } + switch (hasContactProcessingThreshold_case()) { + // double contactProcessingThreshold = 16; + case kContactProcessingThreshold: { + total_size += 2 + 8; + break; + } + case HASCONTACTPROCESSINGTHRESHOLD_NOT_SET: { + break; + } + } + switch (hasActivationState_case()) { + // int32 activationState = 17; + case kActivationState: { + total_size += 2 + + ::google::protobuf::internal::WireFormatLite::Int32Size( + this->activationstate()); + break; + } + case HASACTIVATIONSTATE_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 ChangeDynamicsCommand::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:pybullet_grpc.ChangeDynamicsCommand) + GOOGLE_DCHECK_NE(&from, this); + const ChangeDynamicsCommand* source = + ::google::protobuf::internal::DynamicCastToGenerated( + &from); + if (source == NULL) { + // @@protoc_insertion_point(generalized_merge_from_cast_fail:pybullet_grpc.ChangeDynamicsCommand) + ::google::protobuf::internal::ReflectionOps::Merge(from, this); + } else { + // @@protoc_insertion_point(generalized_merge_from_cast_success:pybullet_grpc.ChangeDynamicsCommand) + MergeFrom(*source); + } +} + +void ChangeDynamicsCommand::MergeFrom(const ChangeDynamicsCommand& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:pybullet_grpc.ChangeDynamicsCommand) + GOOGLE_DCHECK_NE(&from, this); + _internal_metadata_.MergeFrom(from._internal_metadata_); + if (from.bodyuniqueid() != 0) { + set_bodyuniqueid(from.bodyuniqueid()); + } + if (from.linkindex() != 0) { + set_linkindex(from.linkindex()); + } + switch (from.hasMass_case()) { + case kMass: { + set_mass(from.mass()); + break; + } + case HASMASS_NOT_SET: { + break; + } + } + switch (from.hasLateralFriction_case()) { + case kLateralFriction: { + set_lateralfriction(from.lateralfriction()); + break; + } + case HASLATERALFRICTION_NOT_SET: { + break; + } + } + switch (from.hasSpinningFriction_case()) { + case kSpinningFriction: { + set_spinningfriction(from.spinningfriction()); + break; + } + case HASSPINNINGFRICTION_NOT_SET: { + break; + } + } + switch (from.hasRollingFriction_case()) { + case kRollingFriction: { + set_rollingfriction(from.rollingfriction()); + break; + } + case HASROLLINGFRICTION_NOT_SET: { + break; + } + } + switch (from.hasRestitution_case()) { + case kRestitution: { + set_restitution(from.restitution()); + break; + } + case HASRESTITUTION_NOT_SET: { + break; + } + } + switch (from.haslinearDamping_case()) { + case kLinearDamping: { + set_lineardamping(from.lineardamping()); + break; + } + case HASLINEARDAMPING_NOT_SET: { + break; + } + } + switch (from.hasangularDamping_case()) { + case kAngularDamping: { + set_angulardamping(from.angulardamping()); + break; + } + case HASANGULARDAMPING_NOT_SET: { + break; + } + } + switch (from.hasContactStiffness_case()) { + case kContactStiffness: { + set_contactstiffness(from.contactstiffness()); + break; + } + case HASCONTACTSTIFFNESS_NOT_SET: { + break; + } + } + switch (from.hasContactDamping_case()) { + case kContactDamping: { + set_contactdamping(from.contactdamping()); + break; + } + case HASCONTACTDAMPING_NOT_SET: { + break; + } + } + switch (from.hasLocalInertiaDiagonal_case()) { + case kLocalInertiaDiagonal: { + mutable_localinertiadiagonal()->::pybullet_grpc::vec3::MergeFrom(from.localinertiadiagonal()); + break; + } + case HASLOCALINERTIADIAGONAL_NOT_SET: { + break; + } + } + switch (from.hasFrictionAnchor_case()) { + case kFrictionAnchor: { + set_frictionanchor(from.frictionanchor()); + break; + } + case HASFRICTIONANCHOR_NOT_SET: { + break; + } + } + switch (from.hasccdSweptSphereRadius_case()) { + case kCcdSweptSphereRadius: { + set_ccdsweptsphereradius(from.ccdsweptsphereradius()); + break; + } + case HASCCDSWEPTSPHERERADIUS_NOT_SET: { + break; + } + } + switch (from.hasContactProcessingThreshold_case()) { + case kContactProcessingThreshold: { + set_contactprocessingthreshold(from.contactprocessingthreshold()); + break; + } + case HASCONTACTPROCESSINGTHRESHOLD_NOT_SET: { + break; + } + } + switch (from.hasActivationState_case()) { + case kActivationState: { + set_activationstate(from.activationstate()); + break; + } + case HASACTIVATIONSTATE_NOT_SET: { + break; + } + } +} + +void ChangeDynamicsCommand::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:pybullet_grpc.ChangeDynamicsCommand) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +void ChangeDynamicsCommand::CopyFrom(const ChangeDynamicsCommand& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:pybullet_grpc.ChangeDynamicsCommand) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool ChangeDynamicsCommand::IsInitialized() const { + return true; +} + +void ChangeDynamicsCommand::Swap(ChangeDynamicsCommand* other) { + if (other == this) return; + InternalSwap(other); +} +void ChangeDynamicsCommand::InternalSwap(ChangeDynamicsCommand* other) { + std::swap(bodyuniqueid_, other->bodyuniqueid_); + std::swap(linkindex_, other->linkindex_); + std::swap(hasMass_, other->hasMass_); + std::swap(_oneof_case_[0], other->_oneof_case_[0]); + std::swap(hasLateralFriction_, other->hasLateralFriction_); + std::swap(_oneof_case_[1], other->_oneof_case_[1]); + std::swap(hasSpinningFriction_, other->hasSpinningFriction_); + std::swap(_oneof_case_[2], other->_oneof_case_[2]); + std::swap(hasRollingFriction_, other->hasRollingFriction_); + std::swap(_oneof_case_[3], other->_oneof_case_[3]); + std::swap(hasRestitution_, other->hasRestitution_); + std::swap(_oneof_case_[4], other->_oneof_case_[4]); + std::swap(haslinearDamping_, other->haslinearDamping_); + std::swap(_oneof_case_[5], other->_oneof_case_[5]); + std::swap(hasangularDamping_, other->hasangularDamping_); + std::swap(_oneof_case_[6], other->_oneof_case_[6]); + std::swap(hasContactStiffness_, other->hasContactStiffness_); + std::swap(_oneof_case_[7], other->_oneof_case_[7]); + std::swap(hasContactDamping_, other->hasContactDamping_); + std::swap(_oneof_case_[8], other->_oneof_case_[8]); + std::swap(hasLocalInertiaDiagonal_, other->hasLocalInertiaDiagonal_); + std::swap(_oneof_case_[9], other->_oneof_case_[9]); + std::swap(hasFrictionAnchor_, other->hasFrictionAnchor_); + std::swap(_oneof_case_[10], other->_oneof_case_[10]); + std::swap(hasccdSweptSphereRadius_, other->hasccdSweptSphereRadius_); + std::swap(_oneof_case_[11], other->_oneof_case_[11]); + std::swap(hasContactProcessingThreshold_, other->hasContactProcessingThreshold_); + std::swap(_oneof_case_[12], other->_oneof_case_[12]); + std::swap(hasActivationState_, other->hasActivationState_); + std::swap(_oneof_case_[13], other->_oneof_case_[13]); + std::swap(_cached_size_, other->_cached_size_); +} + +::google::protobuf::Metadata ChangeDynamicsCommand::GetMetadata() const { + protobuf_pybullet_2eproto::protobuf_AssignDescriptorsOnce(); + return protobuf_pybullet_2eproto::file_level_metadata[10]; +} + +#if PROTOBUF_INLINE_NOT_IN_HEADERS +// ChangeDynamicsCommand + +// int32 bodyUniqueId = 1; +void ChangeDynamicsCommand::clear_bodyuniqueid() { + bodyuniqueid_ = 0; +} +::google::protobuf::int32 ChangeDynamicsCommand::bodyuniqueid() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.ChangeDynamicsCommand.bodyUniqueId) + return bodyuniqueid_; +} +void ChangeDynamicsCommand::set_bodyuniqueid(::google::protobuf::int32 value) { + + bodyuniqueid_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.ChangeDynamicsCommand.bodyUniqueId) +} + +// int32 linkIndex = 2; +void ChangeDynamicsCommand::clear_linkindex() { + linkindex_ = 0; +} +::google::protobuf::int32 ChangeDynamicsCommand::linkindex() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.ChangeDynamicsCommand.linkIndex) + return linkindex_; +} +void ChangeDynamicsCommand::set_linkindex(::google::protobuf::int32 value) { + + linkindex_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.ChangeDynamicsCommand.linkIndex) +} + +// double mass = 3; +bool ChangeDynamicsCommand::has_mass() const { + return hasMass_case() == kMass; +} +void ChangeDynamicsCommand::set_has_mass() { + _oneof_case_[0] = kMass; +} +void ChangeDynamicsCommand::clear_mass() { + if (has_mass()) { + hasMass_.mass_ = 0; + clear_has_hasMass(); + } +} +double ChangeDynamicsCommand::mass() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.ChangeDynamicsCommand.mass) + if (has_mass()) { + return hasMass_.mass_; + } + return 0; +} +void ChangeDynamicsCommand::set_mass(double value) { + if (!has_mass()) { + clear_hasMass(); + set_has_mass(); + } + hasMass_.mass_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.ChangeDynamicsCommand.mass) +} + +// double lateralFriction = 5; +bool ChangeDynamicsCommand::has_lateralfriction() const { + return hasLateralFriction_case() == kLateralFriction; +} +void ChangeDynamicsCommand::set_has_lateralfriction() { + _oneof_case_[1] = kLateralFriction; +} +void ChangeDynamicsCommand::clear_lateralfriction() { + if (has_lateralfriction()) { + hasLateralFriction_.lateralfriction_ = 0; + clear_has_hasLateralFriction(); + } +} +double ChangeDynamicsCommand::lateralfriction() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.ChangeDynamicsCommand.lateralFriction) + if (has_lateralfriction()) { + return hasLateralFriction_.lateralfriction_; + } + return 0; +} +void ChangeDynamicsCommand::set_lateralfriction(double value) { + if (!has_lateralfriction()) { + clear_hasLateralFriction(); + set_has_lateralfriction(); + } + hasLateralFriction_.lateralfriction_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.ChangeDynamicsCommand.lateralFriction) +} + +// double spinningFriction = 6; +bool ChangeDynamicsCommand::has_spinningfriction() const { + return hasSpinningFriction_case() == kSpinningFriction; +} +void ChangeDynamicsCommand::set_has_spinningfriction() { + _oneof_case_[2] = kSpinningFriction; +} +void ChangeDynamicsCommand::clear_spinningfriction() { + if (has_spinningfriction()) { + hasSpinningFriction_.spinningfriction_ = 0; + clear_has_hasSpinningFriction(); + } +} +double ChangeDynamicsCommand::spinningfriction() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.ChangeDynamicsCommand.spinningFriction) + if (has_spinningfriction()) { + return hasSpinningFriction_.spinningfriction_; + } + return 0; +} +void ChangeDynamicsCommand::set_spinningfriction(double value) { + if (!has_spinningfriction()) { + clear_hasSpinningFriction(); + set_has_spinningfriction(); + } + hasSpinningFriction_.spinningfriction_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.ChangeDynamicsCommand.spinningFriction) +} + +// double rollingFriction = 7; +bool ChangeDynamicsCommand::has_rollingfriction() const { + return hasRollingFriction_case() == kRollingFriction; +} +void ChangeDynamicsCommand::set_has_rollingfriction() { + _oneof_case_[3] = kRollingFriction; +} +void ChangeDynamicsCommand::clear_rollingfriction() { + if (has_rollingfriction()) { + hasRollingFriction_.rollingfriction_ = 0; + clear_has_hasRollingFriction(); + } +} +double ChangeDynamicsCommand::rollingfriction() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.ChangeDynamicsCommand.rollingFriction) + if (has_rollingfriction()) { + return hasRollingFriction_.rollingfriction_; + } + return 0; +} +void ChangeDynamicsCommand::set_rollingfriction(double value) { + if (!has_rollingfriction()) { + clear_hasRollingFriction(); + set_has_rollingfriction(); + } + hasRollingFriction_.rollingfriction_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.ChangeDynamicsCommand.rollingFriction) +} + +// double restitution = 8; +bool ChangeDynamicsCommand::has_restitution() const { + return hasRestitution_case() == kRestitution; +} +void ChangeDynamicsCommand::set_has_restitution() { + _oneof_case_[4] = kRestitution; +} +void ChangeDynamicsCommand::clear_restitution() { + if (has_restitution()) { + hasRestitution_.restitution_ = 0; + clear_has_hasRestitution(); + } +} +double ChangeDynamicsCommand::restitution() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.ChangeDynamicsCommand.restitution) + if (has_restitution()) { + return hasRestitution_.restitution_; + } + return 0; +} +void ChangeDynamicsCommand::set_restitution(double value) { + if (!has_restitution()) { + clear_hasRestitution(); + set_has_restitution(); + } + hasRestitution_.restitution_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.ChangeDynamicsCommand.restitution) +} + +// double linearDamping = 9; +bool ChangeDynamicsCommand::has_lineardamping() const { + return haslinearDamping_case() == kLinearDamping; +} +void ChangeDynamicsCommand::set_has_lineardamping() { + _oneof_case_[5] = kLinearDamping; +} +void ChangeDynamicsCommand::clear_lineardamping() { + if (has_lineardamping()) { + haslinearDamping_.lineardamping_ = 0; + clear_has_haslinearDamping(); + } +} +double ChangeDynamicsCommand::lineardamping() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.ChangeDynamicsCommand.linearDamping) + if (has_lineardamping()) { + return haslinearDamping_.lineardamping_; + } + return 0; +} +void ChangeDynamicsCommand::set_lineardamping(double value) { + if (!has_lineardamping()) { + clear_haslinearDamping(); + set_has_lineardamping(); + } + haslinearDamping_.lineardamping_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.ChangeDynamicsCommand.linearDamping) +} + +// double angularDamping = 10; +bool ChangeDynamicsCommand::has_angulardamping() const { + return hasangularDamping_case() == kAngularDamping; +} +void ChangeDynamicsCommand::set_has_angulardamping() { + _oneof_case_[6] = kAngularDamping; +} +void ChangeDynamicsCommand::clear_angulardamping() { + if (has_angulardamping()) { + hasangularDamping_.angulardamping_ = 0; + clear_has_hasangularDamping(); + } +} +double ChangeDynamicsCommand::angulardamping() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.ChangeDynamicsCommand.angularDamping) + if (has_angulardamping()) { + return hasangularDamping_.angulardamping_; + } + return 0; +} +void ChangeDynamicsCommand::set_angulardamping(double value) { + if (!has_angulardamping()) { + clear_hasangularDamping(); + set_has_angulardamping(); + } + hasangularDamping_.angulardamping_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.ChangeDynamicsCommand.angularDamping) +} + +// double contactStiffness = 11; +bool ChangeDynamicsCommand::has_contactstiffness() const { + return hasContactStiffness_case() == kContactStiffness; +} +void ChangeDynamicsCommand::set_has_contactstiffness() { + _oneof_case_[7] = kContactStiffness; +} +void ChangeDynamicsCommand::clear_contactstiffness() { + if (has_contactstiffness()) { + hasContactStiffness_.contactstiffness_ = 0; + clear_has_hasContactStiffness(); + } +} +double ChangeDynamicsCommand::contactstiffness() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.ChangeDynamicsCommand.contactStiffness) + if (has_contactstiffness()) { + return hasContactStiffness_.contactstiffness_; + } + return 0; +} +void ChangeDynamicsCommand::set_contactstiffness(double value) { + if (!has_contactstiffness()) { + clear_hasContactStiffness(); + set_has_contactstiffness(); + } + hasContactStiffness_.contactstiffness_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.ChangeDynamicsCommand.contactStiffness) +} + +// double contactDamping = 12; +bool ChangeDynamicsCommand::has_contactdamping() const { + return hasContactDamping_case() == kContactDamping; +} +void ChangeDynamicsCommand::set_has_contactdamping() { + _oneof_case_[8] = kContactDamping; +} +void ChangeDynamicsCommand::clear_contactdamping() { + if (has_contactdamping()) { + hasContactDamping_.contactdamping_ = 0; + clear_has_hasContactDamping(); + } +} +double ChangeDynamicsCommand::contactdamping() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.ChangeDynamicsCommand.contactDamping) + if (has_contactdamping()) { + return hasContactDamping_.contactdamping_; + } + return 0; +} +void ChangeDynamicsCommand::set_contactdamping(double value) { + if (!has_contactdamping()) { + clear_hasContactDamping(); + set_has_contactdamping(); + } + hasContactDamping_.contactdamping_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.ChangeDynamicsCommand.contactDamping) +} + +// .pybullet_grpc.vec3 localInertiaDiagonal = 13; +bool ChangeDynamicsCommand::has_localinertiadiagonal() const { + return hasLocalInertiaDiagonal_case() == kLocalInertiaDiagonal; +} +void ChangeDynamicsCommand::set_has_localinertiadiagonal() { + _oneof_case_[9] = kLocalInertiaDiagonal; +} +void ChangeDynamicsCommand::clear_localinertiadiagonal() { + if (has_localinertiadiagonal()) { + delete hasLocalInertiaDiagonal_.localinertiadiagonal_; + clear_has_hasLocalInertiaDiagonal(); + } +} + const ::pybullet_grpc::vec3& ChangeDynamicsCommand::localinertiadiagonal() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.ChangeDynamicsCommand.localInertiaDiagonal) + return has_localinertiadiagonal() + ? *hasLocalInertiaDiagonal_.localinertiadiagonal_ + : ::pybullet_grpc::vec3::default_instance(); +} +::pybullet_grpc::vec3* ChangeDynamicsCommand::mutable_localinertiadiagonal() { + if (!has_localinertiadiagonal()) { + clear_hasLocalInertiaDiagonal(); + set_has_localinertiadiagonal(); + hasLocalInertiaDiagonal_.localinertiadiagonal_ = new ::pybullet_grpc::vec3; + } + // @@protoc_insertion_point(field_mutable:pybullet_grpc.ChangeDynamicsCommand.localInertiaDiagonal) + return hasLocalInertiaDiagonal_.localinertiadiagonal_; +} +::pybullet_grpc::vec3* ChangeDynamicsCommand::release_localinertiadiagonal() { + // @@protoc_insertion_point(field_release:pybullet_grpc.ChangeDynamicsCommand.localInertiaDiagonal) + if (has_localinertiadiagonal()) { + clear_has_hasLocalInertiaDiagonal(); + ::pybullet_grpc::vec3* temp = hasLocalInertiaDiagonal_.localinertiadiagonal_; + hasLocalInertiaDiagonal_.localinertiadiagonal_ = NULL; + return temp; + } else { + return NULL; + } +} +void ChangeDynamicsCommand::set_allocated_localinertiadiagonal(::pybullet_grpc::vec3* localinertiadiagonal) { + clear_hasLocalInertiaDiagonal(); + if (localinertiadiagonal) { + set_has_localinertiadiagonal(); + hasLocalInertiaDiagonal_.localinertiadiagonal_ = localinertiadiagonal; + } + // @@protoc_insertion_point(field_set_allocated:pybullet_grpc.ChangeDynamicsCommand.localInertiaDiagonal) +} + +// int32 frictionAnchor = 14; +bool ChangeDynamicsCommand::has_frictionanchor() const { + return hasFrictionAnchor_case() == kFrictionAnchor; +} +void ChangeDynamicsCommand::set_has_frictionanchor() { + _oneof_case_[10] = kFrictionAnchor; +} +void ChangeDynamicsCommand::clear_frictionanchor() { + if (has_frictionanchor()) { + hasFrictionAnchor_.frictionanchor_ = 0; + clear_has_hasFrictionAnchor(); + } +} +::google::protobuf::int32 ChangeDynamicsCommand::frictionanchor() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.ChangeDynamicsCommand.frictionAnchor) + if (has_frictionanchor()) { + return hasFrictionAnchor_.frictionanchor_; + } + return 0; +} +void ChangeDynamicsCommand::set_frictionanchor(::google::protobuf::int32 value) { + if (!has_frictionanchor()) { + clear_hasFrictionAnchor(); + set_has_frictionanchor(); + } + hasFrictionAnchor_.frictionanchor_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.ChangeDynamicsCommand.frictionAnchor) +} + +// double ccdSweptSphereRadius = 15; +bool ChangeDynamicsCommand::has_ccdsweptsphereradius() const { + return hasccdSweptSphereRadius_case() == kCcdSweptSphereRadius; +} +void ChangeDynamicsCommand::set_has_ccdsweptsphereradius() { + _oneof_case_[11] = kCcdSweptSphereRadius; +} +void ChangeDynamicsCommand::clear_ccdsweptsphereradius() { + if (has_ccdsweptsphereradius()) { + hasccdSweptSphereRadius_.ccdsweptsphereradius_ = 0; + clear_has_hasccdSweptSphereRadius(); + } +} +double ChangeDynamicsCommand::ccdsweptsphereradius() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.ChangeDynamicsCommand.ccdSweptSphereRadius) + if (has_ccdsweptsphereradius()) { + return hasccdSweptSphereRadius_.ccdsweptsphereradius_; + } + return 0; +} +void ChangeDynamicsCommand::set_ccdsweptsphereradius(double value) { + if (!has_ccdsweptsphereradius()) { + clear_hasccdSweptSphereRadius(); + set_has_ccdsweptsphereradius(); + } + hasccdSweptSphereRadius_.ccdsweptsphereradius_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.ChangeDynamicsCommand.ccdSweptSphereRadius) +} + +// double contactProcessingThreshold = 16; +bool ChangeDynamicsCommand::has_contactprocessingthreshold() const { + return hasContactProcessingThreshold_case() == kContactProcessingThreshold; +} +void ChangeDynamicsCommand::set_has_contactprocessingthreshold() { + _oneof_case_[12] = kContactProcessingThreshold; +} +void ChangeDynamicsCommand::clear_contactprocessingthreshold() { + if (has_contactprocessingthreshold()) { + hasContactProcessingThreshold_.contactprocessingthreshold_ = 0; + clear_has_hasContactProcessingThreshold(); + } +} +double ChangeDynamicsCommand::contactprocessingthreshold() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.ChangeDynamicsCommand.contactProcessingThreshold) + if (has_contactprocessingthreshold()) { + return hasContactProcessingThreshold_.contactprocessingthreshold_; + } + return 0; +} +void ChangeDynamicsCommand::set_contactprocessingthreshold(double value) { + if (!has_contactprocessingthreshold()) { + clear_hasContactProcessingThreshold(); + set_has_contactprocessingthreshold(); + } + hasContactProcessingThreshold_.contactprocessingthreshold_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.ChangeDynamicsCommand.contactProcessingThreshold) +} + +// int32 activationState = 17; +bool ChangeDynamicsCommand::has_activationstate() const { + return hasActivationState_case() == kActivationState; +} +void ChangeDynamicsCommand::set_has_activationstate() { + _oneof_case_[13] = kActivationState; +} +void ChangeDynamicsCommand::clear_activationstate() { + if (has_activationstate()) { + hasActivationState_.activationstate_ = 0; + clear_has_hasActivationState(); + } +} +::google::protobuf::int32 ChangeDynamicsCommand::activationstate() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.ChangeDynamicsCommand.activationState) + if (has_activationstate()) { + return hasActivationState_.activationstate_; + } + return 0; +} +void ChangeDynamicsCommand::set_activationstate(::google::protobuf::int32 value) { + if (!has_activationstate()) { + clear_hasActivationState(); + set_has_activationstate(); + } + hasActivationState_.activationstate_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.ChangeDynamicsCommand.activationState) +} + +bool ChangeDynamicsCommand::has_hasMass() const { + return hasMass_case() != HASMASS_NOT_SET; +} +void ChangeDynamicsCommand::clear_has_hasMass() { + _oneof_case_[0] = HASMASS_NOT_SET; +} +bool ChangeDynamicsCommand::has_hasLateralFriction() const { + return hasLateralFriction_case() != HASLATERALFRICTION_NOT_SET; +} +void ChangeDynamicsCommand::clear_has_hasLateralFriction() { + _oneof_case_[1] = HASLATERALFRICTION_NOT_SET; +} +bool ChangeDynamicsCommand::has_hasSpinningFriction() const { + return hasSpinningFriction_case() != HASSPINNINGFRICTION_NOT_SET; +} +void ChangeDynamicsCommand::clear_has_hasSpinningFriction() { + _oneof_case_[2] = HASSPINNINGFRICTION_NOT_SET; +} +bool ChangeDynamicsCommand::has_hasRollingFriction() const { + return hasRollingFriction_case() != HASROLLINGFRICTION_NOT_SET; +} +void ChangeDynamicsCommand::clear_has_hasRollingFriction() { + _oneof_case_[3] = HASROLLINGFRICTION_NOT_SET; +} +bool ChangeDynamicsCommand::has_hasRestitution() const { + return hasRestitution_case() != HASRESTITUTION_NOT_SET; +} +void ChangeDynamicsCommand::clear_has_hasRestitution() { + _oneof_case_[4] = HASRESTITUTION_NOT_SET; +} +bool ChangeDynamicsCommand::has_haslinearDamping() const { + return haslinearDamping_case() != HASLINEARDAMPING_NOT_SET; +} +void ChangeDynamicsCommand::clear_has_haslinearDamping() { + _oneof_case_[5] = HASLINEARDAMPING_NOT_SET; +} +bool ChangeDynamicsCommand::has_hasangularDamping() const { + return hasangularDamping_case() != HASANGULARDAMPING_NOT_SET; +} +void ChangeDynamicsCommand::clear_has_hasangularDamping() { + _oneof_case_[6] = HASANGULARDAMPING_NOT_SET; +} +bool ChangeDynamicsCommand::has_hasContactStiffness() const { + return hasContactStiffness_case() != HASCONTACTSTIFFNESS_NOT_SET; +} +void ChangeDynamicsCommand::clear_has_hasContactStiffness() { + _oneof_case_[7] = HASCONTACTSTIFFNESS_NOT_SET; +} +bool ChangeDynamicsCommand::has_hasContactDamping() const { + return hasContactDamping_case() != HASCONTACTDAMPING_NOT_SET; +} +void ChangeDynamicsCommand::clear_has_hasContactDamping() { + _oneof_case_[8] = HASCONTACTDAMPING_NOT_SET; +} +bool ChangeDynamicsCommand::has_hasLocalInertiaDiagonal() const { + return hasLocalInertiaDiagonal_case() != HASLOCALINERTIADIAGONAL_NOT_SET; +} +void ChangeDynamicsCommand::clear_has_hasLocalInertiaDiagonal() { + _oneof_case_[9] = HASLOCALINERTIADIAGONAL_NOT_SET; +} +bool ChangeDynamicsCommand::has_hasFrictionAnchor() const { + return hasFrictionAnchor_case() != HASFRICTIONANCHOR_NOT_SET; +} +void ChangeDynamicsCommand::clear_has_hasFrictionAnchor() { + _oneof_case_[10] = HASFRICTIONANCHOR_NOT_SET; +} +bool ChangeDynamicsCommand::has_hasccdSweptSphereRadius() const { + return hasccdSweptSphereRadius_case() != HASCCDSWEPTSPHERERADIUS_NOT_SET; +} +void ChangeDynamicsCommand::clear_has_hasccdSweptSphereRadius() { + _oneof_case_[11] = HASCCDSWEPTSPHERERADIUS_NOT_SET; +} +bool ChangeDynamicsCommand::has_hasContactProcessingThreshold() const { + return hasContactProcessingThreshold_case() != HASCONTACTPROCESSINGTHRESHOLD_NOT_SET; +} +void ChangeDynamicsCommand::clear_has_hasContactProcessingThreshold() { + _oneof_case_[12] = HASCONTACTPROCESSINGTHRESHOLD_NOT_SET; +} +bool ChangeDynamicsCommand::has_hasActivationState() const { + return hasActivationState_case() != HASACTIVATIONSTATE_NOT_SET; +} +void ChangeDynamicsCommand::clear_has_hasActivationState() { + _oneof_case_[13] = HASACTIVATIONSTATE_NOT_SET; +} +ChangeDynamicsCommand::HasMassCase ChangeDynamicsCommand::hasMass_case() const { + return ChangeDynamicsCommand::HasMassCase(_oneof_case_[0]); +} +ChangeDynamicsCommand::HasLateralFrictionCase ChangeDynamicsCommand::hasLateralFriction_case() const { + return ChangeDynamicsCommand::HasLateralFrictionCase(_oneof_case_[1]); +} +ChangeDynamicsCommand::HasSpinningFrictionCase ChangeDynamicsCommand::hasSpinningFriction_case() const { + return ChangeDynamicsCommand::HasSpinningFrictionCase(_oneof_case_[2]); +} +ChangeDynamicsCommand::HasRollingFrictionCase ChangeDynamicsCommand::hasRollingFriction_case() const { + return ChangeDynamicsCommand::HasRollingFrictionCase(_oneof_case_[3]); +} +ChangeDynamicsCommand::HasRestitutionCase ChangeDynamicsCommand::hasRestitution_case() const { + return ChangeDynamicsCommand::HasRestitutionCase(_oneof_case_[4]); +} +ChangeDynamicsCommand::HaslinearDampingCase ChangeDynamicsCommand::haslinearDamping_case() const { + return ChangeDynamicsCommand::HaslinearDampingCase(_oneof_case_[5]); +} +ChangeDynamicsCommand::HasangularDampingCase ChangeDynamicsCommand::hasangularDamping_case() const { + return ChangeDynamicsCommand::HasangularDampingCase(_oneof_case_[6]); +} +ChangeDynamicsCommand::HasContactStiffnessCase ChangeDynamicsCommand::hasContactStiffness_case() const { + return ChangeDynamicsCommand::HasContactStiffnessCase(_oneof_case_[7]); +} +ChangeDynamicsCommand::HasContactDampingCase ChangeDynamicsCommand::hasContactDamping_case() const { + return ChangeDynamicsCommand::HasContactDampingCase(_oneof_case_[8]); +} +ChangeDynamicsCommand::HasLocalInertiaDiagonalCase ChangeDynamicsCommand::hasLocalInertiaDiagonal_case() const { + return ChangeDynamicsCommand::HasLocalInertiaDiagonalCase(_oneof_case_[9]); +} +ChangeDynamicsCommand::HasFrictionAnchorCase ChangeDynamicsCommand::hasFrictionAnchor_case() const { + return ChangeDynamicsCommand::HasFrictionAnchorCase(_oneof_case_[10]); +} +ChangeDynamicsCommand::HasccdSweptSphereRadiusCase ChangeDynamicsCommand::hasccdSweptSphereRadius_case() const { + return ChangeDynamicsCommand::HasccdSweptSphereRadiusCase(_oneof_case_[11]); +} +ChangeDynamicsCommand::HasContactProcessingThresholdCase ChangeDynamicsCommand::hasContactProcessingThreshold_case() const { + return ChangeDynamicsCommand::HasContactProcessingThresholdCase(_oneof_case_[12]); +} +ChangeDynamicsCommand::HasActivationStateCase ChangeDynamicsCommand::hasActivationState_case() const { + return ChangeDynamicsCommand::HasActivationStateCase(_oneof_case_[13]); +} +#endif // PROTOBUF_INLINE_NOT_IN_HEADERS + +// =================================================================== + +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const int GetDynamicsCommand::kBodyUniqueIdFieldNumber; +const int GetDynamicsCommand::kLinkIndexFieldNumber; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 + +GetDynamicsCommand::GetDynamicsCommand() + : ::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.GetDynamicsCommand) +} +GetDynamicsCommand::GetDynamicsCommand(const GetDynamicsCommand& from) + : ::google::protobuf::Message(), + _internal_metadata_(NULL), + _cached_size_(0) { + _internal_metadata_.MergeFrom(from._internal_metadata_); + ::memcpy(&bodyuniqueid_, &from.bodyuniqueid_, + reinterpret_cast(&linkindex_) - + reinterpret_cast(&bodyuniqueid_) + sizeof(linkindex_)); + // @@protoc_insertion_point(copy_constructor:pybullet_grpc.GetDynamicsCommand) +} + +void GetDynamicsCommand::SharedCtor() { + ::memset(&bodyuniqueid_, 0, reinterpret_cast(&linkindex_) - + reinterpret_cast(&bodyuniqueid_) + sizeof(linkindex_)); + _cached_size_ = 0; +} + +GetDynamicsCommand::~GetDynamicsCommand() { + // @@protoc_insertion_point(destructor:pybullet_grpc.GetDynamicsCommand) + SharedDtor(); +} + +void GetDynamicsCommand::SharedDtor() { +} + +void GetDynamicsCommand::SetCachedSize(int size) const { + GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN(); + _cached_size_ = size; + GOOGLE_SAFE_CONCURRENT_WRITES_END(); +} +const ::google::protobuf::Descriptor* GetDynamicsCommand::descriptor() { + protobuf_pybullet_2eproto::protobuf_AssignDescriptorsOnce(); + return protobuf_pybullet_2eproto::file_level_metadata[11].descriptor; +} + +const GetDynamicsCommand& GetDynamicsCommand::default_instance() { + protobuf_pybullet_2eproto::InitDefaults(); + return *internal_default_instance(); +} + +GetDynamicsCommand* GetDynamicsCommand::New(::google::protobuf::Arena* arena) const { + GetDynamicsCommand* n = new GetDynamicsCommand; + if (arena != NULL) { + arena->Own(n); + } + return n; +} + +void GetDynamicsCommand::Clear() { +// @@protoc_insertion_point(message_clear_start:pybullet_grpc.GetDynamicsCommand) + ::memset(&bodyuniqueid_, 0, reinterpret_cast(&linkindex_) - + reinterpret_cast(&bodyuniqueid_) + sizeof(linkindex_)); +} + +bool GetDynamicsCommand::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.GetDynamicsCommand) + 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 bodyUniqueId = 1; + case 1: { + if (tag == 8u) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>( + input, &bodyuniqueid_))); + } else { + goto handle_unusual; + } + break; + } + + // int32 linkIndex = 2; + case 2: { + if (tag == 16u) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>( + input, &linkindex_))); + } 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.GetDynamicsCommand) + return true; +failure: + // @@protoc_insertion_point(parse_failure:pybullet_grpc.GetDynamicsCommand) + return false; +#undef DO_ +} + +void GetDynamicsCommand::SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const { + // @@protoc_insertion_point(serialize_start:pybullet_grpc.GetDynamicsCommand) + // int32 bodyUniqueId = 1; + if (this->bodyuniqueid() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteInt32(1, this->bodyuniqueid(), output); + } + + // int32 linkIndex = 2; + if (this->linkindex() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteInt32(2, this->linkindex(), output); + } + + // @@protoc_insertion_point(serialize_end:pybullet_grpc.GetDynamicsCommand) +} + +::google::protobuf::uint8* GetDynamicsCommand::InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const { + (void)deterministic; // Unused + // @@protoc_insertion_point(serialize_to_array_start:pybullet_grpc.GetDynamicsCommand) + // int32 bodyUniqueId = 1; + if (this->bodyuniqueid() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteInt32ToArray(1, this->bodyuniqueid(), target); + } + + // int32 linkIndex = 2; + if (this->linkindex() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteInt32ToArray(2, this->linkindex(), target); + } + + // @@protoc_insertion_point(serialize_to_array_end:pybullet_grpc.GetDynamicsCommand) + return target; +} + +size_t GetDynamicsCommand::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:pybullet_grpc.GetDynamicsCommand) + size_t total_size = 0; + + // int32 bodyUniqueId = 1; + if (this->bodyuniqueid() != 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::Int32Size( + this->bodyuniqueid()); + } + + // int32 linkIndex = 2; + if (this->linkindex() != 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::Int32Size( + this->linkindex()); + } + + 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 GetDynamicsCommand::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:pybullet_grpc.GetDynamicsCommand) + GOOGLE_DCHECK_NE(&from, this); + const GetDynamicsCommand* source = + ::google::protobuf::internal::DynamicCastToGenerated( + &from); + if (source == NULL) { + // @@protoc_insertion_point(generalized_merge_from_cast_fail:pybullet_grpc.GetDynamicsCommand) + ::google::protobuf::internal::ReflectionOps::Merge(from, this); + } else { + // @@protoc_insertion_point(generalized_merge_from_cast_success:pybullet_grpc.GetDynamicsCommand) + MergeFrom(*source); + } +} + +void GetDynamicsCommand::MergeFrom(const GetDynamicsCommand& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:pybullet_grpc.GetDynamicsCommand) + GOOGLE_DCHECK_NE(&from, this); + _internal_metadata_.MergeFrom(from._internal_metadata_); + if (from.bodyuniqueid() != 0) { + set_bodyuniqueid(from.bodyuniqueid()); + } + if (from.linkindex() != 0) { + set_linkindex(from.linkindex()); + } +} + +void GetDynamicsCommand::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:pybullet_grpc.GetDynamicsCommand) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +void GetDynamicsCommand::CopyFrom(const GetDynamicsCommand& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:pybullet_grpc.GetDynamicsCommand) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool GetDynamicsCommand::IsInitialized() const { + return true; +} + +void GetDynamicsCommand::Swap(GetDynamicsCommand* other) { + if (other == this) return; + InternalSwap(other); +} +void GetDynamicsCommand::InternalSwap(GetDynamicsCommand* other) { + std::swap(bodyuniqueid_, other->bodyuniqueid_); + std::swap(linkindex_, other->linkindex_); + std::swap(_cached_size_, other->_cached_size_); +} + +::google::protobuf::Metadata GetDynamicsCommand::GetMetadata() const { + protobuf_pybullet_2eproto::protobuf_AssignDescriptorsOnce(); + return protobuf_pybullet_2eproto::file_level_metadata[11]; +} + +#if PROTOBUF_INLINE_NOT_IN_HEADERS +// GetDynamicsCommand + +// int32 bodyUniqueId = 1; +void GetDynamicsCommand::clear_bodyuniqueid() { + bodyuniqueid_ = 0; +} +::google::protobuf::int32 GetDynamicsCommand::bodyuniqueid() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.GetDynamicsCommand.bodyUniqueId) + return bodyuniqueid_; +} +void GetDynamicsCommand::set_bodyuniqueid(::google::protobuf::int32 value) { + + bodyuniqueid_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.GetDynamicsCommand.bodyUniqueId) +} + +// int32 linkIndex = 2; +void GetDynamicsCommand::clear_linkindex() { + linkindex_ = 0; +} +::google::protobuf::int32 GetDynamicsCommand::linkindex() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.GetDynamicsCommand.linkIndex) + return linkindex_; +} +void GetDynamicsCommand::set_linkindex(::google::protobuf::int32 value) { + + linkindex_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.GetDynamicsCommand.linkIndex) +} + +#endif // PROTOBUF_INLINE_NOT_IN_HEADERS + +// =================================================================== + +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const int GetDynamicsStatus::kMassFieldNumber; +const int GetDynamicsStatus::kLateralFrictionFieldNumber; +const int GetDynamicsStatus::kSpinningFrictionFieldNumber; +const int GetDynamicsStatus::kRollingFrictionFieldNumber; +const int GetDynamicsStatus::kRestitutionFieldNumber; +const int GetDynamicsStatus::kLinearDampingFieldNumber; +const int GetDynamicsStatus::kAngularDampingFieldNumber; +const int GetDynamicsStatus::kContactStiffnessFieldNumber; +const int GetDynamicsStatus::kContactDampingFieldNumber; +const int GetDynamicsStatus::kLocalInertiaDiagonalFieldNumber; +const int GetDynamicsStatus::kFrictionAnchorFieldNumber; +const int GetDynamicsStatus::kCcdSweptSphereRadiusFieldNumber; +const int GetDynamicsStatus::kContactProcessingThresholdFieldNumber; +const int GetDynamicsStatus::kActivationStateFieldNumber; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 + +GetDynamicsStatus::GetDynamicsStatus() + : ::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.GetDynamicsStatus) +} +GetDynamicsStatus::GetDynamicsStatus(const GetDynamicsStatus& from) + : ::google::protobuf::Message(), + _internal_metadata_(NULL), + _cached_size_(0) { + _internal_metadata_.MergeFrom(from._internal_metadata_); + if (from.has_localinertiadiagonal()) { + localinertiadiagonal_ = new ::pybullet_grpc::vec3(*from.localinertiadiagonal_); + } else { + localinertiadiagonal_ = NULL; + } + ::memcpy(&mass_, &from.mass_, + reinterpret_cast(&contactprocessingthreshold_) - + reinterpret_cast(&mass_) + sizeof(contactprocessingthreshold_)); + // @@protoc_insertion_point(copy_constructor:pybullet_grpc.GetDynamicsStatus) +} + +void GetDynamicsStatus::SharedCtor() { + ::memset(&localinertiadiagonal_, 0, reinterpret_cast(&contactprocessingthreshold_) - + reinterpret_cast(&localinertiadiagonal_) + sizeof(contactprocessingthreshold_)); + _cached_size_ = 0; +} + +GetDynamicsStatus::~GetDynamicsStatus() { + // @@protoc_insertion_point(destructor:pybullet_grpc.GetDynamicsStatus) + SharedDtor(); +} + +void GetDynamicsStatus::SharedDtor() { + if (this != internal_default_instance()) { + delete localinertiadiagonal_; + } +} + +void GetDynamicsStatus::SetCachedSize(int size) const { + GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN(); + _cached_size_ = size; + GOOGLE_SAFE_CONCURRENT_WRITES_END(); +} +const ::google::protobuf::Descriptor* GetDynamicsStatus::descriptor() { + protobuf_pybullet_2eproto::protobuf_AssignDescriptorsOnce(); + return protobuf_pybullet_2eproto::file_level_metadata[12].descriptor; +} + +const GetDynamicsStatus& GetDynamicsStatus::default_instance() { + protobuf_pybullet_2eproto::InitDefaults(); + return *internal_default_instance(); +} + +GetDynamicsStatus* GetDynamicsStatus::New(::google::protobuf::Arena* arena) const { + GetDynamicsStatus* n = new GetDynamicsStatus; + if (arena != NULL) { + arena->Own(n); + } + return n; +} + +void GetDynamicsStatus::Clear() { +// @@protoc_insertion_point(message_clear_start:pybullet_grpc.GetDynamicsStatus) + if (GetArenaNoVirtual() == NULL && localinertiadiagonal_ != NULL) { + delete localinertiadiagonal_; + } + localinertiadiagonal_ = NULL; + ::memset(&mass_, 0, reinterpret_cast(&contactprocessingthreshold_) - + reinterpret_cast(&mass_) + sizeof(contactprocessingthreshold_)); +} + +bool GetDynamicsStatus::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.GetDynamicsStatus) + for (;;) { + ::std::pair< ::google::protobuf::uint32, bool> p = input->ReadTagWithCutoffNoLastTag(16383u); + tag = p.first; + if (!p.second) goto handle_unusual; + switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { + // double mass = 3; + case 3: { + if (tag == 25u) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &mass_))); + } else { + goto handle_unusual; + } + break; + } + + // double lateralFriction = 5; + case 5: { + if (tag == 41u) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &lateralfriction_))); + } else { + goto handle_unusual; + } + break; + } + + // double spinningFriction = 6; + case 6: { + if (tag == 49u) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &spinningfriction_))); + } else { + goto handle_unusual; + } + break; + } + + // double rollingFriction = 7; + case 7: { + if (tag == 57u) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &rollingfriction_))); + } else { + goto handle_unusual; + } + break; + } + + // double restitution = 8; + case 8: { + if (tag == 65u) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &restitution_))); + } else { + goto handle_unusual; + } + break; + } + + // double linearDamping = 9; + case 9: { + if (tag == 73u) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &lineardamping_))); + } else { + goto handle_unusual; + } + break; + } + + // double angularDamping = 10; + case 10: { + if (tag == 81u) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &angulardamping_))); + } else { + goto handle_unusual; + } + break; + } + + // double contactStiffness = 11; + case 11: { + if (tag == 89u) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &contactstiffness_))); + } else { + goto handle_unusual; + } + break; + } + + // double contactDamping = 12; + case 12: { + if (tag == 97u) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &contactdamping_))); + } else { + goto handle_unusual; + } + break; + } + + // .pybullet_grpc.vec3 localInertiaDiagonal = 13; + case 13: { + if (tag == 106u) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessageNoVirtual( + input, mutable_localinertiadiagonal())); + } else { + goto handle_unusual; + } + break; + } + + // int32 frictionAnchor = 14; + case 14: { + if (tag == 112u) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>( + input, &frictionanchor_))); + } else { + goto handle_unusual; + } + break; + } + + // double ccdSweptSphereRadius = 15; + case 15: { + if (tag == 121u) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &ccdsweptsphereradius_))); + } else { + goto handle_unusual; + } + break; + } + + // double contactProcessingThreshold = 16; + case 16: { + if (tag == 129u) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &contactprocessingthreshold_))); + } else { + goto handle_unusual; + } + break; + } + + // int32 activationState = 17; + case 17: { + if (tag == 136u) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>( + input, &activationstate_))); + } 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.GetDynamicsStatus) + return true; +failure: + // @@protoc_insertion_point(parse_failure:pybullet_grpc.GetDynamicsStatus) + return false; +#undef DO_ +} + +void GetDynamicsStatus::SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const { + // @@protoc_insertion_point(serialize_start:pybullet_grpc.GetDynamicsStatus) + // double mass = 3; + if (this->mass() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(3, this->mass(), output); + } + + // double lateralFriction = 5; + if (this->lateralfriction() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(5, this->lateralfriction(), output); + } + + // double spinningFriction = 6; + if (this->spinningfriction() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(6, this->spinningfriction(), output); + } + + // double rollingFriction = 7; + if (this->rollingfriction() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(7, this->rollingfriction(), output); + } + + // double restitution = 8; + if (this->restitution() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(8, this->restitution(), output); + } + + // double linearDamping = 9; + if (this->lineardamping() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(9, this->lineardamping(), output); + } + + // double angularDamping = 10; + if (this->angulardamping() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(10, this->angulardamping(), output); + } + + // double contactStiffness = 11; + if (this->contactstiffness() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(11, this->contactstiffness(), output); + } + + // double contactDamping = 12; + if (this->contactdamping() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(12, this->contactdamping(), output); + } + + // .pybullet_grpc.vec3 localInertiaDiagonal = 13; + if (this->has_localinertiadiagonal()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 13, *this->localinertiadiagonal_, output); + } + + // int32 frictionAnchor = 14; + if (this->frictionanchor() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteInt32(14, this->frictionanchor(), output); + } + + // double ccdSweptSphereRadius = 15; + if (this->ccdsweptsphereradius() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(15, this->ccdsweptsphereradius(), output); + } + + // double contactProcessingThreshold = 16; + if (this->contactprocessingthreshold() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(16, this->contactprocessingthreshold(), output); + } + + // int32 activationState = 17; + if (this->activationstate() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteInt32(17, this->activationstate(), output); + } + + // @@protoc_insertion_point(serialize_end:pybullet_grpc.GetDynamicsStatus) +} + +::google::protobuf::uint8* GetDynamicsStatus::InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const { + (void)deterministic; // Unused + // @@protoc_insertion_point(serialize_to_array_start:pybullet_grpc.GetDynamicsStatus) + // double mass = 3; + if (this->mass() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(3, this->mass(), target); + } + + // double lateralFriction = 5; + if (this->lateralfriction() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(5, this->lateralfriction(), target); + } + + // double spinningFriction = 6; + if (this->spinningfriction() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(6, this->spinningfriction(), target); + } + + // double rollingFriction = 7; + if (this->rollingfriction() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(7, this->rollingfriction(), target); + } + + // double restitution = 8; + if (this->restitution() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(8, this->restitution(), target); + } + + // double linearDamping = 9; + if (this->lineardamping() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(9, this->lineardamping(), target); + } + + // double angularDamping = 10; + if (this->angulardamping() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(10, this->angulardamping(), target); + } + + // double contactStiffness = 11; + if (this->contactstiffness() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(11, this->contactstiffness(), target); + } + + // double contactDamping = 12; + if (this->contactdamping() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(12, this->contactdamping(), target); + } + + // .pybullet_grpc.vec3 localInertiaDiagonal = 13; + if (this->has_localinertiadiagonal()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageNoVirtualToArray( + 13, *this->localinertiadiagonal_, false, target); + } + + // int32 frictionAnchor = 14; + if (this->frictionanchor() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteInt32ToArray(14, this->frictionanchor(), target); + } + + // double ccdSweptSphereRadius = 15; + if (this->ccdsweptsphereradius() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(15, this->ccdsweptsphereradius(), target); + } + + // double contactProcessingThreshold = 16; + if (this->contactprocessingthreshold() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(16, this->contactprocessingthreshold(), target); + } + + // int32 activationState = 17; + if (this->activationstate() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteInt32ToArray(17, this->activationstate(), target); + } + + // @@protoc_insertion_point(serialize_to_array_end:pybullet_grpc.GetDynamicsStatus) + return target; +} + +size_t GetDynamicsStatus::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:pybullet_grpc.GetDynamicsStatus) + size_t total_size = 0; + + // .pybullet_grpc.vec3 localInertiaDiagonal = 13; + if (this->has_localinertiadiagonal()) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSizeNoVirtual( + *this->localinertiadiagonal_); + } + + // double mass = 3; + if (this->mass() != 0) { + total_size += 1 + 8; + } + + // double lateralFriction = 5; + if (this->lateralfriction() != 0) { + total_size += 1 + 8; + } + + // double spinningFriction = 6; + if (this->spinningfriction() != 0) { + total_size += 1 + 8; + } + + // double rollingFriction = 7; + if (this->rollingfriction() != 0) { + total_size += 1 + 8; + } + + // double restitution = 8; + if (this->restitution() != 0) { + total_size += 1 + 8; + } + + // double linearDamping = 9; + if (this->lineardamping() != 0) { + total_size += 1 + 8; + } + + // double angularDamping = 10; + if (this->angulardamping() != 0) { + total_size += 1 + 8; + } + + // double contactStiffness = 11; + if (this->contactstiffness() != 0) { + total_size += 1 + 8; + } + + // double contactDamping = 12; + if (this->contactdamping() != 0) { + total_size += 1 + 8; + } + + // double ccdSweptSphereRadius = 15; + if (this->ccdsweptsphereradius() != 0) { + total_size += 1 + 8; + } + + // int32 frictionAnchor = 14; + if (this->frictionanchor() != 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::Int32Size( + this->frictionanchor()); + } + + // int32 activationState = 17; + if (this->activationstate() != 0) { + total_size += 2 + + ::google::protobuf::internal::WireFormatLite::Int32Size( + this->activationstate()); + } + + // double contactProcessingThreshold = 16; + if (this->contactprocessingthreshold() != 0) { + total_size += 2 + 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 GetDynamicsStatus::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:pybullet_grpc.GetDynamicsStatus) + GOOGLE_DCHECK_NE(&from, this); + const GetDynamicsStatus* source = + ::google::protobuf::internal::DynamicCastToGenerated( + &from); + if (source == NULL) { + // @@protoc_insertion_point(generalized_merge_from_cast_fail:pybullet_grpc.GetDynamicsStatus) + ::google::protobuf::internal::ReflectionOps::Merge(from, this); + } else { + // @@protoc_insertion_point(generalized_merge_from_cast_success:pybullet_grpc.GetDynamicsStatus) + MergeFrom(*source); + } +} + +void GetDynamicsStatus::MergeFrom(const GetDynamicsStatus& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:pybullet_grpc.GetDynamicsStatus) + GOOGLE_DCHECK_NE(&from, this); + _internal_metadata_.MergeFrom(from._internal_metadata_); + if (from.has_localinertiadiagonal()) { + mutable_localinertiadiagonal()->::pybullet_grpc::vec3::MergeFrom(from.localinertiadiagonal()); + } + if (from.mass() != 0) { + set_mass(from.mass()); + } + if (from.lateralfriction() != 0) { + set_lateralfriction(from.lateralfriction()); + } + if (from.spinningfriction() != 0) { + set_spinningfriction(from.spinningfriction()); + } + if (from.rollingfriction() != 0) { + set_rollingfriction(from.rollingfriction()); + } + if (from.restitution() != 0) { + set_restitution(from.restitution()); + } + if (from.lineardamping() != 0) { + set_lineardamping(from.lineardamping()); + } + if (from.angulardamping() != 0) { + set_angulardamping(from.angulardamping()); + } + if (from.contactstiffness() != 0) { + set_contactstiffness(from.contactstiffness()); + } + if (from.contactdamping() != 0) { + set_contactdamping(from.contactdamping()); + } + if (from.ccdsweptsphereradius() != 0) { + set_ccdsweptsphereradius(from.ccdsweptsphereradius()); + } + if (from.frictionanchor() != 0) { + set_frictionanchor(from.frictionanchor()); + } + if (from.activationstate() != 0) { + set_activationstate(from.activationstate()); + } + if (from.contactprocessingthreshold() != 0) { + set_contactprocessingthreshold(from.contactprocessingthreshold()); + } +} + +void GetDynamicsStatus::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:pybullet_grpc.GetDynamicsStatus) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +void GetDynamicsStatus::CopyFrom(const GetDynamicsStatus& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:pybullet_grpc.GetDynamicsStatus) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool GetDynamicsStatus::IsInitialized() const { + return true; +} + +void GetDynamicsStatus::Swap(GetDynamicsStatus* other) { + if (other == this) return; + InternalSwap(other); +} +void GetDynamicsStatus::InternalSwap(GetDynamicsStatus* other) { + std::swap(localinertiadiagonal_, other->localinertiadiagonal_); + std::swap(mass_, other->mass_); + std::swap(lateralfriction_, other->lateralfriction_); + std::swap(spinningfriction_, other->spinningfriction_); + std::swap(rollingfriction_, other->rollingfriction_); + std::swap(restitution_, other->restitution_); + std::swap(lineardamping_, other->lineardamping_); + std::swap(angulardamping_, other->angulardamping_); + std::swap(contactstiffness_, other->contactstiffness_); + std::swap(contactdamping_, other->contactdamping_); + std::swap(ccdsweptsphereradius_, other->ccdsweptsphereradius_); + std::swap(frictionanchor_, other->frictionanchor_); + std::swap(activationstate_, other->activationstate_); + std::swap(contactprocessingthreshold_, other->contactprocessingthreshold_); + std::swap(_cached_size_, other->_cached_size_); +} + +::google::protobuf::Metadata GetDynamicsStatus::GetMetadata() const { + protobuf_pybullet_2eproto::protobuf_AssignDescriptorsOnce(); + return protobuf_pybullet_2eproto::file_level_metadata[12]; +} + +#if PROTOBUF_INLINE_NOT_IN_HEADERS +// GetDynamicsStatus + +// double mass = 3; +void GetDynamicsStatus::clear_mass() { + mass_ = 0; +} +double GetDynamicsStatus::mass() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.GetDynamicsStatus.mass) + return mass_; +} +void GetDynamicsStatus::set_mass(double value) { + + mass_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.GetDynamicsStatus.mass) +} + +// double lateralFriction = 5; +void GetDynamicsStatus::clear_lateralfriction() { + lateralfriction_ = 0; +} +double GetDynamicsStatus::lateralfriction() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.GetDynamicsStatus.lateralFriction) + return lateralfriction_; +} +void GetDynamicsStatus::set_lateralfriction(double value) { + + lateralfriction_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.GetDynamicsStatus.lateralFriction) +} + +// double spinningFriction = 6; +void GetDynamicsStatus::clear_spinningfriction() { + spinningfriction_ = 0; +} +double GetDynamicsStatus::spinningfriction() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.GetDynamicsStatus.spinningFriction) + return spinningfriction_; +} +void GetDynamicsStatus::set_spinningfriction(double value) { + + spinningfriction_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.GetDynamicsStatus.spinningFriction) +} + +// double rollingFriction = 7; +void GetDynamicsStatus::clear_rollingfriction() { + rollingfriction_ = 0; +} +double GetDynamicsStatus::rollingfriction() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.GetDynamicsStatus.rollingFriction) + return rollingfriction_; +} +void GetDynamicsStatus::set_rollingfriction(double value) { + + rollingfriction_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.GetDynamicsStatus.rollingFriction) +} + +// double restitution = 8; +void GetDynamicsStatus::clear_restitution() { + restitution_ = 0; +} +double GetDynamicsStatus::restitution() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.GetDynamicsStatus.restitution) + return restitution_; +} +void GetDynamicsStatus::set_restitution(double value) { + + restitution_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.GetDynamicsStatus.restitution) +} + +// double linearDamping = 9; +void GetDynamicsStatus::clear_lineardamping() { + lineardamping_ = 0; +} +double GetDynamicsStatus::lineardamping() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.GetDynamicsStatus.linearDamping) + return lineardamping_; +} +void GetDynamicsStatus::set_lineardamping(double value) { + + lineardamping_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.GetDynamicsStatus.linearDamping) +} + +// double angularDamping = 10; +void GetDynamicsStatus::clear_angulardamping() { + angulardamping_ = 0; +} +double GetDynamicsStatus::angulardamping() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.GetDynamicsStatus.angularDamping) + return angulardamping_; +} +void GetDynamicsStatus::set_angulardamping(double value) { + + angulardamping_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.GetDynamicsStatus.angularDamping) +} + +// double contactStiffness = 11; +void GetDynamicsStatus::clear_contactstiffness() { + contactstiffness_ = 0; +} +double GetDynamicsStatus::contactstiffness() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.GetDynamicsStatus.contactStiffness) + return contactstiffness_; +} +void GetDynamicsStatus::set_contactstiffness(double value) { + + contactstiffness_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.GetDynamicsStatus.contactStiffness) +} + +// double contactDamping = 12; +void GetDynamicsStatus::clear_contactdamping() { + contactdamping_ = 0; +} +double GetDynamicsStatus::contactdamping() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.GetDynamicsStatus.contactDamping) + return contactdamping_; +} +void GetDynamicsStatus::set_contactdamping(double value) { + + contactdamping_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.GetDynamicsStatus.contactDamping) +} + +// .pybullet_grpc.vec3 localInertiaDiagonal = 13; +bool GetDynamicsStatus::has_localinertiadiagonal() const { + return this != internal_default_instance() && localinertiadiagonal_ != NULL; +} +void GetDynamicsStatus::clear_localinertiadiagonal() { + if (GetArenaNoVirtual() == NULL && localinertiadiagonal_ != NULL) delete localinertiadiagonal_; + localinertiadiagonal_ = NULL; +} +const ::pybullet_grpc::vec3& GetDynamicsStatus::localinertiadiagonal() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.GetDynamicsStatus.localInertiaDiagonal) + return localinertiadiagonal_ != NULL ? *localinertiadiagonal_ + : *::pybullet_grpc::vec3::internal_default_instance(); +} +::pybullet_grpc::vec3* GetDynamicsStatus::mutable_localinertiadiagonal() { + + if (localinertiadiagonal_ == NULL) { + localinertiadiagonal_ = new ::pybullet_grpc::vec3; + } + // @@protoc_insertion_point(field_mutable:pybullet_grpc.GetDynamicsStatus.localInertiaDiagonal) + return localinertiadiagonal_; +} +::pybullet_grpc::vec3* GetDynamicsStatus::release_localinertiadiagonal() { + // @@protoc_insertion_point(field_release:pybullet_grpc.GetDynamicsStatus.localInertiaDiagonal) + + ::pybullet_grpc::vec3* temp = localinertiadiagonal_; + localinertiadiagonal_ = NULL; + return temp; +} +void GetDynamicsStatus::set_allocated_localinertiadiagonal(::pybullet_grpc::vec3* localinertiadiagonal) { + delete localinertiadiagonal_; + localinertiadiagonal_ = localinertiadiagonal; + if (localinertiadiagonal) { + + } else { + + } + // @@protoc_insertion_point(field_set_allocated:pybullet_grpc.GetDynamicsStatus.localInertiaDiagonal) +} + +// int32 frictionAnchor = 14; +void GetDynamicsStatus::clear_frictionanchor() { + frictionanchor_ = 0; +} +::google::protobuf::int32 GetDynamicsStatus::frictionanchor() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.GetDynamicsStatus.frictionAnchor) + return frictionanchor_; +} +void GetDynamicsStatus::set_frictionanchor(::google::protobuf::int32 value) { + + frictionanchor_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.GetDynamicsStatus.frictionAnchor) +} + +// double ccdSweptSphereRadius = 15; +void GetDynamicsStatus::clear_ccdsweptsphereradius() { + ccdsweptsphereradius_ = 0; +} +double GetDynamicsStatus::ccdsweptsphereradius() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.GetDynamicsStatus.ccdSweptSphereRadius) + return ccdsweptsphereradius_; +} +void GetDynamicsStatus::set_ccdsweptsphereradius(double value) { + + ccdsweptsphereradius_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.GetDynamicsStatus.ccdSweptSphereRadius) +} + +// double contactProcessingThreshold = 16; +void GetDynamicsStatus::clear_contactprocessingthreshold() { + contactprocessingthreshold_ = 0; +} +double GetDynamicsStatus::contactprocessingthreshold() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.GetDynamicsStatus.contactProcessingThreshold) + return contactprocessingthreshold_; +} +void GetDynamicsStatus::set_contactprocessingthreshold(double value) { + + contactprocessingthreshold_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.GetDynamicsStatus.contactProcessingThreshold) +} + +// int32 activationState = 17; +void GetDynamicsStatus::clear_activationstate() { + activationstate_ = 0; +} +::google::protobuf::int32 GetDynamicsStatus::activationstate() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.GetDynamicsStatus.activationState) + return activationstate_; +} +void GetDynamicsStatus::set_activationstate(::google::protobuf::int32 value) { + + activationstate_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.GetDynamicsStatus.activationState) +} + +#endif // PROTOBUF_INLINE_NOT_IN_HEADERS + +// =================================================================== + +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const int InitPoseCommand::kBodyUniqueIdFieldNumber; +const int InitPoseCommand::kHasInitialStateQFieldNumber; +const int InitPoseCommand::kInitialStateQFieldNumber; +const int InitPoseCommand::kHasInitialStateQdotFieldNumber; +const int InitPoseCommand::kInitialStateQdotFieldNumber; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 + +InitPoseCommand::InitPoseCommand() + : ::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.InitPoseCommand) +} +InitPoseCommand::InitPoseCommand(const InitPoseCommand& from) + : ::google::protobuf::Message(), + _internal_metadata_(NULL), + hasinitialstateq_(from.hasinitialstateq_), + initialstateq_(from.initialstateq_), + hasinitialstateqdot_(from.hasinitialstateqdot_), + initialstateqdot_(from.initialstateqdot_), + _cached_size_(0) { + _internal_metadata_.MergeFrom(from._internal_metadata_); + bodyuniqueid_ = from.bodyuniqueid_; + // @@protoc_insertion_point(copy_constructor:pybullet_grpc.InitPoseCommand) +} + +void InitPoseCommand::SharedCtor() { + bodyuniqueid_ = 0; + _cached_size_ = 0; +} + +InitPoseCommand::~InitPoseCommand() { + // @@protoc_insertion_point(destructor:pybullet_grpc.InitPoseCommand) + SharedDtor(); +} + +void InitPoseCommand::SharedDtor() { +} + +void InitPoseCommand::SetCachedSize(int size) const { + GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN(); + _cached_size_ = size; + GOOGLE_SAFE_CONCURRENT_WRITES_END(); +} +const ::google::protobuf::Descriptor* InitPoseCommand::descriptor() { + protobuf_pybullet_2eproto::protobuf_AssignDescriptorsOnce(); + return protobuf_pybullet_2eproto::file_level_metadata[13].descriptor; +} + +const InitPoseCommand& InitPoseCommand::default_instance() { + protobuf_pybullet_2eproto::InitDefaults(); + return *internal_default_instance(); +} + +InitPoseCommand* InitPoseCommand::New(::google::protobuf::Arena* arena) const { + InitPoseCommand* n = new InitPoseCommand; + if (arena != NULL) { + arena->Own(n); + } + return n; +} + +void InitPoseCommand::Clear() { +// @@protoc_insertion_point(message_clear_start:pybullet_grpc.InitPoseCommand) + hasinitialstateq_.Clear(); + initialstateq_.Clear(); + hasinitialstateqdot_.Clear(); + initialstateqdot_.Clear(); + bodyuniqueid_ = 0; +} + +bool InitPoseCommand::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.InitPoseCommand) + 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 bodyUniqueId = 1; + case 1: { + if (tag == 8u) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>( + input, &bodyuniqueid_))); + } else { + goto handle_unusual; + } + break; + } + + // repeated int32 hasInitialStateQ = 2; + case 2: { + if (tag == 18u) { + DO_((::google::protobuf::internal::WireFormatLite::ReadPackedPrimitive< + ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>( + input, this->mutable_hasinitialstateq()))); + } else if (tag == 16u) { + DO_((::google::protobuf::internal::WireFormatLite::ReadRepeatedPrimitiveNoInline< + ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>( + 1, 18u, input, this->mutable_hasinitialstateq()))); + } else { + goto handle_unusual; + } + break; + } + + // repeated double initialStateQ = 3; + case 3: { + if (tag == 26u) { + DO_((::google::protobuf::internal::WireFormatLite::ReadPackedPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, this->mutable_initialstateq()))); + } else if (tag == 25u) { + DO_((::google::protobuf::internal::WireFormatLite::ReadRepeatedPrimitiveNoInline< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + 1, 26u, input, this->mutable_initialstateq()))); + } else { + goto handle_unusual; + } + break; + } + + // repeated int32 hasInitialStateQdot = 4; + case 4: { + if (tag == 34u) { + DO_((::google::protobuf::internal::WireFormatLite::ReadPackedPrimitive< + ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>( + input, this->mutable_hasinitialstateqdot()))); + } else if (tag == 32u) { + DO_((::google::protobuf::internal::WireFormatLite::ReadRepeatedPrimitiveNoInline< + ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>( + 1, 34u, input, this->mutable_hasinitialstateqdot()))); + } else { + goto handle_unusual; + } + break; + } + + // repeated double initialStateQdot = 5; + case 5: { + if (tag == 42u) { + DO_((::google::protobuf::internal::WireFormatLite::ReadPackedPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, this->mutable_initialstateqdot()))); + } else if (tag == 41u) { + DO_((::google::protobuf::internal::WireFormatLite::ReadRepeatedPrimitiveNoInline< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + 1, 42u, input, this->mutable_initialstateqdot()))); + } 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.InitPoseCommand) + return true; +failure: + // @@protoc_insertion_point(parse_failure:pybullet_grpc.InitPoseCommand) + return false; +#undef DO_ +} + +void InitPoseCommand::SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const { + // @@protoc_insertion_point(serialize_start:pybullet_grpc.InitPoseCommand) + // int32 bodyUniqueId = 1; + if (this->bodyuniqueid() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteInt32(1, this->bodyuniqueid(), output); + } + + // repeated int32 hasInitialStateQ = 2; + if (this->hasinitialstateq_size() > 0) { + ::google::protobuf::internal::WireFormatLite::WriteTag(2, ::google::protobuf::internal::WireFormatLite::WIRETYPE_LENGTH_DELIMITED, output); + output->WriteVarint32(_hasinitialstateq_cached_byte_size_); + } + for (int i = 0; i < this->hasinitialstateq_size(); i++) { + ::google::protobuf::internal::WireFormatLite::WriteInt32NoTag( + this->hasinitialstateq(i), output); + } + + // repeated double initialStateQ = 3; + if (this->initialstateq_size() > 0) { + ::google::protobuf::internal::WireFormatLite::WriteTag(3, ::google::protobuf::internal::WireFormatLite::WIRETYPE_LENGTH_DELIMITED, output); + output->WriteVarint32(_initialstateq_cached_byte_size_); + ::google::protobuf::internal::WireFormatLite::WriteDoubleArray( + this->initialstateq().data(), this->initialstateq_size(), output); + } + + // repeated int32 hasInitialStateQdot = 4; + if (this->hasinitialstateqdot_size() > 0) { + ::google::protobuf::internal::WireFormatLite::WriteTag(4, ::google::protobuf::internal::WireFormatLite::WIRETYPE_LENGTH_DELIMITED, output); + output->WriteVarint32(_hasinitialstateqdot_cached_byte_size_); + } + for (int i = 0; i < this->hasinitialstateqdot_size(); i++) { + ::google::protobuf::internal::WireFormatLite::WriteInt32NoTag( + this->hasinitialstateqdot(i), output); + } + + // repeated double initialStateQdot = 5; + if (this->initialstateqdot_size() > 0) { + ::google::protobuf::internal::WireFormatLite::WriteTag(5, ::google::protobuf::internal::WireFormatLite::WIRETYPE_LENGTH_DELIMITED, output); + output->WriteVarint32(_initialstateqdot_cached_byte_size_); + ::google::protobuf::internal::WireFormatLite::WriteDoubleArray( + this->initialstateqdot().data(), this->initialstateqdot_size(), output); + } + + // @@protoc_insertion_point(serialize_end:pybullet_grpc.InitPoseCommand) +} + +::google::protobuf::uint8* InitPoseCommand::InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const { + (void)deterministic; // Unused + // @@protoc_insertion_point(serialize_to_array_start:pybullet_grpc.InitPoseCommand) + // int32 bodyUniqueId = 1; + if (this->bodyuniqueid() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteInt32ToArray(1, this->bodyuniqueid(), target); + } + + // repeated int32 hasInitialStateQ = 2; + if (this->hasinitialstateq_size() > 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteTagToArray( + 2, + ::google::protobuf::internal::WireFormatLite::WIRETYPE_LENGTH_DELIMITED, + target); + target = ::google::protobuf::io::CodedOutputStream::WriteVarint32ToArray( + _hasinitialstateq_cached_byte_size_, target); + } + for (int i = 0; i < this->hasinitialstateq_size(); i++) { + target = ::google::protobuf::internal::WireFormatLite:: + WriteInt32NoTagToArray(this->hasinitialstateq(i), target); + } + + // repeated double initialStateQ = 3; + if (this->initialstateq_size() > 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteTagToArray( + 3, + ::google::protobuf::internal::WireFormatLite::WIRETYPE_LENGTH_DELIMITED, + target); + target = ::google::protobuf::io::CodedOutputStream::WriteVarint32ToArray( + _initialstateq_cached_byte_size_, target); + } + for (int i = 0; i < this->initialstateq_size(); i++) { + target = ::google::protobuf::internal::WireFormatLite:: + WriteDoubleNoTagToArray(this->initialstateq(i), target); + } + + // repeated int32 hasInitialStateQdot = 4; + if (this->hasinitialstateqdot_size() > 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteTagToArray( + 4, + ::google::protobuf::internal::WireFormatLite::WIRETYPE_LENGTH_DELIMITED, + target); + target = ::google::protobuf::io::CodedOutputStream::WriteVarint32ToArray( + _hasinitialstateqdot_cached_byte_size_, target); + } + for (int i = 0; i < this->hasinitialstateqdot_size(); i++) { + target = ::google::protobuf::internal::WireFormatLite:: + WriteInt32NoTagToArray(this->hasinitialstateqdot(i), target); + } + + // repeated double initialStateQdot = 5; + if (this->initialstateqdot_size() > 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteTagToArray( + 5, + ::google::protobuf::internal::WireFormatLite::WIRETYPE_LENGTH_DELIMITED, + target); + target = ::google::protobuf::io::CodedOutputStream::WriteVarint32ToArray( + _initialstateqdot_cached_byte_size_, target); + } + for (int i = 0; i < this->initialstateqdot_size(); i++) { + target = ::google::protobuf::internal::WireFormatLite:: + WriteDoubleNoTagToArray(this->initialstateqdot(i), target); + } + + // @@protoc_insertion_point(serialize_to_array_end:pybullet_grpc.InitPoseCommand) + return target; +} + +size_t InitPoseCommand::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:pybullet_grpc.InitPoseCommand) + size_t total_size = 0; + + // repeated int32 hasInitialStateQ = 2; + { + size_t data_size = ::google::protobuf::internal::WireFormatLite:: + Int32Size(this->hasinitialstateq_); + if (data_size > 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::Int32Size(data_size); + } + int cached_size = ::google::protobuf::internal::ToCachedSize(data_size); + GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN(); + _hasinitialstateq_cached_byte_size_ = cached_size; + GOOGLE_SAFE_CONCURRENT_WRITES_END(); + total_size += data_size; + } + + // repeated double initialStateQ = 3; + { + unsigned int count = this->initialstateq_size(); + size_t data_size = 8UL * count; + if (data_size > 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::Int32Size(data_size); + } + int cached_size = ::google::protobuf::internal::ToCachedSize(data_size); + GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN(); + _initialstateq_cached_byte_size_ = cached_size; + GOOGLE_SAFE_CONCURRENT_WRITES_END(); + total_size += data_size; + } + + // repeated int32 hasInitialStateQdot = 4; + { + size_t data_size = ::google::protobuf::internal::WireFormatLite:: + Int32Size(this->hasinitialstateqdot_); + if (data_size > 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::Int32Size(data_size); + } + int cached_size = ::google::protobuf::internal::ToCachedSize(data_size); + GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN(); + _hasinitialstateqdot_cached_byte_size_ = cached_size; + GOOGLE_SAFE_CONCURRENT_WRITES_END(); + total_size += data_size; + } + + // repeated double initialStateQdot = 5; + { + unsigned int count = this->initialstateqdot_size(); + size_t data_size = 8UL * count; + if (data_size > 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::Int32Size(data_size); + } + int cached_size = ::google::protobuf::internal::ToCachedSize(data_size); + GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN(); + _initialstateqdot_cached_byte_size_ = cached_size; + GOOGLE_SAFE_CONCURRENT_WRITES_END(); + total_size += data_size; + } + + // int32 bodyUniqueId = 1; + if (this->bodyuniqueid() != 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::Int32Size( + this->bodyuniqueid()); + } + + 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 InitPoseCommand::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:pybullet_grpc.InitPoseCommand) + GOOGLE_DCHECK_NE(&from, this); + const InitPoseCommand* source = + ::google::protobuf::internal::DynamicCastToGenerated( + &from); + if (source == NULL) { + // @@protoc_insertion_point(generalized_merge_from_cast_fail:pybullet_grpc.InitPoseCommand) + ::google::protobuf::internal::ReflectionOps::Merge(from, this); + } else { + // @@protoc_insertion_point(generalized_merge_from_cast_success:pybullet_grpc.InitPoseCommand) + MergeFrom(*source); + } +} + +void InitPoseCommand::MergeFrom(const InitPoseCommand& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:pybullet_grpc.InitPoseCommand) + GOOGLE_DCHECK_NE(&from, this); + _internal_metadata_.MergeFrom(from._internal_metadata_); + hasinitialstateq_.MergeFrom(from.hasinitialstateq_); + initialstateq_.MergeFrom(from.initialstateq_); + hasinitialstateqdot_.MergeFrom(from.hasinitialstateqdot_); + initialstateqdot_.MergeFrom(from.initialstateqdot_); + if (from.bodyuniqueid() != 0) { + set_bodyuniqueid(from.bodyuniqueid()); + } +} + +void InitPoseCommand::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:pybullet_grpc.InitPoseCommand) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +void InitPoseCommand::CopyFrom(const InitPoseCommand& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:pybullet_grpc.InitPoseCommand) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool InitPoseCommand::IsInitialized() const { + return true; +} + +void InitPoseCommand::Swap(InitPoseCommand* other) { + if (other == this) return; + InternalSwap(other); +} +void InitPoseCommand::InternalSwap(InitPoseCommand* other) { + hasinitialstateq_.UnsafeArenaSwap(&other->hasinitialstateq_); + initialstateq_.UnsafeArenaSwap(&other->initialstateq_); + hasinitialstateqdot_.UnsafeArenaSwap(&other->hasinitialstateqdot_); + initialstateqdot_.UnsafeArenaSwap(&other->initialstateqdot_); + std::swap(bodyuniqueid_, other->bodyuniqueid_); + std::swap(_cached_size_, other->_cached_size_); +} + +::google::protobuf::Metadata InitPoseCommand::GetMetadata() const { + protobuf_pybullet_2eproto::protobuf_AssignDescriptorsOnce(); + return protobuf_pybullet_2eproto::file_level_metadata[13]; +} + +#if PROTOBUF_INLINE_NOT_IN_HEADERS +// InitPoseCommand + +// int32 bodyUniqueId = 1; +void InitPoseCommand::clear_bodyuniqueid() { + bodyuniqueid_ = 0; +} +::google::protobuf::int32 InitPoseCommand::bodyuniqueid() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.InitPoseCommand.bodyUniqueId) + return bodyuniqueid_; +} +void InitPoseCommand::set_bodyuniqueid(::google::protobuf::int32 value) { + + bodyuniqueid_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.InitPoseCommand.bodyUniqueId) +} + +// repeated int32 hasInitialStateQ = 2; +int InitPoseCommand::hasinitialstateq_size() const { + return hasinitialstateq_.size(); +} +void InitPoseCommand::clear_hasinitialstateq() { + hasinitialstateq_.Clear(); +} +::google::protobuf::int32 InitPoseCommand::hasinitialstateq(int index) const { + // @@protoc_insertion_point(field_get:pybullet_grpc.InitPoseCommand.hasInitialStateQ) + return hasinitialstateq_.Get(index); +} +void InitPoseCommand::set_hasinitialstateq(int index, ::google::protobuf::int32 value) { + hasinitialstateq_.Set(index, value); + // @@protoc_insertion_point(field_set:pybullet_grpc.InitPoseCommand.hasInitialStateQ) +} +void InitPoseCommand::add_hasinitialstateq(::google::protobuf::int32 value) { + hasinitialstateq_.Add(value); + // @@protoc_insertion_point(field_add:pybullet_grpc.InitPoseCommand.hasInitialStateQ) +} +const ::google::protobuf::RepeatedField< ::google::protobuf::int32 >& +InitPoseCommand::hasinitialstateq() const { + // @@protoc_insertion_point(field_list:pybullet_grpc.InitPoseCommand.hasInitialStateQ) + return hasinitialstateq_; +} +::google::protobuf::RepeatedField< ::google::protobuf::int32 >* +InitPoseCommand::mutable_hasinitialstateq() { + // @@protoc_insertion_point(field_mutable_list:pybullet_grpc.InitPoseCommand.hasInitialStateQ) + return &hasinitialstateq_; +} + +// repeated double initialStateQ = 3; +int InitPoseCommand::initialstateq_size() const { + return initialstateq_.size(); +} +void InitPoseCommand::clear_initialstateq() { + initialstateq_.Clear(); +} +double InitPoseCommand::initialstateq(int index) const { + // @@protoc_insertion_point(field_get:pybullet_grpc.InitPoseCommand.initialStateQ) + return initialstateq_.Get(index); +} +void InitPoseCommand::set_initialstateq(int index, double value) { + initialstateq_.Set(index, value); + // @@protoc_insertion_point(field_set:pybullet_grpc.InitPoseCommand.initialStateQ) +} +void InitPoseCommand::add_initialstateq(double value) { + initialstateq_.Add(value); + // @@protoc_insertion_point(field_add:pybullet_grpc.InitPoseCommand.initialStateQ) +} +const ::google::protobuf::RepeatedField< double >& +InitPoseCommand::initialstateq() const { + // @@protoc_insertion_point(field_list:pybullet_grpc.InitPoseCommand.initialStateQ) + return initialstateq_; +} +::google::protobuf::RepeatedField< double >* +InitPoseCommand::mutable_initialstateq() { + // @@protoc_insertion_point(field_mutable_list:pybullet_grpc.InitPoseCommand.initialStateQ) + return &initialstateq_; +} + +// repeated int32 hasInitialStateQdot = 4; +int InitPoseCommand::hasinitialstateqdot_size() const { + return hasinitialstateqdot_.size(); +} +void InitPoseCommand::clear_hasinitialstateqdot() { + hasinitialstateqdot_.Clear(); +} +::google::protobuf::int32 InitPoseCommand::hasinitialstateqdot(int index) const { + // @@protoc_insertion_point(field_get:pybullet_grpc.InitPoseCommand.hasInitialStateQdot) + return hasinitialstateqdot_.Get(index); +} +void InitPoseCommand::set_hasinitialstateqdot(int index, ::google::protobuf::int32 value) { + hasinitialstateqdot_.Set(index, value); + // @@protoc_insertion_point(field_set:pybullet_grpc.InitPoseCommand.hasInitialStateQdot) +} +void InitPoseCommand::add_hasinitialstateqdot(::google::protobuf::int32 value) { + hasinitialstateqdot_.Add(value); + // @@protoc_insertion_point(field_add:pybullet_grpc.InitPoseCommand.hasInitialStateQdot) +} +const ::google::protobuf::RepeatedField< ::google::protobuf::int32 >& +InitPoseCommand::hasinitialstateqdot() const { + // @@protoc_insertion_point(field_list:pybullet_grpc.InitPoseCommand.hasInitialStateQdot) + return hasinitialstateqdot_; +} +::google::protobuf::RepeatedField< ::google::protobuf::int32 >* +InitPoseCommand::mutable_hasinitialstateqdot() { + // @@protoc_insertion_point(field_mutable_list:pybullet_grpc.InitPoseCommand.hasInitialStateQdot) + return &hasinitialstateqdot_; +} + +// repeated double initialStateQdot = 5; +int InitPoseCommand::initialstateqdot_size() const { + return initialstateqdot_.size(); +} +void InitPoseCommand::clear_initialstateqdot() { + initialstateqdot_.Clear(); +} +double InitPoseCommand::initialstateqdot(int index) const { + // @@protoc_insertion_point(field_get:pybullet_grpc.InitPoseCommand.initialStateQdot) + return initialstateqdot_.Get(index); +} +void InitPoseCommand::set_initialstateqdot(int index, double value) { + initialstateqdot_.Set(index, value); + // @@protoc_insertion_point(field_set:pybullet_grpc.InitPoseCommand.initialStateQdot) +} +void InitPoseCommand::add_initialstateqdot(double value) { + initialstateqdot_.Add(value); + // @@protoc_insertion_point(field_add:pybullet_grpc.InitPoseCommand.initialStateQdot) +} +const ::google::protobuf::RepeatedField< double >& +InitPoseCommand::initialstateqdot() const { + // @@protoc_insertion_point(field_list:pybullet_grpc.InitPoseCommand.initialStateQdot) + return initialstateqdot_; +} +::google::protobuf::RepeatedField< double >* +InitPoseCommand::mutable_initialstateqdot() { + // @@protoc_insertion_point(field_mutable_list:pybullet_grpc.InitPoseCommand.initialStateQdot) + return &initialstateqdot_; +} + +#endif // PROTOBUF_INLINE_NOT_IN_HEADERS + +// =================================================================== + +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const int RequestActualStateCommand::kBodyUniqueIdFieldNumber; +const int RequestActualStateCommand::kComputeForwardKinematicsFieldNumber; +const int RequestActualStateCommand::kComputeLinkVelocitiesFieldNumber; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 + +RequestActualStateCommand::RequestActualStateCommand() + : ::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.RequestActualStateCommand) +} +RequestActualStateCommand::RequestActualStateCommand(const RequestActualStateCommand& from) + : ::google::protobuf::Message(), + _internal_metadata_(NULL), + _cached_size_(0) { + _internal_metadata_.MergeFrom(from._internal_metadata_); + ::memcpy(&bodyuniqueid_, &from.bodyuniqueid_, + reinterpret_cast(&computelinkvelocities_) - + reinterpret_cast(&bodyuniqueid_) + sizeof(computelinkvelocities_)); + // @@protoc_insertion_point(copy_constructor:pybullet_grpc.RequestActualStateCommand) +} + +void RequestActualStateCommand::SharedCtor() { + ::memset(&bodyuniqueid_, 0, reinterpret_cast(&computelinkvelocities_) - + reinterpret_cast(&bodyuniqueid_) + sizeof(computelinkvelocities_)); + _cached_size_ = 0; +} + +RequestActualStateCommand::~RequestActualStateCommand() { + // @@protoc_insertion_point(destructor:pybullet_grpc.RequestActualStateCommand) + SharedDtor(); +} + +void RequestActualStateCommand::SharedDtor() { +} + +void RequestActualStateCommand::SetCachedSize(int size) const { + GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN(); + _cached_size_ = size; + GOOGLE_SAFE_CONCURRENT_WRITES_END(); +} +const ::google::protobuf::Descriptor* RequestActualStateCommand::descriptor() { + protobuf_pybullet_2eproto::protobuf_AssignDescriptorsOnce(); + return protobuf_pybullet_2eproto::file_level_metadata[14].descriptor; +} + +const RequestActualStateCommand& RequestActualStateCommand::default_instance() { + protobuf_pybullet_2eproto::InitDefaults(); + return *internal_default_instance(); +} + +RequestActualStateCommand* RequestActualStateCommand::New(::google::protobuf::Arena* arena) const { + RequestActualStateCommand* n = new RequestActualStateCommand; + if (arena != NULL) { + arena->Own(n); + } + return n; +} + +void RequestActualStateCommand::Clear() { +// @@protoc_insertion_point(message_clear_start:pybullet_grpc.RequestActualStateCommand) + ::memset(&bodyuniqueid_, 0, reinterpret_cast(&computelinkvelocities_) - + reinterpret_cast(&bodyuniqueid_) + sizeof(computelinkvelocities_)); +} + +bool RequestActualStateCommand::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.RequestActualStateCommand) + 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 bodyUniqueId = 1; + case 1: { + if (tag == 8u) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>( + input, &bodyuniqueid_))); + } else { + goto handle_unusual; + } + break; + } + + // bool computeForwardKinematics = 2; + case 2: { + if (tag == 16u) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + bool, ::google::protobuf::internal::WireFormatLite::TYPE_BOOL>( + input, &computeforwardkinematics_))); + } else { + goto handle_unusual; + } + break; + } + + // bool computeLinkVelocities = 3; + case 3: { + if (tag == 24u) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + bool, ::google::protobuf::internal::WireFormatLite::TYPE_BOOL>( + input, &computelinkvelocities_))); + } 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.RequestActualStateCommand) + return true; +failure: + // @@protoc_insertion_point(parse_failure:pybullet_grpc.RequestActualStateCommand) + return false; +#undef DO_ +} + +void RequestActualStateCommand::SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const { + // @@protoc_insertion_point(serialize_start:pybullet_grpc.RequestActualStateCommand) + // int32 bodyUniqueId = 1; + if (this->bodyuniqueid() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteInt32(1, this->bodyuniqueid(), output); + } + + // bool computeForwardKinematics = 2; + if (this->computeforwardkinematics() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteBool(2, this->computeforwardkinematics(), output); + } + + // bool computeLinkVelocities = 3; + if (this->computelinkvelocities() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteBool(3, this->computelinkvelocities(), output); + } + + // @@protoc_insertion_point(serialize_end:pybullet_grpc.RequestActualStateCommand) +} + +::google::protobuf::uint8* RequestActualStateCommand::InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const { + (void)deterministic; // Unused + // @@protoc_insertion_point(serialize_to_array_start:pybullet_grpc.RequestActualStateCommand) + // int32 bodyUniqueId = 1; + if (this->bodyuniqueid() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteInt32ToArray(1, this->bodyuniqueid(), target); + } + + // bool computeForwardKinematics = 2; + if (this->computeforwardkinematics() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteBoolToArray(2, this->computeforwardkinematics(), target); + } + + // bool computeLinkVelocities = 3; + if (this->computelinkvelocities() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteBoolToArray(3, this->computelinkvelocities(), target); + } + + // @@protoc_insertion_point(serialize_to_array_end:pybullet_grpc.RequestActualStateCommand) + return target; +} + +size_t RequestActualStateCommand::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:pybullet_grpc.RequestActualStateCommand) + size_t total_size = 0; + + // int32 bodyUniqueId = 1; + if (this->bodyuniqueid() != 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::Int32Size( + this->bodyuniqueid()); + } + + // bool computeForwardKinematics = 2; + if (this->computeforwardkinematics() != 0) { + total_size += 1 + 1; + } + + // bool computeLinkVelocities = 3; + if (this->computelinkvelocities() != 0) { + total_size += 1 + 1; + } + + 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 RequestActualStateCommand::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:pybullet_grpc.RequestActualStateCommand) + GOOGLE_DCHECK_NE(&from, this); + const RequestActualStateCommand* source = + ::google::protobuf::internal::DynamicCastToGenerated( + &from); + if (source == NULL) { + // @@protoc_insertion_point(generalized_merge_from_cast_fail:pybullet_grpc.RequestActualStateCommand) + ::google::protobuf::internal::ReflectionOps::Merge(from, this); + } else { + // @@protoc_insertion_point(generalized_merge_from_cast_success:pybullet_grpc.RequestActualStateCommand) + MergeFrom(*source); + } +} + +void RequestActualStateCommand::MergeFrom(const RequestActualStateCommand& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:pybullet_grpc.RequestActualStateCommand) + GOOGLE_DCHECK_NE(&from, this); + _internal_metadata_.MergeFrom(from._internal_metadata_); + if (from.bodyuniqueid() != 0) { + set_bodyuniqueid(from.bodyuniqueid()); + } + if (from.computeforwardkinematics() != 0) { + set_computeforwardkinematics(from.computeforwardkinematics()); + } + if (from.computelinkvelocities() != 0) { + set_computelinkvelocities(from.computelinkvelocities()); + } +} + +void RequestActualStateCommand::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:pybullet_grpc.RequestActualStateCommand) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +void RequestActualStateCommand::CopyFrom(const RequestActualStateCommand& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:pybullet_grpc.RequestActualStateCommand) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool RequestActualStateCommand::IsInitialized() const { + return true; +} + +void RequestActualStateCommand::Swap(RequestActualStateCommand* other) { + if (other == this) return; + InternalSwap(other); +} +void RequestActualStateCommand::InternalSwap(RequestActualStateCommand* other) { + std::swap(bodyuniqueid_, other->bodyuniqueid_); + std::swap(computeforwardkinematics_, other->computeforwardkinematics_); + std::swap(computelinkvelocities_, other->computelinkvelocities_); + std::swap(_cached_size_, other->_cached_size_); +} + +::google::protobuf::Metadata RequestActualStateCommand::GetMetadata() const { + protobuf_pybullet_2eproto::protobuf_AssignDescriptorsOnce(); + return protobuf_pybullet_2eproto::file_level_metadata[14]; +} + +#if PROTOBUF_INLINE_NOT_IN_HEADERS +// RequestActualStateCommand + +// int32 bodyUniqueId = 1; +void RequestActualStateCommand::clear_bodyuniqueid() { + bodyuniqueid_ = 0; +} +::google::protobuf::int32 RequestActualStateCommand::bodyuniqueid() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.RequestActualStateCommand.bodyUniqueId) + return bodyuniqueid_; +} +void RequestActualStateCommand::set_bodyuniqueid(::google::protobuf::int32 value) { + + bodyuniqueid_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.RequestActualStateCommand.bodyUniqueId) +} + +// bool computeForwardKinematics = 2; +void RequestActualStateCommand::clear_computeforwardkinematics() { + computeforwardkinematics_ = false; +} +bool RequestActualStateCommand::computeforwardkinematics() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.RequestActualStateCommand.computeForwardKinematics) + return computeforwardkinematics_; +} +void RequestActualStateCommand::set_computeforwardkinematics(bool value) { + + computeforwardkinematics_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.RequestActualStateCommand.computeForwardKinematics) +} + +// bool computeLinkVelocities = 3; +void RequestActualStateCommand::clear_computelinkvelocities() { + computelinkvelocities_ = false; +} +bool RequestActualStateCommand::computelinkvelocities() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.RequestActualStateCommand.computeLinkVelocities) + return computelinkvelocities_; +} +void RequestActualStateCommand::set_computelinkvelocities(bool value) { + + computelinkvelocities_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.RequestActualStateCommand.computeLinkVelocities) +} + +#endif // PROTOBUF_INLINE_NOT_IN_HEADERS + +// =================================================================== + +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const int SendActualStateStatus::kBodyUniqueIdFieldNumber; +const int SendActualStateStatus::kNumLinksFieldNumber; +const int SendActualStateStatus::kNumDegreeOfFreedomQFieldNumber; +const int SendActualStateStatus::kNumDegreeOfFreedomUFieldNumber; +const int SendActualStateStatus::kRootLocalInertialFrameFieldNumber; +const int SendActualStateStatus::kActualStateQFieldNumber; +const int SendActualStateStatus::kActualStateQdotFieldNumber; +const int SendActualStateStatus::kJointReactionForcesFieldNumber; +const int SendActualStateStatus::kJointMotorForceFieldNumber; +const int SendActualStateStatus::kLinkStateFieldNumber; +const int SendActualStateStatus::kLinkWorldVelocitiesFieldNumber; +const int SendActualStateStatus::kLinkLocalInertialFramesFieldNumber; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 + +SendActualStateStatus::SendActualStateStatus() + : ::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.SendActualStateStatus) +} +SendActualStateStatus::SendActualStateStatus(const SendActualStateStatus& from) + : ::google::protobuf::Message(), + _internal_metadata_(NULL), + rootlocalinertialframe_(from.rootlocalinertialframe_), + actualstateq_(from.actualstateq_), + actualstateqdot_(from.actualstateqdot_), + jointreactionforces_(from.jointreactionforces_), + jointmotorforce_(from.jointmotorforce_), + linkstate_(from.linkstate_), + linkworldvelocities_(from.linkworldvelocities_), + linklocalinertialframes_(from.linklocalinertialframes_), + _cached_size_(0) { + _internal_metadata_.MergeFrom(from._internal_metadata_); + ::memcpy(&bodyuniqueid_, &from.bodyuniqueid_, + reinterpret_cast(&numdegreeoffreedomu_) - + reinterpret_cast(&bodyuniqueid_) + sizeof(numdegreeoffreedomu_)); + // @@protoc_insertion_point(copy_constructor:pybullet_grpc.SendActualStateStatus) +} + +void SendActualStateStatus::SharedCtor() { + ::memset(&bodyuniqueid_, 0, reinterpret_cast(&numdegreeoffreedomu_) - + reinterpret_cast(&bodyuniqueid_) + sizeof(numdegreeoffreedomu_)); + _cached_size_ = 0; +} + +SendActualStateStatus::~SendActualStateStatus() { + // @@protoc_insertion_point(destructor:pybullet_grpc.SendActualStateStatus) + SharedDtor(); +} + +void SendActualStateStatus::SharedDtor() { +} + +void SendActualStateStatus::SetCachedSize(int size) const { + GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN(); + _cached_size_ = size; + GOOGLE_SAFE_CONCURRENT_WRITES_END(); +} +const ::google::protobuf::Descriptor* SendActualStateStatus::descriptor() { + protobuf_pybullet_2eproto::protobuf_AssignDescriptorsOnce(); + return protobuf_pybullet_2eproto::file_level_metadata[15].descriptor; +} + +const SendActualStateStatus& SendActualStateStatus::default_instance() { + protobuf_pybullet_2eproto::InitDefaults(); + return *internal_default_instance(); +} + +SendActualStateStatus* SendActualStateStatus::New(::google::protobuf::Arena* arena) const { + SendActualStateStatus* n = new SendActualStateStatus; + if (arena != NULL) { + arena->Own(n); + } + return n; +} + +void SendActualStateStatus::Clear() { +// @@protoc_insertion_point(message_clear_start:pybullet_grpc.SendActualStateStatus) + rootlocalinertialframe_.Clear(); + actualstateq_.Clear(); + actualstateqdot_.Clear(); + jointreactionforces_.Clear(); + jointmotorforce_.Clear(); + linkstate_.Clear(); + linkworldvelocities_.Clear(); + linklocalinertialframes_.Clear(); + ::memset(&bodyuniqueid_, 0, reinterpret_cast(&numdegreeoffreedomu_) - + reinterpret_cast(&bodyuniqueid_) + sizeof(numdegreeoffreedomu_)); +} + +bool SendActualStateStatus::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.SendActualStateStatus) + 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 bodyUniqueId = 1; + case 1: { + if (tag == 8u) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>( + input, &bodyuniqueid_))); + } else { + goto handle_unusual; + } + break; + } + + // int32 numLinks = 2; + case 2: { + if (tag == 16u) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>( + input, &numlinks_))); + } else { + goto handle_unusual; + } + break; + } + + // int32 numDegreeOfFreedomQ = 3; + case 3: { + if (tag == 24u) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>( + input, &numdegreeoffreedomq_))); + } else { + goto handle_unusual; + } + break; + } + + // int32 numDegreeOfFreedomU = 4; + case 4: { + if (tag == 32u) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>( + input, &numdegreeoffreedomu_))); + } else { + goto handle_unusual; + } + break; + } + + // repeated double rootLocalInertialFrame = 5; + case 5: { + if (tag == 42u) { + DO_((::google::protobuf::internal::WireFormatLite::ReadPackedPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, this->mutable_rootlocalinertialframe()))); + } else if (tag == 41u) { + DO_((::google::protobuf::internal::WireFormatLite::ReadRepeatedPrimitiveNoInline< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + 1, 42u, input, this->mutable_rootlocalinertialframe()))); + } else { + goto handle_unusual; + } + break; + } + + // repeated double actualStateQ = 6; + case 6: { + if (tag == 50u) { + DO_((::google::protobuf::internal::WireFormatLite::ReadPackedPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, this->mutable_actualstateq()))); + } else if (tag == 49u) { + DO_((::google::protobuf::internal::WireFormatLite::ReadRepeatedPrimitiveNoInline< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + 1, 50u, input, this->mutable_actualstateq()))); + } else { + goto handle_unusual; + } + break; + } + + // repeated double actualStateQdot = 7; + case 7: { + if (tag == 58u) { + DO_((::google::protobuf::internal::WireFormatLite::ReadPackedPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, this->mutable_actualstateqdot()))); + } else if (tag == 57u) { + DO_((::google::protobuf::internal::WireFormatLite::ReadRepeatedPrimitiveNoInline< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + 1, 58u, input, this->mutable_actualstateqdot()))); + } else { + goto handle_unusual; + } + break; + } + + // repeated double jointReactionForces = 8; + case 8: { + if (tag == 66u) { + DO_((::google::protobuf::internal::WireFormatLite::ReadPackedPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, this->mutable_jointreactionforces()))); + } else if (tag == 65u) { + DO_((::google::protobuf::internal::WireFormatLite::ReadRepeatedPrimitiveNoInline< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + 1, 66u, input, this->mutable_jointreactionforces()))); + } else { + goto handle_unusual; + } + break; + } + + // repeated double jointMotorForce = 9; + case 9: { + if (tag == 74u) { + DO_((::google::protobuf::internal::WireFormatLite::ReadPackedPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, this->mutable_jointmotorforce()))); + } else if (tag == 73u) { + DO_((::google::protobuf::internal::WireFormatLite::ReadRepeatedPrimitiveNoInline< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + 1, 74u, input, this->mutable_jointmotorforce()))); + } else { + goto handle_unusual; + } + break; + } + + // repeated double linkState = 10; + case 10: { + if (tag == 82u) { + DO_((::google::protobuf::internal::WireFormatLite::ReadPackedPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, this->mutable_linkstate()))); + } else if (tag == 81u) { + DO_((::google::protobuf::internal::WireFormatLite::ReadRepeatedPrimitiveNoInline< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + 1, 82u, input, this->mutable_linkstate()))); + } else { + goto handle_unusual; + } + break; + } + + // repeated double linkWorldVelocities = 11; + case 11: { + if (tag == 90u) { + DO_((::google::protobuf::internal::WireFormatLite::ReadPackedPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, this->mutable_linkworldvelocities()))); + } else if (tag == 89u) { + DO_((::google::protobuf::internal::WireFormatLite::ReadRepeatedPrimitiveNoInline< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + 1, 90u, input, this->mutable_linkworldvelocities()))); + } else { + goto handle_unusual; + } + break; + } + + // repeated double linkLocalInertialFrames = 12; + case 12: { + if (tag == 98u) { + DO_((::google::protobuf::internal::WireFormatLite::ReadPackedPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, this->mutable_linklocalinertialframes()))); + } else if (tag == 97u) { + DO_((::google::protobuf::internal::WireFormatLite::ReadRepeatedPrimitiveNoInline< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + 1, 98u, input, this->mutable_linklocalinertialframes()))); + } 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.SendActualStateStatus) + return true; +failure: + // @@protoc_insertion_point(parse_failure:pybullet_grpc.SendActualStateStatus) + return false; +#undef DO_ +} + +void SendActualStateStatus::SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const { + // @@protoc_insertion_point(serialize_start:pybullet_grpc.SendActualStateStatus) + // int32 bodyUniqueId = 1; + if (this->bodyuniqueid() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteInt32(1, this->bodyuniqueid(), output); + } + + // int32 numLinks = 2; + if (this->numlinks() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteInt32(2, this->numlinks(), output); + } + + // int32 numDegreeOfFreedomQ = 3; + if (this->numdegreeoffreedomq() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteInt32(3, this->numdegreeoffreedomq(), output); + } + + // int32 numDegreeOfFreedomU = 4; + if (this->numdegreeoffreedomu() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteInt32(4, this->numdegreeoffreedomu(), output); + } + + // repeated double rootLocalInertialFrame = 5; + if (this->rootlocalinertialframe_size() > 0) { + ::google::protobuf::internal::WireFormatLite::WriteTag(5, ::google::protobuf::internal::WireFormatLite::WIRETYPE_LENGTH_DELIMITED, output); + output->WriteVarint32(_rootlocalinertialframe_cached_byte_size_); + ::google::protobuf::internal::WireFormatLite::WriteDoubleArray( + this->rootlocalinertialframe().data(), this->rootlocalinertialframe_size(), output); + } + + // repeated double actualStateQ = 6; + if (this->actualstateq_size() > 0) { + ::google::protobuf::internal::WireFormatLite::WriteTag(6, ::google::protobuf::internal::WireFormatLite::WIRETYPE_LENGTH_DELIMITED, output); + output->WriteVarint32(_actualstateq_cached_byte_size_); + ::google::protobuf::internal::WireFormatLite::WriteDoubleArray( + this->actualstateq().data(), this->actualstateq_size(), output); + } + + // repeated double actualStateQdot = 7; + if (this->actualstateqdot_size() > 0) { + ::google::protobuf::internal::WireFormatLite::WriteTag(7, ::google::protobuf::internal::WireFormatLite::WIRETYPE_LENGTH_DELIMITED, output); + output->WriteVarint32(_actualstateqdot_cached_byte_size_); + ::google::protobuf::internal::WireFormatLite::WriteDoubleArray( + this->actualstateqdot().data(), this->actualstateqdot_size(), output); + } + + // repeated double jointReactionForces = 8; + if (this->jointreactionforces_size() > 0) { + ::google::protobuf::internal::WireFormatLite::WriteTag(8, ::google::protobuf::internal::WireFormatLite::WIRETYPE_LENGTH_DELIMITED, output); + output->WriteVarint32(_jointreactionforces_cached_byte_size_); + ::google::protobuf::internal::WireFormatLite::WriteDoubleArray( + this->jointreactionforces().data(), this->jointreactionforces_size(), output); + } + + // repeated double jointMotorForce = 9; + if (this->jointmotorforce_size() > 0) { + ::google::protobuf::internal::WireFormatLite::WriteTag(9, ::google::protobuf::internal::WireFormatLite::WIRETYPE_LENGTH_DELIMITED, output); + output->WriteVarint32(_jointmotorforce_cached_byte_size_); + ::google::protobuf::internal::WireFormatLite::WriteDoubleArray( + this->jointmotorforce().data(), this->jointmotorforce_size(), output); + } + + // repeated double linkState = 10; + if (this->linkstate_size() > 0) { + ::google::protobuf::internal::WireFormatLite::WriteTag(10, ::google::protobuf::internal::WireFormatLite::WIRETYPE_LENGTH_DELIMITED, output); + output->WriteVarint32(_linkstate_cached_byte_size_); + ::google::protobuf::internal::WireFormatLite::WriteDoubleArray( + this->linkstate().data(), this->linkstate_size(), output); + } + + // repeated double linkWorldVelocities = 11; + if (this->linkworldvelocities_size() > 0) { + ::google::protobuf::internal::WireFormatLite::WriteTag(11, ::google::protobuf::internal::WireFormatLite::WIRETYPE_LENGTH_DELIMITED, output); + output->WriteVarint32(_linkworldvelocities_cached_byte_size_); + ::google::protobuf::internal::WireFormatLite::WriteDoubleArray( + this->linkworldvelocities().data(), this->linkworldvelocities_size(), output); + } + + // repeated double linkLocalInertialFrames = 12; + if (this->linklocalinertialframes_size() > 0) { + ::google::protobuf::internal::WireFormatLite::WriteTag(12, ::google::protobuf::internal::WireFormatLite::WIRETYPE_LENGTH_DELIMITED, output); + output->WriteVarint32(_linklocalinertialframes_cached_byte_size_); + ::google::protobuf::internal::WireFormatLite::WriteDoubleArray( + this->linklocalinertialframes().data(), this->linklocalinertialframes_size(), output); + } + + // @@protoc_insertion_point(serialize_end:pybullet_grpc.SendActualStateStatus) +} + +::google::protobuf::uint8* SendActualStateStatus::InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const { + (void)deterministic; // Unused + // @@protoc_insertion_point(serialize_to_array_start:pybullet_grpc.SendActualStateStatus) + // int32 bodyUniqueId = 1; + if (this->bodyuniqueid() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteInt32ToArray(1, this->bodyuniqueid(), target); + } + + // int32 numLinks = 2; + if (this->numlinks() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteInt32ToArray(2, this->numlinks(), target); + } + + // int32 numDegreeOfFreedomQ = 3; + if (this->numdegreeoffreedomq() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteInt32ToArray(3, this->numdegreeoffreedomq(), target); + } + + // int32 numDegreeOfFreedomU = 4; + if (this->numdegreeoffreedomu() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteInt32ToArray(4, this->numdegreeoffreedomu(), target); + } + + // repeated double rootLocalInertialFrame = 5; + if (this->rootlocalinertialframe_size() > 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteTagToArray( + 5, + ::google::protobuf::internal::WireFormatLite::WIRETYPE_LENGTH_DELIMITED, + target); + target = ::google::protobuf::io::CodedOutputStream::WriteVarint32ToArray( + _rootlocalinertialframe_cached_byte_size_, target); + } + for (int i = 0; i < this->rootlocalinertialframe_size(); i++) { + target = ::google::protobuf::internal::WireFormatLite:: + WriteDoubleNoTagToArray(this->rootlocalinertialframe(i), target); + } + + // repeated double actualStateQ = 6; + if (this->actualstateq_size() > 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteTagToArray( + 6, + ::google::protobuf::internal::WireFormatLite::WIRETYPE_LENGTH_DELIMITED, + target); + target = ::google::protobuf::io::CodedOutputStream::WriteVarint32ToArray( + _actualstateq_cached_byte_size_, target); + } + for (int i = 0; i < this->actualstateq_size(); i++) { + target = ::google::protobuf::internal::WireFormatLite:: + WriteDoubleNoTagToArray(this->actualstateq(i), target); + } + + // repeated double actualStateQdot = 7; + if (this->actualstateqdot_size() > 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteTagToArray( + 7, + ::google::protobuf::internal::WireFormatLite::WIRETYPE_LENGTH_DELIMITED, + target); + target = ::google::protobuf::io::CodedOutputStream::WriteVarint32ToArray( + _actualstateqdot_cached_byte_size_, target); + } + for (int i = 0; i < this->actualstateqdot_size(); i++) { + target = ::google::protobuf::internal::WireFormatLite:: + WriteDoubleNoTagToArray(this->actualstateqdot(i), target); + } + + // repeated double jointReactionForces = 8; + if (this->jointreactionforces_size() > 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteTagToArray( + 8, + ::google::protobuf::internal::WireFormatLite::WIRETYPE_LENGTH_DELIMITED, + target); + target = ::google::protobuf::io::CodedOutputStream::WriteVarint32ToArray( + _jointreactionforces_cached_byte_size_, target); + } + for (int i = 0; i < this->jointreactionforces_size(); i++) { + target = ::google::protobuf::internal::WireFormatLite:: + WriteDoubleNoTagToArray(this->jointreactionforces(i), target); + } + + // repeated double jointMotorForce = 9; + if (this->jointmotorforce_size() > 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteTagToArray( + 9, + ::google::protobuf::internal::WireFormatLite::WIRETYPE_LENGTH_DELIMITED, + target); + target = ::google::protobuf::io::CodedOutputStream::WriteVarint32ToArray( + _jointmotorforce_cached_byte_size_, target); + } + for (int i = 0; i < this->jointmotorforce_size(); i++) { + target = ::google::protobuf::internal::WireFormatLite:: + WriteDoubleNoTagToArray(this->jointmotorforce(i), target); + } + + // repeated double linkState = 10; + if (this->linkstate_size() > 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteTagToArray( + 10, + ::google::protobuf::internal::WireFormatLite::WIRETYPE_LENGTH_DELIMITED, + target); + target = ::google::protobuf::io::CodedOutputStream::WriteVarint32ToArray( + _linkstate_cached_byte_size_, target); + } + for (int i = 0; i < this->linkstate_size(); i++) { + target = ::google::protobuf::internal::WireFormatLite:: + WriteDoubleNoTagToArray(this->linkstate(i), target); + } + + // repeated double linkWorldVelocities = 11; + if (this->linkworldvelocities_size() > 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteTagToArray( + 11, + ::google::protobuf::internal::WireFormatLite::WIRETYPE_LENGTH_DELIMITED, + target); + target = ::google::protobuf::io::CodedOutputStream::WriteVarint32ToArray( + _linkworldvelocities_cached_byte_size_, target); + } + for (int i = 0; i < this->linkworldvelocities_size(); i++) { + target = ::google::protobuf::internal::WireFormatLite:: + WriteDoubleNoTagToArray(this->linkworldvelocities(i), target); + } + + // repeated double linkLocalInertialFrames = 12; + if (this->linklocalinertialframes_size() > 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteTagToArray( + 12, + ::google::protobuf::internal::WireFormatLite::WIRETYPE_LENGTH_DELIMITED, + target); + target = ::google::protobuf::io::CodedOutputStream::WriteVarint32ToArray( + _linklocalinertialframes_cached_byte_size_, target); + } + for (int i = 0; i < this->linklocalinertialframes_size(); i++) { + target = ::google::protobuf::internal::WireFormatLite:: + WriteDoubleNoTagToArray(this->linklocalinertialframes(i), target); + } + + // @@protoc_insertion_point(serialize_to_array_end:pybullet_grpc.SendActualStateStatus) + return target; +} + +size_t SendActualStateStatus::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:pybullet_grpc.SendActualStateStatus) + size_t total_size = 0; + + // repeated double rootLocalInertialFrame = 5; + { + unsigned int count = this->rootlocalinertialframe_size(); + size_t data_size = 8UL * count; + if (data_size > 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::Int32Size(data_size); + } + int cached_size = ::google::protobuf::internal::ToCachedSize(data_size); + GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN(); + _rootlocalinertialframe_cached_byte_size_ = cached_size; + GOOGLE_SAFE_CONCURRENT_WRITES_END(); + total_size += data_size; + } + + // repeated double actualStateQ = 6; + { + unsigned int count = this->actualstateq_size(); + size_t data_size = 8UL * count; + if (data_size > 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::Int32Size(data_size); + } + int cached_size = ::google::protobuf::internal::ToCachedSize(data_size); + GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN(); + _actualstateq_cached_byte_size_ = cached_size; + GOOGLE_SAFE_CONCURRENT_WRITES_END(); + total_size += data_size; + } + + // repeated double actualStateQdot = 7; + { + unsigned int count = this->actualstateqdot_size(); + size_t data_size = 8UL * count; + if (data_size > 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::Int32Size(data_size); + } + int cached_size = ::google::protobuf::internal::ToCachedSize(data_size); + GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN(); + _actualstateqdot_cached_byte_size_ = cached_size; + GOOGLE_SAFE_CONCURRENT_WRITES_END(); + total_size += data_size; + } + + // repeated double jointReactionForces = 8; + { + unsigned int count = this->jointreactionforces_size(); + size_t data_size = 8UL * count; + if (data_size > 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::Int32Size(data_size); + } + int cached_size = ::google::protobuf::internal::ToCachedSize(data_size); + GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN(); + _jointreactionforces_cached_byte_size_ = cached_size; + GOOGLE_SAFE_CONCURRENT_WRITES_END(); + total_size += data_size; + } + + // repeated double jointMotorForce = 9; + { + unsigned int count = this->jointmotorforce_size(); + size_t data_size = 8UL * count; + if (data_size > 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::Int32Size(data_size); + } + int cached_size = ::google::protobuf::internal::ToCachedSize(data_size); + GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN(); + _jointmotorforce_cached_byte_size_ = cached_size; + GOOGLE_SAFE_CONCURRENT_WRITES_END(); + total_size += data_size; + } + + // repeated double linkState = 10; + { + unsigned int count = this->linkstate_size(); + size_t data_size = 8UL * count; + if (data_size > 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::Int32Size(data_size); + } + int cached_size = ::google::protobuf::internal::ToCachedSize(data_size); + GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN(); + _linkstate_cached_byte_size_ = cached_size; + GOOGLE_SAFE_CONCURRENT_WRITES_END(); + total_size += data_size; + } + + // repeated double linkWorldVelocities = 11; + { + unsigned int count = this->linkworldvelocities_size(); + size_t data_size = 8UL * count; + if (data_size > 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::Int32Size(data_size); + } + int cached_size = ::google::protobuf::internal::ToCachedSize(data_size); + GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN(); + _linkworldvelocities_cached_byte_size_ = cached_size; + GOOGLE_SAFE_CONCURRENT_WRITES_END(); + total_size += data_size; + } + + // repeated double linkLocalInertialFrames = 12; + { + unsigned int count = this->linklocalinertialframes_size(); + size_t data_size = 8UL * count; + if (data_size > 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::Int32Size(data_size); + } + int cached_size = ::google::protobuf::internal::ToCachedSize(data_size); + GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN(); + _linklocalinertialframes_cached_byte_size_ = cached_size; + GOOGLE_SAFE_CONCURRENT_WRITES_END(); + total_size += data_size; + } + + // int32 bodyUniqueId = 1; + if (this->bodyuniqueid() != 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::Int32Size( + this->bodyuniqueid()); + } + + // int32 numLinks = 2; + if (this->numlinks() != 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::Int32Size( + this->numlinks()); + } + + // int32 numDegreeOfFreedomQ = 3; + if (this->numdegreeoffreedomq() != 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::Int32Size( + this->numdegreeoffreedomq()); + } + + // int32 numDegreeOfFreedomU = 4; + if (this->numdegreeoffreedomu() != 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::Int32Size( + this->numdegreeoffreedomu()); + } + + 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 SendActualStateStatus::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:pybullet_grpc.SendActualStateStatus) + GOOGLE_DCHECK_NE(&from, this); + const SendActualStateStatus* source = + ::google::protobuf::internal::DynamicCastToGenerated( + &from); + if (source == NULL) { + // @@protoc_insertion_point(generalized_merge_from_cast_fail:pybullet_grpc.SendActualStateStatus) + ::google::protobuf::internal::ReflectionOps::Merge(from, this); + } else { + // @@protoc_insertion_point(generalized_merge_from_cast_success:pybullet_grpc.SendActualStateStatus) + MergeFrom(*source); + } +} + +void SendActualStateStatus::MergeFrom(const SendActualStateStatus& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:pybullet_grpc.SendActualStateStatus) + GOOGLE_DCHECK_NE(&from, this); + _internal_metadata_.MergeFrom(from._internal_metadata_); + rootlocalinertialframe_.MergeFrom(from.rootlocalinertialframe_); + actualstateq_.MergeFrom(from.actualstateq_); + actualstateqdot_.MergeFrom(from.actualstateqdot_); + jointreactionforces_.MergeFrom(from.jointreactionforces_); + jointmotorforce_.MergeFrom(from.jointmotorforce_); + linkstate_.MergeFrom(from.linkstate_); + linkworldvelocities_.MergeFrom(from.linkworldvelocities_); + linklocalinertialframes_.MergeFrom(from.linklocalinertialframes_); + if (from.bodyuniqueid() != 0) { + set_bodyuniqueid(from.bodyuniqueid()); + } + if (from.numlinks() != 0) { + set_numlinks(from.numlinks()); + } + if (from.numdegreeoffreedomq() != 0) { + set_numdegreeoffreedomq(from.numdegreeoffreedomq()); + } + if (from.numdegreeoffreedomu() != 0) { + set_numdegreeoffreedomu(from.numdegreeoffreedomu()); + } +} + +void SendActualStateStatus::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:pybullet_grpc.SendActualStateStatus) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +void SendActualStateStatus::CopyFrom(const SendActualStateStatus& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:pybullet_grpc.SendActualStateStatus) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool SendActualStateStatus::IsInitialized() const { + return true; +} + +void SendActualStateStatus::Swap(SendActualStateStatus* other) { + if (other == this) return; + InternalSwap(other); +} +void SendActualStateStatus::InternalSwap(SendActualStateStatus* other) { + rootlocalinertialframe_.UnsafeArenaSwap(&other->rootlocalinertialframe_); + actualstateq_.UnsafeArenaSwap(&other->actualstateq_); + actualstateqdot_.UnsafeArenaSwap(&other->actualstateqdot_); + jointreactionforces_.UnsafeArenaSwap(&other->jointreactionforces_); + jointmotorforce_.UnsafeArenaSwap(&other->jointmotorforce_); + linkstate_.UnsafeArenaSwap(&other->linkstate_); + linkworldvelocities_.UnsafeArenaSwap(&other->linkworldvelocities_); + linklocalinertialframes_.UnsafeArenaSwap(&other->linklocalinertialframes_); + std::swap(bodyuniqueid_, other->bodyuniqueid_); + std::swap(numlinks_, other->numlinks_); + std::swap(numdegreeoffreedomq_, other->numdegreeoffreedomq_); + std::swap(numdegreeoffreedomu_, other->numdegreeoffreedomu_); + std::swap(_cached_size_, other->_cached_size_); +} + +::google::protobuf::Metadata SendActualStateStatus::GetMetadata() const { + protobuf_pybullet_2eproto::protobuf_AssignDescriptorsOnce(); + return protobuf_pybullet_2eproto::file_level_metadata[15]; +} + +#if PROTOBUF_INLINE_NOT_IN_HEADERS +// SendActualStateStatus + +// int32 bodyUniqueId = 1; +void SendActualStateStatus::clear_bodyuniqueid() { + bodyuniqueid_ = 0; +} +::google::protobuf::int32 SendActualStateStatus::bodyuniqueid() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.SendActualStateStatus.bodyUniqueId) + return bodyuniqueid_; +} +void SendActualStateStatus::set_bodyuniqueid(::google::protobuf::int32 value) { + + bodyuniqueid_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.SendActualStateStatus.bodyUniqueId) +} + +// int32 numLinks = 2; +void SendActualStateStatus::clear_numlinks() { + numlinks_ = 0; +} +::google::protobuf::int32 SendActualStateStatus::numlinks() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.SendActualStateStatus.numLinks) + return numlinks_; +} +void SendActualStateStatus::set_numlinks(::google::protobuf::int32 value) { + + numlinks_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.SendActualStateStatus.numLinks) +} + +// int32 numDegreeOfFreedomQ = 3; +void SendActualStateStatus::clear_numdegreeoffreedomq() { + numdegreeoffreedomq_ = 0; +} +::google::protobuf::int32 SendActualStateStatus::numdegreeoffreedomq() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.SendActualStateStatus.numDegreeOfFreedomQ) + return numdegreeoffreedomq_; +} +void SendActualStateStatus::set_numdegreeoffreedomq(::google::protobuf::int32 value) { + + numdegreeoffreedomq_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.SendActualStateStatus.numDegreeOfFreedomQ) +} + +// int32 numDegreeOfFreedomU = 4; +void SendActualStateStatus::clear_numdegreeoffreedomu() { + numdegreeoffreedomu_ = 0; +} +::google::protobuf::int32 SendActualStateStatus::numdegreeoffreedomu() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.SendActualStateStatus.numDegreeOfFreedomU) + return numdegreeoffreedomu_; +} +void SendActualStateStatus::set_numdegreeoffreedomu(::google::protobuf::int32 value) { + + numdegreeoffreedomu_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.SendActualStateStatus.numDegreeOfFreedomU) +} + +// repeated double rootLocalInertialFrame = 5; +int SendActualStateStatus::rootlocalinertialframe_size() const { + return rootlocalinertialframe_.size(); +} +void SendActualStateStatus::clear_rootlocalinertialframe() { + rootlocalinertialframe_.Clear(); +} +double SendActualStateStatus::rootlocalinertialframe(int index) const { + // @@protoc_insertion_point(field_get:pybullet_grpc.SendActualStateStatus.rootLocalInertialFrame) + return rootlocalinertialframe_.Get(index); +} +void SendActualStateStatus::set_rootlocalinertialframe(int index, double value) { + rootlocalinertialframe_.Set(index, value); + // @@protoc_insertion_point(field_set:pybullet_grpc.SendActualStateStatus.rootLocalInertialFrame) +} +void SendActualStateStatus::add_rootlocalinertialframe(double value) { + rootlocalinertialframe_.Add(value); + // @@protoc_insertion_point(field_add:pybullet_grpc.SendActualStateStatus.rootLocalInertialFrame) +} +const ::google::protobuf::RepeatedField< double >& +SendActualStateStatus::rootlocalinertialframe() const { + // @@protoc_insertion_point(field_list:pybullet_grpc.SendActualStateStatus.rootLocalInertialFrame) + return rootlocalinertialframe_; +} +::google::protobuf::RepeatedField< double >* +SendActualStateStatus::mutable_rootlocalinertialframe() { + // @@protoc_insertion_point(field_mutable_list:pybullet_grpc.SendActualStateStatus.rootLocalInertialFrame) + return &rootlocalinertialframe_; +} + +// repeated double actualStateQ = 6; +int SendActualStateStatus::actualstateq_size() const { + return actualstateq_.size(); +} +void SendActualStateStatus::clear_actualstateq() { + actualstateq_.Clear(); +} +double SendActualStateStatus::actualstateq(int index) const { + // @@protoc_insertion_point(field_get:pybullet_grpc.SendActualStateStatus.actualStateQ) + return actualstateq_.Get(index); +} +void SendActualStateStatus::set_actualstateq(int index, double value) { + actualstateq_.Set(index, value); + // @@protoc_insertion_point(field_set:pybullet_grpc.SendActualStateStatus.actualStateQ) +} +void SendActualStateStatus::add_actualstateq(double value) { + actualstateq_.Add(value); + // @@protoc_insertion_point(field_add:pybullet_grpc.SendActualStateStatus.actualStateQ) +} +const ::google::protobuf::RepeatedField< double >& +SendActualStateStatus::actualstateq() const { + // @@protoc_insertion_point(field_list:pybullet_grpc.SendActualStateStatus.actualStateQ) + return actualstateq_; +} +::google::protobuf::RepeatedField< double >* +SendActualStateStatus::mutable_actualstateq() { + // @@protoc_insertion_point(field_mutable_list:pybullet_grpc.SendActualStateStatus.actualStateQ) + return &actualstateq_; +} + +// repeated double actualStateQdot = 7; +int SendActualStateStatus::actualstateqdot_size() const { + return actualstateqdot_.size(); +} +void SendActualStateStatus::clear_actualstateqdot() { + actualstateqdot_.Clear(); +} +double SendActualStateStatus::actualstateqdot(int index) const { + // @@protoc_insertion_point(field_get:pybullet_grpc.SendActualStateStatus.actualStateQdot) + return actualstateqdot_.Get(index); +} +void SendActualStateStatus::set_actualstateqdot(int index, double value) { + actualstateqdot_.Set(index, value); + // @@protoc_insertion_point(field_set:pybullet_grpc.SendActualStateStatus.actualStateQdot) +} +void SendActualStateStatus::add_actualstateqdot(double value) { + actualstateqdot_.Add(value); + // @@protoc_insertion_point(field_add:pybullet_grpc.SendActualStateStatus.actualStateQdot) +} +const ::google::protobuf::RepeatedField< double >& +SendActualStateStatus::actualstateqdot() const { + // @@protoc_insertion_point(field_list:pybullet_grpc.SendActualStateStatus.actualStateQdot) + return actualstateqdot_; +} +::google::protobuf::RepeatedField< double >* +SendActualStateStatus::mutable_actualstateqdot() { + // @@protoc_insertion_point(field_mutable_list:pybullet_grpc.SendActualStateStatus.actualStateQdot) + return &actualstateqdot_; +} + +// repeated double jointReactionForces = 8; +int SendActualStateStatus::jointreactionforces_size() const { + return jointreactionforces_.size(); +} +void SendActualStateStatus::clear_jointreactionforces() { + jointreactionforces_.Clear(); +} +double SendActualStateStatus::jointreactionforces(int index) const { + // @@protoc_insertion_point(field_get:pybullet_grpc.SendActualStateStatus.jointReactionForces) + return jointreactionforces_.Get(index); +} +void SendActualStateStatus::set_jointreactionforces(int index, double value) { + jointreactionforces_.Set(index, value); + // @@protoc_insertion_point(field_set:pybullet_grpc.SendActualStateStatus.jointReactionForces) +} +void SendActualStateStatus::add_jointreactionforces(double value) { + jointreactionforces_.Add(value); + // @@protoc_insertion_point(field_add:pybullet_grpc.SendActualStateStatus.jointReactionForces) +} +const ::google::protobuf::RepeatedField< double >& +SendActualStateStatus::jointreactionforces() const { + // @@protoc_insertion_point(field_list:pybullet_grpc.SendActualStateStatus.jointReactionForces) + return jointreactionforces_; +} +::google::protobuf::RepeatedField< double >* +SendActualStateStatus::mutable_jointreactionforces() { + // @@protoc_insertion_point(field_mutable_list:pybullet_grpc.SendActualStateStatus.jointReactionForces) + return &jointreactionforces_; +} + +// repeated double jointMotorForce = 9; +int SendActualStateStatus::jointmotorforce_size() const { + return jointmotorforce_.size(); +} +void SendActualStateStatus::clear_jointmotorforce() { + jointmotorforce_.Clear(); +} +double SendActualStateStatus::jointmotorforce(int index) const { + // @@protoc_insertion_point(field_get:pybullet_grpc.SendActualStateStatus.jointMotorForce) + return jointmotorforce_.Get(index); +} +void SendActualStateStatus::set_jointmotorforce(int index, double value) { + jointmotorforce_.Set(index, value); + // @@protoc_insertion_point(field_set:pybullet_grpc.SendActualStateStatus.jointMotorForce) +} +void SendActualStateStatus::add_jointmotorforce(double value) { + jointmotorforce_.Add(value); + // @@protoc_insertion_point(field_add:pybullet_grpc.SendActualStateStatus.jointMotorForce) +} +const ::google::protobuf::RepeatedField< double >& +SendActualStateStatus::jointmotorforce() const { + // @@protoc_insertion_point(field_list:pybullet_grpc.SendActualStateStatus.jointMotorForce) + return jointmotorforce_; +} +::google::protobuf::RepeatedField< double >* +SendActualStateStatus::mutable_jointmotorforce() { + // @@protoc_insertion_point(field_mutable_list:pybullet_grpc.SendActualStateStatus.jointMotorForce) + return &jointmotorforce_; +} + +// repeated double linkState = 10; +int SendActualStateStatus::linkstate_size() const { + return linkstate_.size(); +} +void SendActualStateStatus::clear_linkstate() { + linkstate_.Clear(); +} +double SendActualStateStatus::linkstate(int index) const { + // @@protoc_insertion_point(field_get:pybullet_grpc.SendActualStateStatus.linkState) + return linkstate_.Get(index); +} +void SendActualStateStatus::set_linkstate(int index, double value) { + linkstate_.Set(index, value); + // @@protoc_insertion_point(field_set:pybullet_grpc.SendActualStateStatus.linkState) +} +void SendActualStateStatus::add_linkstate(double value) { + linkstate_.Add(value); + // @@protoc_insertion_point(field_add:pybullet_grpc.SendActualStateStatus.linkState) +} +const ::google::protobuf::RepeatedField< double >& +SendActualStateStatus::linkstate() const { + // @@protoc_insertion_point(field_list:pybullet_grpc.SendActualStateStatus.linkState) + return linkstate_; +} +::google::protobuf::RepeatedField< double >* +SendActualStateStatus::mutable_linkstate() { + // @@protoc_insertion_point(field_mutable_list:pybullet_grpc.SendActualStateStatus.linkState) + return &linkstate_; +} + +// repeated double linkWorldVelocities = 11; +int SendActualStateStatus::linkworldvelocities_size() const { + return linkworldvelocities_.size(); +} +void SendActualStateStatus::clear_linkworldvelocities() { + linkworldvelocities_.Clear(); +} +double SendActualStateStatus::linkworldvelocities(int index) const { + // @@protoc_insertion_point(field_get:pybullet_grpc.SendActualStateStatus.linkWorldVelocities) + return linkworldvelocities_.Get(index); +} +void SendActualStateStatus::set_linkworldvelocities(int index, double value) { + linkworldvelocities_.Set(index, value); + // @@protoc_insertion_point(field_set:pybullet_grpc.SendActualStateStatus.linkWorldVelocities) +} +void SendActualStateStatus::add_linkworldvelocities(double value) { + linkworldvelocities_.Add(value); + // @@protoc_insertion_point(field_add:pybullet_grpc.SendActualStateStatus.linkWorldVelocities) +} +const ::google::protobuf::RepeatedField< double >& +SendActualStateStatus::linkworldvelocities() const { + // @@protoc_insertion_point(field_list:pybullet_grpc.SendActualStateStatus.linkWorldVelocities) + return linkworldvelocities_; +} +::google::protobuf::RepeatedField< double >* +SendActualStateStatus::mutable_linkworldvelocities() { + // @@protoc_insertion_point(field_mutable_list:pybullet_grpc.SendActualStateStatus.linkWorldVelocities) + return &linkworldvelocities_; +} + +// repeated double linkLocalInertialFrames = 12; +int SendActualStateStatus::linklocalinertialframes_size() const { + return linklocalinertialframes_.size(); +} +void SendActualStateStatus::clear_linklocalinertialframes() { + linklocalinertialframes_.Clear(); +} +double SendActualStateStatus::linklocalinertialframes(int index) const { + // @@protoc_insertion_point(field_get:pybullet_grpc.SendActualStateStatus.linkLocalInertialFrames) + return linklocalinertialframes_.Get(index); +} +void SendActualStateStatus::set_linklocalinertialframes(int index, double value) { + linklocalinertialframes_.Set(index, value); + // @@protoc_insertion_point(field_set:pybullet_grpc.SendActualStateStatus.linkLocalInertialFrames) +} +void SendActualStateStatus::add_linklocalinertialframes(double value) { + linklocalinertialframes_.Add(value); + // @@protoc_insertion_point(field_add:pybullet_grpc.SendActualStateStatus.linkLocalInertialFrames) +} +const ::google::protobuf::RepeatedField< double >& +SendActualStateStatus::linklocalinertialframes() const { + // @@protoc_insertion_point(field_list:pybullet_grpc.SendActualStateStatus.linkLocalInertialFrames) + return linklocalinertialframes_; +} +::google::protobuf::RepeatedField< double >* +SendActualStateStatus::mutable_linklocalinertialframes() { + // @@protoc_insertion_point(field_mutable_list:pybullet_grpc.SendActualStateStatus.linkLocalInertialFrames) + return &linklocalinertialframes_; } #endif // PROTOBUF_INLINE_NOT_IN_HEADERS @@ -2484,6 +9213,12 @@ const int PyBulletCommand::kCommandTypeFieldNumber; const int PyBulletCommand::kLoadUrdfCommandFieldNumber; const int PyBulletCommand::kTerminateServerCommandFieldNumber; const int PyBulletCommand::kStepSimulationCommandFieldNumber; +const int PyBulletCommand::kLoadSdfCommandFieldNumber; +const int PyBulletCommand::kLoadMjcfCommandFieldNumber; +const int PyBulletCommand::kChangeDynamicsCommandFieldNumber; +const int PyBulletCommand::kGetDynamicsCommandFieldNumber; +const int PyBulletCommand::kInitPoseCommandFieldNumber; +const int PyBulletCommand::kRequestActualStateCommandFieldNumber; #endif // !defined(_MSC_VER) || _MSC_VER >= 1900 PyBulletCommand::PyBulletCommand() @@ -2514,6 +9249,30 @@ PyBulletCommand::PyBulletCommand(const PyBulletCommand& from) mutable_stepsimulationcommand()->::pybullet_grpc::StepSimulationCommand::MergeFrom(from.stepsimulationcommand()); break; } + case kLoadSdfCommand: { + mutable_loadsdfcommand()->::pybullet_grpc::LoadSdfCommand::MergeFrom(from.loadsdfcommand()); + break; + } + case kLoadMjcfCommand: { + mutable_loadmjcfcommand()->::pybullet_grpc::LoadMjcfCommand::MergeFrom(from.loadmjcfcommand()); + break; + } + case kChangeDynamicsCommand: { + mutable_changedynamicscommand()->::pybullet_grpc::ChangeDynamicsCommand::MergeFrom(from.changedynamicscommand()); + break; + } + case kGetDynamicsCommand: { + mutable_getdynamicscommand()->::pybullet_grpc::GetDynamicsCommand::MergeFrom(from.getdynamicscommand()); + break; + } + case kInitPoseCommand: { + mutable_initposecommand()->::pybullet_grpc::InitPoseCommand::MergeFrom(from.initposecommand()); + break; + } + case kRequestActualStateCommand: { + mutable_requestactualstatecommand()->::pybullet_grpc::RequestActualStateCommand::MergeFrom(from.requestactualstatecommand()); + break; + } case COMMANDS_NOT_SET: { break; } @@ -2545,7 +9304,7 @@ void PyBulletCommand::SetCachedSize(int size) const { } const ::google::protobuf::Descriptor* PyBulletCommand::descriptor() { protobuf_pybullet_2eproto::protobuf_AssignDescriptorsOnce(); - return protobuf_pybullet_2eproto::file_level_metadata[6].descriptor; + return protobuf_pybullet_2eproto::file_level_metadata[16].descriptor; } const PyBulletCommand& PyBulletCommand::default_instance() { @@ -2576,6 +9335,30 @@ void PyBulletCommand::clear_commands() { delete commands_.stepsimulationcommand_; break; } + case kLoadSdfCommand: { + delete commands_.loadsdfcommand_; + break; + } + case kLoadMjcfCommand: { + delete commands_.loadmjcfcommand_; + break; + } + case kChangeDynamicsCommand: { + delete commands_.changedynamicscommand_; + break; + } + case kGetDynamicsCommand: { + delete commands_.getdynamicscommand_; + break; + } + case kInitPoseCommand: { + delete commands_.initposecommand_; + break; + } + case kRequestActualStateCommand: { + delete commands_.requestactualstatecommand_; + break; + } case COMMANDS_NOT_SET: { break; } @@ -2646,6 +9429,72 @@ bool PyBulletCommand::MergePartialFromCodedStream( break; } + // .pybullet_grpc.LoadSdfCommand loadSdfCommand = 6; + case 6: { + if (tag == 50u) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessageNoVirtual( + input, mutable_loadsdfcommand())); + } else { + goto handle_unusual; + } + break; + } + + // .pybullet_grpc.LoadMjcfCommand loadMjcfCommand = 7; + case 7: { + if (tag == 58u) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessageNoVirtual( + input, mutable_loadmjcfcommand())); + } else { + goto handle_unusual; + } + break; + } + + // .pybullet_grpc.ChangeDynamicsCommand changeDynamicsCommand = 8; + case 8: { + if (tag == 66u) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessageNoVirtual( + input, mutable_changedynamicscommand())); + } else { + goto handle_unusual; + } + break; + } + + // .pybullet_grpc.GetDynamicsCommand getDynamicsCommand = 9; + case 9: { + if (tag == 74u) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessageNoVirtual( + input, mutable_getdynamicscommand())); + } else { + goto handle_unusual; + } + break; + } + + // .pybullet_grpc.InitPoseCommand initPoseCommand = 10; + case 10: { + if (tag == 82u) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessageNoVirtual( + input, mutable_initposecommand())); + } else { + goto handle_unusual; + } + break; + } + + // .pybullet_grpc.RequestActualStateCommand requestActualStateCommand = 11; + case 11: { + if (tag == 90u) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessageNoVirtual( + input, mutable_requestactualstatecommand())); + } else { + goto handle_unusual; + } + break; + } + default: { handle_unusual: if (tag == 0 || @@ -2693,6 +9542,42 @@ void PyBulletCommand::SerializeWithCachedSizes( 5, *commands_.stepsimulationcommand_, output); } + // .pybullet_grpc.LoadSdfCommand loadSdfCommand = 6; + if (has_loadsdfcommand()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 6, *commands_.loadsdfcommand_, output); + } + + // .pybullet_grpc.LoadMjcfCommand loadMjcfCommand = 7; + if (has_loadmjcfcommand()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 7, *commands_.loadmjcfcommand_, output); + } + + // .pybullet_grpc.ChangeDynamicsCommand changeDynamicsCommand = 8; + if (has_changedynamicscommand()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 8, *commands_.changedynamicscommand_, output); + } + + // .pybullet_grpc.GetDynamicsCommand getDynamicsCommand = 9; + if (has_getdynamicscommand()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 9, *commands_.getdynamicscommand_, output); + } + + // .pybullet_grpc.InitPoseCommand initPoseCommand = 10; + if (has_initposecommand()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 10, *commands_.initposecommand_, output); + } + + // .pybullet_grpc.RequestActualStateCommand requestActualStateCommand = 11; + if (has_requestactualstatecommand()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 11, *commands_.requestactualstatecommand_, output); + } + // @@protoc_insertion_point(serialize_end:pybullet_grpc.PyBulletCommand) } @@ -2726,6 +9611,48 @@ void PyBulletCommand::SerializeWithCachedSizes( 5, *commands_.stepsimulationcommand_, false, target); } + // .pybullet_grpc.LoadSdfCommand loadSdfCommand = 6; + if (has_loadsdfcommand()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageNoVirtualToArray( + 6, *commands_.loadsdfcommand_, false, target); + } + + // .pybullet_grpc.LoadMjcfCommand loadMjcfCommand = 7; + if (has_loadmjcfcommand()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageNoVirtualToArray( + 7, *commands_.loadmjcfcommand_, false, target); + } + + // .pybullet_grpc.ChangeDynamicsCommand changeDynamicsCommand = 8; + if (has_changedynamicscommand()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageNoVirtualToArray( + 8, *commands_.changedynamicscommand_, false, target); + } + + // .pybullet_grpc.GetDynamicsCommand getDynamicsCommand = 9; + if (has_getdynamicscommand()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageNoVirtualToArray( + 9, *commands_.getdynamicscommand_, false, target); + } + + // .pybullet_grpc.InitPoseCommand initPoseCommand = 10; + if (has_initposecommand()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageNoVirtualToArray( + 10, *commands_.initposecommand_, false, target); + } + + // .pybullet_grpc.RequestActualStateCommand requestActualStateCommand = 11; + if (has_requestactualstatecommand()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageNoVirtualToArray( + 11, *commands_.requestactualstatecommand_, false, target); + } + // @@protoc_insertion_point(serialize_to_array_end:pybullet_grpc.PyBulletCommand) return target; } @@ -2763,6 +9690,48 @@ size_t PyBulletCommand::ByteSizeLong() const { *commands_.stepsimulationcommand_); break; } + // .pybullet_grpc.LoadSdfCommand loadSdfCommand = 6; + case kLoadSdfCommand: { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSizeNoVirtual( + *commands_.loadsdfcommand_); + break; + } + // .pybullet_grpc.LoadMjcfCommand loadMjcfCommand = 7; + case kLoadMjcfCommand: { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSizeNoVirtual( + *commands_.loadmjcfcommand_); + break; + } + // .pybullet_grpc.ChangeDynamicsCommand changeDynamicsCommand = 8; + case kChangeDynamicsCommand: { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSizeNoVirtual( + *commands_.changedynamicscommand_); + break; + } + // .pybullet_grpc.GetDynamicsCommand getDynamicsCommand = 9; + case kGetDynamicsCommand: { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSizeNoVirtual( + *commands_.getdynamicscommand_); + break; + } + // .pybullet_grpc.InitPoseCommand initPoseCommand = 10; + case kInitPoseCommand: { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSizeNoVirtual( + *commands_.initposecommand_); + break; + } + // .pybullet_grpc.RequestActualStateCommand requestActualStateCommand = 11; + case kRequestActualStateCommand: { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSizeNoVirtual( + *commands_.requestactualstatecommand_); + break; + } case COMMANDS_NOT_SET: { break; } @@ -2809,6 +9778,30 @@ void PyBulletCommand::MergeFrom(const PyBulletCommand& from) { mutable_stepsimulationcommand()->::pybullet_grpc::StepSimulationCommand::MergeFrom(from.stepsimulationcommand()); break; } + case kLoadSdfCommand: { + mutable_loadsdfcommand()->::pybullet_grpc::LoadSdfCommand::MergeFrom(from.loadsdfcommand()); + break; + } + case kLoadMjcfCommand: { + mutable_loadmjcfcommand()->::pybullet_grpc::LoadMjcfCommand::MergeFrom(from.loadmjcfcommand()); + break; + } + case kChangeDynamicsCommand: { + mutable_changedynamicscommand()->::pybullet_grpc::ChangeDynamicsCommand::MergeFrom(from.changedynamicscommand()); + break; + } + case kGetDynamicsCommand: { + mutable_getdynamicscommand()->::pybullet_grpc::GetDynamicsCommand::MergeFrom(from.getdynamicscommand()); + break; + } + case kInitPoseCommand: { + mutable_initposecommand()->::pybullet_grpc::InitPoseCommand::MergeFrom(from.initposecommand()); + break; + } + case kRequestActualStateCommand: { + mutable_requestactualstatecommand()->::pybullet_grpc::RequestActualStateCommand::MergeFrom(from.requestactualstatecommand()); + break; + } case COMMANDS_NOT_SET: { break; } @@ -2846,7 +9839,7 @@ void PyBulletCommand::InternalSwap(PyBulletCommand* other) { ::google::protobuf::Metadata PyBulletCommand::GetMetadata() const { protobuf_pybullet_2eproto::protobuf_AssignDescriptorsOnce(); - return protobuf_pybullet_2eproto::file_level_metadata[6]; + return protobuf_pybullet_2eproto::file_level_metadata[16]; } #if PROTOBUF_INLINE_NOT_IN_HEADERS @@ -3010,6 +10003,294 @@ void PyBulletCommand::set_allocated_stepsimulationcommand(::pybullet_grpc::StepS // @@protoc_insertion_point(field_set_allocated:pybullet_grpc.PyBulletCommand.stepSimulationCommand) } +// .pybullet_grpc.LoadSdfCommand loadSdfCommand = 6; +bool PyBulletCommand::has_loadsdfcommand() const { + return commands_case() == kLoadSdfCommand; +} +void PyBulletCommand::set_has_loadsdfcommand() { + _oneof_case_[0] = kLoadSdfCommand; +} +void PyBulletCommand::clear_loadsdfcommand() { + if (has_loadsdfcommand()) { + delete commands_.loadsdfcommand_; + clear_has_commands(); + } +} + const ::pybullet_grpc::LoadSdfCommand& PyBulletCommand::loadsdfcommand() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.PyBulletCommand.loadSdfCommand) + return has_loadsdfcommand() + ? *commands_.loadsdfcommand_ + : ::pybullet_grpc::LoadSdfCommand::default_instance(); +} +::pybullet_grpc::LoadSdfCommand* PyBulletCommand::mutable_loadsdfcommand() { + if (!has_loadsdfcommand()) { + clear_commands(); + set_has_loadsdfcommand(); + commands_.loadsdfcommand_ = new ::pybullet_grpc::LoadSdfCommand; + } + // @@protoc_insertion_point(field_mutable:pybullet_grpc.PyBulletCommand.loadSdfCommand) + return commands_.loadsdfcommand_; +} +::pybullet_grpc::LoadSdfCommand* PyBulletCommand::release_loadsdfcommand() { + // @@protoc_insertion_point(field_release:pybullet_grpc.PyBulletCommand.loadSdfCommand) + if (has_loadsdfcommand()) { + clear_has_commands(); + ::pybullet_grpc::LoadSdfCommand* temp = commands_.loadsdfcommand_; + commands_.loadsdfcommand_ = NULL; + return temp; + } else { + return NULL; + } +} +void PyBulletCommand::set_allocated_loadsdfcommand(::pybullet_grpc::LoadSdfCommand* loadsdfcommand) { + clear_commands(); + if (loadsdfcommand) { + set_has_loadsdfcommand(); + commands_.loadsdfcommand_ = loadsdfcommand; + } + // @@protoc_insertion_point(field_set_allocated:pybullet_grpc.PyBulletCommand.loadSdfCommand) +} + +// .pybullet_grpc.LoadMjcfCommand loadMjcfCommand = 7; +bool PyBulletCommand::has_loadmjcfcommand() const { + return commands_case() == kLoadMjcfCommand; +} +void PyBulletCommand::set_has_loadmjcfcommand() { + _oneof_case_[0] = kLoadMjcfCommand; +} +void PyBulletCommand::clear_loadmjcfcommand() { + if (has_loadmjcfcommand()) { + delete commands_.loadmjcfcommand_; + clear_has_commands(); + } +} + const ::pybullet_grpc::LoadMjcfCommand& PyBulletCommand::loadmjcfcommand() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.PyBulletCommand.loadMjcfCommand) + return has_loadmjcfcommand() + ? *commands_.loadmjcfcommand_ + : ::pybullet_grpc::LoadMjcfCommand::default_instance(); +} +::pybullet_grpc::LoadMjcfCommand* PyBulletCommand::mutable_loadmjcfcommand() { + if (!has_loadmjcfcommand()) { + clear_commands(); + set_has_loadmjcfcommand(); + commands_.loadmjcfcommand_ = new ::pybullet_grpc::LoadMjcfCommand; + } + // @@protoc_insertion_point(field_mutable:pybullet_grpc.PyBulletCommand.loadMjcfCommand) + return commands_.loadmjcfcommand_; +} +::pybullet_grpc::LoadMjcfCommand* PyBulletCommand::release_loadmjcfcommand() { + // @@protoc_insertion_point(field_release:pybullet_grpc.PyBulletCommand.loadMjcfCommand) + if (has_loadmjcfcommand()) { + clear_has_commands(); + ::pybullet_grpc::LoadMjcfCommand* temp = commands_.loadmjcfcommand_; + commands_.loadmjcfcommand_ = NULL; + return temp; + } else { + return NULL; + } +} +void PyBulletCommand::set_allocated_loadmjcfcommand(::pybullet_grpc::LoadMjcfCommand* loadmjcfcommand) { + clear_commands(); + if (loadmjcfcommand) { + set_has_loadmjcfcommand(); + commands_.loadmjcfcommand_ = loadmjcfcommand; + } + // @@protoc_insertion_point(field_set_allocated:pybullet_grpc.PyBulletCommand.loadMjcfCommand) +} + +// .pybullet_grpc.ChangeDynamicsCommand changeDynamicsCommand = 8; +bool PyBulletCommand::has_changedynamicscommand() const { + return commands_case() == kChangeDynamicsCommand; +} +void PyBulletCommand::set_has_changedynamicscommand() { + _oneof_case_[0] = kChangeDynamicsCommand; +} +void PyBulletCommand::clear_changedynamicscommand() { + if (has_changedynamicscommand()) { + delete commands_.changedynamicscommand_; + clear_has_commands(); + } +} + const ::pybullet_grpc::ChangeDynamicsCommand& PyBulletCommand::changedynamicscommand() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.PyBulletCommand.changeDynamicsCommand) + return has_changedynamicscommand() + ? *commands_.changedynamicscommand_ + : ::pybullet_grpc::ChangeDynamicsCommand::default_instance(); +} +::pybullet_grpc::ChangeDynamicsCommand* PyBulletCommand::mutable_changedynamicscommand() { + if (!has_changedynamicscommand()) { + clear_commands(); + set_has_changedynamicscommand(); + commands_.changedynamicscommand_ = new ::pybullet_grpc::ChangeDynamicsCommand; + } + // @@protoc_insertion_point(field_mutable:pybullet_grpc.PyBulletCommand.changeDynamicsCommand) + return commands_.changedynamicscommand_; +} +::pybullet_grpc::ChangeDynamicsCommand* PyBulletCommand::release_changedynamicscommand() { + // @@protoc_insertion_point(field_release:pybullet_grpc.PyBulletCommand.changeDynamicsCommand) + if (has_changedynamicscommand()) { + clear_has_commands(); + ::pybullet_grpc::ChangeDynamicsCommand* temp = commands_.changedynamicscommand_; + commands_.changedynamicscommand_ = NULL; + return temp; + } else { + return NULL; + } +} +void PyBulletCommand::set_allocated_changedynamicscommand(::pybullet_grpc::ChangeDynamicsCommand* changedynamicscommand) { + clear_commands(); + if (changedynamicscommand) { + set_has_changedynamicscommand(); + commands_.changedynamicscommand_ = changedynamicscommand; + } + // @@protoc_insertion_point(field_set_allocated:pybullet_grpc.PyBulletCommand.changeDynamicsCommand) +} + +// .pybullet_grpc.GetDynamicsCommand getDynamicsCommand = 9; +bool PyBulletCommand::has_getdynamicscommand() const { + return commands_case() == kGetDynamicsCommand; +} +void PyBulletCommand::set_has_getdynamicscommand() { + _oneof_case_[0] = kGetDynamicsCommand; +} +void PyBulletCommand::clear_getdynamicscommand() { + if (has_getdynamicscommand()) { + delete commands_.getdynamicscommand_; + clear_has_commands(); + } +} + const ::pybullet_grpc::GetDynamicsCommand& PyBulletCommand::getdynamicscommand() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.PyBulletCommand.getDynamicsCommand) + return has_getdynamicscommand() + ? *commands_.getdynamicscommand_ + : ::pybullet_grpc::GetDynamicsCommand::default_instance(); +} +::pybullet_grpc::GetDynamicsCommand* PyBulletCommand::mutable_getdynamicscommand() { + if (!has_getdynamicscommand()) { + clear_commands(); + set_has_getdynamicscommand(); + commands_.getdynamicscommand_ = new ::pybullet_grpc::GetDynamicsCommand; + } + // @@protoc_insertion_point(field_mutable:pybullet_grpc.PyBulletCommand.getDynamicsCommand) + return commands_.getdynamicscommand_; +} +::pybullet_grpc::GetDynamicsCommand* PyBulletCommand::release_getdynamicscommand() { + // @@protoc_insertion_point(field_release:pybullet_grpc.PyBulletCommand.getDynamicsCommand) + if (has_getdynamicscommand()) { + clear_has_commands(); + ::pybullet_grpc::GetDynamicsCommand* temp = commands_.getdynamicscommand_; + commands_.getdynamicscommand_ = NULL; + return temp; + } else { + return NULL; + } +} +void PyBulletCommand::set_allocated_getdynamicscommand(::pybullet_grpc::GetDynamicsCommand* getdynamicscommand) { + clear_commands(); + if (getdynamicscommand) { + set_has_getdynamicscommand(); + commands_.getdynamicscommand_ = getdynamicscommand; + } + // @@protoc_insertion_point(field_set_allocated:pybullet_grpc.PyBulletCommand.getDynamicsCommand) +} + +// .pybullet_grpc.InitPoseCommand initPoseCommand = 10; +bool PyBulletCommand::has_initposecommand() const { + return commands_case() == kInitPoseCommand; +} +void PyBulletCommand::set_has_initposecommand() { + _oneof_case_[0] = kInitPoseCommand; +} +void PyBulletCommand::clear_initposecommand() { + if (has_initposecommand()) { + delete commands_.initposecommand_; + clear_has_commands(); + } +} + const ::pybullet_grpc::InitPoseCommand& PyBulletCommand::initposecommand() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.PyBulletCommand.initPoseCommand) + return has_initposecommand() + ? *commands_.initposecommand_ + : ::pybullet_grpc::InitPoseCommand::default_instance(); +} +::pybullet_grpc::InitPoseCommand* PyBulletCommand::mutable_initposecommand() { + if (!has_initposecommand()) { + clear_commands(); + set_has_initposecommand(); + commands_.initposecommand_ = new ::pybullet_grpc::InitPoseCommand; + } + // @@protoc_insertion_point(field_mutable:pybullet_grpc.PyBulletCommand.initPoseCommand) + return commands_.initposecommand_; +} +::pybullet_grpc::InitPoseCommand* PyBulletCommand::release_initposecommand() { + // @@protoc_insertion_point(field_release:pybullet_grpc.PyBulletCommand.initPoseCommand) + if (has_initposecommand()) { + clear_has_commands(); + ::pybullet_grpc::InitPoseCommand* temp = commands_.initposecommand_; + commands_.initposecommand_ = NULL; + return temp; + } else { + return NULL; + } +} +void PyBulletCommand::set_allocated_initposecommand(::pybullet_grpc::InitPoseCommand* initposecommand) { + clear_commands(); + if (initposecommand) { + set_has_initposecommand(); + commands_.initposecommand_ = initposecommand; + } + // @@protoc_insertion_point(field_set_allocated:pybullet_grpc.PyBulletCommand.initPoseCommand) +} + +// .pybullet_grpc.RequestActualStateCommand requestActualStateCommand = 11; +bool PyBulletCommand::has_requestactualstatecommand() const { + return commands_case() == kRequestActualStateCommand; +} +void PyBulletCommand::set_has_requestactualstatecommand() { + _oneof_case_[0] = kRequestActualStateCommand; +} +void PyBulletCommand::clear_requestactualstatecommand() { + if (has_requestactualstatecommand()) { + delete commands_.requestactualstatecommand_; + clear_has_commands(); + } +} + const ::pybullet_grpc::RequestActualStateCommand& PyBulletCommand::requestactualstatecommand() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.PyBulletCommand.requestActualStateCommand) + return has_requestactualstatecommand() + ? *commands_.requestactualstatecommand_ + : ::pybullet_grpc::RequestActualStateCommand::default_instance(); +} +::pybullet_grpc::RequestActualStateCommand* PyBulletCommand::mutable_requestactualstatecommand() { + if (!has_requestactualstatecommand()) { + clear_commands(); + set_has_requestactualstatecommand(); + commands_.requestactualstatecommand_ = new ::pybullet_grpc::RequestActualStateCommand; + } + // @@protoc_insertion_point(field_mutable:pybullet_grpc.PyBulletCommand.requestActualStateCommand) + return commands_.requestactualstatecommand_; +} +::pybullet_grpc::RequestActualStateCommand* PyBulletCommand::release_requestactualstatecommand() { + // @@protoc_insertion_point(field_release:pybullet_grpc.PyBulletCommand.requestActualStateCommand) + if (has_requestactualstatecommand()) { + clear_has_commands(); + ::pybullet_grpc::RequestActualStateCommand* temp = commands_.requestactualstatecommand_; + commands_.requestactualstatecommand_ = NULL; + return temp; + } else { + return NULL; + } +} +void PyBulletCommand::set_allocated_requestactualstatecommand(::pybullet_grpc::RequestActualStateCommand* requestactualstatecommand) { + clear_commands(); + if (requestactualstatecommand) { + set_has_requestactualstatecommand(); + commands_.requestactualstatecommand_ = requestactualstatecommand; + } + // @@protoc_insertion_point(field_set_allocated:pybullet_grpc.PyBulletCommand.requestActualStateCommand) +} + bool PyBulletCommand::has_commands() const { return commands_case() != COMMANDS_NOT_SET; } @@ -3026,6 +10307,10 @@ PyBulletCommand::CommandsCase PyBulletCommand::commands_case() const { #if !defined(_MSC_VER) || _MSC_VER >= 1900 const int PyBulletStatus::kStatusTypeFieldNumber; const int PyBulletStatus::kUrdfStatusFieldNumber; +const int PyBulletStatus::kSdfStatusFieldNumber; +const int PyBulletStatus::kMjcfStatusFieldNumber; +const int PyBulletStatus::kGetDynamicsStatusFieldNumber; +const int PyBulletStatus::kActualStateStatusFieldNumber; #endif // !defined(_MSC_VER) || _MSC_VER >= 1900 PyBulletStatus::PyBulletStatus() @@ -3048,6 +10333,22 @@ PyBulletStatus::PyBulletStatus(const PyBulletStatus& from) mutable_urdfstatus()->::pybullet_grpc::LoadUrdfStatus::MergeFrom(from.urdfstatus()); break; } + case kSdfStatus: { + mutable_sdfstatus()->::pybullet_grpc::SdfLoadedStatus::MergeFrom(from.sdfstatus()); + break; + } + case kMjcfStatus: { + mutable_mjcfstatus()->::pybullet_grpc::MjcfLoadedStatus::MergeFrom(from.mjcfstatus()); + break; + } + case kGetDynamicsStatus: { + mutable_getdynamicsstatus()->::pybullet_grpc::GetDynamicsStatus::MergeFrom(from.getdynamicsstatus()); + break; + } + case kActualStateStatus: { + mutable_actualstatestatus()->::pybullet_grpc::SendActualStateStatus::MergeFrom(from.actualstatestatus()); + break; + } case STATUS_NOT_SET: { break; } @@ -3079,7 +10380,7 @@ void PyBulletStatus::SetCachedSize(int size) const { } const ::google::protobuf::Descriptor* PyBulletStatus::descriptor() { protobuf_pybullet_2eproto::protobuf_AssignDescriptorsOnce(); - return protobuf_pybullet_2eproto::file_level_metadata[7].descriptor; + return protobuf_pybullet_2eproto::file_level_metadata[17].descriptor; } const PyBulletStatus& PyBulletStatus::default_instance() { @@ -3102,6 +10403,22 @@ void PyBulletStatus::clear_status() { delete status_.urdfstatus_; break; } + case kSdfStatus: { + delete status_.sdfstatus_; + break; + } + case kMjcfStatus: { + delete status_.mjcfstatus_; + break; + } + case kGetDynamicsStatus: { + delete status_.getdynamicsstatus_; + break; + } + case kActualStateStatus: { + delete status_.actualstatestatus_; + break; + } case STATUS_NOT_SET: { break; } @@ -3150,6 +10467,50 @@ bool PyBulletStatus::MergePartialFromCodedStream( break; } + // .pybullet_grpc.SdfLoadedStatus sdfStatus = 3; + case 3: { + if (tag == 26u) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessageNoVirtual( + input, mutable_sdfstatus())); + } else { + goto handle_unusual; + } + break; + } + + // .pybullet_grpc.MjcfLoadedStatus mjcfStatus = 4; + case 4: { + if (tag == 34u) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessageNoVirtual( + input, mutable_mjcfstatus())); + } else { + goto handle_unusual; + } + break; + } + + // .pybullet_grpc.GetDynamicsStatus getDynamicsStatus = 5; + case 5: { + if (tag == 42u) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessageNoVirtual( + input, mutable_getdynamicsstatus())); + } else { + goto handle_unusual; + } + break; + } + + // .pybullet_grpc.SendActualStateStatus actualStateStatus = 6; + case 6: { + if (tag == 50u) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessageNoVirtual( + input, mutable_actualstatestatus())); + } else { + goto handle_unusual; + } + break; + } + default: { handle_unusual: if (tag == 0 || @@ -3185,6 +10546,30 @@ void PyBulletStatus::SerializeWithCachedSizes( 2, *status_.urdfstatus_, output); } + // .pybullet_grpc.SdfLoadedStatus sdfStatus = 3; + if (has_sdfstatus()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 3, *status_.sdfstatus_, output); + } + + // .pybullet_grpc.MjcfLoadedStatus mjcfStatus = 4; + if (has_mjcfstatus()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 4, *status_.mjcfstatus_, output); + } + + // .pybullet_grpc.GetDynamicsStatus getDynamicsStatus = 5; + if (has_getdynamicsstatus()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 5, *status_.getdynamicsstatus_, output); + } + + // .pybullet_grpc.SendActualStateStatus actualStateStatus = 6; + if (has_actualstatestatus()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 6, *status_.actualstatestatus_, output); + } + // @@protoc_insertion_point(serialize_end:pybullet_grpc.PyBulletStatus) } @@ -3204,6 +10589,34 @@ void PyBulletStatus::SerializeWithCachedSizes( 2, *status_.urdfstatus_, false, target); } + // .pybullet_grpc.SdfLoadedStatus sdfStatus = 3; + if (has_sdfstatus()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageNoVirtualToArray( + 3, *status_.sdfstatus_, false, target); + } + + // .pybullet_grpc.MjcfLoadedStatus mjcfStatus = 4; + if (has_mjcfstatus()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageNoVirtualToArray( + 4, *status_.mjcfstatus_, false, target); + } + + // .pybullet_grpc.GetDynamicsStatus getDynamicsStatus = 5; + if (has_getdynamicsstatus()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageNoVirtualToArray( + 5, *status_.getdynamicsstatus_, false, target); + } + + // .pybullet_grpc.SendActualStateStatus actualStateStatus = 6; + if (has_actualstatestatus()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageNoVirtualToArray( + 6, *status_.actualstatestatus_, false, target); + } + // @@protoc_insertion_point(serialize_to_array_end:pybullet_grpc.PyBulletStatus) return target; } @@ -3227,6 +10640,34 @@ size_t PyBulletStatus::ByteSizeLong() const { *status_.urdfstatus_); break; } + // .pybullet_grpc.SdfLoadedStatus sdfStatus = 3; + case kSdfStatus: { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSizeNoVirtual( + *status_.sdfstatus_); + break; + } + // .pybullet_grpc.MjcfLoadedStatus mjcfStatus = 4; + case kMjcfStatus: { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSizeNoVirtual( + *status_.mjcfstatus_); + break; + } + // .pybullet_grpc.GetDynamicsStatus getDynamicsStatus = 5; + case kGetDynamicsStatus: { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSizeNoVirtual( + *status_.getdynamicsstatus_); + break; + } + // .pybullet_grpc.SendActualStateStatus actualStateStatus = 6; + case kActualStateStatus: { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSizeNoVirtual( + *status_.actualstatestatus_); + break; + } case STATUS_NOT_SET: { break; } @@ -3265,6 +10706,22 @@ void PyBulletStatus::MergeFrom(const PyBulletStatus& from) { mutable_urdfstatus()->::pybullet_grpc::LoadUrdfStatus::MergeFrom(from.urdfstatus()); break; } + case kSdfStatus: { + mutable_sdfstatus()->::pybullet_grpc::SdfLoadedStatus::MergeFrom(from.sdfstatus()); + break; + } + case kMjcfStatus: { + mutable_mjcfstatus()->::pybullet_grpc::MjcfLoadedStatus::MergeFrom(from.mjcfstatus()); + break; + } + case kGetDynamicsStatus: { + mutable_getdynamicsstatus()->::pybullet_grpc::GetDynamicsStatus::MergeFrom(from.getdynamicsstatus()); + break; + } + case kActualStateStatus: { + mutable_actualstatestatus()->::pybullet_grpc::SendActualStateStatus::MergeFrom(from.actualstatestatus()); + break; + } case STATUS_NOT_SET: { break; } @@ -3302,7 +10759,7 @@ void PyBulletStatus::InternalSwap(PyBulletStatus* other) { ::google::protobuf::Metadata PyBulletStatus::GetMetadata() const { protobuf_pybullet_2eproto::protobuf_AssignDescriptorsOnce(); - return protobuf_pybullet_2eproto::file_level_metadata[7]; + return protobuf_pybullet_2eproto::file_level_metadata[17]; } #if PROTOBUF_INLINE_NOT_IN_HEADERS @@ -3370,6 +10827,198 @@ void PyBulletStatus::set_allocated_urdfstatus(::pybullet_grpc::LoadUrdfStatus* u // @@protoc_insertion_point(field_set_allocated:pybullet_grpc.PyBulletStatus.urdfStatus) } +// .pybullet_grpc.SdfLoadedStatus sdfStatus = 3; +bool PyBulletStatus::has_sdfstatus() const { + return status_case() == kSdfStatus; +} +void PyBulletStatus::set_has_sdfstatus() { + _oneof_case_[0] = kSdfStatus; +} +void PyBulletStatus::clear_sdfstatus() { + if (has_sdfstatus()) { + delete status_.sdfstatus_; + clear_has_status(); + } +} + const ::pybullet_grpc::SdfLoadedStatus& PyBulletStatus::sdfstatus() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.PyBulletStatus.sdfStatus) + return has_sdfstatus() + ? *status_.sdfstatus_ + : ::pybullet_grpc::SdfLoadedStatus::default_instance(); +} +::pybullet_grpc::SdfLoadedStatus* PyBulletStatus::mutable_sdfstatus() { + if (!has_sdfstatus()) { + clear_status(); + set_has_sdfstatus(); + status_.sdfstatus_ = new ::pybullet_grpc::SdfLoadedStatus; + } + // @@protoc_insertion_point(field_mutable:pybullet_grpc.PyBulletStatus.sdfStatus) + return status_.sdfstatus_; +} +::pybullet_grpc::SdfLoadedStatus* PyBulletStatus::release_sdfstatus() { + // @@protoc_insertion_point(field_release:pybullet_grpc.PyBulletStatus.sdfStatus) + if (has_sdfstatus()) { + clear_has_status(); + ::pybullet_grpc::SdfLoadedStatus* temp = status_.sdfstatus_; + status_.sdfstatus_ = NULL; + return temp; + } else { + return NULL; + } +} +void PyBulletStatus::set_allocated_sdfstatus(::pybullet_grpc::SdfLoadedStatus* sdfstatus) { + clear_status(); + if (sdfstatus) { + set_has_sdfstatus(); + status_.sdfstatus_ = sdfstatus; + } + // @@protoc_insertion_point(field_set_allocated:pybullet_grpc.PyBulletStatus.sdfStatus) +} + +// .pybullet_grpc.MjcfLoadedStatus mjcfStatus = 4; +bool PyBulletStatus::has_mjcfstatus() const { + return status_case() == kMjcfStatus; +} +void PyBulletStatus::set_has_mjcfstatus() { + _oneof_case_[0] = kMjcfStatus; +} +void PyBulletStatus::clear_mjcfstatus() { + if (has_mjcfstatus()) { + delete status_.mjcfstatus_; + clear_has_status(); + } +} + const ::pybullet_grpc::MjcfLoadedStatus& PyBulletStatus::mjcfstatus() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.PyBulletStatus.mjcfStatus) + return has_mjcfstatus() + ? *status_.mjcfstatus_ + : ::pybullet_grpc::MjcfLoadedStatus::default_instance(); +} +::pybullet_grpc::MjcfLoadedStatus* PyBulletStatus::mutable_mjcfstatus() { + if (!has_mjcfstatus()) { + clear_status(); + set_has_mjcfstatus(); + status_.mjcfstatus_ = new ::pybullet_grpc::MjcfLoadedStatus; + } + // @@protoc_insertion_point(field_mutable:pybullet_grpc.PyBulletStatus.mjcfStatus) + return status_.mjcfstatus_; +} +::pybullet_grpc::MjcfLoadedStatus* PyBulletStatus::release_mjcfstatus() { + // @@protoc_insertion_point(field_release:pybullet_grpc.PyBulletStatus.mjcfStatus) + if (has_mjcfstatus()) { + clear_has_status(); + ::pybullet_grpc::MjcfLoadedStatus* temp = status_.mjcfstatus_; + status_.mjcfstatus_ = NULL; + return temp; + } else { + return NULL; + } +} +void PyBulletStatus::set_allocated_mjcfstatus(::pybullet_grpc::MjcfLoadedStatus* mjcfstatus) { + clear_status(); + if (mjcfstatus) { + set_has_mjcfstatus(); + status_.mjcfstatus_ = mjcfstatus; + } + // @@protoc_insertion_point(field_set_allocated:pybullet_grpc.PyBulletStatus.mjcfStatus) +} + +// .pybullet_grpc.GetDynamicsStatus getDynamicsStatus = 5; +bool PyBulletStatus::has_getdynamicsstatus() const { + return status_case() == kGetDynamicsStatus; +} +void PyBulletStatus::set_has_getdynamicsstatus() { + _oneof_case_[0] = kGetDynamicsStatus; +} +void PyBulletStatus::clear_getdynamicsstatus() { + if (has_getdynamicsstatus()) { + delete status_.getdynamicsstatus_; + clear_has_status(); + } +} + const ::pybullet_grpc::GetDynamicsStatus& PyBulletStatus::getdynamicsstatus() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.PyBulletStatus.getDynamicsStatus) + return has_getdynamicsstatus() + ? *status_.getdynamicsstatus_ + : ::pybullet_grpc::GetDynamicsStatus::default_instance(); +} +::pybullet_grpc::GetDynamicsStatus* PyBulletStatus::mutable_getdynamicsstatus() { + if (!has_getdynamicsstatus()) { + clear_status(); + set_has_getdynamicsstatus(); + status_.getdynamicsstatus_ = new ::pybullet_grpc::GetDynamicsStatus; + } + // @@protoc_insertion_point(field_mutable:pybullet_grpc.PyBulletStatus.getDynamicsStatus) + return status_.getdynamicsstatus_; +} +::pybullet_grpc::GetDynamicsStatus* PyBulletStatus::release_getdynamicsstatus() { + // @@protoc_insertion_point(field_release:pybullet_grpc.PyBulletStatus.getDynamicsStatus) + if (has_getdynamicsstatus()) { + clear_has_status(); + ::pybullet_grpc::GetDynamicsStatus* temp = status_.getdynamicsstatus_; + status_.getdynamicsstatus_ = NULL; + return temp; + } else { + return NULL; + } +} +void PyBulletStatus::set_allocated_getdynamicsstatus(::pybullet_grpc::GetDynamicsStatus* getdynamicsstatus) { + clear_status(); + if (getdynamicsstatus) { + set_has_getdynamicsstatus(); + status_.getdynamicsstatus_ = getdynamicsstatus; + } + // @@protoc_insertion_point(field_set_allocated:pybullet_grpc.PyBulletStatus.getDynamicsStatus) +} + +// .pybullet_grpc.SendActualStateStatus actualStateStatus = 6; +bool PyBulletStatus::has_actualstatestatus() const { + return status_case() == kActualStateStatus; +} +void PyBulletStatus::set_has_actualstatestatus() { + _oneof_case_[0] = kActualStateStatus; +} +void PyBulletStatus::clear_actualstatestatus() { + if (has_actualstatestatus()) { + delete status_.actualstatestatus_; + clear_has_status(); + } +} + const ::pybullet_grpc::SendActualStateStatus& PyBulletStatus::actualstatestatus() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.PyBulletStatus.actualStateStatus) + return has_actualstatestatus() + ? *status_.actualstatestatus_ + : ::pybullet_grpc::SendActualStateStatus::default_instance(); +} +::pybullet_grpc::SendActualStateStatus* PyBulletStatus::mutable_actualstatestatus() { + if (!has_actualstatestatus()) { + clear_status(); + set_has_actualstatestatus(); + status_.actualstatestatus_ = new ::pybullet_grpc::SendActualStateStatus; + } + // @@protoc_insertion_point(field_mutable:pybullet_grpc.PyBulletStatus.actualStateStatus) + return status_.actualstatestatus_; +} +::pybullet_grpc::SendActualStateStatus* PyBulletStatus::release_actualstatestatus() { + // @@protoc_insertion_point(field_release:pybullet_grpc.PyBulletStatus.actualStateStatus) + if (has_actualstatestatus()) { + clear_has_status(); + ::pybullet_grpc::SendActualStateStatus* temp = status_.actualstatestatus_; + status_.actualstatestatus_ = NULL; + return temp; + } else { + return NULL; + } +} +void PyBulletStatus::set_allocated_actualstatestatus(::pybullet_grpc::SendActualStateStatus* actualstatestatus) { + clear_status(); + if (actualstatestatus) { + set_has_actualstatestatus(); + status_.actualstatestatus_ = actualstatestatus; + } + // @@protoc_insertion_point(field_set_allocated:pybullet_grpc.PyBulletStatus.actualStateStatus) +} + bool PyBulletStatus::has_status() const { return status_case() != STATUS_NOT_SET; } diff --git a/examples/SharedMemory/grpc/pybullet.pb.h b/examples/SharedMemory/grpc/pybullet.pb.h index 41ebe4126..526b694f3 100644 --- a/examples/SharedMemory/grpc/pybullet.pb.h +++ b/examples/SharedMemory/grpc/pybullet.pb.h @@ -30,18 +30,48 @@ #include // @@protoc_insertion_point(includes) namespace pybullet_grpc { +class ChangeDynamicsCommand; +class ChangeDynamicsCommandDefaultTypeInternal; +extern ChangeDynamicsCommandDefaultTypeInternal _ChangeDynamicsCommand_default_instance_; +class GetDynamicsCommand; +class GetDynamicsCommandDefaultTypeInternal; +extern GetDynamicsCommandDefaultTypeInternal _GetDynamicsCommand_default_instance_; +class GetDynamicsStatus; +class GetDynamicsStatusDefaultTypeInternal; +extern GetDynamicsStatusDefaultTypeInternal _GetDynamicsStatus_default_instance_; +class InitPoseCommand; +class InitPoseCommandDefaultTypeInternal; +extern InitPoseCommandDefaultTypeInternal _InitPoseCommand_default_instance_; +class LoadMjcfCommand; +class LoadMjcfCommandDefaultTypeInternal; +extern LoadMjcfCommandDefaultTypeInternal _LoadMjcfCommand_default_instance_; +class LoadSdfCommand; +class LoadSdfCommandDefaultTypeInternal; +extern LoadSdfCommandDefaultTypeInternal _LoadSdfCommand_default_instance_; class LoadUrdfCommand; class LoadUrdfCommandDefaultTypeInternal; extern LoadUrdfCommandDefaultTypeInternal _LoadUrdfCommand_default_instance_; class LoadUrdfStatus; class LoadUrdfStatusDefaultTypeInternal; extern LoadUrdfStatusDefaultTypeInternal _LoadUrdfStatus_default_instance_; +class MjcfLoadedStatus; +class MjcfLoadedStatusDefaultTypeInternal; +extern MjcfLoadedStatusDefaultTypeInternal _MjcfLoadedStatus_default_instance_; class PyBulletCommand; class PyBulletCommandDefaultTypeInternal; extern PyBulletCommandDefaultTypeInternal _PyBulletCommand_default_instance_; class PyBulletStatus; class PyBulletStatusDefaultTypeInternal; extern PyBulletStatusDefaultTypeInternal _PyBulletStatus_default_instance_; +class RequestActualStateCommand; +class RequestActualStateCommandDefaultTypeInternal; +extern RequestActualStateCommandDefaultTypeInternal _RequestActualStateCommand_default_instance_; +class SdfLoadedStatus; +class SdfLoadedStatusDefaultTypeInternal; +extern SdfLoadedStatusDefaultTypeInternal _SdfLoadedStatus_default_instance_; +class SendActualStateStatus; +class SendActualStateStatusDefaultTypeInternal; +extern SendActualStateStatusDefaultTypeInternal _SendActualStateStatus_default_instance_; class StepSimulationCommand; class StepSimulationCommandDefaultTypeInternal; extern StepSimulationCommandDefaultTypeInternal _StepSimulationCommand_default_instance_; @@ -521,19 +551,19 @@ class LoadUrdfCommand : public ::google::protobuf::Message /* @@protoc_insertion // accessors ------------------------------------------------------- - // string urdfFileName = 1; - void clear_urdffilename(); - static const int kUrdfFileNameFieldNumber = 1; - const ::std::string& urdffilename() const; - void set_urdffilename(const ::std::string& value); + // string fileName = 1; + void clear_filename(); + static const int kFileNameFieldNumber = 1; + const ::std::string& filename() const; + void set_filename(const ::std::string& value); #if LANG_CXX11 - void set_urdffilename(::std::string&& value); + void set_filename(::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); + void set_filename(const char* value); + void set_filename(const char* value, size_t size); + ::std::string* mutable_filename(); + ::std::string* release_filename(); + void set_allocated_filename(::std::string* filename); // .pybullet_grpc.vec3 initialPosition = 2; bool has_initialposition() const; @@ -553,11 +583,11 @@ class LoadUrdfCommand : public ::google::protobuf::Message /* @@protoc_insertion ::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 flags = 6; + void clear_flags(); + static const int kFlagsFieldNumber = 6; + ::google::protobuf::int32 flags() const; + void set_flags(::google::protobuf::int32 value); // int32 useMultiBody = 4; private: @@ -608,10 +638,10 @@ class LoadUrdfCommand : public ::google::protobuf::Message /* @@protoc_insertion inline void clear_has_hasGlobalScaling(); ::google::protobuf::internal::InternalMetadataWithArena _internal_metadata_; - ::google::protobuf::internal::ArenaStringPtr urdffilename_; + ::google::protobuf::internal::ArenaStringPtr filename_; ::pybullet_grpc::vec3* initialposition_; ::pybullet_grpc::quat4* initialorientation_; - ::google::protobuf::int32 urdfflags_; + ::google::protobuf::int32 flags_; union HasUseMultiBodyUnion { HasUseMultiBodyUnion() {} ::google::protobuf::int32 usemultibody_; @@ -698,17 +728,1583 @@ class LoadUrdfStatus : public ::google::protobuf::Message /* @@protoc_insertion_ // accessors ------------------------------------------------------- - // int32 objectUniqueId = 1; - void clear_objectuniqueid(); - static const int kObjectUniqueIdFieldNumber = 1; - ::google::protobuf::int32 objectuniqueid() const; - void set_objectuniqueid(::google::protobuf::int32 value); + // int32 bodyUniqueId = 1; + void clear_bodyuniqueid(); + static const int kBodyUniqueIdFieldNumber = 1; + ::google::protobuf::int32 bodyuniqueid() const; + void set_bodyuniqueid(::google::protobuf::int32 value); // @@protoc_insertion_point(class_scope:pybullet_grpc.LoadUrdfStatus) private: ::google::protobuf::internal::InternalMetadataWithArena _internal_metadata_; - ::google::protobuf::int32 objectuniqueid_; + ::google::protobuf::int32 bodyuniqueid_; + mutable int _cached_size_; + friend struct protobuf_pybullet_2eproto::TableStruct; +}; +// ------------------------------------------------------------------- + +class LoadSdfCommand : public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:pybullet_grpc.LoadSdfCommand) */ { + public: + LoadSdfCommand(); + virtual ~LoadSdfCommand(); + + LoadSdfCommand(const LoadSdfCommand& from); + + inline LoadSdfCommand& operator=(const LoadSdfCommand& from) { + CopyFrom(from); + return *this; + } + + static const ::google::protobuf::Descriptor* descriptor(); + static const LoadSdfCommand& default_instance(); + + enum HasUseMultiBodyCase { + kUseMultiBody = 2, + HASUSEMULTIBODY_NOT_SET = 0, + }; + + enum HasGlobalScalingCase { + kGlobalScaling = 3, + HASGLOBALSCALING_NOT_SET = 0, + }; + + static inline const LoadSdfCommand* internal_default_instance() { + return reinterpret_cast( + &_LoadSdfCommand_default_instance_); + } + + void Swap(LoadSdfCommand* other); + + // implements Message ---------------------------------------------- + + inline LoadSdfCommand* New() const PROTOBUF_FINAL { return New(NULL); } + + LoadSdfCommand* 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 LoadSdfCommand& from); + void MergeFrom(const LoadSdfCommand& 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(LoadSdfCommand* 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 fileName = 1; + void clear_filename(); + static const int kFileNameFieldNumber = 1; + const ::std::string& filename() const; + void set_filename(const ::std::string& value); + #if LANG_CXX11 + void set_filename(::std::string&& value); + #endif + void set_filename(const char* value); + void set_filename(const char* value, size_t size); + ::std::string* mutable_filename(); + ::std::string* release_filename(); + void set_allocated_filename(::std::string* filename); + + // int32 useMultiBody = 2; + private: + bool has_usemultibody() const; + public: + void clear_usemultibody(); + static const int kUseMultiBodyFieldNumber = 2; + ::google::protobuf::int32 usemultibody() const; + void set_usemultibody(::google::protobuf::int32 value); + + // double globalScaling = 3; + private: + bool has_globalscaling() const; + public: + void clear_globalscaling(); + static const int kGlobalScalingFieldNumber = 3; + double globalscaling() const; + void set_globalscaling(double value); + + HasUseMultiBodyCase hasUseMultiBody_case() const; + HasGlobalScalingCase hasGlobalScaling_case() const; + // @@protoc_insertion_point(class_scope:pybullet_grpc.LoadSdfCommand) + private: + void set_has_usemultibody(); + void set_has_globalscaling(); + + inline bool has_hasUseMultiBody() const; + void clear_hasUseMultiBody(); + inline void clear_has_hasUseMultiBody(); + + inline bool has_hasGlobalScaling() const; + void clear_hasGlobalScaling(); + inline void clear_has_hasGlobalScaling(); + + ::google::protobuf::internal::InternalMetadataWithArena _internal_metadata_; + ::google::protobuf::internal::ArenaStringPtr filename_; + union HasUseMultiBodyUnion { + HasUseMultiBodyUnion() {} + ::google::protobuf::int32 usemultibody_; + } hasUseMultiBody_; + union HasGlobalScalingUnion { + HasGlobalScalingUnion() {} + double globalscaling_; + } hasGlobalScaling_; + mutable int _cached_size_; + ::google::protobuf::uint32 _oneof_case_[2]; + + friend struct protobuf_pybullet_2eproto::TableStruct; +}; +// ------------------------------------------------------------------- + +class SdfLoadedStatus : public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:pybullet_grpc.SdfLoadedStatus) */ { + public: + SdfLoadedStatus(); + virtual ~SdfLoadedStatus(); + + SdfLoadedStatus(const SdfLoadedStatus& from); + + inline SdfLoadedStatus& operator=(const SdfLoadedStatus& from) { + CopyFrom(from); + return *this; + } + + static const ::google::protobuf::Descriptor* descriptor(); + static const SdfLoadedStatus& default_instance(); + + static inline const SdfLoadedStatus* internal_default_instance() { + return reinterpret_cast( + &_SdfLoadedStatus_default_instance_); + } + + void Swap(SdfLoadedStatus* other); + + // implements Message ---------------------------------------------- + + inline SdfLoadedStatus* New() const PROTOBUF_FINAL { return New(NULL); } + + SdfLoadedStatus* 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 SdfLoadedStatus& from); + void MergeFrom(const SdfLoadedStatus& 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(SdfLoadedStatus* 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 ------------------------------------------------------- + + // repeated int32 bodyUniqueIds = 2; + int bodyuniqueids_size() const; + void clear_bodyuniqueids(); + static const int kBodyUniqueIdsFieldNumber = 2; + ::google::protobuf::int32 bodyuniqueids(int index) const; + void set_bodyuniqueids(int index, ::google::protobuf::int32 value); + void add_bodyuniqueids(::google::protobuf::int32 value); + const ::google::protobuf::RepeatedField< ::google::protobuf::int32 >& + bodyuniqueids() const; + ::google::protobuf::RepeatedField< ::google::protobuf::int32 >* + mutable_bodyuniqueids(); + + // @@protoc_insertion_point(class_scope:pybullet_grpc.SdfLoadedStatus) + private: + + ::google::protobuf::internal::InternalMetadataWithArena _internal_metadata_; + ::google::protobuf::RepeatedField< ::google::protobuf::int32 > bodyuniqueids_; + mutable int _bodyuniqueids_cached_byte_size_; + mutable int _cached_size_; + friend struct protobuf_pybullet_2eproto::TableStruct; +}; +// ------------------------------------------------------------------- + +class LoadMjcfCommand : public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:pybullet_grpc.LoadMjcfCommand) */ { + public: + LoadMjcfCommand(); + virtual ~LoadMjcfCommand(); + + LoadMjcfCommand(const LoadMjcfCommand& from); + + inline LoadMjcfCommand& operator=(const LoadMjcfCommand& from) { + CopyFrom(from); + return *this; + } + + static const ::google::protobuf::Descriptor* descriptor(); + static const LoadMjcfCommand& default_instance(); + + static inline const LoadMjcfCommand* internal_default_instance() { + return reinterpret_cast( + &_LoadMjcfCommand_default_instance_); + } + + void Swap(LoadMjcfCommand* other); + + // implements Message ---------------------------------------------- + + inline LoadMjcfCommand* New() const PROTOBUF_FINAL { return New(NULL); } + + LoadMjcfCommand* 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 LoadMjcfCommand& from); + void MergeFrom(const LoadMjcfCommand& 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(LoadMjcfCommand* 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 fileName = 1; + void clear_filename(); + static const int kFileNameFieldNumber = 1; + const ::std::string& filename() const; + void set_filename(const ::std::string& value); + #if LANG_CXX11 + void set_filename(::std::string&& value); + #endif + void set_filename(const char* value); + void set_filename(const char* value, size_t size); + ::std::string* mutable_filename(); + ::std::string* release_filename(); + void set_allocated_filename(::std::string* filename); + + // int32 flags = 2; + void clear_flags(); + static const int kFlagsFieldNumber = 2; + ::google::protobuf::int32 flags() const; + void set_flags(::google::protobuf::int32 value); + + // @@protoc_insertion_point(class_scope:pybullet_grpc.LoadMjcfCommand) + private: + + ::google::protobuf::internal::InternalMetadataWithArena _internal_metadata_; + ::google::protobuf::internal::ArenaStringPtr filename_; + ::google::protobuf::int32 flags_; + mutable int _cached_size_; + friend struct protobuf_pybullet_2eproto::TableStruct; +}; +// ------------------------------------------------------------------- + +class MjcfLoadedStatus : public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:pybullet_grpc.MjcfLoadedStatus) */ { + public: + MjcfLoadedStatus(); + virtual ~MjcfLoadedStatus(); + + MjcfLoadedStatus(const MjcfLoadedStatus& from); + + inline MjcfLoadedStatus& operator=(const MjcfLoadedStatus& from) { + CopyFrom(from); + return *this; + } + + static const ::google::protobuf::Descriptor* descriptor(); + static const MjcfLoadedStatus& default_instance(); + + static inline const MjcfLoadedStatus* internal_default_instance() { + return reinterpret_cast( + &_MjcfLoadedStatus_default_instance_); + } + + void Swap(MjcfLoadedStatus* other); + + // implements Message ---------------------------------------------- + + inline MjcfLoadedStatus* New() const PROTOBUF_FINAL { return New(NULL); } + + MjcfLoadedStatus* 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 MjcfLoadedStatus& from); + void MergeFrom(const MjcfLoadedStatus& 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(MjcfLoadedStatus* 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 ------------------------------------------------------- + + // repeated int32 bodyUniqueIds = 2; + int bodyuniqueids_size() const; + void clear_bodyuniqueids(); + static const int kBodyUniqueIdsFieldNumber = 2; + ::google::protobuf::int32 bodyuniqueids(int index) const; + void set_bodyuniqueids(int index, ::google::protobuf::int32 value); + void add_bodyuniqueids(::google::protobuf::int32 value); + const ::google::protobuf::RepeatedField< ::google::protobuf::int32 >& + bodyuniqueids() const; + ::google::protobuf::RepeatedField< ::google::protobuf::int32 >* + mutable_bodyuniqueids(); + + // @@protoc_insertion_point(class_scope:pybullet_grpc.MjcfLoadedStatus) + private: + + ::google::protobuf::internal::InternalMetadataWithArena _internal_metadata_; + ::google::protobuf::RepeatedField< ::google::protobuf::int32 > bodyuniqueids_; + mutable int _bodyuniqueids_cached_byte_size_; + mutable int _cached_size_; + friend struct protobuf_pybullet_2eproto::TableStruct; +}; +// ------------------------------------------------------------------- + +class ChangeDynamicsCommand : public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:pybullet_grpc.ChangeDynamicsCommand) */ { + public: + ChangeDynamicsCommand(); + virtual ~ChangeDynamicsCommand(); + + ChangeDynamicsCommand(const ChangeDynamicsCommand& from); + + inline ChangeDynamicsCommand& operator=(const ChangeDynamicsCommand& from) { + CopyFrom(from); + return *this; + } + + static const ::google::protobuf::Descriptor* descriptor(); + static const ChangeDynamicsCommand& default_instance(); + + enum HasMassCase { + kMass = 3, + HASMASS_NOT_SET = 0, + }; + + enum HasLateralFrictionCase { + kLateralFriction = 5, + HASLATERALFRICTION_NOT_SET = 0, + }; + + enum HasSpinningFrictionCase { + kSpinningFriction = 6, + HASSPINNINGFRICTION_NOT_SET = 0, + }; + + enum HasRollingFrictionCase { + kRollingFriction = 7, + HASROLLINGFRICTION_NOT_SET = 0, + }; + + enum HasRestitutionCase { + kRestitution = 8, + HASRESTITUTION_NOT_SET = 0, + }; + + enum HaslinearDampingCase { + kLinearDamping = 9, + HASLINEARDAMPING_NOT_SET = 0, + }; + + enum HasangularDampingCase { + kAngularDamping = 10, + HASANGULARDAMPING_NOT_SET = 0, + }; + + enum HasContactStiffnessCase { + kContactStiffness = 11, + HASCONTACTSTIFFNESS_NOT_SET = 0, + }; + + enum HasContactDampingCase { + kContactDamping = 12, + HASCONTACTDAMPING_NOT_SET = 0, + }; + + enum HasLocalInertiaDiagonalCase { + kLocalInertiaDiagonal = 13, + HASLOCALINERTIADIAGONAL_NOT_SET = 0, + }; + + enum HasFrictionAnchorCase { + kFrictionAnchor = 14, + HASFRICTIONANCHOR_NOT_SET = 0, + }; + + enum HasccdSweptSphereRadiusCase { + kCcdSweptSphereRadius = 15, + HASCCDSWEPTSPHERERADIUS_NOT_SET = 0, + }; + + enum HasContactProcessingThresholdCase { + kContactProcessingThreshold = 16, + HASCONTACTPROCESSINGTHRESHOLD_NOT_SET = 0, + }; + + enum HasActivationStateCase { + kActivationState = 17, + HASACTIVATIONSTATE_NOT_SET = 0, + }; + + static inline const ChangeDynamicsCommand* internal_default_instance() { + return reinterpret_cast( + &_ChangeDynamicsCommand_default_instance_); + } + + void Swap(ChangeDynamicsCommand* other); + + // implements Message ---------------------------------------------- + + inline ChangeDynamicsCommand* New() const PROTOBUF_FINAL { return New(NULL); } + + ChangeDynamicsCommand* 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 ChangeDynamicsCommand& from); + void MergeFrom(const ChangeDynamicsCommand& 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(ChangeDynamicsCommand* 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 bodyUniqueId = 1; + void clear_bodyuniqueid(); + static const int kBodyUniqueIdFieldNumber = 1; + ::google::protobuf::int32 bodyuniqueid() const; + void set_bodyuniqueid(::google::protobuf::int32 value); + + // int32 linkIndex = 2; + void clear_linkindex(); + static const int kLinkIndexFieldNumber = 2; + ::google::protobuf::int32 linkindex() const; + void set_linkindex(::google::protobuf::int32 value); + + // double mass = 3; + private: + bool has_mass() const; + public: + void clear_mass(); + static const int kMassFieldNumber = 3; + double mass() const; + void set_mass(double value); + + // double lateralFriction = 5; + private: + bool has_lateralfriction() const; + public: + void clear_lateralfriction(); + static const int kLateralFrictionFieldNumber = 5; + double lateralfriction() const; + void set_lateralfriction(double value); + + // double spinningFriction = 6; + private: + bool has_spinningfriction() const; + public: + void clear_spinningfriction(); + static const int kSpinningFrictionFieldNumber = 6; + double spinningfriction() const; + void set_spinningfriction(double value); + + // double rollingFriction = 7; + private: + bool has_rollingfriction() const; + public: + void clear_rollingfriction(); + static const int kRollingFrictionFieldNumber = 7; + double rollingfriction() const; + void set_rollingfriction(double value); + + // double restitution = 8; + private: + bool has_restitution() const; + public: + void clear_restitution(); + static const int kRestitutionFieldNumber = 8; + double restitution() const; + void set_restitution(double value); + + // double linearDamping = 9; + private: + bool has_lineardamping() const; + public: + void clear_lineardamping(); + static const int kLinearDampingFieldNumber = 9; + double lineardamping() const; + void set_lineardamping(double value); + + // double angularDamping = 10; + private: + bool has_angulardamping() const; + public: + void clear_angulardamping(); + static const int kAngularDampingFieldNumber = 10; + double angulardamping() const; + void set_angulardamping(double value); + + // double contactStiffness = 11; + private: + bool has_contactstiffness() const; + public: + void clear_contactstiffness(); + static const int kContactStiffnessFieldNumber = 11; + double contactstiffness() const; + void set_contactstiffness(double value); + + // double contactDamping = 12; + private: + bool has_contactdamping() const; + public: + void clear_contactdamping(); + static const int kContactDampingFieldNumber = 12; + double contactdamping() const; + void set_contactdamping(double value); + + // .pybullet_grpc.vec3 localInertiaDiagonal = 13; + bool has_localinertiadiagonal() const; + void clear_localinertiadiagonal(); + static const int kLocalInertiaDiagonalFieldNumber = 13; + const ::pybullet_grpc::vec3& localinertiadiagonal() const; + ::pybullet_grpc::vec3* mutable_localinertiadiagonal(); + ::pybullet_grpc::vec3* release_localinertiadiagonal(); + void set_allocated_localinertiadiagonal(::pybullet_grpc::vec3* localinertiadiagonal); + + // int32 frictionAnchor = 14; + private: + bool has_frictionanchor() const; + public: + void clear_frictionanchor(); + static const int kFrictionAnchorFieldNumber = 14; + ::google::protobuf::int32 frictionanchor() const; + void set_frictionanchor(::google::protobuf::int32 value); + + // double ccdSweptSphereRadius = 15; + private: + bool has_ccdsweptsphereradius() const; + public: + void clear_ccdsweptsphereradius(); + static const int kCcdSweptSphereRadiusFieldNumber = 15; + double ccdsweptsphereradius() const; + void set_ccdsweptsphereradius(double value); + + // double contactProcessingThreshold = 16; + private: + bool has_contactprocessingthreshold() const; + public: + void clear_contactprocessingthreshold(); + static const int kContactProcessingThresholdFieldNumber = 16; + double contactprocessingthreshold() const; + void set_contactprocessingthreshold(double value); + + // int32 activationState = 17; + private: + bool has_activationstate() const; + public: + void clear_activationstate(); + static const int kActivationStateFieldNumber = 17; + ::google::protobuf::int32 activationstate() const; + void set_activationstate(::google::protobuf::int32 value); + + HasMassCase hasMass_case() const; + HasLateralFrictionCase hasLateralFriction_case() const; + HasSpinningFrictionCase hasSpinningFriction_case() const; + HasRollingFrictionCase hasRollingFriction_case() const; + HasRestitutionCase hasRestitution_case() const; + HaslinearDampingCase haslinearDamping_case() const; + HasangularDampingCase hasangularDamping_case() const; + HasContactStiffnessCase hasContactStiffness_case() const; + HasContactDampingCase hasContactDamping_case() const; + HasLocalInertiaDiagonalCase hasLocalInertiaDiagonal_case() const; + HasFrictionAnchorCase hasFrictionAnchor_case() const; + HasccdSweptSphereRadiusCase hasccdSweptSphereRadius_case() const; + HasContactProcessingThresholdCase hasContactProcessingThreshold_case() const; + HasActivationStateCase hasActivationState_case() const; + // @@protoc_insertion_point(class_scope:pybullet_grpc.ChangeDynamicsCommand) + private: + void set_has_mass(); + void set_has_lateralfriction(); + void set_has_spinningfriction(); + void set_has_rollingfriction(); + void set_has_restitution(); + void set_has_lineardamping(); + void set_has_angulardamping(); + void set_has_contactstiffness(); + void set_has_contactdamping(); + void set_has_localinertiadiagonal(); + void set_has_frictionanchor(); + void set_has_ccdsweptsphereradius(); + void set_has_contactprocessingthreshold(); + void set_has_activationstate(); + + inline bool has_hasMass() const; + void clear_hasMass(); + inline void clear_has_hasMass(); + + inline bool has_hasLateralFriction() const; + void clear_hasLateralFriction(); + inline void clear_has_hasLateralFriction(); + + inline bool has_hasSpinningFriction() const; + void clear_hasSpinningFriction(); + inline void clear_has_hasSpinningFriction(); + + inline bool has_hasRollingFriction() const; + void clear_hasRollingFriction(); + inline void clear_has_hasRollingFriction(); + + inline bool has_hasRestitution() const; + void clear_hasRestitution(); + inline void clear_has_hasRestitution(); + + inline bool has_haslinearDamping() const; + void clear_haslinearDamping(); + inline void clear_has_haslinearDamping(); + + inline bool has_hasangularDamping() const; + void clear_hasangularDamping(); + inline void clear_has_hasangularDamping(); + + inline bool has_hasContactStiffness() const; + void clear_hasContactStiffness(); + inline void clear_has_hasContactStiffness(); + + inline bool has_hasContactDamping() const; + void clear_hasContactDamping(); + inline void clear_has_hasContactDamping(); + + inline bool has_hasLocalInertiaDiagonal() const; + void clear_hasLocalInertiaDiagonal(); + inline void clear_has_hasLocalInertiaDiagonal(); + + inline bool has_hasFrictionAnchor() const; + void clear_hasFrictionAnchor(); + inline void clear_has_hasFrictionAnchor(); + + inline bool has_hasccdSweptSphereRadius() const; + void clear_hasccdSweptSphereRadius(); + inline void clear_has_hasccdSweptSphereRadius(); + + inline bool has_hasContactProcessingThreshold() const; + void clear_hasContactProcessingThreshold(); + inline void clear_has_hasContactProcessingThreshold(); + + inline bool has_hasActivationState() const; + void clear_hasActivationState(); + inline void clear_has_hasActivationState(); + + ::google::protobuf::internal::InternalMetadataWithArena _internal_metadata_; + ::google::protobuf::int32 bodyuniqueid_; + ::google::protobuf::int32 linkindex_; + union HasMassUnion { + HasMassUnion() {} + double mass_; + } hasMass_; + union HasLateralFrictionUnion { + HasLateralFrictionUnion() {} + double lateralfriction_; + } hasLateralFriction_; + union HasSpinningFrictionUnion { + HasSpinningFrictionUnion() {} + double spinningfriction_; + } hasSpinningFriction_; + union HasRollingFrictionUnion { + HasRollingFrictionUnion() {} + double rollingfriction_; + } hasRollingFriction_; + union HasRestitutionUnion { + HasRestitutionUnion() {} + double restitution_; + } hasRestitution_; + union HaslinearDampingUnion { + HaslinearDampingUnion() {} + double lineardamping_; + } haslinearDamping_; + union HasangularDampingUnion { + HasangularDampingUnion() {} + double angulardamping_; + } hasangularDamping_; + union HasContactStiffnessUnion { + HasContactStiffnessUnion() {} + double contactstiffness_; + } hasContactStiffness_; + union HasContactDampingUnion { + HasContactDampingUnion() {} + double contactdamping_; + } hasContactDamping_; + union HasLocalInertiaDiagonalUnion { + HasLocalInertiaDiagonalUnion() {} + ::pybullet_grpc::vec3* localinertiadiagonal_; + } hasLocalInertiaDiagonal_; + union HasFrictionAnchorUnion { + HasFrictionAnchorUnion() {} + ::google::protobuf::int32 frictionanchor_; + } hasFrictionAnchor_; + union HasccdSweptSphereRadiusUnion { + HasccdSweptSphereRadiusUnion() {} + double ccdsweptsphereradius_; + } hasccdSweptSphereRadius_; + union HasContactProcessingThresholdUnion { + HasContactProcessingThresholdUnion() {} + double contactprocessingthreshold_; + } hasContactProcessingThreshold_; + union HasActivationStateUnion { + HasActivationStateUnion() {} + ::google::protobuf::int32 activationstate_; + } hasActivationState_; + mutable int _cached_size_; + ::google::protobuf::uint32 _oneof_case_[14]; + + friend struct protobuf_pybullet_2eproto::TableStruct; +}; +// ------------------------------------------------------------------- + +class GetDynamicsCommand : public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:pybullet_grpc.GetDynamicsCommand) */ { + public: + GetDynamicsCommand(); + virtual ~GetDynamicsCommand(); + + GetDynamicsCommand(const GetDynamicsCommand& from); + + inline GetDynamicsCommand& operator=(const GetDynamicsCommand& from) { + CopyFrom(from); + return *this; + } + + static const ::google::protobuf::Descriptor* descriptor(); + static const GetDynamicsCommand& default_instance(); + + static inline const GetDynamicsCommand* internal_default_instance() { + return reinterpret_cast( + &_GetDynamicsCommand_default_instance_); + } + + void Swap(GetDynamicsCommand* other); + + // implements Message ---------------------------------------------- + + inline GetDynamicsCommand* New() const PROTOBUF_FINAL { return New(NULL); } + + GetDynamicsCommand* 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 GetDynamicsCommand& from); + void MergeFrom(const GetDynamicsCommand& 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(GetDynamicsCommand* 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 bodyUniqueId = 1; + void clear_bodyuniqueid(); + static const int kBodyUniqueIdFieldNumber = 1; + ::google::protobuf::int32 bodyuniqueid() const; + void set_bodyuniqueid(::google::protobuf::int32 value); + + // int32 linkIndex = 2; + void clear_linkindex(); + static const int kLinkIndexFieldNumber = 2; + ::google::protobuf::int32 linkindex() const; + void set_linkindex(::google::protobuf::int32 value); + + // @@protoc_insertion_point(class_scope:pybullet_grpc.GetDynamicsCommand) + private: + + ::google::protobuf::internal::InternalMetadataWithArena _internal_metadata_; + ::google::protobuf::int32 bodyuniqueid_; + ::google::protobuf::int32 linkindex_; + mutable int _cached_size_; + friend struct protobuf_pybullet_2eproto::TableStruct; +}; +// ------------------------------------------------------------------- + +class GetDynamicsStatus : public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:pybullet_grpc.GetDynamicsStatus) */ { + public: + GetDynamicsStatus(); + virtual ~GetDynamicsStatus(); + + GetDynamicsStatus(const GetDynamicsStatus& from); + + inline GetDynamicsStatus& operator=(const GetDynamicsStatus& from) { + CopyFrom(from); + return *this; + } + + static const ::google::protobuf::Descriptor* descriptor(); + static const GetDynamicsStatus& default_instance(); + + static inline const GetDynamicsStatus* internal_default_instance() { + return reinterpret_cast( + &_GetDynamicsStatus_default_instance_); + } + + void Swap(GetDynamicsStatus* other); + + // implements Message ---------------------------------------------- + + inline GetDynamicsStatus* New() const PROTOBUF_FINAL { return New(NULL); } + + GetDynamicsStatus* 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 GetDynamicsStatus& from); + void MergeFrom(const GetDynamicsStatus& 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(GetDynamicsStatus* 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 ------------------------------------------------------- + + // .pybullet_grpc.vec3 localInertiaDiagonal = 13; + bool has_localinertiadiagonal() const; + void clear_localinertiadiagonal(); + static const int kLocalInertiaDiagonalFieldNumber = 13; + const ::pybullet_grpc::vec3& localinertiadiagonal() const; + ::pybullet_grpc::vec3* mutable_localinertiadiagonal(); + ::pybullet_grpc::vec3* release_localinertiadiagonal(); + void set_allocated_localinertiadiagonal(::pybullet_grpc::vec3* localinertiadiagonal); + + // double mass = 3; + void clear_mass(); + static const int kMassFieldNumber = 3; + double mass() const; + void set_mass(double value); + + // double lateralFriction = 5; + void clear_lateralfriction(); + static const int kLateralFrictionFieldNumber = 5; + double lateralfriction() const; + void set_lateralfriction(double value); + + // double spinningFriction = 6; + void clear_spinningfriction(); + static const int kSpinningFrictionFieldNumber = 6; + double spinningfriction() const; + void set_spinningfriction(double value); + + // double rollingFriction = 7; + void clear_rollingfriction(); + static const int kRollingFrictionFieldNumber = 7; + double rollingfriction() const; + void set_rollingfriction(double value); + + // double restitution = 8; + void clear_restitution(); + static const int kRestitutionFieldNumber = 8; + double restitution() const; + void set_restitution(double value); + + // double linearDamping = 9; + void clear_lineardamping(); + static const int kLinearDampingFieldNumber = 9; + double lineardamping() const; + void set_lineardamping(double value); + + // double angularDamping = 10; + void clear_angulardamping(); + static const int kAngularDampingFieldNumber = 10; + double angulardamping() const; + void set_angulardamping(double value); + + // double contactStiffness = 11; + void clear_contactstiffness(); + static const int kContactStiffnessFieldNumber = 11; + double contactstiffness() const; + void set_contactstiffness(double value); + + // double contactDamping = 12; + void clear_contactdamping(); + static const int kContactDampingFieldNumber = 12; + double contactdamping() const; + void set_contactdamping(double value); + + // double ccdSweptSphereRadius = 15; + void clear_ccdsweptsphereradius(); + static const int kCcdSweptSphereRadiusFieldNumber = 15; + double ccdsweptsphereradius() const; + void set_ccdsweptsphereradius(double value); + + // int32 frictionAnchor = 14; + void clear_frictionanchor(); + static const int kFrictionAnchorFieldNumber = 14; + ::google::protobuf::int32 frictionanchor() const; + void set_frictionanchor(::google::protobuf::int32 value); + + // int32 activationState = 17; + void clear_activationstate(); + static const int kActivationStateFieldNumber = 17; + ::google::protobuf::int32 activationstate() const; + void set_activationstate(::google::protobuf::int32 value); + + // double contactProcessingThreshold = 16; + void clear_contactprocessingthreshold(); + static const int kContactProcessingThresholdFieldNumber = 16; + double contactprocessingthreshold() const; + void set_contactprocessingthreshold(double value); + + // @@protoc_insertion_point(class_scope:pybullet_grpc.GetDynamicsStatus) + private: + + ::google::protobuf::internal::InternalMetadataWithArena _internal_metadata_; + ::pybullet_grpc::vec3* localinertiadiagonal_; + double mass_; + double lateralfriction_; + double spinningfriction_; + double rollingfriction_; + double restitution_; + double lineardamping_; + double angulardamping_; + double contactstiffness_; + double contactdamping_; + double ccdsweptsphereradius_; + ::google::protobuf::int32 frictionanchor_; + ::google::protobuf::int32 activationstate_; + double contactprocessingthreshold_; + mutable int _cached_size_; + friend struct protobuf_pybullet_2eproto::TableStruct; +}; +// ------------------------------------------------------------------- + +class InitPoseCommand : public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:pybullet_grpc.InitPoseCommand) */ { + public: + InitPoseCommand(); + virtual ~InitPoseCommand(); + + InitPoseCommand(const InitPoseCommand& from); + + inline InitPoseCommand& operator=(const InitPoseCommand& from) { + CopyFrom(from); + return *this; + } + + static const ::google::protobuf::Descriptor* descriptor(); + static const InitPoseCommand& default_instance(); + + static inline const InitPoseCommand* internal_default_instance() { + return reinterpret_cast( + &_InitPoseCommand_default_instance_); + } + + void Swap(InitPoseCommand* other); + + // implements Message ---------------------------------------------- + + inline InitPoseCommand* New() const PROTOBUF_FINAL { return New(NULL); } + + InitPoseCommand* 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 InitPoseCommand& from); + void MergeFrom(const InitPoseCommand& 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(InitPoseCommand* 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 ------------------------------------------------------- + + // repeated int32 hasInitialStateQ = 2; + int hasinitialstateq_size() const; + void clear_hasinitialstateq(); + static const int kHasInitialStateQFieldNumber = 2; + ::google::protobuf::int32 hasinitialstateq(int index) const; + void set_hasinitialstateq(int index, ::google::protobuf::int32 value); + void add_hasinitialstateq(::google::protobuf::int32 value); + const ::google::protobuf::RepeatedField< ::google::protobuf::int32 >& + hasinitialstateq() const; + ::google::protobuf::RepeatedField< ::google::protobuf::int32 >* + mutable_hasinitialstateq(); + + // repeated double initialStateQ = 3; + int initialstateq_size() const; + void clear_initialstateq(); + static const int kInitialStateQFieldNumber = 3; + double initialstateq(int index) const; + void set_initialstateq(int index, double value); + void add_initialstateq(double value); + const ::google::protobuf::RepeatedField< double >& + initialstateq() const; + ::google::protobuf::RepeatedField< double >* + mutable_initialstateq(); + + // repeated int32 hasInitialStateQdot = 4; + int hasinitialstateqdot_size() const; + void clear_hasinitialstateqdot(); + static const int kHasInitialStateQdotFieldNumber = 4; + ::google::protobuf::int32 hasinitialstateqdot(int index) const; + void set_hasinitialstateqdot(int index, ::google::protobuf::int32 value); + void add_hasinitialstateqdot(::google::protobuf::int32 value); + const ::google::protobuf::RepeatedField< ::google::protobuf::int32 >& + hasinitialstateqdot() const; + ::google::protobuf::RepeatedField< ::google::protobuf::int32 >* + mutable_hasinitialstateqdot(); + + // repeated double initialStateQdot = 5; + int initialstateqdot_size() const; + void clear_initialstateqdot(); + static const int kInitialStateQdotFieldNumber = 5; + double initialstateqdot(int index) const; + void set_initialstateqdot(int index, double value); + void add_initialstateqdot(double value); + const ::google::protobuf::RepeatedField< double >& + initialstateqdot() const; + ::google::protobuf::RepeatedField< double >* + mutable_initialstateqdot(); + + // int32 bodyUniqueId = 1; + void clear_bodyuniqueid(); + static const int kBodyUniqueIdFieldNumber = 1; + ::google::protobuf::int32 bodyuniqueid() const; + void set_bodyuniqueid(::google::protobuf::int32 value); + + // @@protoc_insertion_point(class_scope:pybullet_grpc.InitPoseCommand) + private: + + ::google::protobuf::internal::InternalMetadataWithArena _internal_metadata_; + ::google::protobuf::RepeatedField< ::google::protobuf::int32 > hasinitialstateq_; + mutable int _hasinitialstateq_cached_byte_size_; + ::google::protobuf::RepeatedField< double > initialstateq_; + mutable int _initialstateq_cached_byte_size_; + ::google::protobuf::RepeatedField< ::google::protobuf::int32 > hasinitialstateqdot_; + mutable int _hasinitialstateqdot_cached_byte_size_; + ::google::protobuf::RepeatedField< double > initialstateqdot_; + mutable int _initialstateqdot_cached_byte_size_; + ::google::protobuf::int32 bodyuniqueid_; + mutable int _cached_size_; + friend struct protobuf_pybullet_2eproto::TableStruct; +}; +// ------------------------------------------------------------------- + +class RequestActualStateCommand : public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:pybullet_grpc.RequestActualStateCommand) */ { + public: + RequestActualStateCommand(); + virtual ~RequestActualStateCommand(); + + RequestActualStateCommand(const RequestActualStateCommand& from); + + inline RequestActualStateCommand& operator=(const RequestActualStateCommand& from) { + CopyFrom(from); + return *this; + } + + static const ::google::protobuf::Descriptor* descriptor(); + static const RequestActualStateCommand& default_instance(); + + static inline const RequestActualStateCommand* internal_default_instance() { + return reinterpret_cast( + &_RequestActualStateCommand_default_instance_); + } + + void Swap(RequestActualStateCommand* other); + + // implements Message ---------------------------------------------- + + inline RequestActualStateCommand* New() const PROTOBUF_FINAL { return New(NULL); } + + RequestActualStateCommand* 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 RequestActualStateCommand& from); + void MergeFrom(const RequestActualStateCommand& 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(RequestActualStateCommand* 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 bodyUniqueId = 1; + void clear_bodyuniqueid(); + static const int kBodyUniqueIdFieldNumber = 1; + ::google::protobuf::int32 bodyuniqueid() const; + void set_bodyuniqueid(::google::protobuf::int32 value); + + // bool computeForwardKinematics = 2; + void clear_computeforwardkinematics(); + static const int kComputeForwardKinematicsFieldNumber = 2; + bool computeforwardkinematics() const; + void set_computeforwardkinematics(bool value); + + // bool computeLinkVelocities = 3; + void clear_computelinkvelocities(); + static const int kComputeLinkVelocitiesFieldNumber = 3; + bool computelinkvelocities() const; + void set_computelinkvelocities(bool value); + + // @@protoc_insertion_point(class_scope:pybullet_grpc.RequestActualStateCommand) + private: + + ::google::protobuf::internal::InternalMetadataWithArena _internal_metadata_; + ::google::protobuf::int32 bodyuniqueid_; + bool computeforwardkinematics_; + bool computelinkvelocities_; + mutable int _cached_size_; + friend struct protobuf_pybullet_2eproto::TableStruct; +}; +// ------------------------------------------------------------------- + +class SendActualStateStatus : public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:pybullet_grpc.SendActualStateStatus) */ { + public: + SendActualStateStatus(); + virtual ~SendActualStateStatus(); + + SendActualStateStatus(const SendActualStateStatus& from); + + inline SendActualStateStatus& operator=(const SendActualStateStatus& from) { + CopyFrom(from); + return *this; + } + + static const ::google::protobuf::Descriptor* descriptor(); + static const SendActualStateStatus& default_instance(); + + static inline const SendActualStateStatus* internal_default_instance() { + return reinterpret_cast( + &_SendActualStateStatus_default_instance_); + } + + void Swap(SendActualStateStatus* other); + + // implements Message ---------------------------------------------- + + inline SendActualStateStatus* New() const PROTOBUF_FINAL { return New(NULL); } + + SendActualStateStatus* 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 SendActualStateStatus& from); + void MergeFrom(const SendActualStateStatus& 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(SendActualStateStatus* 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 ------------------------------------------------------- + + // repeated double rootLocalInertialFrame = 5; + int rootlocalinertialframe_size() const; + void clear_rootlocalinertialframe(); + static const int kRootLocalInertialFrameFieldNumber = 5; + double rootlocalinertialframe(int index) const; + void set_rootlocalinertialframe(int index, double value); + void add_rootlocalinertialframe(double value); + const ::google::protobuf::RepeatedField< double >& + rootlocalinertialframe() const; + ::google::protobuf::RepeatedField< double >* + mutable_rootlocalinertialframe(); + + // repeated double actualStateQ = 6; + int actualstateq_size() const; + void clear_actualstateq(); + static const int kActualStateQFieldNumber = 6; + double actualstateq(int index) const; + void set_actualstateq(int index, double value); + void add_actualstateq(double value); + const ::google::protobuf::RepeatedField< double >& + actualstateq() const; + ::google::protobuf::RepeatedField< double >* + mutable_actualstateq(); + + // repeated double actualStateQdot = 7; + int actualstateqdot_size() const; + void clear_actualstateqdot(); + static const int kActualStateQdotFieldNumber = 7; + double actualstateqdot(int index) const; + void set_actualstateqdot(int index, double value); + void add_actualstateqdot(double value); + const ::google::protobuf::RepeatedField< double >& + actualstateqdot() const; + ::google::protobuf::RepeatedField< double >* + mutable_actualstateqdot(); + + // repeated double jointReactionForces = 8; + int jointreactionforces_size() const; + void clear_jointreactionforces(); + static const int kJointReactionForcesFieldNumber = 8; + double jointreactionforces(int index) const; + void set_jointreactionforces(int index, double value); + void add_jointreactionforces(double value); + const ::google::protobuf::RepeatedField< double >& + jointreactionforces() const; + ::google::protobuf::RepeatedField< double >* + mutable_jointreactionforces(); + + // repeated double jointMotorForce = 9; + int jointmotorforce_size() const; + void clear_jointmotorforce(); + static const int kJointMotorForceFieldNumber = 9; + double jointmotorforce(int index) const; + void set_jointmotorforce(int index, double value); + void add_jointmotorforce(double value); + const ::google::protobuf::RepeatedField< double >& + jointmotorforce() const; + ::google::protobuf::RepeatedField< double >* + mutable_jointmotorforce(); + + // repeated double linkState = 10; + int linkstate_size() const; + void clear_linkstate(); + static const int kLinkStateFieldNumber = 10; + double linkstate(int index) const; + void set_linkstate(int index, double value); + void add_linkstate(double value); + const ::google::protobuf::RepeatedField< double >& + linkstate() const; + ::google::protobuf::RepeatedField< double >* + mutable_linkstate(); + + // repeated double linkWorldVelocities = 11; + int linkworldvelocities_size() const; + void clear_linkworldvelocities(); + static const int kLinkWorldVelocitiesFieldNumber = 11; + double linkworldvelocities(int index) const; + void set_linkworldvelocities(int index, double value); + void add_linkworldvelocities(double value); + const ::google::protobuf::RepeatedField< double >& + linkworldvelocities() const; + ::google::protobuf::RepeatedField< double >* + mutable_linkworldvelocities(); + + // repeated double linkLocalInertialFrames = 12; + int linklocalinertialframes_size() const; + void clear_linklocalinertialframes(); + static const int kLinkLocalInertialFramesFieldNumber = 12; + double linklocalinertialframes(int index) const; + void set_linklocalinertialframes(int index, double value); + void add_linklocalinertialframes(double value); + const ::google::protobuf::RepeatedField< double >& + linklocalinertialframes() const; + ::google::protobuf::RepeatedField< double >* + mutable_linklocalinertialframes(); + + // int32 bodyUniqueId = 1; + void clear_bodyuniqueid(); + static const int kBodyUniqueIdFieldNumber = 1; + ::google::protobuf::int32 bodyuniqueid() const; + void set_bodyuniqueid(::google::protobuf::int32 value); + + // int32 numLinks = 2; + void clear_numlinks(); + static const int kNumLinksFieldNumber = 2; + ::google::protobuf::int32 numlinks() const; + void set_numlinks(::google::protobuf::int32 value); + + // int32 numDegreeOfFreedomQ = 3; + void clear_numdegreeoffreedomq(); + static const int kNumDegreeOfFreedomQFieldNumber = 3; + ::google::protobuf::int32 numdegreeoffreedomq() const; + void set_numdegreeoffreedomq(::google::protobuf::int32 value); + + // int32 numDegreeOfFreedomU = 4; + void clear_numdegreeoffreedomu(); + static const int kNumDegreeOfFreedomUFieldNumber = 4; + ::google::protobuf::int32 numdegreeoffreedomu() const; + void set_numdegreeoffreedomu(::google::protobuf::int32 value); + + // @@protoc_insertion_point(class_scope:pybullet_grpc.SendActualStateStatus) + private: + + ::google::protobuf::internal::InternalMetadataWithArena _internal_metadata_; + ::google::protobuf::RepeatedField< double > rootlocalinertialframe_; + mutable int _rootlocalinertialframe_cached_byte_size_; + ::google::protobuf::RepeatedField< double > actualstateq_; + mutable int _actualstateq_cached_byte_size_; + ::google::protobuf::RepeatedField< double > actualstateqdot_; + mutable int _actualstateqdot_cached_byte_size_; + ::google::protobuf::RepeatedField< double > jointreactionforces_; + mutable int _jointreactionforces_cached_byte_size_; + ::google::protobuf::RepeatedField< double > jointmotorforce_; + mutable int _jointmotorforce_cached_byte_size_; + ::google::protobuf::RepeatedField< double > linkstate_; + mutable int _linkstate_cached_byte_size_; + ::google::protobuf::RepeatedField< double > linkworldvelocities_; + mutable int _linkworldvelocities_cached_byte_size_; + ::google::protobuf::RepeatedField< double > linklocalinertialframes_; + mutable int _linklocalinertialframes_cached_byte_size_; + ::google::protobuf::int32 bodyuniqueid_; + ::google::protobuf::int32 numlinks_; + ::google::protobuf::int32 numdegreeoffreedomq_; + ::google::protobuf::int32 numdegreeoffreedomu_; mutable int _cached_size_; friend struct protobuf_pybullet_2eproto::TableStruct; }; @@ -733,6 +2329,12 @@ class PyBulletCommand : public ::google::protobuf::Message /* @@protoc_insertion kLoadUrdfCommand = 3, kTerminateServerCommand = 4, kStepSimulationCommand = 5, + kLoadSdfCommand = 6, + kLoadMjcfCommand = 7, + kChangeDynamicsCommand = 8, + kGetDynamicsCommand = 9, + kInitPoseCommand = 10, + kRequestActualStateCommand = 11, COMMANDS_NOT_SET = 0, }; @@ -821,12 +2423,72 @@ class PyBulletCommand : public ::google::protobuf::Message /* @@protoc_insertion ::pybullet_grpc::StepSimulationCommand* release_stepsimulationcommand(); void set_allocated_stepsimulationcommand(::pybullet_grpc::StepSimulationCommand* stepsimulationcommand); + // .pybullet_grpc.LoadSdfCommand loadSdfCommand = 6; + bool has_loadsdfcommand() const; + void clear_loadsdfcommand(); + static const int kLoadSdfCommandFieldNumber = 6; + const ::pybullet_grpc::LoadSdfCommand& loadsdfcommand() const; + ::pybullet_grpc::LoadSdfCommand* mutable_loadsdfcommand(); + ::pybullet_grpc::LoadSdfCommand* release_loadsdfcommand(); + void set_allocated_loadsdfcommand(::pybullet_grpc::LoadSdfCommand* loadsdfcommand); + + // .pybullet_grpc.LoadMjcfCommand loadMjcfCommand = 7; + bool has_loadmjcfcommand() const; + void clear_loadmjcfcommand(); + static const int kLoadMjcfCommandFieldNumber = 7; + const ::pybullet_grpc::LoadMjcfCommand& loadmjcfcommand() const; + ::pybullet_grpc::LoadMjcfCommand* mutable_loadmjcfcommand(); + ::pybullet_grpc::LoadMjcfCommand* release_loadmjcfcommand(); + void set_allocated_loadmjcfcommand(::pybullet_grpc::LoadMjcfCommand* loadmjcfcommand); + + // .pybullet_grpc.ChangeDynamicsCommand changeDynamicsCommand = 8; + bool has_changedynamicscommand() const; + void clear_changedynamicscommand(); + static const int kChangeDynamicsCommandFieldNumber = 8; + const ::pybullet_grpc::ChangeDynamicsCommand& changedynamicscommand() const; + ::pybullet_grpc::ChangeDynamicsCommand* mutable_changedynamicscommand(); + ::pybullet_grpc::ChangeDynamicsCommand* release_changedynamicscommand(); + void set_allocated_changedynamicscommand(::pybullet_grpc::ChangeDynamicsCommand* changedynamicscommand); + + // .pybullet_grpc.GetDynamicsCommand getDynamicsCommand = 9; + bool has_getdynamicscommand() const; + void clear_getdynamicscommand(); + static const int kGetDynamicsCommandFieldNumber = 9; + const ::pybullet_grpc::GetDynamicsCommand& getdynamicscommand() const; + ::pybullet_grpc::GetDynamicsCommand* mutable_getdynamicscommand(); + ::pybullet_grpc::GetDynamicsCommand* release_getdynamicscommand(); + void set_allocated_getdynamicscommand(::pybullet_grpc::GetDynamicsCommand* getdynamicscommand); + + // .pybullet_grpc.InitPoseCommand initPoseCommand = 10; + bool has_initposecommand() const; + void clear_initposecommand(); + static const int kInitPoseCommandFieldNumber = 10; + const ::pybullet_grpc::InitPoseCommand& initposecommand() const; + ::pybullet_grpc::InitPoseCommand* mutable_initposecommand(); + ::pybullet_grpc::InitPoseCommand* release_initposecommand(); + void set_allocated_initposecommand(::pybullet_grpc::InitPoseCommand* initposecommand); + + // .pybullet_grpc.RequestActualStateCommand requestActualStateCommand = 11; + bool has_requestactualstatecommand() const; + void clear_requestactualstatecommand(); + static const int kRequestActualStateCommandFieldNumber = 11; + const ::pybullet_grpc::RequestActualStateCommand& requestactualstatecommand() const; + ::pybullet_grpc::RequestActualStateCommand* mutable_requestactualstatecommand(); + ::pybullet_grpc::RequestActualStateCommand* release_requestactualstatecommand(); + void set_allocated_requestactualstatecommand(::pybullet_grpc::RequestActualStateCommand* requestactualstatecommand); + 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(); + void set_has_loadsdfcommand(); + void set_has_loadmjcfcommand(); + void set_has_changedynamicscommand(); + void set_has_getdynamicscommand(); + void set_has_initposecommand(); + void set_has_requestactualstatecommand(); inline bool has_commands() const; void clear_commands(); @@ -839,6 +2501,12 @@ class PyBulletCommand : public ::google::protobuf::Message /* @@protoc_insertion ::pybullet_grpc::LoadUrdfCommand* loadurdfcommand_; ::pybullet_grpc::TerminateServerCommand* terminateservercommand_; ::pybullet_grpc::StepSimulationCommand* stepsimulationcommand_; + ::pybullet_grpc::LoadSdfCommand* loadsdfcommand_; + ::pybullet_grpc::LoadMjcfCommand* loadmjcfcommand_; + ::pybullet_grpc::ChangeDynamicsCommand* changedynamicscommand_; + ::pybullet_grpc::GetDynamicsCommand* getdynamicscommand_; + ::pybullet_grpc::InitPoseCommand* initposecommand_; + ::pybullet_grpc::RequestActualStateCommand* requestactualstatecommand_; } commands_; mutable int _cached_size_; ::google::protobuf::uint32 _oneof_case_[1]; @@ -864,6 +2532,10 @@ class PyBulletStatus : public ::google::protobuf::Message /* @@protoc_insertion_ enum StatusCase { kUrdfStatus = 2, + kSdfStatus = 3, + kMjcfStatus = 4, + kGetDynamicsStatus = 5, + kActualStateStatus = 6, STATUS_NOT_SET = 0, }; @@ -934,10 +2606,50 @@ class PyBulletStatus : public ::google::protobuf::Message /* @@protoc_insertion_ ::pybullet_grpc::LoadUrdfStatus* release_urdfstatus(); void set_allocated_urdfstatus(::pybullet_grpc::LoadUrdfStatus* urdfstatus); + // .pybullet_grpc.SdfLoadedStatus sdfStatus = 3; + bool has_sdfstatus() const; + void clear_sdfstatus(); + static const int kSdfStatusFieldNumber = 3; + const ::pybullet_grpc::SdfLoadedStatus& sdfstatus() const; + ::pybullet_grpc::SdfLoadedStatus* mutable_sdfstatus(); + ::pybullet_grpc::SdfLoadedStatus* release_sdfstatus(); + void set_allocated_sdfstatus(::pybullet_grpc::SdfLoadedStatus* sdfstatus); + + // .pybullet_grpc.MjcfLoadedStatus mjcfStatus = 4; + bool has_mjcfstatus() const; + void clear_mjcfstatus(); + static const int kMjcfStatusFieldNumber = 4; + const ::pybullet_grpc::MjcfLoadedStatus& mjcfstatus() const; + ::pybullet_grpc::MjcfLoadedStatus* mutable_mjcfstatus(); + ::pybullet_grpc::MjcfLoadedStatus* release_mjcfstatus(); + void set_allocated_mjcfstatus(::pybullet_grpc::MjcfLoadedStatus* mjcfstatus); + + // .pybullet_grpc.GetDynamicsStatus getDynamicsStatus = 5; + bool has_getdynamicsstatus() const; + void clear_getdynamicsstatus(); + static const int kGetDynamicsStatusFieldNumber = 5; + const ::pybullet_grpc::GetDynamicsStatus& getdynamicsstatus() const; + ::pybullet_grpc::GetDynamicsStatus* mutable_getdynamicsstatus(); + ::pybullet_grpc::GetDynamicsStatus* release_getdynamicsstatus(); + void set_allocated_getdynamicsstatus(::pybullet_grpc::GetDynamicsStatus* getdynamicsstatus); + + // .pybullet_grpc.SendActualStateStatus actualStateStatus = 6; + bool has_actualstatestatus() const; + void clear_actualstatestatus(); + static const int kActualStateStatusFieldNumber = 6; + const ::pybullet_grpc::SendActualStateStatus& actualstatestatus() const; + ::pybullet_grpc::SendActualStateStatus* mutable_actualstatestatus(); + ::pybullet_grpc::SendActualStateStatus* release_actualstatestatus(); + void set_allocated_actualstatestatus(::pybullet_grpc::SendActualStateStatus* actualstatestatus); + StatusCase status_case() const; // @@protoc_insertion_point(class_scope:pybullet_grpc.PyBulletStatus) private: void set_has_urdfstatus(); + void set_has_sdfstatus(); + void set_has_mjcfstatus(); + void set_has_getdynamicsstatus(); + void set_has_actualstatestatus(); inline bool has_status() const; void clear_status(); @@ -948,6 +2660,10 @@ class PyBulletStatus : public ::google::protobuf::Message /* @@protoc_insertion_ union StatusUnion { StatusUnion() {} ::pybullet_grpc::LoadUrdfStatus* urdfstatus_; + ::pybullet_grpc::SdfLoadedStatus* sdfstatus_; + ::pybullet_grpc::MjcfLoadedStatus* mjcfstatus_; + ::pybullet_grpc::GetDynamicsStatus* getdynamicsstatus_; + ::pybullet_grpc::SendActualStateStatus* actualstatestatus_; } status_; mutable int _cached_size_; ::google::protobuf::uint32 _oneof_case_[1]; @@ -1128,56 +2844,56 @@ inline void TerminateServerCommand::set_allocated_exitreason(::std::string* exit // LoadUrdfCommand -// string urdfFileName = 1; -inline void LoadUrdfCommand::clear_urdffilename() { - urdffilename_.ClearToEmptyNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); +// string fileName = 1; +inline void LoadUrdfCommand::clear_filename() { + filename_.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 const ::std::string& LoadUrdfCommand::filename() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.LoadUrdfCommand.fileName) + return filename_.GetNoArena(); } -inline void LoadUrdfCommand::set_urdffilename(const ::std::string& value) { +inline void LoadUrdfCommand::set_filename(const ::std::string& value) { - urdffilename_.SetNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), value); - // @@protoc_insertion_point(field_set:pybullet_grpc.LoadUrdfCommand.urdfFileName) + filename_.SetNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), value); + // @@protoc_insertion_point(field_set:pybullet_grpc.LoadUrdfCommand.fileName) } #if LANG_CXX11 -inline void LoadUrdfCommand::set_urdffilename(::std::string&& value) { +inline void LoadUrdfCommand::set_filename(::std::string&& value) { - urdffilename_.SetNoArena( + filename_.SetNoArena( &::google::protobuf::internal::GetEmptyStringAlreadyInited(), std::move(value)); - // @@protoc_insertion_point(field_set_rvalue:pybullet_grpc.LoadUrdfCommand.urdfFileName) + // @@protoc_insertion_point(field_set_rvalue:pybullet_grpc.LoadUrdfCommand.fileName) } #endif -inline void LoadUrdfCommand::set_urdffilename(const char* value) { +inline void LoadUrdfCommand::set_filename(const char* value) { - urdffilename_.SetNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), ::std::string(value)); - // @@protoc_insertion_point(field_set_char:pybullet_grpc.LoadUrdfCommand.urdfFileName) + filename_.SetNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), ::std::string(value)); + // @@protoc_insertion_point(field_set_char:pybullet_grpc.LoadUrdfCommand.fileName) } -inline void LoadUrdfCommand::set_urdffilename(const char* value, size_t size) { +inline void LoadUrdfCommand::set_filename(const char* value, size_t size) { - urdffilename_.SetNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), + filename_.SetNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), ::std::string(reinterpret_cast(value), size)); - // @@protoc_insertion_point(field_set_pointer:pybullet_grpc.LoadUrdfCommand.urdfFileName) + // @@protoc_insertion_point(field_set_pointer:pybullet_grpc.LoadUrdfCommand.fileName) } -inline ::std::string* LoadUrdfCommand::mutable_urdffilename() { +inline ::std::string* LoadUrdfCommand::mutable_filename() { - // @@protoc_insertion_point(field_mutable:pybullet_grpc.LoadUrdfCommand.urdfFileName) - return urdffilename_.MutableNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); + // @@protoc_insertion_point(field_mutable:pybullet_grpc.LoadUrdfCommand.fileName) + return filename_.MutableNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); } -inline ::std::string* LoadUrdfCommand::release_urdffilename() { - // @@protoc_insertion_point(field_release:pybullet_grpc.LoadUrdfCommand.urdfFileName) +inline ::std::string* LoadUrdfCommand::release_filename() { + // @@protoc_insertion_point(field_release:pybullet_grpc.LoadUrdfCommand.fileName) - return urdffilename_.ReleaseNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); + return filename_.ReleaseNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); } -inline void LoadUrdfCommand::set_allocated_urdffilename(::std::string* urdffilename) { - if (urdffilename != NULL) { +inline void LoadUrdfCommand::set_allocated_filename(::std::string* filename) { + if (filename != NULL) { } else { } - urdffilename_.SetAllocatedNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), urdffilename); - // @@protoc_insertion_point(field_set_allocated:pybullet_grpc.LoadUrdfCommand.urdfFileName) + filename_.SetAllocatedNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), filename); + // @@protoc_insertion_point(field_set_allocated:pybullet_grpc.LoadUrdfCommand.fileName) } // .pybullet_grpc.vec3 initialPosition = 2; @@ -1316,18 +3032,18 @@ inline void LoadUrdfCommand::set_usefixedbase(bool value) { // @@protoc_insertion_point(field_set:pybullet_grpc.LoadUrdfCommand.useFixedBase) } -// int32 urdfFlags = 6; -inline void LoadUrdfCommand::clear_urdfflags() { - urdfflags_ = 0; +// int32 flags = 6; +inline void LoadUrdfCommand::clear_flags() { + flags_ = 0; } -inline ::google::protobuf::int32 LoadUrdfCommand::urdfflags() const { - // @@protoc_insertion_point(field_get:pybullet_grpc.LoadUrdfCommand.urdfFlags) - return urdfflags_; +inline ::google::protobuf::int32 LoadUrdfCommand::flags() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.LoadUrdfCommand.flags) + return flags_; } -inline void LoadUrdfCommand::set_urdfflags(::google::protobuf::int32 value) { +inline void LoadUrdfCommand::set_flags(::google::protobuf::int32 value) { - urdfflags_ = value; - // @@protoc_insertion_point(field_set:pybullet_grpc.LoadUrdfCommand.urdfFlags) + flags_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.LoadUrdfCommand.flags) } // double globalScaling = 7; @@ -1390,18 +3106,1612 @@ inline LoadUrdfCommand::HasGlobalScalingCase LoadUrdfCommand::hasGlobalScaling_c // LoadUrdfStatus -// int32 objectUniqueId = 1; -inline void LoadUrdfStatus::clear_objectuniqueid() { - objectuniqueid_ = 0; +// int32 bodyUniqueId = 1; +inline void LoadUrdfStatus::clear_bodyuniqueid() { + bodyuniqueid_ = 0; } -inline ::google::protobuf::int32 LoadUrdfStatus::objectuniqueid() const { - // @@protoc_insertion_point(field_get:pybullet_grpc.LoadUrdfStatus.objectUniqueId) - return objectuniqueid_; +inline ::google::protobuf::int32 LoadUrdfStatus::bodyuniqueid() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.LoadUrdfStatus.bodyUniqueId) + return bodyuniqueid_; } -inline void LoadUrdfStatus::set_objectuniqueid(::google::protobuf::int32 value) { +inline void LoadUrdfStatus::set_bodyuniqueid(::google::protobuf::int32 value) { - objectuniqueid_ = value; - // @@protoc_insertion_point(field_set:pybullet_grpc.LoadUrdfStatus.objectUniqueId) + bodyuniqueid_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.LoadUrdfStatus.bodyUniqueId) +} + +// ------------------------------------------------------------------- + +// LoadSdfCommand + +// string fileName = 1; +inline void LoadSdfCommand::clear_filename() { + filename_.ClearToEmptyNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); +} +inline const ::std::string& LoadSdfCommand::filename() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.LoadSdfCommand.fileName) + return filename_.GetNoArena(); +} +inline void LoadSdfCommand::set_filename(const ::std::string& value) { + + filename_.SetNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), value); + // @@protoc_insertion_point(field_set:pybullet_grpc.LoadSdfCommand.fileName) +} +#if LANG_CXX11 +inline void LoadSdfCommand::set_filename(::std::string&& value) { + + filename_.SetNoArena( + &::google::protobuf::internal::GetEmptyStringAlreadyInited(), std::move(value)); + // @@protoc_insertion_point(field_set_rvalue:pybullet_grpc.LoadSdfCommand.fileName) +} +#endif +inline void LoadSdfCommand::set_filename(const char* value) { + + filename_.SetNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), ::std::string(value)); + // @@protoc_insertion_point(field_set_char:pybullet_grpc.LoadSdfCommand.fileName) +} +inline void LoadSdfCommand::set_filename(const char* value, size_t size) { + + filename_.SetNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), + ::std::string(reinterpret_cast(value), size)); + // @@protoc_insertion_point(field_set_pointer:pybullet_grpc.LoadSdfCommand.fileName) +} +inline ::std::string* LoadSdfCommand::mutable_filename() { + + // @@protoc_insertion_point(field_mutable:pybullet_grpc.LoadSdfCommand.fileName) + return filename_.MutableNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); +} +inline ::std::string* LoadSdfCommand::release_filename() { + // @@protoc_insertion_point(field_release:pybullet_grpc.LoadSdfCommand.fileName) + + return filename_.ReleaseNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); +} +inline void LoadSdfCommand::set_allocated_filename(::std::string* filename) { + if (filename != NULL) { + + } else { + + } + filename_.SetAllocatedNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), filename); + // @@protoc_insertion_point(field_set_allocated:pybullet_grpc.LoadSdfCommand.fileName) +} + +// int32 useMultiBody = 2; +inline bool LoadSdfCommand::has_usemultibody() const { + return hasUseMultiBody_case() == kUseMultiBody; +} +inline void LoadSdfCommand::set_has_usemultibody() { + _oneof_case_[0] = kUseMultiBody; +} +inline void LoadSdfCommand::clear_usemultibody() { + if (has_usemultibody()) { + hasUseMultiBody_.usemultibody_ = 0; + clear_has_hasUseMultiBody(); + } +} +inline ::google::protobuf::int32 LoadSdfCommand::usemultibody() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.LoadSdfCommand.useMultiBody) + if (has_usemultibody()) { + return hasUseMultiBody_.usemultibody_; + } + return 0; +} +inline void LoadSdfCommand::set_usemultibody(::google::protobuf::int32 value) { + if (!has_usemultibody()) { + clear_hasUseMultiBody(); + set_has_usemultibody(); + } + hasUseMultiBody_.usemultibody_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.LoadSdfCommand.useMultiBody) +} + +// double globalScaling = 3; +inline bool LoadSdfCommand::has_globalscaling() const { + return hasGlobalScaling_case() == kGlobalScaling; +} +inline void LoadSdfCommand::set_has_globalscaling() { + _oneof_case_[1] = kGlobalScaling; +} +inline void LoadSdfCommand::clear_globalscaling() { + if (has_globalscaling()) { + hasGlobalScaling_.globalscaling_ = 0; + clear_has_hasGlobalScaling(); + } +} +inline double LoadSdfCommand::globalscaling() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.LoadSdfCommand.globalScaling) + if (has_globalscaling()) { + return hasGlobalScaling_.globalscaling_; + } + return 0; +} +inline void LoadSdfCommand::set_globalscaling(double value) { + if (!has_globalscaling()) { + clear_hasGlobalScaling(); + set_has_globalscaling(); + } + hasGlobalScaling_.globalscaling_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.LoadSdfCommand.globalScaling) +} + +inline bool LoadSdfCommand::has_hasUseMultiBody() const { + return hasUseMultiBody_case() != HASUSEMULTIBODY_NOT_SET; +} +inline void LoadSdfCommand::clear_has_hasUseMultiBody() { + _oneof_case_[0] = HASUSEMULTIBODY_NOT_SET; +} +inline bool LoadSdfCommand::has_hasGlobalScaling() const { + return hasGlobalScaling_case() != HASGLOBALSCALING_NOT_SET; +} +inline void LoadSdfCommand::clear_has_hasGlobalScaling() { + _oneof_case_[1] = HASGLOBALSCALING_NOT_SET; +} +inline LoadSdfCommand::HasUseMultiBodyCase LoadSdfCommand::hasUseMultiBody_case() const { + return LoadSdfCommand::HasUseMultiBodyCase(_oneof_case_[0]); +} +inline LoadSdfCommand::HasGlobalScalingCase LoadSdfCommand::hasGlobalScaling_case() const { + return LoadSdfCommand::HasGlobalScalingCase(_oneof_case_[1]); +} +// ------------------------------------------------------------------- + +// SdfLoadedStatus + +// repeated int32 bodyUniqueIds = 2; +inline int SdfLoadedStatus::bodyuniqueids_size() const { + return bodyuniqueids_.size(); +} +inline void SdfLoadedStatus::clear_bodyuniqueids() { + bodyuniqueids_.Clear(); +} +inline ::google::protobuf::int32 SdfLoadedStatus::bodyuniqueids(int index) const { + // @@protoc_insertion_point(field_get:pybullet_grpc.SdfLoadedStatus.bodyUniqueIds) + return bodyuniqueids_.Get(index); +} +inline void SdfLoadedStatus::set_bodyuniqueids(int index, ::google::protobuf::int32 value) { + bodyuniqueids_.Set(index, value); + // @@protoc_insertion_point(field_set:pybullet_grpc.SdfLoadedStatus.bodyUniqueIds) +} +inline void SdfLoadedStatus::add_bodyuniqueids(::google::protobuf::int32 value) { + bodyuniqueids_.Add(value); + // @@protoc_insertion_point(field_add:pybullet_grpc.SdfLoadedStatus.bodyUniqueIds) +} +inline const ::google::protobuf::RepeatedField< ::google::protobuf::int32 >& +SdfLoadedStatus::bodyuniqueids() const { + // @@protoc_insertion_point(field_list:pybullet_grpc.SdfLoadedStatus.bodyUniqueIds) + return bodyuniqueids_; +} +inline ::google::protobuf::RepeatedField< ::google::protobuf::int32 >* +SdfLoadedStatus::mutable_bodyuniqueids() { + // @@protoc_insertion_point(field_mutable_list:pybullet_grpc.SdfLoadedStatus.bodyUniqueIds) + return &bodyuniqueids_; +} + +// ------------------------------------------------------------------- + +// LoadMjcfCommand + +// string fileName = 1; +inline void LoadMjcfCommand::clear_filename() { + filename_.ClearToEmptyNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); +} +inline const ::std::string& LoadMjcfCommand::filename() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.LoadMjcfCommand.fileName) + return filename_.GetNoArena(); +} +inline void LoadMjcfCommand::set_filename(const ::std::string& value) { + + filename_.SetNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), value); + // @@protoc_insertion_point(field_set:pybullet_grpc.LoadMjcfCommand.fileName) +} +#if LANG_CXX11 +inline void LoadMjcfCommand::set_filename(::std::string&& value) { + + filename_.SetNoArena( + &::google::protobuf::internal::GetEmptyStringAlreadyInited(), std::move(value)); + // @@protoc_insertion_point(field_set_rvalue:pybullet_grpc.LoadMjcfCommand.fileName) +} +#endif +inline void LoadMjcfCommand::set_filename(const char* value) { + + filename_.SetNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), ::std::string(value)); + // @@protoc_insertion_point(field_set_char:pybullet_grpc.LoadMjcfCommand.fileName) +} +inline void LoadMjcfCommand::set_filename(const char* value, size_t size) { + + filename_.SetNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), + ::std::string(reinterpret_cast(value), size)); + // @@protoc_insertion_point(field_set_pointer:pybullet_grpc.LoadMjcfCommand.fileName) +} +inline ::std::string* LoadMjcfCommand::mutable_filename() { + + // @@protoc_insertion_point(field_mutable:pybullet_grpc.LoadMjcfCommand.fileName) + return filename_.MutableNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); +} +inline ::std::string* LoadMjcfCommand::release_filename() { + // @@protoc_insertion_point(field_release:pybullet_grpc.LoadMjcfCommand.fileName) + + return filename_.ReleaseNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); +} +inline void LoadMjcfCommand::set_allocated_filename(::std::string* filename) { + if (filename != NULL) { + + } else { + + } + filename_.SetAllocatedNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), filename); + // @@protoc_insertion_point(field_set_allocated:pybullet_grpc.LoadMjcfCommand.fileName) +} + +// int32 flags = 2; +inline void LoadMjcfCommand::clear_flags() { + flags_ = 0; +} +inline ::google::protobuf::int32 LoadMjcfCommand::flags() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.LoadMjcfCommand.flags) + return flags_; +} +inline void LoadMjcfCommand::set_flags(::google::protobuf::int32 value) { + + flags_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.LoadMjcfCommand.flags) +} + +// ------------------------------------------------------------------- + +// MjcfLoadedStatus + +// repeated int32 bodyUniqueIds = 2; +inline int MjcfLoadedStatus::bodyuniqueids_size() const { + return bodyuniqueids_.size(); +} +inline void MjcfLoadedStatus::clear_bodyuniqueids() { + bodyuniqueids_.Clear(); +} +inline ::google::protobuf::int32 MjcfLoadedStatus::bodyuniqueids(int index) const { + // @@protoc_insertion_point(field_get:pybullet_grpc.MjcfLoadedStatus.bodyUniqueIds) + return bodyuniqueids_.Get(index); +} +inline void MjcfLoadedStatus::set_bodyuniqueids(int index, ::google::protobuf::int32 value) { + bodyuniqueids_.Set(index, value); + // @@protoc_insertion_point(field_set:pybullet_grpc.MjcfLoadedStatus.bodyUniqueIds) +} +inline void MjcfLoadedStatus::add_bodyuniqueids(::google::protobuf::int32 value) { + bodyuniqueids_.Add(value); + // @@protoc_insertion_point(field_add:pybullet_grpc.MjcfLoadedStatus.bodyUniqueIds) +} +inline const ::google::protobuf::RepeatedField< ::google::protobuf::int32 >& +MjcfLoadedStatus::bodyuniqueids() const { + // @@protoc_insertion_point(field_list:pybullet_grpc.MjcfLoadedStatus.bodyUniqueIds) + return bodyuniqueids_; +} +inline ::google::protobuf::RepeatedField< ::google::protobuf::int32 >* +MjcfLoadedStatus::mutable_bodyuniqueids() { + // @@protoc_insertion_point(field_mutable_list:pybullet_grpc.MjcfLoadedStatus.bodyUniqueIds) + return &bodyuniqueids_; +} + +// ------------------------------------------------------------------- + +// ChangeDynamicsCommand + +// int32 bodyUniqueId = 1; +inline void ChangeDynamicsCommand::clear_bodyuniqueid() { + bodyuniqueid_ = 0; +} +inline ::google::protobuf::int32 ChangeDynamicsCommand::bodyuniqueid() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.ChangeDynamicsCommand.bodyUniqueId) + return bodyuniqueid_; +} +inline void ChangeDynamicsCommand::set_bodyuniqueid(::google::protobuf::int32 value) { + + bodyuniqueid_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.ChangeDynamicsCommand.bodyUniqueId) +} + +// int32 linkIndex = 2; +inline void ChangeDynamicsCommand::clear_linkindex() { + linkindex_ = 0; +} +inline ::google::protobuf::int32 ChangeDynamicsCommand::linkindex() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.ChangeDynamicsCommand.linkIndex) + return linkindex_; +} +inline void ChangeDynamicsCommand::set_linkindex(::google::protobuf::int32 value) { + + linkindex_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.ChangeDynamicsCommand.linkIndex) +} + +// double mass = 3; +inline bool ChangeDynamicsCommand::has_mass() const { + return hasMass_case() == kMass; +} +inline void ChangeDynamicsCommand::set_has_mass() { + _oneof_case_[0] = kMass; +} +inline void ChangeDynamicsCommand::clear_mass() { + if (has_mass()) { + hasMass_.mass_ = 0; + clear_has_hasMass(); + } +} +inline double ChangeDynamicsCommand::mass() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.ChangeDynamicsCommand.mass) + if (has_mass()) { + return hasMass_.mass_; + } + return 0; +} +inline void ChangeDynamicsCommand::set_mass(double value) { + if (!has_mass()) { + clear_hasMass(); + set_has_mass(); + } + hasMass_.mass_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.ChangeDynamicsCommand.mass) +} + +// double lateralFriction = 5; +inline bool ChangeDynamicsCommand::has_lateralfriction() const { + return hasLateralFriction_case() == kLateralFriction; +} +inline void ChangeDynamicsCommand::set_has_lateralfriction() { + _oneof_case_[1] = kLateralFriction; +} +inline void ChangeDynamicsCommand::clear_lateralfriction() { + if (has_lateralfriction()) { + hasLateralFriction_.lateralfriction_ = 0; + clear_has_hasLateralFriction(); + } +} +inline double ChangeDynamicsCommand::lateralfriction() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.ChangeDynamicsCommand.lateralFriction) + if (has_lateralfriction()) { + return hasLateralFriction_.lateralfriction_; + } + return 0; +} +inline void ChangeDynamicsCommand::set_lateralfriction(double value) { + if (!has_lateralfriction()) { + clear_hasLateralFriction(); + set_has_lateralfriction(); + } + hasLateralFriction_.lateralfriction_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.ChangeDynamicsCommand.lateralFriction) +} + +// double spinningFriction = 6; +inline bool ChangeDynamicsCommand::has_spinningfriction() const { + return hasSpinningFriction_case() == kSpinningFriction; +} +inline void ChangeDynamicsCommand::set_has_spinningfriction() { + _oneof_case_[2] = kSpinningFriction; +} +inline void ChangeDynamicsCommand::clear_spinningfriction() { + if (has_spinningfriction()) { + hasSpinningFriction_.spinningfriction_ = 0; + clear_has_hasSpinningFriction(); + } +} +inline double ChangeDynamicsCommand::spinningfriction() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.ChangeDynamicsCommand.spinningFriction) + if (has_spinningfriction()) { + return hasSpinningFriction_.spinningfriction_; + } + return 0; +} +inline void ChangeDynamicsCommand::set_spinningfriction(double value) { + if (!has_spinningfriction()) { + clear_hasSpinningFriction(); + set_has_spinningfriction(); + } + hasSpinningFriction_.spinningfriction_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.ChangeDynamicsCommand.spinningFriction) +} + +// double rollingFriction = 7; +inline bool ChangeDynamicsCommand::has_rollingfriction() const { + return hasRollingFriction_case() == kRollingFriction; +} +inline void ChangeDynamicsCommand::set_has_rollingfriction() { + _oneof_case_[3] = kRollingFriction; +} +inline void ChangeDynamicsCommand::clear_rollingfriction() { + if (has_rollingfriction()) { + hasRollingFriction_.rollingfriction_ = 0; + clear_has_hasRollingFriction(); + } +} +inline double ChangeDynamicsCommand::rollingfriction() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.ChangeDynamicsCommand.rollingFriction) + if (has_rollingfriction()) { + return hasRollingFriction_.rollingfriction_; + } + return 0; +} +inline void ChangeDynamicsCommand::set_rollingfriction(double value) { + if (!has_rollingfriction()) { + clear_hasRollingFriction(); + set_has_rollingfriction(); + } + hasRollingFriction_.rollingfriction_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.ChangeDynamicsCommand.rollingFriction) +} + +// double restitution = 8; +inline bool ChangeDynamicsCommand::has_restitution() const { + return hasRestitution_case() == kRestitution; +} +inline void ChangeDynamicsCommand::set_has_restitution() { + _oneof_case_[4] = kRestitution; +} +inline void ChangeDynamicsCommand::clear_restitution() { + if (has_restitution()) { + hasRestitution_.restitution_ = 0; + clear_has_hasRestitution(); + } +} +inline double ChangeDynamicsCommand::restitution() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.ChangeDynamicsCommand.restitution) + if (has_restitution()) { + return hasRestitution_.restitution_; + } + return 0; +} +inline void ChangeDynamicsCommand::set_restitution(double value) { + if (!has_restitution()) { + clear_hasRestitution(); + set_has_restitution(); + } + hasRestitution_.restitution_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.ChangeDynamicsCommand.restitution) +} + +// double linearDamping = 9; +inline bool ChangeDynamicsCommand::has_lineardamping() const { + return haslinearDamping_case() == kLinearDamping; +} +inline void ChangeDynamicsCommand::set_has_lineardamping() { + _oneof_case_[5] = kLinearDamping; +} +inline void ChangeDynamicsCommand::clear_lineardamping() { + if (has_lineardamping()) { + haslinearDamping_.lineardamping_ = 0; + clear_has_haslinearDamping(); + } +} +inline double ChangeDynamicsCommand::lineardamping() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.ChangeDynamicsCommand.linearDamping) + if (has_lineardamping()) { + return haslinearDamping_.lineardamping_; + } + return 0; +} +inline void ChangeDynamicsCommand::set_lineardamping(double value) { + if (!has_lineardamping()) { + clear_haslinearDamping(); + set_has_lineardamping(); + } + haslinearDamping_.lineardamping_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.ChangeDynamicsCommand.linearDamping) +} + +// double angularDamping = 10; +inline bool ChangeDynamicsCommand::has_angulardamping() const { + return hasangularDamping_case() == kAngularDamping; +} +inline void ChangeDynamicsCommand::set_has_angulardamping() { + _oneof_case_[6] = kAngularDamping; +} +inline void ChangeDynamicsCommand::clear_angulardamping() { + if (has_angulardamping()) { + hasangularDamping_.angulardamping_ = 0; + clear_has_hasangularDamping(); + } +} +inline double ChangeDynamicsCommand::angulardamping() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.ChangeDynamicsCommand.angularDamping) + if (has_angulardamping()) { + return hasangularDamping_.angulardamping_; + } + return 0; +} +inline void ChangeDynamicsCommand::set_angulardamping(double value) { + if (!has_angulardamping()) { + clear_hasangularDamping(); + set_has_angulardamping(); + } + hasangularDamping_.angulardamping_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.ChangeDynamicsCommand.angularDamping) +} + +// double contactStiffness = 11; +inline bool ChangeDynamicsCommand::has_contactstiffness() const { + return hasContactStiffness_case() == kContactStiffness; +} +inline void ChangeDynamicsCommand::set_has_contactstiffness() { + _oneof_case_[7] = kContactStiffness; +} +inline void ChangeDynamicsCommand::clear_contactstiffness() { + if (has_contactstiffness()) { + hasContactStiffness_.contactstiffness_ = 0; + clear_has_hasContactStiffness(); + } +} +inline double ChangeDynamicsCommand::contactstiffness() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.ChangeDynamicsCommand.contactStiffness) + if (has_contactstiffness()) { + return hasContactStiffness_.contactstiffness_; + } + return 0; +} +inline void ChangeDynamicsCommand::set_contactstiffness(double value) { + if (!has_contactstiffness()) { + clear_hasContactStiffness(); + set_has_contactstiffness(); + } + hasContactStiffness_.contactstiffness_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.ChangeDynamicsCommand.contactStiffness) +} + +// double contactDamping = 12; +inline bool ChangeDynamicsCommand::has_contactdamping() const { + return hasContactDamping_case() == kContactDamping; +} +inline void ChangeDynamicsCommand::set_has_contactdamping() { + _oneof_case_[8] = kContactDamping; +} +inline void ChangeDynamicsCommand::clear_contactdamping() { + if (has_contactdamping()) { + hasContactDamping_.contactdamping_ = 0; + clear_has_hasContactDamping(); + } +} +inline double ChangeDynamicsCommand::contactdamping() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.ChangeDynamicsCommand.contactDamping) + if (has_contactdamping()) { + return hasContactDamping_.contactdamping_; + } + return 0; +} +inline void ChangeDynamicsCommand::set_contactdamping(double value) { + if (!has_contactdamping()) { + clear_hasContactDamping(); + set_has_contactdamping(); + } + hasContactDamping_.contactdamping_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.ChangeDynamicsCommand.contactDamping) +} + +// .pybullet_grpc.vec3 localInertiaDiagonal = 13; +inline bool ChangeDynamicsCommand::has_localinertiadiagonal() const { + return hasLocalInertiaDiagonal_case() == kLocalInertiaDiagonal; +} +inline void ChangeDynamicsCommand::set_has_localinertiadiagonal() { + _oneof_case_[9] = kLocalInertiaDiagonal; +} +inline void ChangeDynamicsCommand::clear_localinertiadiagonal() { + if (has_localinertiadiagonal()) { + delete hasLocalInertiaDiagonal_.localinertiadiagonal_; + clear_has_hasLocalInertiaDiagonal(); + } +} +inline const ::pybullet_grpc::vec3& ChangeDynamicsCommand::localinertiadiagonal() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.ChangeDynamicsCommand.localInertiaDiagonal) + return has_localinertiadiagonal() + ? *hasLocalInertiaDiagonal_.localinertiadiagonal_ + : ::pybullet_grpc::vec3::default_instance(); +} +inline ::pybullet_grpc::vec3* ChangeDynamicsCommand::mutable_localinertiadiagonal() { + if (!has_localinertiadiagonal()) { + clear_hasLocalInertiaDiagonal(); + set_has_localinertiadiagonal(); + hasLocalInertiaDiagonal_.localinertiadiagonal_ = new ::pybullet_grpc::vec3; + } + // @@protoc_insertion_point(field_mutable:pybullet_grpc.ChangeDynamicsCommand.localInertiaDiagonal) + return hasLocalInertiaDiagonal_.localinertiadiagonal_; +} +inline ::pybullet_grpc::vec3* ChangeDynamicsCommand::release_localinertiadiagonal() { + // @@protoc_insertion_point(field_release:pybullet_grpc.ChangeDynamicsCommand.localInertiaDiagonal) + if (has_localinertiadiagonal()) { + clear_has_hasLocalInertiaDiagonal(); + ::pybullet_grpc::vec3* temp = hasLocalInertiaDiagonal_.localinertiadiagonal_; + hasLocalInertiaDiagonal_.localinertiadiagonal_ = NULL; + return temp; + } else { + return NULL; + } +} +inline void ChangeDynamicsCommand::set_allocated_localinertiadiagonal(::pybullet_grpc::vec3* localinertiadiagonal) { + clear_hasLocalInertiaDiagonal(); + if (localinertiadiagonal) { + set_has_localinertiadiagonal(); + hasLocalInertiaDiagonal_.localinertiadiagonal_ = localinertiadiagonal; + } + // @@protoc_insertion_point(field_set_allocated:pybullet_grpc.ChangeDynamicsCommand.localInertiaDiagonal) +} + +// int32 frictionAnchor = 14; +inline bool ChangeDynamicsCommand::has_frictionanchor() const { + return hasFrictionAnchor_case() == kFrictionAnchor; +} +inline void ChangeDynamicsCommand::set_has_frictionanchor() { + _oneof_case_[10] = kFrictionAnchor; +} +inline void ChangeDynamicsCommand::clear_frictionanchor() { + if (has_frictionanchor()) { + hasFrictionAnchor_.frictionanchor_ = 0; + clear_has_hasFrictionAnchor(); + } +} +inline ::google::protobuf::int32 ChangeDynamicsCommand::frictionanchor() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.ChangeDynamicsCommand.frictionAnchor) + if (has_frictionanchor()) { + return hasFrictionAnchor_.frictionanchor_; + } + return 0; +} +inline void ChangeDynamicsCommand::set_frictionanchor(::google::protobuf::int32 value) { + if (!has_frictionanchor()) { + clear_hasFrictionAnchor(); + set_has_frictionanchor(); + } + hasFrictionAnchor_.frictionanchor_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.ChangeDynamicsCommand.frictionAnchor) +} + +// double ccdSweptSphereRadius = 15; +inline bool ChangeDynamicsCommand::has_ccdsweptsphereradius() const { + return hasccdSweptSphereRadius_case() == kCcdSweptSphereRadius; +} +inline void ChangeDynamicsCommand::set_has_ccdsweptsphereradius() { + _oneof_case_[11] = kCcdSweptSphereRadius; +} +inline void ChangeDynamicsCommand::clear_ccdsweptsphereradius() { + if (has_ccdsweptsphereradius()) { + hasccdSweptSphereRadius_.ccdsweptsphereradius_ = 0; + clear_has_hasccdSweptSphereRadius(); + } +} +inline double ChangeDynamicsCommand::ccdsweptsphereradius() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.ChangeDynamicsCommand.ccdSweptSphereRadius) + if (has_ccdsweptsphereradius()) { + return hasccdSweptSphereRadius_.ccdsweptsphereradius_; + } + return 0; +} +inline void ChangeDynamicsCommand::set_ccdsweptsphereradius(double value) { + if (!has_ccdsweptsphereradius()) { + clear_hasccdSweptSphereRadius(); + set_has_ccdsweptsphereradius(); + } + hasccdSweptSphereRadius_.ccdsweptsphereradius_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.ChangeDynamicsCommand.ccdSweptSphereRadius) +} + +// double contactProcessingThreshold = 16; +inline bool ChangeDynamicsCommand::has_contactprocessingthreshold() const { + return hasContactProcessingThreshold_case() == kContactProcessingThreshold; +} +inline void ChangeDynamicsCommand::set_has_contactprocessingthreshold() { + _oneof_case_[12] = kContactProcessingThreshold; +} +inline void ChangeDynamicsCommand::clear_contactprocessingthreshold() { + if (has_contactprocessingthreshold()) { + hasContactProcessingThreshold_.contactprocessingthreshold_ = 0; + clear_has_hasContactProcessingThreshold(); + } +} +inline double ChangeDynamicsCommand::contactprocessingthreshold() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.ChangeDynamicsCommand.contactProcessingThreshold) + if (has_contactprocessingthreshold()) { + return hasContactProcessingThreshold_.contactprocessingthreshold_; + } + return 0; +} +inline void ChangeDynamicsCommand::set_contactprocessingthreshold(double value) { + if (!has_contactprocessingthreshold()) { + clear_hasContactProcessingThreshold(); + set_has_contactprocessingthreshold(); + } + hasContactProcessingThreshold_.contactprocessingthreshold_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.ChangeDynamicsCommand.contactProcessingThreshold) +} + +// int32 activationState = 17; +inline bool ChangeDynamicsCommand::has_activationstate() const { + return hasActivationState_case() == kActivationState; +} +inline void ChangeDynamicsCommand::set_has_activationstate() { + _oneof_case_[13] = kActivationState; +} +inline void ChangeDynamicsCommand::clear_activationstate() { + if (has_activationstate()) { + hasActivationState_.activationstate_ = 0; + clear_has_hasActivationState(); + } +} +inline ::google::protobuf::int32 ChangeDynamicsCommand::activationstate() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.ChangeDynamicsCommand.activationState) + if (has_activationstate()) { + return hasActivationState_.activationstate_; + } + return 0; +} +inline void ChangeDynamicsCommand::set_activationstate(::google::protobuf::int32 value) { + if (!has_activationstate()) { + clear_hasActivationState(); + set_has_activationstate(); + } + hasActivationState_.activationstate_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.ChangeDynamicsCommand.activationState) +} + +inline bool ChangeDynamicsCommand::has_hasMass() const { + return hasMass_case() != HASMASS_NOT_SET; +} +inline void ChangeDynamicsCommand::clear_has_hasMass() { + _oneof_case_[0] = HASMASS_NOT_SET; +} +inline bool ChangeDynamicsCommand::has_hasLateralFriction() const { + return hasLateralFriction_case() != HASLATERALFRICTION_NOT_SET; +} +inline void ChangeDynamicsCommand::clear_has_hasLateralFriction() { + _oneof_case_[1] = HASLATERALFRICTION_NOT_SET; +} +inline bool ChangeDynamicsCommand::has_hasSpinningFriction() const { + return hasSpinningFriction_case() != HASSPINNINGFRICTION_NOT_SET; +} +inline void ChangeDynamicsCommand::clear_has_hasSpinningFriction() { + _oneof_case_[2] = HASSPINNINGFRICTION_NOT_SET; +} +inline bool ChangeDynamicsCommand::has_hasRollingFriction() const { + return hasRollingFriction_case() != HASROLLINGFRICTION_NOT_SET; +} +inline void ChangeDynamicsCommand::clear_has_hasRollingFriction() { + _oneof_case_[3] = HASROLLINGFRICTION_NOT_SET; +} +inline bool ChangeDynamicsCommand::has_hasRestitution() const { + return hasRestitution_case() != HASRESTITUTION_NOT_SET; +} +inline void ChangeDynamicsCommand::clear_has_hasRestitution() { + _oneof_case_[4] = HASRESTITUTION_NOT_SET; +} +inline bool ChangeDynamicsCommand::has_haslinearDamping() const { + return haslinearDamping_case() != HASLINEARDAMPING_NOT_SET; +} +inline void ChangeDynamicsCommand::clear_has_haslinearDamping() { + _oneof_case_[5] = HASLINEARDAMPING_NOT_SET; +} +inline bool ChangeDynamicsCommand::has_hasangularDamping() const { + return hasangularDamping_case() != HASANGULARDAMPING_NOT_SET; +} +inline void ChangeDynamicsCommand::clear_has_hasangularDamping() { + _oneof_case_[6] = HASANGULARDAMPING_NOT_SET; +} +inline bool ChangeDynamicsCommand::has_hasContactStiffness() const { + return hasContactStiffness_case() != HASCONTACTSTIFFNESS_NOT_SET; +} +inline void ChangeDynamicsCommand::clear_has_hasContactStiffness() { + _oneof_case_[7] = HASCONTACTSTIFFNESS_NOT_SET; +} +inline bool ChangeDynamicsCommand::has_hasContactDamping() const { + return hasContactDamping_case() != HASCONTACTDAMPING_NOT_SET; +} +inline void ChangeDynamicsCommand::clear_has_hasContactDamping() { + _oneof_case_[8] = HASCONTACTDAMPING_NOT_SET; +} +inline bool ChangeDynamicsCommand::has_hasLocalInertiaDiagonal() const { + return hasLocalInertiaDiagonal_case() != HASLOCALINERTIADIAGONAL_NOT_SET; +} +inline void ChangeDynamicsCommand::clear_has_hasLocalInertiaDiagonal() { + _oneof_case_[9] = HASLOCALINERTIADIAGONAL_NOT_SET; +} +inline bool ChangeDynamicsCommand::has_hasFrictionAnchor() const { + return hasFrictionAnchor_case() != HASFRICTIONANCHOR_NOT_SET; +} +inline void ChangeDynamicsCommand::clear_has_hasFrictionAnchor() { + _oneof_case_[10] = HASFRICTIONANCHOR_NOT_SET; +} +inline bool ChangeDynamicsCommand::has_hasccdSweptSphereRadius() const { + return hasccdSweptSphereRadius_case() != HASCCDSWEPTSPHERERADIUS_NOT_SET; +} +inline void ChangeDynamicsCommand::clear_has_hasccdSweptSphereRadius() { + _oneof_case_[11] = HASCCDSWEPTSPHERERADIUS_NOT_SET; +} +inline bool ChangeDynamicsCommand::has_hasContactProcessingThreshold() const { + return hasContactProcessingThreshold_case() != HASCONTACTPROCESSINGTHRESHOLD_NOT_SET; +} +inline void ChangeDynamicsCommand::clear_has_hasContactProcessingThreshold() { + _oneof_case_[12] = HASCONTACTPROCESSINGTHRESHOLD_NOT_SET; +} +inline bool ChangeDynamicsCommand::has_hasActivationState() const { + return hasActivationState_case() != HASACTIVATIONSTATE_NOT_SET; +} +inline void ChangeDynamicsCommand::clear_has_hasActivationState() { + _oneof_case_[13] = HASACTIVATIONSTATE_NOT_SET; +} +inline ChangeDynamicsCommand::HasMassCase ChangeDynamicsCommand::hasMass_case() const { + return ChangeDynamicsCommand::HasMassCase(_oneof_case_[0]); +} +inline ChangeDynamicsCommand::HasLateralFrictionCase ChangeDynamicsCommand::hasLateralFriction_case() const { + return ChangeDynamicsCommand::HasLateralFrictionCase(_oneof_case_[1]); +} +inline ChangeDynamicsCommand::HasSpinningFrictionCase ChangeDynamicsCommand::hasSpinningFriction_case() const { + return ChangeDynamicsCommand::HasSpinningFrictionCase(_oneof_case_[2]); +} +inline ChangeDynamicsCommand::HasRollingFrictionCase ChangeDynamicsCommand::hasRollingFriction_case() const { + return ChangeDynamicsCommand::HasRollingFrictionCase(_oneof_case_[3]); +} +inline ChangeDynamicsCommand::HasRestitutionCase ChangeDynamicsCommand::hasRestitution_case() const { + return ChangeDynamicsCommand::HasRestitutionCase(_oneof_case_[4]); +} +inline ChangeDynamicsCommand::HaslinearDampingCase ChangeDynamicsCommand::haslinearDamping_case() const { + return ChangeDynamicsCommand::HaslinearDampingCase(_oneof_case_[5]); +} +inline ChangeDynamicsCommand::HasangularDampingCase ChangeDynamicsCommand::hasangularDamping_case() const { + return ChangeDynamicsCommand::HasangularDampingCase(_oneof_case_[6]); +} +inline ChangeDynamicsCommand::HasContactStiffnessCase ChangeDynamicsCommand::hasContactStiffness_case() const { + return ChangeDynamicsCommand::HasContactStiffnessCase(_oneof_case_[7]); +} +inline ChangeDynamicsCommand::HasContactDampingCase ChangeDynamicsCommand::hasContactDamping_case() const { + return ChangeDynamicsCommand::HasContactDampingCase(_oneof_case_[8]); +} +inline ChangeDynamicsCommand::HasLocalInertiaDiagonalCase ChangeDynamicsCommand::hasLocalInertiaDiagonal_case() const { + return ChangeDynamicsCommand::HasLocalInertiaDiagonalCase(_oneof_case_[9]); +} +inline ChangeDynamicsCommand::HasFrictionAnchorCase ChangeDynamicsCommand::hasFrictionAnchor_case() const { + return ChangeDynamicsCommand::HasFrictionAnchorCase(_oneof_case_[10]); +} +inline ChangeDynamicsCommand::HasccdSweptSphereRadiusCase ChangeDynamicsCommand::hasccdSweptSphereRadius_case() const { + return ChangeDynamicsCommand::HasccdSweptSphereRadiusCase(_oneof_case_[11]); +} +inline ChangeDynamicsCommand::HasContactProcessingThresholdCase ChangeDynamicsCommand::hasContactProcessingThreshold_case() const { + return ChangeDynamicsCommand::HasContactProcessingThresholdCase(_oneof_case_[12]); +} +inline ChangeDynamicsCommand::HasActivationStateCase ChangeDynamicsCommand::hasActivationState_case() const { + return ChangeDynamicsCommand::HasActivationStateCase(_oneof_case_[13]); +} +// ------------------------------------------------------------------- + +// GetDynamicsCommand + +// int32 bodyUniqueId = 1; +inline void GetDynamicsCommand::clear_bodyuniqueid() { + bodyuniqueid_ = 0; +} +inline ::google::protobuf::int32 GetDynamicsCommand::bodyuniqueid() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.GetDynamicsCommand.bodyUniqueId) + return bodyuniqueid_; +} +inline void GetDynamicsCommand::set_bodyuniqueid(::google::protobuf::int32 value) { + + bodyuniqueid_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.GetDynamicsCommand.bodyUniqueId) +} + +// int32 linkIndex = 2; +inline void GetDynamicsCommand::clear_linkindex() { + linkindex_ = 0; +} +inline ::google::protobuf::int32 GetDynamicsCommand::linkindex() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.GetDynamicsCommand.linkIndex) + return linkindex_; +} +inline void GetDynamicsCommand::set_linkindex(::google::protobuf::int32 value) { + + linkindex_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.GetDynamicsCommand.linkIndex) +} + +// ------------------------------------------------------------------- + +// GetDynamicsStatus + +// double mass = 3; +inline void GetDynamicsStatus::clear_mass() { + mass_ = 0; +} +inline double GetDynamicsStatus::mass() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.GetDynamicsStatus.mass) + return mass_; +} +inline void GetDynamicsStatus::set_mass(double value) { + + mass_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.GetDynamicsStatus.mass) +} + +// double lateralFriction = 5; +inline void GetDynamicsStatus::clear_lateralfriction() { + lateralfriction_ = 0; +} +inline double GetDynamicsStatus::lateralfriction() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.GetDynamicsStatus.lateralFriction) + return lateralfriction_; +} +inline void GetDynamicsStatus::set_lateralfriction(double value) { + + lateralfriction_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.GetDynamicsStatus.lateralFriction) +} + +// double spinningFriction = 6; +inline void GetDynamicsStatus::clear_spinningfriction() { + spinningfriction_ = 0; +} +inline double GetDynamicsStatus::spinningfriction() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.GetDynamicsStatus.spinningFriction) + return spinningfriction_; +} +inline void GetDynamicsStatus::set_spinningfriction(double value) { + + spinningfriction_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.GetDynamicsStatus.spinningFriction) +} + +// double rollingFriction = 7; +inline void GetDynamicsStatus::clear_rollingfriction() { + rollingfriction_ = 0; +} +inline double GetDynamicsStatus::rollingfriction() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.GetDynamicsStatus.rollingFriction) + return rollingfriction_; +} +inline void GetDynamicsStatus::set_rollingfriction(double value) { + + rollingfriction_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.GetDynamicsStatus.rollingFriction) +} + +// double restitution = 8; +inline void GetDynamicsStatus::clear_restitution() { + restitution_ = 0; +} +inline double GetDynamicsStatus::restitution() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.GetDynamicsStatus.restitution) + return restitution_; +} +inline void GetDynamicsStatus::set_restitution(double value) { + + restitution_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.GetDynamicsStatus.restitution) +} + +// double linearDamping = 9; +inline void GetDynamicsStatus::clear_lineardamping() { + lineardamping_ = 0; +} +inline double GetDynamicsStatus::lineardamping() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.GetDynamicsStatus.linearDamping) + return lineardamping_; +} +inline void GetDynamicsStatus::set_lineardamping(double value) { + + lineardamping_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.GetDynamicsStatus.linearDamping) +} + +// double angularDamping = 10; +inline void GetDynamicsStatus::clear_angulardamping() { + angulardamping_ = 0; +} +inline double GetDynamicsStatus::angulardamping() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.GetDynamicsStatus.angularDamping) + return angulardamping_; +} +inline void GetDynamicsStatus::set_angulardamping(double value) { + + angulardamping_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.GetDynamicsStatus.angularDamping) +} + +// double contactStiffness = 11; +inline void GetDynamicsStatus::clear_contactstiffness() { + contactstiffness_ = 0; +} +inline double GetDynamicsStatus::contactstiffness() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.GetDynamicsStatus.contactStiffness) + return contactstiffness_; +} +inline void GetDynamicsStatus::set_contactstiffness(double value) { + + contactstiffness_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.GetDynamicsStatus.contactStiffness) +} + +// double contactDamping = 12; +inline void GetDynamicsStatus::clear_contactdamping() { + contactdamping_ = 0; +} +inline double GetDynamicsStatus::contactdamping() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.GetDynamicsStatus.contactDamping) + return contactdamping_; +} +inline void GetDynamicsStatus::set_contactdamping(double value) { + + contactdamping_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.GetDynamicsStatus.contactDamping) +} + +// .pybullet_grpc.vec3 localInertiaDiagonal = 13; +inline bool GetDynamicsStatus::has_localinertiadiagonal() const { + return this != internal_default_instance() && localinertiadiagonal_ != NULL; +} +inline void GetDynamicsStatus::clear_localinertiadiagonal() { + if (GetArenaNoVirtual() == NULL && localinertiadiagonal_ != NULL) delete localinertiadiagonal_; + localinertiadiagonal_ = NULL; +} +inline const ::pybullet_grpc::vec3& GetDynamicsStatus::localinertiadiagonal() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.GetDynamicsStatus.localInertiaDiagonal) + return localinertiadiagonal_ != NULL ? *localinertiadiagonal_ + : *::pybullet_grpc::vec3::internal_default_instance(); +} +inline ::pybullet_grpc::vec3* GetDynamicsStatus::mutable_localinertiadiagonal() { + + if (localinertiadiagonal_ == NULL) { + localinertiadiagonal_ = new ::pybullet_grpc::vec3; + } + // @@protoc_insertion_point(field_mutable:pybullet_grpc.GetDynamicsStatus.localInertiaDiagonal) + return localinertiadiagonal_; +} +inline ::pybullet_grpc::vec3* GetDynamicsStatus::release_localinertiadiagonal() { + // @@protoc_insertion_point(field_release:pybullet_grpc.GetDynamicsStatus.localInertiaDiagonal) + + ::pybullet_grpc::vec3* temp = localinertiadiagonal_; + localinertiadiagonal_ = NULL; + return temp; +} +inline void GetDynamicsStatus::set_allocated_localinertiadiagonal(::pybullet_grpc::vec3* localinertiadiagonal) { + delete localinertiadiagonal_; + localinertiadiagonal_ = localinertiadiagonal; + if (localinertiadiagonal) { + + } else { + + } + // @@protoc_insertion_point(field_set_allocated:pybullet_grpc.GetDynamicsStatus.localInertiaDiagonal) +} + +// int32 frictionAnchor = 14; +inline void GetDynamicsStatus::clear_frictionanchor() { + frictionanchor_ = 0; +} +inline ::google::protobuf::int32 GetDynamicsStatus::frictionanchor() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.GetDynamicsStatus.frictionAnchor) + return frictionanchor_; +} +inline void GetDynamicsStatus::set_frictionanchor(::google::protobuf::int32 value) { + + frictionanchor_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.GetDynamicsStatus.frictionAnchor) +} + +// double ccdSweptSphereRadius = 15; +inline void GetDynamicsStatus::clear_ccdsweptsphereradius() { + ccdsweptsphereradius_ = 0; +} +inline double GetDynamicsStatus::ccdsweptsphereradius() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.GetDynamicsStatus.ccdSweptSphereRadius) + return ccdsweptsphereradius_; +} +inline void GetDynamicsStatus::set_ccdsweptsphereradius(double value) { + + ccdsweptsphereradius_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.GetDynamicsStatus.ccdSweptSphereRadius) +} + +// double contactProcessingThreshold = 16; +inline void GetDynamicsStatus::clear_contactprocessingthreshold() { + contactprocessingthreshold_ = 0; +} +inline double GetDynamicsStatus::contactprocessingthreshold() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.GetDynamicsStatus.contactProcessingThreshold) + return contactprocessingthreshold_; +} +inline void GetDynamicsStatus::set_contactprocessingthreshold(double value) { + + contactprocessingthreshold_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.GetDynamicsStatus.contactProcessingThreshold) +} + +// int32 activationState = 17; +inline void GetDynamicsStatus::clear_activationstate() { + activationstate_ = 0; +} +inline ::google::protobuf::int32 GetDynamicsStatus::activationstate() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.GetDynamicsStatus.activationState) + return activationstate_; +} +inline void GetDynamicsStatus::set_activationstate(::google::protobuf::int32 value) { + + activationstate_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.GetDynamicsStatus.activationState) +} + +// ------------------------------------------------------------------- + +// InitPoseCommand + +// int32 bodyUniqueId = 1; +inline void InitPoseCommand::clear_bodyuniqueid() { + bodyuniqueid_ = 0; +} +inline ::google::protobuf::int32 InitPoseCommand::bodyuniqueid() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.InitPoseCommand.bodyUniqueId) + return bodyuniqueid_; +} +inline void InitPoseCommand::set_bodyuniqueid(::google::protobuf::int32 value) { + + bodyuniqueid_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.InitPoseCommand.bodyUniqueId) +} + +// repeated int32 hasInitialStateQ = 2; +inline int InitPoseCommand::hasinitialstateq_size() const { + return hasinitialstateq_.size(); +} +inline void InitPoseCommand::clear_hasinitialstateq() { + hasinitialstateq_.Clear(); +} +inline ::google::protobuf::int32 InitPoseCommand::hasinitialstateq(int index) const { + // @@protoc_insertion_point(field_get:pybullet_grpc.InitPoseCommand.hasInitialStateQ) + return hasinitialstateq_.Get(index); +} +inline void InitPoseCommand::set_hasinitialstateq(int index, ::google::protobuf::int32 value) { + hasinitialstateq_.Set(index, value); + // @@protoc_insertion_point(field_set:pybullet_grpc.InitPoseCommand.hasInitialStateQ) +} +inline void InitPoseCommand::add_hasinitialstateq(::google::protobuf::int32 value) { + hasinitialstateq_.Add(value); + // @@protoc_insertion_point(field_add:pybullet_grpc.InitPoseCommand.hasInitialStateQ) +} +inline const ::google::protobuf::RepeatedField< ::google::protobuf::int32 >& +InitPoseCommand::hasinitialstateq() const { + // @@protoc_insertion_point(field_list:pybullet_grpc.InitPoseCommand.hasInitialStateQ) + return hasinitialstateq_; +} +inline ::google::protobuf::RepeatedField< ::google::protobuf::int32 >* +InitPoseCommand::mutable_hasinitialstateq() { + // @@protoc_insertion_point(field_mutable_list:pybullet_grpc.InitPoseCommand.hasInitialStateQ) + return &hasinitialstateq_; +} + +// repeated double initialStateQ = 3; +inline int InitPoseCommand::initialstateq_size() const { + return initialstateq_.size(); +} +inline void InitPoseCommand::clear_initialstateq() { + initialstateq_.Clear(); +} +inline double InitPoseCommand::initialstateq(int index) const { + // @@protoc_insertion_point(field_get:pybullet_grpc.InitPoseCommand.initialStateQ) + return initialstateq_.Get(index); +} +inline void InitPoseCommand::set_initialstateq(int index, double value) { + initialstateq_.Set(index, value); + // @@protoc_insertion_point(field_set:pybullet_grpc.InitPoseCommand.initialStateQ) +} +inline void InitPoseCommand::add_initialstateq(double value) { + initialstateq_.Add(value); + // @@protoc_insertion_point(field_add:pybullet_grpc.InitPoseCommand.initialStateQ) +} +inline const ::google::protobuf::RepeatedField< double >& +InitPoseCommand::initialstateq() const { + // @@protoc_insertion_point(field_list:pybullet_grpc.InitPoseCommand.initialStateQ) + return initialstateq_; +} +inline ::google::protobuf::RepeatedField< double >* +InitPoseCommand::mutable_initialstateq() { + // @@protoc_insertion_point(field_mutable_list:pybullet_grpc.InitPoseCommand.initialStateQ) + return &initialstateq_; +} + +// repeated int32 hasInitialStateQdot = 4; +inline int InitPoseCommand::hasinitialstateqdot_size() const { + return hasinitialstateqdot_.size(); +} +inline void InitPoseCommand::clear_hasinitialstateqdot() { + hasinitialstateqdot_.Clear(); +} +inline ::google::protobuf::int32 InitPoseCommand::hasinitialstateqdot(int index) const { + // @@protoc_insertion_point(field_get:pybullet_grpc.InitPoseCommand.hasInitialStateQdot) + return hasinitialstateqdot_.Get(index); +} +inline void InitPoseCommand::set_hasinitialstateqdot(int index, ::google::protobuf::int32 value) { + hasinitialstateqdot_.Set(index, value); + // @@protoc_insertion_point(field_set:pybullet_grpc.InitPoseCommand.hasInitialStateQdot) +} +inline void InitPoseCommand::add_hasinitialstateqdot(::google::protobuf::int32 value) { + hasinitialstateqdot_.Add(value); + // @@protoc_insertion_point(field_add:pybullet_grpc.InitPoseCommand.hasInitialStateQdot) +} +inline const ::google::protobuf::RepeatedField< ::google::protobuf::int32 >& +InitPoseCommand::hasinitialstateqdot() const { + // @@protoc_insertion_point(field_list:pybullet_grpc.InitPoseCommand.hasInitialStateQdot) + return hasinitialstateqdot_; +} +inline ::google::protobuf::RepeatedField< ::google::protobuf::int32 >* +InitPoseCommand::mutable_hasinitialstateqdot() { + // @@protoc_insertion_point(field_mutable_list:pybullet_grpc.InitPoseCommand.hasInitialStateQdot) + return &hasinitialstateqdot_; +} + +// repeated double initialStateQdot = 5; +inline int InitPoseCommand::initialstateqdot_size() const { + return initialstateqdot_.size(); +} +inline void InitPoseCommand::clear_initialstateqdot() { + initialstateqdot_.Clear(); +} +inline double InitPoseCommand::initialstateqdot(int index) const { + // @@protoc_insertion_point(field_get:pybullet_grpc.InitPoseCommand.initialStateQdot) + return initialstateqdot_.Get(index); +} +inline void InitPoseCommand::set_initialstateqdot(int index, double value) { + initialstateqdot_.Set(index, value); + // @@protoc_insertion_point(field_set:pybullet_grpc.InitPoseCommand.initialStateQdot) +} +inline void InitPoseCommand::add_initialstateqdot(double value) { + initialstateqdot_.Add(value); + // @@protoc_insertion_point(field_add:pybullet_grpc.InitPoseCommand.initialStateQdot) +} +inline const ::google::protobuf::RepeatedField< double >& +InitPoseCommand::initialstateqdot() const { + // @@protoc_insertion_point(field_list:pybullet_grpc.InitPoseCommand.initialStateQdot) + return initialstateqdot_; +} +inline ::google::protobuf::RepeatedField< double >* +InitPoseCommand::mutable_initialstateqdot() { + // @@protoc_insertion_point(field_mutable_list:pybullet_grpc.InitPoseCommand.initialStateQdot) + return &initialstateqdot_; +} + +// ------------------------------------------------------------------- + +// RequestActualStateCommand + +// int32 bodyUniqueId = 1; +inline void RequestActualStateCommand::clear_bodyuniqueid() { + bodyuniqueid_ = 0; +} +inline ::google::protobuf::int32 RequestActualStateCommand::bodyuniqueid() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.RequestActualStateCommand.bodyUniqueId) + return bodyuniqueid_; +} +inline void RequestActualStateCommand::set_bodyuniqueid(::google::protobuf::int32 value) { + + bodyuniqueid_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.RequestActualStateCommand.bodyUniqueId) +} + +// bool computeForwardKinematics = 2; +inline void RequestActualStateCommand::clear_computeforwardkinematics() { + computeforwardkinematics_ = false; +} +inline bool RequestActualStateCommand::computeforwardkinematics() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.RequestActualStateCommand.computeForwardKinematics) + return computeforwardkinematics_; +} +inline void RequestActualStateCommand::set_computeforwardkinematics(bool value) { + + computeforwardkinematics_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.RequestActualStateCommand.computeForwardKinematics) +} + +// bool computeLinkVelocities = 3; +inline void RequestActualStateCommand::clear_computelinkvelocities() { + computelinkvelocities_ = false; +} +inline bool RequestActualStateCommand::computelinkvelocities() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.RequestActualStateCommand.computeLinkVelocities) + return computelinkvelocities_; +} +inline void RequestActualStateCommand::set_computelinkvelocities(bool value) { + + computelinkvelocities_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.RequestActualStateCommand.computeLinkVelocities) +} + +// ------------------------------------------------------------------- + +// SendActualStateStatus + +// int32 bodyUniqueId = 1; +inline void SendActualStateStatus::clear_bodyuniqueid() { + bodyuniqueid_ = 0; +} +inline ::google::protobuf::int32 SendActualStateStatus::bodyuniqueid() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.SendActualStateStatus.bodyUniqueId) + return bodyuniqueid_; +} +inline void SendActualStateStatus::set_bodyuniqueid(::google::protobuf::int32 value) { + + bodyuniqueid_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.SendActualStateStatus.bodyUniqueId) +} + +// int32 numLinks = 2; +inline void SendActualStateStatus::clear_numlinks() { + numlinks_ = 0; +} +inline ::google::protobuf::int32 SendActualStateStatus::numlinks() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.SendActualStateStatus.numLinks) + return numlinks_; +} +inline void SendActualStateStatus::set_numlinks(::google::protobuf::int32 value) { + + numlinks_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.SendActualStateStatus.numLinks) +} + +// int32 numDegreeOfFreedomQ = 3; +inline void SendActualStateStatus::clear_numdegreeoffreedomq() { + numdegreeoffreedomq_ = 0; +} +inline ::google::protobuf::int32 SendActualStateStatus::numdegreeoffreedomq() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.SendActualStateStatus.numDegreeOfFreedomQ) + return numdegreeoffreedomq_; +} +inline void SendActualStateStatus::set_numdegreeoffreedomq(::google::protobuf::int32 value) { + + numdegreeoffreedomq_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.SendActualStateStatus.numDegreeOfFreedomQ) +} + +// int32 numDegreeOfFreedomU = 4; +inline void SendActualStateStatus::clear_numdegreeoffreedomu() { + numdegreeoffreedomu_ = 0; +} +inline ::google::protobuf::int32 SendActualStateStatus::numdegreeoffreedomu() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.SendActualStateStatus.numDegreeOfFreedomU) + return numdegreeoffreedomu_; +} +inline void SendActualStateStatus::set_numdegreeoffreedomu(::google::protobuf::int32 value) { + + numdegreeoffreedomu_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.SendActualStateStatus.numDegreeOfFreedomU) +} + +// repeated double rootLocalInertialFrame = 5; +inline int SendActualStateStatus::rootlocalinertialframe_size() const { + return rootlocalinertialframe_.size(); +} +inline void SendActualStateStatus::clear_rootlocalinertialframe() { + rootlocalinertialframe_.Clear(); +} +inline double SendActualStateStatus::rootlocalinertialframe(int index) const { + // @@protoc_insertion_point(field_get:pybullet_grpc.SendActualStateStatus.rootLocalInertialFrame) + return rootlocalinertialframe_.Get(index); +} +inline void SendActualStateStatus::set_rootlocalinertialframe(int index, double value) { + rootlocalinertialframe_.Set(index, value); + // @@protoc_insertion_point(field_set:pybullet_grpc.SendActualStateStatus.rootLocalInertialFrame) +} +inline void SendActualStateStatus::add_rootlocalinertialframe(double value) { + rootlocalinertialframe_.Add(value); + // @@protoc_insertion_point(field_add:pybullet_grpc.SendActualStateStatus.rootLocalInertialFrame) +} +inline const ::google::protobuf::RepeatedField< double >& +SendActualStateStatus::rootlocalinertialframe() const { + // @@protoc_insertion_point(field_list:pybullet_grpc.SendActualStateStatus.rootLocalInertialFrame) + return rootlocalinertialframe_; +} +inline ::google::protobuf::RepeatedField< double >* +SendActualStateStatus::mutable_rootlocalinertialframe() { + // @@protoc_insertion_point(field_mutable_list:pybullet_grpc.SendActualStateStatus.rootLocalInertialFrame) + return &rootlocalinertialframe_; +} + +// repeated double actualStateQ = 6; +inline int SendActualStateStatus::actualstateq_size() const { + return actualstateq_.size(); +} +inline void SendActualStateStatus::clear_actualstateq() { + actualstateq_.Clear(); +} +inline double SendActualStateStatus::actualstateq(int index) const { + // @@protoc_insertion_point(field_get:pybullet_grpc.SendActualStateStatus.actualStateQ) + return actualstateq_.Get(index); +} +inline void SendActualStateStatus::set_actualstateq(int index, double value) { + actualstateq_.Set(index, value); + // @@protoc_insertion_point(field_set:pybullet_grpc.SendActualStateStatus.actualStateQ) +} +inline void SendActualStateStatus::add_actualstateq(double value) { + actualstateq_.Add(value); + // @@protoc_insertion_point(field_add:pybullet_grpc.SendActualStateStatus.actualStateQ) +} +inline const ::google::protobuf::RepeatedField< double >& +SendActualStateStatus::actualstateq() const { + // @@protoc_insertion_point(field_list:pybullet_grpc.SendActualStateStatus.actualStateQ) + return actualstateq_; +} +inline ::google::protobuf::RepeatedField< double >* +SendActualStateStatus::mutable_actualstateq() { + // @@protoc_insertion_point(field_mutable_list:pybullet_grpc.SendActualStateStatus.actualStateQ) + return &actualstateq_; +} + +// repeated double actualStateQdot = 7; +inline int SendActualStateStatus::actualstateqdot_size() const { + return actualstateqdot_.size(); +} +inline void SendActualStateStatus::clear_actualstateqdot() { + actualstateqdot_.Clear(); +} +inline double SendActualStateStatus::actualstateqdot(int index) const { + // @@protoc_insertion_point(field_get:pybullet_grpc.SendActualStateStatus.actualStateQdot) + return actualstateqdot_.Get(index); +} +inline void SendActualStateStatus::set_actualstateqdot(int index, double value) { + actualstateqdot_.Set(index, value); + // @@protoc_insertion_point(field_set:pybullet_grpc.SendActualStateStatus.actualStateQdot) +} +inline void SendActualStateStatus::add_actualstateqdot(double value) { + actualstateqdot_.Add(value); + // @@protoc_insertion_point(field_add:pybullet_grpc.SendActualStateStatus.actualStateQdot) +} +inline const ::google::protobuf::RepeatedField< double >& +SendActualStateStatus::actualstateqdot() const { + // @@protoc_insertion_point(field_list:pybullet_grpc.SendActualStateStatus.actualStateQdot) + return actualstateqdot_; +} +inline ::google::protobuf::RepeatedField< double >* +SendActualStateStatus::mutable_actualstateqdot() { + // @@protoc_insertion_point(field_mutable_list:pybullet_grpc.SendActualStateStatus.actualStateQdot) + return &actualstateqdot_; +} + +// repeated double jointReactionForces = 8; +inline int SendActualStateStatus::jointreactionforces_size() const { + return jointreactionforces_.size(); +} +inline void SendActualStateStatus::clear_jointreactionforces() { + jointreactionforces_.Clear(); +} +inline double SendActualStateStatus::jointreactionforces(int index) const { + // @@protoc_insertion_point(field_get:pybullet_grpc.SendActualStateStatus.jointReactionForces) + return jointreactionforces_.Get(index); +} +inline void SendActualStateStatus::set_jointreactionforces(int index, double value) { + jointreactionforces_.Set(index, value); + // @@protoc_insertion_point(field_set:pybullet_grpc.SendActualStateStatus.jointReactionForces) +} +inline void SendActualStateStatus::add_jointreactionforces(double value) { + jointreactionforces_.Add(value); + // @@protoc_insertion_point(field_add:pybullet_grpc.SendActualStateStatus.jointReactionForces) +} +inline const ::google::protobuf::RepeatedField< double >& +SendActualStateStatus::jointreactionforces() const { + // @@protoc_insertion_point(field_list:pybullet_grpc.SendActualStateStatus.jointReactionForces) + return jointreactionforces_; +} +inline ::google::protobuf::RepeatedField< double >* +SendActualStateStatus::mutable_jointreactionforces() { + // @@protoc_insertion_point(field_mutable_list:pybullet_grpc.SendActualStateStatus.jointReactionForces) + return &jointreactionforces_; +} + +// repeated double jointMotorForce = 9; +inline int SendActualStateStatus::jointmotorforce_size() const { + return jointmotorforce_.size(); +} +inline void SendActualStateStatus::clear_jointmotorforce() { + jointmotorforce_.Clear(); +} +inline double SendActualStateStatus::jointmotorforce(int index) const { + // @@protoc_insertion_point(field_get:pybullet_grpc.SendActualStateStatus.jointMotorForce) + return jointmotorforce_.Get(index); +} +inline void SendActualStateStatus::set_jointmotorforce(int index, double value) { + jointmotorforce_.Set(index, value); + // @@protoc_insertion_point(field_set:pybullet_grpc.SendActualStateStatus.jointMotorForce) +} +inline void SendActualStateStatus::add_jointmotorforce(double value) { + jointmotorforce_.Add(value); + // @@protoc_insertion_point(field_add:pybullet_grpc.SendActualStateStatus.jointMotorForce) +} +inline const ::google::protobuf::RepeatedField< double >& +SendActualStateStatus::jointmotorforce() const { + // @@protoc_insertion_point(field_list:pybullet_grpc.SendActualStateStatus.jointMotorForce) + return jointmotorforce_; +} +inline ::google::protobuf::RepeatedField< double >* +SendActualStateStatus::mutable_jointmotorforce() { + // @@protoc_insertion_point(field_mutable_list:pybullet_grpc.SendActualStateStatus.jointMotorForce) + return &jointmotorforce_; +} + +// repeated double linkState = 10; +inline int SendActualStateStatus::linkstate_size() const { + return linkstate_.size(); +} +inline void SendActualStateStatus::clear_linkstate() { + linkstate_.Clear(); +} +inline double SendActualStateStatus::linkstate(int index) const { + // @@protoc_insertion_point(field_get:pybullet_grpc.SendActualStateStatus.linkState) + return linkstate_.Get(index); +} +inline void SendActualStateStatus::set_linkstate(int index, double value) { + linkstate_.Set(index, value); + // @@protoc_insertion_point(field_set:pybullet_grpc.SendActualStateStatus.linkState) +} +inline void SendActualStateStatus::add_linkstate(double value) { + linkstate_.Add(value); + // @@protoc_insertion_point(field_add:pybullet_grpc.SendActualStateStatus.linkState) +} +inline const ::google::protobuf::RepeatedField< double >& +SendActualStateStatus::linkstate() const { + // @@protoc_insertion_point(field_list:pybullet_grpc.SendActualStateStatus.linkState) + return linkstate_; +} +inline ::google::protobuf::RepeatedField< double >* +SendActualStateStatus::mutable_linkstate() { + // @@protoc_insertion_point(field_mutable_list:pybullet_grpc.SendActualStateStatus.linkState) + return &linkstate_; +} + +// repeated double linkWorldVelocities = 11; +inline int SendActualStateStatus::linkworldvelocities_size() const { + return linkworldvelocities_.size(); +} +inline void SendActualStateStatus::clear_linkworldvelocities() { + linkworldvelocities_.Clear(); +} +inline double SendActualStateStatus::linkworldvelocities(int index) const { + // @@protoc_insertion_point(field_get:pybullet_grpc.SendActualStateStatus.linkWorldVelocities) + return linkworldvelocities_.Get(index); +} +inline void SendActualStateStatus::set_linkworldvelocities(int index, double value) { + linkworldvelocities_.Set(index, value); + // @@protoc_insertion_point(field_set:pybullet_grpc.SendActualStateStatus.linkWorldVelocities) +} +inline void SendActualStateStatus::add_linkworldvelocities(double value) { + linkworldvelocities_.Add(value); + // @@protoc_insertion_point(field_add:pybullet_grpc.SendActualStateStatus.linkWorldVelocities) +} +inline const ::google::protobuf::RepeatedField< double >& +SendActualStateStatus::linkworldvelocities() const { + // @@protoc_insertion_point(field_list:pybullet_grpc.SendActualStateStatus.linkWorldVelocities) + return linkworldvelocities_; +} +inline ::google::protobuf::RepeatedField< double >* +SendActualStateStatus::mutable_linkworldvelocities() { + // @@protoc_insertion_point(field_mutable_list:pybullet_grpc.SendActualStateStatus.linkWorldVelocities) + return &linkworldvelocities_; +} + +// repeated double linkLocalInertialFrames = 12; +inline int SendActualStateStatus::linklocalinertialframes_size() const { + return linklocalinertialframes_.size(); +} +inline void SendActualStateStatus::clear_linklocalinertialframes() { + linklocalinertialframes_.Clear(); +} +inline double SendActualStateStatus::linklocalinertialframes(int index) const { + // @@protoc_insertion_point(field_get:pybullet_grpc.SendActualStateStatus.linkLocalInertialFrames) + return linklocalinertialframes_.Get(index); +} +inline void SendActualStateStatus::set_linklocalinertialframes(int index, double value) { + linklocalinertialframes_.Set(index, value); + // @@protoc_insertion_point(field_set:pybullet_grpc.SendActualStateStatus.linkLocalInertialFrames) +} +inline void SendActualStateStatus::add_linklocalinertialframes(double value) { + linklocalinertialframes_.Add(value); + // @@protoc_insertion_point(field_add:pybullet_grpc.SendActualStateStatus.linkLocalInertialFrames) +} +inline const ::google::protobuf::RepeatedField< double >& +SendActualStateStatus::linklocalinertialframes() const { + // @@protoc_insertion_point(field_list:pybullet_grpc.SendActualStateStatus.linkLocalInertialFrames) + return linklocalinertialframes_; +} +inline ::google::protobuf::RepeatedField< double >* +SendActualStateStatus::mutable_linklocalinertialframes() { + // @@protoc_insertion_point(field_mutable_list:pybullet_grpc.SendActualStateStatus.linkLocalInertialFrames) + return &linklocalinertialframes_; } // ------------------------------------------------------------------- @@ -1566,6 +4876,294 @@ inline void PyBulletCommand::set_allocated_stepsimulationcommand(::pybullet_grpc // @@protoc_insertion_point(field_set_allocated:pybullet_grpc.PyBulletCommand.stepSimulationCommand) } +// .pybullet_grpc.LoadSdfCommand loadSdfCommand = 6; +inline bool PyBulletCommand::has_loadsdfcommand() const { + return commands_case() == kLoadSdfCommand; +} +inline void PyBulletCommand::set_has_loadsdfcommand() { + _oneof_case_[0] = kLoadSdfCommand; +} +inline void PyBulletCommand::clear_loadsdfcommand() { + if (has_loadsdfcommand()) { + delete commands_.loadsdfcommand_; + clear_has_commands(); + } +} +inline const ::pybullet_grpc::LoadSdfCommand& PyBulletCommand::loadsdfcommand() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.PyBulletCommand.loadSdfCommand) + return has_loadsdfcommand() + ? *commands_.loadsdfcommand_ + : ::pybullet_grpc::LoadSdfCommand::default_instance(); +} +inline ::pybullet_grpc::LoadSdfCommand* PyBulletCommand::mutable_loadsdfcommand() { + if (!has_loadsdfcommand()) { + clear_commands(); + set_has_loadsdfcommand(); + commands_.loadsdfcommand_ = new ::pybullet_grpc::LoadSdfCommand; + } + // @@protoc_insertion_point(field_mutable:pybullet_grpc.PyBulletCommand.loadSdfCommand) + return commands_.loadsdfcommand_; +} +inline ::pybullet_grpc::LoadSdfCommand* PyBulletCommand::release_loadsdfcommand() { + // @@protoc_insertion_point(field_release:pybullet_grpc.PyBulletCommand.loadSdfCommand) + if (has_loadsdfcommand()) { + clear_has_commands(); + ::pybullet_grpc::LoadSdfCommand* temp = commands_.loadsdfcommand_; + commands_.loadsdfcommand_ = NULL; + return temp; + } else { + return NULL; + } +} +inline void PyBulletCommand::set_allocated_loadsdfcommand(::pybullet_grpc::LoadSdfCommand* loadsdfcommand) { + clear_commands(); + if (loadsdfcommand) { + set_has_loadsdfcommand(); + commands_.loadsdfcommand_ = loadsdfcommand; + } + // @@protoc_insertion_point(field_set_allocated:pybullet_grpc.PyBulletCommand.loadSdfCommand) +} + +// .pybullet_grpc.LoadMjcfCommand loadMjcfCommand = 7; +inline bool PyBulletCommand::has_loadmjcfcommand() const { + return commands_case() == kLoadMjcfCommand; +} +inline void PyBulletCommand::set_has_loadmjcfcommand() { + _oneof_case_[0] = kLoadMjcfCommand; +} +inline void PyBulletCommand::clear_loadmjcfcommand() { + if (has_loadmjcfcommand()) { + delete commands_.loadmjcfcommand_; + clear_has_commands(); + } +} +inline const ::pybullet_grpc::LoadMjcfCommand& PyBulletCommand::loadmjcfcommand() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.PyBulletCommand.loadMjcfCommand) + return has_loadmjcfcommand() + ? *commands_.loadmjcfcommand_ + : ::pybullet_grpc::LoadMjcfCommand::default_instance(); +} +inline ::pybullet_grpc::LoadMjcfCommand* PyBulletCommand::mutable_loadmjcfcommand() { + if (!has_loadmjcfcommand()) { + clear_commands(); + set_has_loadmjcfcommand(); + commands_.loadmjcfcommand_ = new ::pybullet_grpc::LoadMjcfCommand; + } + // @@protoc_insertion_point(field_mutable:pybullet_grpc.PyBulletCommand.loadMjcfCommand) + return commands_.loadmjcfcommand_; +} +inline ::pybullet_grpc::LoadMjcfCommand* PyBulletCommand::release_loadmjcfcommand() { + // @@protoc_insertion_point(field_release:pybullet_grpc.PyBulletCommand.loadMjcfCommand) + if (has_loadmjcfcommand()) { + clear_has_commands(); + ::pybullet_grpc::LoadMjcfCommand* temp = commands_.loadmjcfcommand_; + commands_.loadmjcfcommand_ = NULL; + return temp; + } else { + return NULL; + } +} +inline void PyBulletCommand::set_allocated_loadmjcfcommand(::pybullet_grpc::LoadMjcfCommand* loadmjcfcommand) { + clear_commands(); + if (loadmjcfcommand) { + set_has_loadmjcfcommand(); + commands_.loadmjcfcommand_ = loadmjcfcommand; + } + // @@protoc_insertion_point(field_set_allocated:pybullet_grpc.PyBulletCommand.loadMjcfCommand) +} + +// .pybullet_grpc.ChangeDynamicsCommand changeDynamicsCommand = 8; +inline bool PyBulletCommand::has_changedynamicscommand() const { + return commands_case() == kChangeDynamicsCommand; +} +inline void PyBulletCommand::set_has_changedynamicscommand() { + _oneof_case_[0] = kChangeDynamicsCommand; +} +inline void PyBulletCommand::clear_changedynamicscommand() { + if (has_changedynamicscommand()) { + delete commands_.changedynamicscommand_; + clear_has_commands(); + } +} +inline const ::pybullet_grpc::ChangeDynamicsCommand& PyBulletCommand::changedynamicscommand() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.PyBulletCommand.changeDynamicsCommand) + return has_changedynamicscommand() + ? *commands_.changedynamicscommand_ + : ::pybullet_grpc::ChangeDynamicsCommand::default_instance(); +} +inline ::pybullet_grpc::ChangeDynamicsCommand* PyBulletCommand::mutable_changedynamicscommand() { + if (!has_changedynamicscommand()) { + clear_commands(); + set_has_changedynamicscommand(); + commands_.changedynamicscommand_ = new ::pybullet_grpc::ChangeDynamicsCommand; + } + // @@protoc_insertion_point(field_mutable:pybullet_grpc.PyBulletCommand.changeDynamicsCommand) + return commands_.changedynamicscommand_; +} +inline ::pybullet_grpc::ChangeDynamicsCommand* PyBulletCommand::release_changedynamicscommand() { + // @@protoc_insertion_point(field_release:pybullet_grpc.PyBulletCommand.changeDynamicsCommand) + if (has_changedynamicscommand()) { + clear_has_commands(); + ::pybullet_grpc::ChangeDynamicsCommand* temp = commands_.changedynamicscommand_; + commands_.changedynamicscommand_ = NULL; + return temp; + } else { + return NULL; + } +} +inline void PyBulletCommand::set_allocated_changedynamicscommand(::pybullet_grpc::ChangeDynamicsCommand* changedynamicscommand) { + clear_commands(); + if (changedynamicscommand) { + set_has_changedynamicscommand(); + commands_.changedynamicscommand_ = changedynamicscommand; + } + // @@protoc_insertion_point(field_set_allocated:pybullet_grpc.PyBulletCommand.changeDynamicsCommand) +} + +// .pybullet_grpc.GetDynamicsCommand getDynamicsCommand = 9; +inline bool PyBulletCommand::has_getdynamicscommand() const { + return commands_case() == kGetDynamicsCommand; +} +inline void PyBulletCommand::set_has_getdynamicscommand() { + _oneof_case_[0] = kGetDynamicsCommand; +} +inline void PyBulletCommand::clear_getdynamicscommand() { + if (has_getdynamicscommand()) { + delete commands_.getdynamicscommand_; + clear_has_commands(); + } +} +inline const ::pybullet_grpc::GetDynamicsCommand& PyBulletCommand::getdynamicscommand() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.PyBulletCommand.getDynamicsCommand) + return has_getdynamicscommand() + ? *commands_.getdynamicscommand_ + : ::pybullet_grpc::GetDynamicsCommand::default_instance(); +} +inline ::pybullet_grpc::GetDynamicsCommand* PyBulletCommand::mutable_getdynamicscommand() { + if (!has_getdynamicscommand()) { + clear_commands(); + set_has_getdynamicscommand(); + commands_.getdynamicscommand_ = new ::pybullet_grpc::GetDynamicsCommand; + } + // @@protoc_insertion_point(field_mutable:pybullet_grpc.PyBulletCommand.getDynamicsCommand) + return commands_.getdynamicscommand_; +} +inline ::pybullet_grpc::GetDynamicsCommand* PyBulletCommand::release_getdynamicscommand() { + // @@protoc_insertion_point(field_release:pybullet_grpc.PyBulletCommand.getDynamicsCommand) + if (has_getdynamicscommand()) { + clear_has_commands(); + ::pybullet_grpc::GetDynamicsCommand* temp = commands_.getdynamicscommand_; + commands_.getdynamicscommand_ = NULL; + return temp; + } else { + return NULL; + } +} +inline void PyBulletCommand::set_allocated_getdynamicscommand(::pybullet_grpc::GetDynamicsCommand* getdynamicscommand) { + clear_commands(); + if (getdynamicscommand) { + set_has_getdynamicscommand(); + commands_.getdynamicscommand_ = getdynamicscommand; + } + // @@protoc_insertion_point(field_set_allocated:pybullet_grpc.PyBulletCommand.getDynamicsCommand) +} + +// .pybullet_grpc.InitPoseCommand initPoseCommand = 10; +inline bool PyBulletCommand::has_initposecommand() const { + return commands_case() == kInitPoseCommand; +} +inline void PyBulletCommand::set_has_initposecommand() { + _oneof_case_[0] = kInitPoseCommand; +} +inline void PyBulletCommand::clear_initposecommand() { + if (has_initposecommand()) { + delete commands_.initposecommand_; + clear_has_commands(); + } +} +inline const ::pybullet_grpc::InitPoseCommand& PyBulletCommand::initposecommand() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.PyBulletCommand.initPoseCommand) + return has_initposecommand() + ? *commands_.initposecommand_ + : ::pybullet_grpc::InitPoseCommand::default_instance(); +} +inline ::pybullet_grpc::InitPoseCommand* PyBulletCommand::mutable_initposecommand() { + if (!has_initposecommand()) { + clear_commands(); + set_has_initposecommand(); + commands_.initposecommand_ = new ::pybullet_grpc::InitPoseCommand; + } + // @@protoc_insertion_point(field_mutable:pybullet_grpc.PyBulletCommand.initPoseCommand) + return commands_.initposecommand_; +} +inline ::pybullet_grpc::InitPoseCommand* PyBulletCommand::release_initposecommand() { + // @@protoc_insertion_point(field_release:pybullet_grpc.PyBulletCommand.initPoseCommand) + if (has_initposecommand()) { + clear_has_commands(); + ::pybullet_grpc::InitPoseCommand* temp = commands_.initposecommand_; + commands_.initposecommand_ = NULL; + return temp; + } else { + return NULL; + } +} +inline void PyBulletCommand::set_allocated_initposecommand(::pybullet_grpc::InitPoseCommand* initposecommand) { + clear_commands(); + if (initposecommand) { + set_has_initposecommand(); + commands_.initposecommand_ = initposecommand; + } + // @@protoc_insertion_point(field_set_allocated:pybullet_grpc.PyBulletCommand.initPoseCommand) +} + +// .pybullet_grpc.RequestActualStateCommand requestActualStateCommand = 11; +inline bool PyBulletCommand::has_requestactualstatecommand() const { + return commands_case() == kRequestActualStateCommand; +} +inline void PyBulletCommand::set_has_requestactualstatecommand() { + _oneof_case_[0] = kRequestActualStateCommand; +} +inline void PyBulletCommand::clear_requestactualstatecommand() { + if (has_requestactualstatecommand()) { + delete commands_.requestactualstatecommand_; + clear_has_commands(); + } +} +inline const ::pybullet_grpc::RequestActualStateCommand& PyBulletCommand::requestactualstatecommand() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.PyBulletCommand.requestActualStateCommand) + return has_requestactualstatecommand() + ? *commands_.requestactualstatecommand_ + : ::pybullet_grpc::RequestActualStateCommand::default_instance(); +} +inline ::pybullet_grpc::RequestActualStateCommand* PyBulletCommand::mutable_requestactualstatecommand() { + if (!has_requestactualstatecommand()) { + clear_commands(); + set_has_requestactualstatecommand(); + commands_.requestactualstatecommand_ = new ::pybullet_grpc::RequestActualStateCommand; + } + // @@protoc_insertion_point(field_mutable:pybullet_grpc.PyBulletCommand.requestActualStateCommand) + return commands_.requestactualstatecommand_; +} +inline ::pybullet_grpc::RequestActualStateCommand* PyBulletCommand::release_requestactualstatecommand() { + // @@protoc_insertion_point(field_release:pybullet_grpc.PyBulletCommand.requestActualStateCommand) + if (has_requestactualstatecommand()) { + clear_has_commands(); + ::pybullet_grpc::RequestActualStateCommand* temp = commands_.requestactualstatecommand_; + commands_.requestactualstatecommand_ = NULL; + return temp; + } else { + return NULL; + } +} +inline void PyBulletCommand::set_allocated_requestactualstatecommand(::pybullet_grpc::RequestActualStateCommand* requestactualstatecommand) { + clear_commands(); + if (requestactualstatecommand) { + set_has_requestactualstatecommand(); + commands_.requestactualstatecommand_ = requestactualstatecommand; + } + // @@protoc_insertion_point(field_set_allocated:pybullet_grpc.PyBulletCommand.requestActualStateCommand) +} + inline bool PyBulletCommand::has_commands() const { return commands_case() != COMMANDS_NOT_SET; } @@ -1641,6 +5239,198 @@ inline void PyBulletStatus::set_allocated_urdfstatus(::pybullet_grpc::LoadUrdfSt // @@protoc_insertion_point(field_set_allocated:pybullet_grpc.PyBulletStatus.urdfStatus) } +// .pybullet_grpc.SdfLoadedStatus sdfStatus = 3; +inline bool PyBulletStatus::has_sdfstatus() const { + return status_case() == kSdfStatus; +} +inline void PyBulletStatus::set_has_sdfstatus() { + _oneof_case_[0] = kSdfStatus; +} +inline void PyBulletStatus::clear_sdfstatus() { + if (has_sdfstatus()) { + delete status_.sdfstatus_; + clear_has_status(); + } +} +inline const ::pybullet_grpc::SdfLoadedStatus& PyBulletStatus::sdfstatus() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.PyBulletStatus.sdfStatus) + return has_sdfstatus() + ? *status_.sdfstatus_ + : ::pybullet_grpc::SdfLoadedStatus::default_instance(); +} +inline ::pybullet_grpc::SdfLoadedStatus* PyBulletStatus::mutable_sdfstatus() { + if (!has_sdfstatus()) { + clear_status(); + set_has_sdfstatus(); + status_.sdfstatus_ = new ::pybullet_grpc::SdfLoadedStatus; + } + // @@protoc_insertion_point(field_mutable:pybullet_grpc.PyBulletStatus.sdfStatus) + return status_.sdfstatus_; +} +inline ::pybullet_grpc::SdfLoadedStatus* PyBulletStatus::release_sdfstatus() { + // @@protoc_insertion_point(field_release:pybullet_grpc.PyBulletStatus.sdfStatus) + if (has_sdfstatus()) { + clear_has_status(); + ::pybullet_grpc::SdfLoadedStatus* temp = status_.sdfstatus_; + status_.sdfstatus_ = NULL; + return temp; + } else { + return NULL; + } +} +inline void PyBulletStatus::set_allocated_sdfstatus(::pybullet_grpc::SdfLoadedStatus* sdfstatus) { + clear_status(); + if (sdfstatus) { + set_has_sdfstatus(); + status_.sdfstatus_ = sdfstatus; + } + // @@protoc_insertion_point(field_set_allocated:pybullet_grpc.PyBulletStatus.sdfStatus) +} + +// .pybullet_grpc.MjcfLoadedStatus mjcfStatus = 4; +inline bool PyBulletStatus::has_mjcfstatus() const { + return status_case() == kMjcfStatus; +} +inline void PyBulletStatus::set_has_mjcfstatus() { + _oneof_case_[0] = kMjcfStatus; +} +inline void PyBulletStatus::clear_mjcfstatus() { + if (has_mjcfstatus()) { + delete status_.mjcfstatus_; + clear_has_status(); + } +} +inline const ::pybullet_grpc::MjcfLoadedStatus& PyBulletStatus::mjcfstatus() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.PyBulletStatus.mjcfStatus) + return has_mjcfstatus() + ? *status_.mjcfstatus_ + : ::pybullet_grpc::MjcfLoadedStatus::default_instance(); +} +inline ::pybullet_grpc::MjcfLoadedStatus* PyBulletStatus::mutable_mjcfstatus() { + if (!has_mjcfstatus()) { + clear_status(); + set_has_mjcfstatus(); + status_.mjcfstatus_ = new ::pybullet_grpc::MjcfLoadedStatus; + } + // @@protoc_insertion_point(field_mutable:pybullet_grpc.PyBulletStatus.mjcfStatus) + return status_.mjcfstatus_; +} +inline ::pybullet_grpc::MjcfLoadedStatus* PyBulletStatus::release_mjcfstatus() { + // @@protoc_insertion_point(field_release:pybullet_grpc.PyBulletStatus.mjcfStatus) + if (has_mjcfstatus()) { + clear_has_status(); + ::pybullet_grpc::MjcfLoadedStatus* temp = status_.mjcfstatus_; + status_.mjcfstatus_ = NULL; + return temp; + } else { + return NULL; + } +} +inline void PyBulletStatus::set_allocated_mjcfstatus(::pybullet_grpc::MjcfLoadedStatus* mjcfstatus) { + clear_status(); + if (mjcfstatus) { + set_has_mjcfstatus(); + status_.mjcfstatus_ = mjcfstatus; + } + // @@protoc_insertion_point(field_set_allocated:pybullet_grpc.PyBulletStatus.mjcfStatus) +} + +// .pybullet_grpc.GetDynamicsStatus getDynamicsStatus = 5; +inline bool PyBulletStatus::has_getdynamicsstatus() const { + return status_case() == kGetDynamicsStatus; +} +inline void PyBulletStatus::set_has_getdynamicsstatus() { + _oneof_case_[0] = kGetDynamicsStatus; +} +inline void PyBulletStatus::clear_getdynamicsstatus() { + if (has_getdynamicsstatus()) { + delete status_.getdynamicsstatus_; + clear_has_status(); + } +} +inline const ::pybullet_grpc::GetDynamicsStatus& PyBulletStatus::getdynamicsstatus() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.PyBulletStatus.getDynamicsStatus) + return has_getdynamicsstatus() + ? *status_.getdynamicsstatus_ + : ::pybullet_grpc::GetDynamicsStatus::default_instance(); +} +inline ::pybullet_grpc::GetDynamicsStatus* PyBulletStatus::mutable_getdynamicsstatus() { + if (!has_getdynamicsstatus()) { + clear_status(); + set_has_getdynamicsstatus(); + status_.getdynamicsstatus_ = new ::pybullet_grpc::GetDynamicsStatus; + } + // @@protoc_insertion_point(field_mutable:pybullet_grpc.PyBulletStatus.getDynamicsStatus) + return status_.getdynamicsstatus_; +} +inline ::pybullet_grpc::GetDynamicsStatus* PyBulletStatus::release_getdynamicsstatus() { + // @@protoc_insertion_point(field_release:pybullet_grpc.PyBulletStatus.getDynamicsStatus) + if (has_getdynamicsstatus()) { + clear_has_status(); + ::pybullet_grpc::GetDynamicsStatus* temp = status_.getdynamicsstatus_; + status_.getdynamicsstatus_ = NULL; + return temp; + } else { + return NULL; + } +} +inline void PyBulletStatus::set_allocated_getdynamicsstatus(::pybullet_grpc::GetDynamicsStatus* getdynamicsstatus) { + clear_status(); + if (getdynamicsstatus) { + set_has_getdynamicsstatus(); + status_.getdynamicsstatus_ = getdynamicsstatus; + } + // @@protoc_insertion_point(field_set_allocated:pybullet_grpc.PyBulletStatus.getDynamicsStatus) +} + +// .pybullet_grpc.SendActualStateStatus actualStateStatus = 6; +inline bool PyBulletStatus::has_actualstatestatus() const { + return status_case() == kActualStateStatus; +} +inline void PyBulletStatus::set_has_actualstatestatus() { + _oneof_case_[0] = kActualStateStatus; +} +inline void PyBulletStatus::clear_actualstatestatus() { + if (has_actualstatestatus()) { + delete status_.actualstatestatus_; + clear_has_status(); + } +} +inline const ::pybullet_grpc::SendActualStateStatus& PyBulletStatus::actualstatestatus() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.PyBulletStatus.actualStateStatus) + return has_actualstatestatus() + ? *status_.actualstatestatus_ + : ::pybullet_grpc::SendActualStateStatus::default_instance(); +} +inline ::pybullet_grpc::SendActualStateStatus* PyBulletStatus::mutable_actualstatestatus() { + if (!has_actualstatestatus()) { + clear_status(); + set_has_actualstatestatus(); + status_.actualstatestatus_ = new ::pybullet_grpc::SendActualStateStatus; + } + // @@protoc_insertion_point(field_mutable:pybullet_grpc.PyBulletStatus.actualStateStatus) + return status_.actualstatestatus_; +} +inline ::pybullet_grpc::SendActualStateStatus* PyBulletStatus::release_actualstatestatus() { + // @@protoc_insertion_point(field_release:pybullet_grpc.PyBulletStatus.actualStateStatus) + if (has_actualstatestatus()) { + clear_has_status(); + ::pybullet_grpc::SendActualStateStatus* temp = status_.actualstatestatus_; + status_.actualstatestatus_ = NULL; + return temp; + } else { + return NULL; + } +} +inline void PyBulletStatus::set_allocated_actualstatestatus(::pybullet_grpc::SendActualStateStatus* actualstatestatus) { + clear_status(); + if (actualstatestatus) { + set_has_actualstatestatus(); + status_.actualstatestatus_ = actualstatestatus; + } + // @@protoc_insertion_point(field_set_allocated:pybullet_grpc.PyBulletStatus.actualStateStatus) +} + inline bool PyBulletStatus::has_status() const { return status_case() != STATUS_NOT_SET; } @@ -1665,6 +5455,26 @@ inline PyBulletStatus::StatusCase PyBulletStatus::status_case() const { // ------------------------------------------------------------------- +// ------------------------------------------------------------------- + +// ------------------------------------------------------------------- + +// ------------------------------------------------------------------- + +// ------------------------------------------------------------------- + +// ------------------------------------------------------------------- + +// ------------------------------------------------------------------- + +// ------------------------------------------------------------------- + +// ------------------------------------------------------------------- + +// ------------------------------------------------------------------- + +// ------------------------------------------------------------------- + // @@protoc_insertion_point(namespace_scope) diff --git a/examples/SharedMemory/grpc/pybullet_client.py b/examples/SharedMemory/grpc/pybullet_client.py index 205113bc9..a042d668c 100644 --- a/examples/SharedMemory/grpc/pybullet_client.py +++ b/examples/SharedMemory/grpc/pybullet_client.py @@ -7,22 +7,58 @@ import grpc import pybullet_pb2 import pybullet_pb2_grpc +#todo: how to add this? +MJCF_COLORS_FROM_FILE = 512 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) - + print("grpc.insecure_channel") + channel = grpc.insecure_channel('localhost:50051') + print("pybullet_pb2_grpc.PyBulletAPIStub") + stub = pybullet_pb2_grpc.PyBulletAPIStub(channel) + response=0 + + print("submit LoadSdfCommand") + response = stub.SubmitCommand(pybullet_pb2.PyBulletCommand(loadSdfCommand=pybullet_pb2.LoadSdfCommand(fileName="two_cubes.sdf", useMultiBody=True, globalScaling=2))) + print("PyBullet client received: " , response) - response = stub.SubmitCommand(pybullet_pb2.PyBulletCommand(stepSimulationCommand=pybullet_pb2.StepSimulationCommand())) - print("PyBullet client received: " , response.statusType) + + print("submit LoadMjcfCommand") + response = stub.SubmitCommand(pybullet_pb2.PyBulletCommand(loadMjcfCommand=pybullet_pb2.LoadMjcfCommand(fileName="mjcf/humanoid.xml",flags=MJCF_COLORS_FROM_FILE))) + print("PyBullet client received: " , response) + + + print("submit LoadUrdfCommand ") + response = stub.SubmitCommand(pybullet_pb2.PyBulletCommand(loadUrdfCommand=pybullet_pb2.LoadUrdfCommand(fileName="door.urdf", initialPosition=pybullet_pb2.vec3(x=0,y=0,z=0), useMultiBody=True, useFixedBase=True, globalScaling=2, flags = 1))) + print("PyBullet client received: " , response) + bodyUniqueId = response.urdfStatus.bodyUniqueId + + print("submit ChangeDynamicsCommand ") + response = stub.SubmitCommand(pybullet_pb2.PyBulletCommand(changeDynamicsCommand=pybullet_pb2.ChangeDynamicsCommand(bodyUniqueId=bodyUniqueId, linkIndex=-1, mass=10))) + print("PyBullet client received: " , response) + + print("submit GetDynamicsCommand ") + response = stub.SubmitCommand(pybullet_pb2.PyBulletCommand(getDynamicsCommand=pybullet_pb2.GetDynamicsCommand(bodyUniqueId=bodyUniqueId, linkIndex=-1))) + print("PyBullet client received: " , response) + + print("submit InitPoseCommand") + response = stub.SubmitCommand(pybullet_pb2.PyBulletCommand(initPoseCommand=pybullet_pb2.InitPoseCommand(bodyUniqueId=bodyUniqueId, initialStateQ=[1,2,3],hasInitialStateQ=[1,1,1]))) + print("PyBullet client received: " , response) + + print("submit RequestActualStateCommand") + response = stub.SubmitCommand(pybullet_pb2.PyBulletCommand(requestActualStateCommand=pybullet_pb2.RequestActualStateCommand(bodyUniqueId=bodyUniqueId, computeForwardKinematics=True, computeLinkVelocities=True ))) + print("PyBullet client received: " , response) + + + + #for i in range (1000): + # print("submit StepSimulationCommand: ", i) + # 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) + #print("TerminateServerCommand") + #response = stub.SubmitCommand(pybullet_pb2.PyBulletCommand(terminateServerCommand=pybullet_pb2.TerminateServerCommand())) + #print("PyBullet client received: " , response.statusType) if __name__ == '__main__': - run() + run() diff --git a/examples/SharedMemory/grpc/pybullet_pb2.py b/examples/SharedMemory/grpc/pybullet_pb2.py index 7bbea2282..706179e12 100644 --- a/examples/SharedMemory/grpc/pybullet_pb2.py +++ b/examples/SharedMemory/grpc/pybullet_pb2.py @@ -19,7 +19,7 @@ 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') + 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\"\x95\x02\n\x0fLoadUrdfCommand\x12\x10\n\x08\x66ileName\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\r\n\x05\x66lags\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\x14\n\x0c\x62odyUniqueId\x18\x01 \x01(\x05\"z\n\x0eLoadSdfCommand\x12\x10\n\x08\x66ileName\x18\x01 \x01(\t\x12\x16\n\x0cuseMultiBody\x18\x02 \x01(\x05H\x00\x12\x17\n\rglobalScaling\x18\x03 \x01(\x01H\x01\x42\x11\n\x0fhasUseMultiBodyB\x12\n\x10hasGlobalScaling\"(\n\x0fSdfLoadedStatus\x12\x15\n\rbodyUniqueIds\x18\x02 \x03(\x05\"2\n\x0fLoadMjcfCommand\x12\x10\n\x08\x66ileName\x18\x01 \x01(\t\x12\r\n\x05\x66lags\x18\x02 \x01(\x05\")\n\x10MjcfLoadedStatus\x12\x15\n\rbodyUniqueIds\x18\x02 \x03(\x05\"\x89\x06\n\x15\x43hangeDynamicsCommand\x12\x14\n\x0c\x62odyUniqueId\x18\x01 \x01(\x05\x12\x11\n\tlinkIndex\x18\x02 \x01(\x05\x12\x0e\n\x04mass\x18\x03 \x01(\x01H\x00\x12\x19\n\x0flateralFriction\x18\x05 \x01(\x01H\x01\x12\x1a\n\x10spinningFriction\x18\x06 \x01(\x01H\x02\x12\x19\n\x0frollingFriction\x18\x07 \x01(\x01H\x03\x12\x15\n\x0brestitution\x18\x08 \x01(\x01H\x04\x12\x17\n\rlinearDamping\x18\t \x01(\x01H\x05\x12\x18\n\x0e\x61ngularDamping\x18\n \x01(\x01H\x06\x12\x1a\n\x10\x63ontactStiffness\x18\x0b \x01(\x01H\x07\x12\x18\n\x0e\x63ontactDamping\x18\x0c \x01(\x01H\x08\x12\x33\n\x14localInertiaDiagonal\x18\r \x01(\x0b\x32\x13.pybullet_grpc.vec3H\t\x12\x18\n\x0e\x66rictionAnchor\x18\x0e \x01(\x05H\n\x12\x1e\n\x14\x63\x63\x64SweptSphereRadius\x18\x0f \x01(\x01H\x0b\x12$\n\x1a\x63ontactProcessingThreshold\x18\x10 \x01(\x01H\x0c\x12\x19\n\x0f\x61\x63tivationState\x18\x11 \x01(\x05H\rB\t\n\x07hasMassB\x14\n\x12hasLateralFrictionB\x15\n\x13hasSpinningFrictionB\x14\n\x12hasRollingFrictionB\x10\n\x0ehasRestitutionB\x12\n\x10haslinearDampingB\x13\n\x11hasangularDampingB\x15\n\x13hasContactStiffnessB\x13\n\x11hasContactDampingB\x19\n\x17hasLocalInertiaDiagonalB\x13\n\x11hasFrictionAnchorB\x19\n\x17hasccdSweptSphereRadiusB\x1f\n\x1dhasContactProcessingThresholdB\x14\n\x12hasActivationState\"=\n\x12GetDynamicsCommand\x12\x14\n\x0c\x62odyUniqueId\x18\x01 \x01(\x05\x12\x11\n\tlinkIndex\x18\x02 \x01(\x05\"\x89\x03\n\x11GetDynamicsStatus\x12\x0c\n\x04mass\x18\x03 \x01(\x01\x12\x17\n\x0flateralFriction\x18\x05 \x01(\x01\x12\x18\n\x10spinningFriction\x18\x06 \x01(\x01\x12\x17\n\x0frollingFriction\x18\x07 \x01(\x01\x12\x13\n\x0brestitution\x18\x08 \x01(\x01\x12\x15\n\rlinearDamping\x18\t \x01(\x01\x12\x16\n\x0e\x61ngularDamping\x18\n \x01(\x01\x12\x18\n\x10\x63ontactStiffness\x18\x0b \x01(\x01\x12\x16\n\x0e\x63ontactDamping\x18\x0c \x01(\x01\x12\x31\n\x14localInertiaDiagonal\x18\r \x01(\x0b\x32\x13.pybullet_grpc.vec3\x12\x16\n\x0e\x66rictionAnchor\x18\x0e \x01(\x05\x12\x1c\n\x14\x63\x63\x64SweptSphereRadius\x18\x0f \x01(\x01\x12\"\n\x1a\x63ontactProcessingThreshold\x18\x10 \x01(\x01\x12\x17\n\x0f\x61\x63tivationState\x18\x11 \x01(\x05\"\x8f\x01\n\x0fInitPoseCommand\x12\x14\n\x0c\x62odyUniqueId\x18\x01 \x01(\x05\x12\x18\n\x10hasInitialStateQ\x18\x02 \x03(\x05\x12\x15\n\rinitialStateQ\x18\x03 \x03(\x01\x12\x1b\n\x13hasInitialStateQdot\x18\x04 \x03(\x05\x12\x18\n\x10initialStateQdot\x18\x05 \x03(\x01\"r\n\x19RequestActualStateCommand\x12\x14\n\x0c\x62odyUniqueId\x18\x01 \x01(\x05\x12 \n\x18\x63omputeForwardKinematics\x18\x02 \x01(\x08\x12\x1d\n\x15\x63omputeLinkVelocities\x18\x03 \x01(\x08\"\xcf\x02\n\x15SendActualStateStatus\x12\x14\n\x0c\x62odyUniqueId\x18\x01 \x01(\x05\x12\x10\n\x08numLinks\x18\x02 \x01(\x05\x12\x1b\n\x13numDegreeOfFreedomQ\x18\x03 \x01(\x05\x12\x1b\n\x13numDegreeOfFreedomU\x18\x04 \x01(\x05\x12\x1e\n\x16rootLocalInertialFrame\x18\x05 \x03(\x01\x12\x14\n\x0c\x61\x63tualStateQ\x18\x06 \x03(\x01\x12\x17\n\x0f\x61\x63tualStateQdot\x18\x07 \x03(\x01\x12\x1b\n\x13jointReactionForces\x18\x08 \x03(\x01\x12\x17\n\x0fjointMotorForce\x18\t \x03(\x01\x12\x11\n\tlinkState\x18\n \x03(\x01\x12\x1b\n\x13linkWorldVelocities\x18\x0b \x03(\x01\x12\x1f\n\x17linkLocalInertialFrames\x18\x0c \x03(\x01\"\x83\x05\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\x12\x37\n\x0eloadSdfCommand\x18\x06 \x01(\x0b\x32\x1d.pybullet_grpc.LoadSdfCommandH\x00\x12\x39\n\x0floadMjcfCommand\x18\x07 \x01(\x0b\x32\x1e.pybullet_grpc.LoadMjcfCommandH\x00\x12\x45\n\x15\x63hangeDynamicsCommand\x18\x08 \x01(\x0b\x32$.pybullet_grpc.ChangeDynamicsCommandH\x00\x12?\n\x12getDynamicsCommand\x18\t \x01(\x0b\x32!.pybullet_grpc.GetDynamicsCommandH\x00\x12\x39\n\x0finitPoseCommand\x18\n \x01(\x0b\x32\x1e.pybullet_grpc.InitPoseCommandH\x00\x12M\n\x19requestActualStateCommand\x18\x0b \x01(\x0b\x32(.pybullet_grpc.RequestActualStateCommandH\x00\x42\n\n\x08\x63ommands\"\xd1\x02\n\x0ePyBulletStatus\x12\x12\n\nstatusType\x18\x01 \x01(\x05\x12\x33\n\nurdfStatus\x18\x02 \x01(\x0b\x32\x1d.pybullet_grpc.LoadUrdfStatusH\x00\x12\x33\n\tsdfStatus\x18\x03 \x01(\x0b\x32\x1e.pybullet_grpc.SdfLoadedStatusH\x00\x12\x35\n\nmjcfStatus\x18\x04 \x01(\x0b\x32\x1f.pybullet_grpc.MjcfLoadedStatusH\x00\x12=\n\x11getDynamicsStatus\x18\x05 \x01(\x0b\x32 .pybullet_grpc.GetDynamicsStatusH\x00\x12\x41\n\x11\x61\x63tualStateStatus\x18\x06 \x01(\x0b\x32$.pybullet_grpc.SendActualStateStatusH\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') ) @@ -185,7 +185,7 @@ _LOADURDFCOMMAND = _descriptor.Descriptor( containing_type=None, fields=[ _descriptor.FieldDescriptor( - name='urdfFileName', full_name='pybullet_grpc.LoadUrdfCommand.urdfFileName', index=0, + name='fileName', full_name='pybullet_grpc.LoadUrdfCommand.fileName', 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, @@ -220,7 +220,7 @@ _LOADURDFCOMMAND = _descriptor.Descriptor( is_extension=False, extension_scope=None, options=None, file=DESCRIPTOR), _descriptor.FieldDescriptor( - name='urdfFlags', full_name='pybullet_grpc.LoadUrdfCommand.urdfFlags', index=5, + name='flags', full_name='pybullet_grpc.LoadUrdfCommand.flags', 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, @@ -255,7 +255,7 @@ _LOADURDFCOMMAND = _descriptor.Descriptor( index=2, containing_type=None, fields=[]), ], serialized_start=199, - serialized_end=484, + serialized_end=476, ) @@ -267,7 +267,7 @@ _LOADURDFSTATUS = _descriptor.Descriptor( containing_type=None, fields=[ _descriptor.FieldDescriptor( - name='objectUniqueId', full_name='pybullet_grpc.LoadUrdfStatus.objectUniqueId', index=0, + name='bodyUniqueId', full_name='pybullet_grpc.LoadUrdfStatus.bodyUniqueId', 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, @@ -285,8 +285,709 @@ _LOADURDFSTATUS = _descriptor.Descriptor( extension_ranges=[], oneofs=[ ], - serialized_start=486, - serialized_end=526, + serialized_start=478, + serialized_end=516, +) + + +_LOADSDFCOMMAND = _descriptor.Descriptor( + name='LoadSdfCommand', + full_name='pybullet_grpc.LoadSdfCommand', + filename=None, + file=DESCRIPTOR, + containing_type=None, + fields=[ + _descriptor.FieldDescriptor( + name='fileName', full_name='pybullet_grpc.LoadSdfCommand.fileName', 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='useMultiBody', full_name='pybullet_grpc.LoadSdfCommand.useMultiBody', index=1, + number=2, 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.LoadSdfCommand.globalScaling', 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=[ + _descriptor.OneofDescriptor( + name='hasUseMultiBody', full_name='pybullet_grpc.LoadSdfCommand.hasUseMultiBody', + index=0, containing_type=None, fields=[]), + _descriptor.OneofDescriptor( + name='hasGlobalScaling', full_name='pybullet_grpc.LoadSdfCommand.hasGlobalScaling', + index=1, containing_type=None, fields=[]), + ], + serialized_start=518, + serialized_end=640, +) + + +_SDFLOADEDSTATUS = _descriptor.Descriptor( + name='SdfLoadedStatus', + full_name='pybullet_grpc.SdfLoadedStatus', + filename=None, + file=DESCRIPTOR, + containing_type=None, + fields=[ + _descriptor.FieldDescriptor( + name='bodyUniqueIds', full_name='pybullet_grpc.SdfLoadedStatus.bodyUniqueIds', index=0, + number=2, type=5, cpp_type=1, label=3, + has_default_value=False, default_value=[], + 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=642, + serialized_end=682, +) + + +_LOADMJCFCOMMAND = _descriptor.Descriptor( + name='LoadMjcfCommand', + full_name='pybullet_grpc.LoadMjcfCommand', + filename=None, + file=DESCRIPTOR, + containing_type=None, + fields=[ + _descriptor.FieldDescriptor( + name='fileName', full_name='pybullet_grpc.LoadMjcfCommand.fileName', 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='flags', full_name='pybullet_grpc.LoadMjcfCommand.flags', index=1, + number=2, 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=684, + serialized_end=734, +) + + +_MJCFLOADEDSTATUS = _descriptor.Descriptor( + name='MjcfLoadedStatus', + full_name='pybullet_grpc.MjcfLoadedStatus', + filename=None, + file=DESCRIPTOR, + containing_type=None, + fields=[ + _descriptor.FieldDescriptor( + name='bodyUniqueIds', full_name='pybullet_grpc.MjcfLoadedStatus.bodyUniqueIds', index=0, + number=2, type=5, cpp_type=1, label=3, + has_default_value=False, default_value=[], + 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=736, + serialized_end=777, +) + + +_CHANGEDYNAMICSCOMMAND = _descriptor.Descriptor( + name='ChangeDynamicsCommand', + full_name='pybullet_grpc.ChangeDynamicsCommand', + filename=None, + file=DESCRIPTOR, + containing_type=None, + fields=[ + _descriptor.FieldDescriptor( + name='bodyUniqueId', full_name='pybullet_grpc.ChangeDynamicsCommand.bodyUniqueId', 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='linkIndex', full_name='pybullet_grpc.ChangeDynamicsCommand.linkIndex', index=1, + number=2, 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='mass', full_name='pybullet_grpc.ChangeDynamicsCommand.mass', 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='lateralFriction', full_name='pybullet_grpc.ChangeDynamicsCommand.lateralFriction', index=3, + number=5, 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='spinningFriction', full_name='pybullet_grpc.ChangeDynamicsCommand.spinningFriction', index=4, + number=6, 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='rollingFriction', full_name='pybullet_grpc.ChangeDynamicsCommand.rollingFriction', index=5, + 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), + _descriptor.FieldDescriptor( + name='restitution', full_name='pybullet_grpc.ChangeDynamicsCommand.restitution', index=6, + number=8, 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='linearDamping', full_name='pybullet_grpc.ChangeDynamicsCommand.linearDamping', index=7, + number=9, 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='angularDamping', full_name='pybullet_grpc.ChangeDynamicsCommand.angularDamping', index=8, + number=10, 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='contactStiffness', full_name='pybullet_grpc.ChangeDynamicsCommand.contactStiffness', index=9, + number=11, 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='contactDamping', full_name='pybullet_grpc.ChangeDynamicsCommand.contactDamping', index=10, + number=12, 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='localInertiaDiagonal', full_name='pybullet_grpc.ChangeDynamicsCommand.localInertiaDiagonal', index=11, + number=13, 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='frictionAnchor', full_name='pybullet_grpc.ChangeDynamicsCommand.frictionAnchor', index=12, + number=14, 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='ccdSweptSphereRadius', full_name='pybullet_grpc.ChangeDynamicsCommand.ccdSweptSphereRadius', index=13, + number=15, 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='contactProcessingThreshold', full_name='pybullet_grpc.ChangeDynamicsCommand.contactProcessingThreshold', index=14, + number=16, 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='activationState', full_name='pybullet_grpc.ChangeDynamicsCommand.activationState', index=15, + number=17, 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=[ + _descriptor.OneofDescriptor( + name='hasMass', full_name='pybullet_grpc.ChangeDynamicsCommand.hasMass', + index=0, containing_type=None, fields=[]), + _descriptor.OneofDescriptor( + name='hasLateralFriction', full_name='pybullet_grpc.ChangeDynamicsCommand.hasLateralFriction', + index=1, containing_type=None, fields=[]), + _descriptor.OneofDescriptor( + name='hasSpinningFriction', full_name='pybullet_grpc.ChangeDynamicsCommand.hasSpinningFriction', + index=2, containing_type=None, fields=[]), + _descriptor.OneofDescriptor( + name='hasRollingFriction', full_name='pybullet_grpc.ChangeDynamicsCommand.hasRollingFriction', + index=3, containing_type=None, fields=[]), + _descriptor.OneofDescriptor( + name='hasRestitution', full_name='pybullet_grpc.ChangeDynamicsCommand.hasRestitution', + index=4, containing_type=None, fields=[]), + _descriptor.OneofDescriptor( + name='haslinearDamping', full_name='pybullet_grpc.ChangeDynamicsCommand.haslinearDamping', + index=5, containing_type=None, fields=[]), + _descriptor.OneofDescriptor( + name='hasangularDamping', full_name='pybullet_grpc.ChangeDynamicsCommand.hasangularDamping', + index=6, containing_type=None, fields=[]), + _descriptor.OneofDescriptor( + name='hasContactStiffness', full_name='pybullet_grpc.ChangeDynamicsCommand.hasContactStiffness', + index=7, containing_type=None, fields=[]), + _descriptor.OneofDescriptor( + name='hasContactDamping', full_name='pybullet_grpc.ChangeDynamicsCommand.hasContactDamping', + index=8, containing_type=None, fields=[]), + _descriptor.OneofDescriptor( + name='hasLocalInertiaDiagonal', full_name='pybullet_grpc.ChangeDynamicsCommand.hasLocalInertiaDiagonal', + index=9, containing_type=None, fields=[]), + _descriptor.OneofDescriptor( + name='hasFrictionAnchor', full_name='pybullet_grpc.ChangeDynamicsCommand.hasFrictionAnchor', + index=10, containing_type=None, fields=[]), + _descriptor.OneofDescriptor( + name='hasccdSweptSphereRadius', full_name='pybullet_grpc.ChangeDynamicsCommand.hasccdSweptSphereRadius', + index=11, containing_type=None, fields=[]), + _descriptor.OneofDescriptor( + name='hasContactProcessingThreshold', full_name='pybullet_grpc.ChangeDynamicsCommand.hasContactProcessingThreshold', + index=12, containing_type=None, fields=[]), + _descriptor.OneofDescriptor( + name='hasActivationState', full_name='pybullet_grpc.ChangeDynamicsCommand.hasActivationState', + index=13, containing_type=None, fields=[]), + ], + serialized_start=780, + serialized_end=1557, +) + + +_GETDYNAMICSCOMMAND = _descriptor.Descriptor( + name='GetDynamicsCommand', + full_name='pybullet_grpc.GetDynamicsCommand', + filename=None, + file=DESCRIPTOR, + containing_type=None, + fields=[ + _descriptor.FieldDescriptor( + name='bodyUniqueId', full_name='pybullet_grpc.GetDynamicsCommand.bodyUniqueId', 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='linkIndex', full_name='pybullet_grpc.GetDynamicsCommand.linkIndex', index=1, + number=2, 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=1559, + serialized_end=1620, +) + + +_GETDYNAMICSSTATUS = _descriptor.Descriptor( + name='GetDynamicsStatus', + full_name='pybullet_grpc.GetDynamicsStatus', + filename=None, + file=DESCRIPTOR, + containing_type=None, + fields=[ + _descriptor.FieldDescriptor( + name='mass', full_name='pybullet_grpc.GetDynamicsStatus.mass', index=0, + 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='lateralFriction', full_name='pybullet_grpc.GetDynamicsStatus.lateralFriction', index=1, + number=5, 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='spinningFriction', full_name='pybullet_grpc.GetDynamicsStatus.spinningFriction', index=2, + number=6, 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='rollingFriction', full_name='pybullet_grpc.GetDynamicsStatus.rollingFriction', index=3, + 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), + _descriptor.FieldDescriptor( + name='restitution', full_name='pybullet_grpc.GetDynamicsStatus.restitution', index=4, + number=8, 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='linearDamping', full_name='pybullet_grpc.GetDynamicsStatus.linearDamping', index=5, + number=9, 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='angularDamping', full_name='pybullet_grpc.GetDynamicsStatus.angularDamping', index=6, + number=10, 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='contactStiffness', full_name='pybullet_grpc.GetDynamicsStatus.contactStiffness', index=7, + number=11, 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='contactDamping', full_name='pybullet_grpc.GetDynamicsStatus.contactDamping', index=8, + number=12, 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='localInertiaDiagonal', full_name='pybullet_grpc.GetDynamicsStatus.localInertiaDiagonal', index=9, + number=13, 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='frictionAnchor', full_name='pybullet_grpc.GetDynamicsStatus.frictionAnchor', index=10, + number=14, 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='ccdSweptSphereRadius', full_name='pybullet_grpc.GetDynamicsStatus.ccdSweptSphereRadius', index=11, + number=15, 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='contactProcessingThreshold', full_name='pybullet_grpc.GetDynamicsStatus.contactProcessingThreshold', index=12, + number=16, 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='activationState', full_name='pybullet_grpc.GetDynamicsStatus.activationState', index=13, + number=17, 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=1623, + serialized_end=2016, +) + + +_INITPOSECOMMAND = _descriptor.Descriptor( + name='InitPoseCommand', + full_name='pybullet_grpc.InitPoseCommand', + filename=None, + file=DESCRIPTOR, + containing_type=None, + fields=[ + _descriptor.FieldDescriptor( + name='bodyUniqueId', full_name='pybullet_grpc.InitPoseCommand.bodyUniqueId', 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='hasInitialStateQ', full_name='pybullet_grpc.InitPoseCommand.hasInitialStateQ', index=1, + number=2, type=5, cpp_type=1, label=3, + has_default_value=False, default_value=[], + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + options=None, file=DESCRIPTOR), + _descriptor.FieldDescriptor( + name='initialStateQ', full_name='pybullet_grpc.InitPoseCommand.initialStateQ', index=2, + number=3, type=1, cpp_type=5, label=3, + has_default_value=False, default_value=[], + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + options=None, file=DESCRIPTOR), + _descriptor.FieldDescriptor( + name='hasInitialStateQdot', full_name='pybullet_grpc.InitPoseCommand.hasInitialStateQdot', index=3, + number=4, type=5, cpp_type=1, label=3, + has_default_value=False, default_value=[], + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + options=None, file=DESCRIPTOR), + _descriptor.FieldDescriptor( + name='initialStateQdot', full_name='pybullet_grpc.InitPoseCommand.initialStateQdot', index=4, + number=5, type=1, cpp_type=5, label=3, + has_default_value=False, default_value=[], + 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=2019, + serialized_end=2162, +) + + +_REQUESTACTUALSTATECOMMAND = _descriptor.Descriptor( + name='RequestActualStateCommand', + full_name='pybullet_grpc.RequestActualStateCommand', + filename=None, + file=DESCRIPTOR, + containing_type=None, + fields=[ + _descriptor.FieldDescriptor( + name='bodyUniqueId', full_name='pybullet_grpc.RequestActualStateCommand.bodyUniqueId', 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='computeForwardKinematics', full_name='pybullet_grpc.RequestActualStateCommand.computeForwardKinematics', index=1, + number=2, 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='computeLinkVelocities', full_name='pybullet_grpc.RequestActualStateCommand.computeLinkVelocities', index=2, + number=3, 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), + ], + extensions=[ + ], + nested_types=[], + enum_types=[ + ], + options=None, + is_extendable=False, + syntax='proto3', + extension_ranges=[], + oneofs=[ + ], + serialized_start=2164, + serialized_end=2278, +) + + +_SENDACTUALSTATESTATUS = _descriptor.Descriptor( + name='SendActualStateStatus', + full_name='pybullet_grpc.SendActualStateStatus', + filename=None, + file=DESCRIPTOR, + containing_type=None, + fields=[ + _descriptor.FieldDescriptor( + name='bodyUniqueId', full_name='pybullet_grpc.SendActualStateStatus.bodyUniqueId', 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='numLinks', full_name='pybullet_grpc.SendActualStateStatus.numLinks', index=1, + number=2, 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='numDegreeOfFreedomQ', full_name='pybullet_grpc.SendActualStateStatus.numDegreeOfFreedomQ', index=2, + number=3, 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='numDegreeOfFreedomU', full_name='pybullet_grpc.SendActualStateStatus.numDegreeOfFreedomU', 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='rootLocalInertialFrame', full_name='pybullet_grpc.SendActualStateStatus.rootLocalInertialFrame', index=4, + number=5, type=1, cpp_type=5, label=3, + has_default_value=False, default_value=[], + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + options=None, file=DESCRIPTOR), + _descriptor.FieldDescriptor( + name='actualStateQ', full_name='pybullet_grpc.SendActualStateStatus.actualStateQ', index=5, + number=6, type=1, cpp_type=5, label=3, + has_default_value=False, default_value=[], + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + options=None, file=DESCRIPTOR), + _descriptor.FieldDescriptor( + name='actualStateQdot', full_name='pybullet_grpc.SendActualStateStatus.actualStateQdot', index=6, + number=7, type=1, cpp_type=5, label=3, + has_default_value=False, default_value=[], + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + options=None, file=DESCRIPTOR), + _descriptor.FieldDescriptor( + name='jointReactionForces', full_name='pybullet_grpc.SendActualStateStatus.jointReactionForces', index=7, + number=8, type=1, cpp_type=5, label=3, + has_default_value=False, default_value=[], + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + options=None, file=DESCRIPTOR), + _descriptor.FieldDescriptor( + name='jointMotorForce', full_name='pybullet_grpc.SendActualStateStatus.jointMotorForce', index=8, + number=9, type=1, cpp_type=5, label=3, + has_default_value=False, default_value=[], + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + options=None, file=DESCRIPTOR), + _descriptor.FieldDescriptor( + name='linkState', full_name='pybullet_grpc.SendActualStateStatus.linkState', index=9, + number=10, type=1, cpp_type=5, label=3, + has_default_value=False, default_value=[], + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + options=None, file=DESCRIPTOR), + _descriptor.FieldDescriptor( + name='linkWorldVelocities', full_name='pybullet_grpc.SendActualStateStatus.linkWorldVelocities', index=10, + number=11, type=1, cpp_type=5, label=3, + has_default_value=False, default_value=[], + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + options=None, file=DESCRIPTOR), + _descriptor.FieldDescriptor( + name='linkLocalInertialFrames', full_name='pybullet_grpc.SendActualStateStatus.linkLocalInertialFrames', index=11, + number=12, type=1, cpp_type=5, label=3, + has_default_value=False, default_value=[], + 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=2281, + serialized_end=2616, ) @@ -325,6 +1026,48 @@ _PYBULLETCOMMAND = _descriptor.Descriptor( message_type=None, enum_type=None, containing_type=None, is_extension=False, extension_scope=None, options=None, file=DESCRIPTOR), + _descriptor.FieldDescriptor( + name='loadSdfCommand', full_name='pybullet_grpc.PyBulletCommand.loadSdfCommand', index=4, + number=6, 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='loadMjcfCommand', full_name='pybullet_grpc.PyBulletCommand.loadMjcfCommand', index=5, + number=7, 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='changeDynamicsCommand', full_name='pybullet_grpc.PyBulletCommand.changeDynamicsCommand', index=6, + number=8, 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='getDynamicsCommand', full_name='pybullet_grpc.PyBulletCommand.getDynamicsCommand', index=7, + number=9, 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='initPoseCommand', full_name='pybullet_grpc.PyBulletCommand.initPoseCommand', index=8, + number=10, 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='requestActualStateCommand', full_name='pybullet_grpc.PyBulletCommand.requestActualStateCommand', index=9, + number=11, 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=[ ], @@ -340,8 +1083,8 @@ _PYBULLETCOMMAND = _descriptor.Descriptor( name='commands', full_name='pybullet_grpc.PyBulletCommand.commands', index=0, containing_type=None, fields=[]), ], - serialized_start=529, - serialized_end=782, + serialized_start=2619, + serialized_end=3262, ) @@ -366,6 +1109,34 @@ _PYBULLETSTATUS = _descriptor.Descriptor( message_type=None, enum_type=None, containing_type=None, is_extension=False, extension_scope=None, options=None, file=DESCRIPTOR), + _descriptor.FieldDescriptor( + name='sdfStatus', full_name='pybullet_grpc.PyBulletStatus.sdfStatus', 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='mjcfStatus', full_name='pybullet_grpc.PyBulletStatus.mjcfStatus', index=3, + 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='getDynamicsStatus', full_name='pybullet_grpc.PyBulletStatus.getDynamicsStatus', index=4, + 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), + _descriptor.FieldDescriptor( + name='actualStateStatus', full_name='pybullet_grpc.PyBulletStatus.actualStateStatus', index=5, + number=6, 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=[ ], @@ -381,8 +1152,8 @@ _PYBULLETSTATUS = _descriptor.Descriptor( name='status', full_name='pybullet_grpc.PyBulletStatus.status', index=0, containing_type=None, fields=[]), ], - serialized_start=784, - serialized_end=883, + serialized_start=3265, + serialized_end=3602, ) _LOADURDFCOMMAND.fields_by_name['initialPosition'].message_type = _VEC3 @@ -396,9 +1167,65 @@ _LOADURDFCOMMAND.fields_by_name['useFixedBase'].containing_oneof = _LOADURDFCOMM _LOADURDFCOMMAND.oneofs_by_name['hasGlobalScaling'].fields.append( _LOADURDFCOMMAND.fields_by_name['globalScaling']) _LOADURDFCOMMAND.fields_by_name['globalScaling'].containing_oneof = _LOADURDFCOMMAND.oneofs_by_name['hasGlobalScaling'] +_LOADSDFCOMMAND.oneofs_by_name['hasUseMultiBody'].fields.append( + _LOADSDFCOMMAND.fields_by_name['useMultiBody']) +_LOADSDFCOMMAND.fields_by_name['useMultiBody'].containing_oneof = _LOADSDFCOMMAND.oneofs_by_name['hasUseMultiBody'] +_LOADSDFCOMMAND.oneofs_by_name['hasGlobalScaling'].fields.append( + _LOADSDFCOMMAND.fields_by_name['globalScaling']) +_LOADSDFCOMMAND.fields_by_name['globalScaling'].containing_oneof = _LOADSDFCOMMAND.oneofs_by_name['hasGlobalScaling'] +_CHANGEDYNAMICSCOMMAND.fields_by_name['localInertiaDiagonal'].message_type = _VEC3 +_CHANGEDYNAMICSCOMMAND.oneofs_by_name['hasMass'].fields.append( + _CHANGEDYNAMICSCOMMAND.fields_by_name['mass']) +_CHANGEDYNAMICSCOMMAND.fields_by_name['mass'].containing_oneof = _CHANGEDYNAMICSCOMMAND.oneofs_by_name['hasMass'] +_CHANGEDYNAMICSCOMMAND.oneofs_by_name['hasLateralFriction'].fields.append( + _CHANGEDYNAMICSCOMMAND.fields_by_name['lateralFriction']) +_CHANGEDYNAMICSCOMMAND.fields_by_name['lateralFriction'].containing_oneof = _CHANGEDYNAMICSCOMMAND.oneofs_by_name['hasLateralFriction'] +_CHANGEDYNAMICSCOMMAND.oneofs_by_name['hasSpinningFriction'].fields.append( + _CHANGEDYNAMICSCOMMAND.fields_by_name['spinningFriction']) +_CHANGEDYNAMICSCOMMAND.fields_by_name['spinningFriction'].containing_oneof = _CHANGEDYNAMICSCOMMAND.oneofs_by_name['hasSpinningFriction'] +_CHANGEDYNAMICSCOMMAND.oneofs_by_name['hasRollingFriction'].fields.append( + _CHANGEDYNAMICSCOMMAND.fields_by_name['rollingFriction']) +_CHANGEDYNAMICSCOMMAND.fields_by_name['rollingFriction'].containing_oneof = _CHANGEDYNAMICSCOMMAND.oneofs_by_name['hasRollingFriction'] +_CHANGEDYNAMICSCOMMAND.oneofs_by_name['hasRestitution'].fields.append( + _CHANGEDYNAMICSCOMMAND.fields_by_name['restitution']) +_CHANGEDYNAMICSCOMMAND.fields_by_name['restitution'].containing_oneof = _CHANGEDYNAMICSCOMMAND.oneofs_by_name['hasRestitution'] +_CHANGEDYNAMICSCOMMAND.oneofs_by_name['haslinearDamping'].fields.append( + _CHANGEDYNAMICSCOMMAND.fields_by_name['linearDamping']) +_CHANGEDYNAMICSCOMMAND.fields_by_name['linearDamping'].containing_oneof = _CHANGEDYNAMICSCOMMAND.oneofs_by_name['haslinearDamping'] +_CHANGEDYNAMICSCOMMAND.oneofs_by_name['hasangularDamping'].fields.append( + _CHANGEDYNAMICSCOMMAND.fields_by_name['angularDamping']) +_CHANGEDYNAMICSCOMMAND.fields_by_name['angularDamping'].containing_oneof = _CHANGEDYNAMICSCOMMAND.oneofs_by_name['hasangularDamping'] +_CHANGEDYNAMICSCOMMAND.oneofs_by_name['hasContactStiffness'].fields.append( + _CHANGEDYNAMICSCOMMAND.fields_by_name['contactStiffness']) +_CHANGEDYNAMICSCOMMAND.fields_by_name['contactStiffness'].containing_oneof = _CHANGEDYNAMICSCOMMAND.oneofs_by_name['hasContactStiffness'] +_CHANGEDYNAMICSCOMMAND.oneofs_by_name['hasContactDamping'].fields.append( + _CHANGEDYNAMICSCOMMAND.fields_by_name['contactDamping']) +_CHANGEDYNAMICSCOMMAND.fields_by_name['contactDamping'].containing_oneof = _CHANGEDYNAMICSCOMMAND.oneofs_by_name['hasContactDamping'] +_CHANGEDYNAMICSCOMMAND.oneofs_by_name['hasLocalInertiaDiagonal'].fields.append( + _CHANGEDYNAMICSCOMMAND.fields_by_name['localInertiaDiagonal']) +_CHANGEDYNAMICSCOMMAND.fields_by_name['localInertiaDiagonal'].containing_oneof = _CHANGEDYNAMICSCOMMAND.oneofs_by_name['hasLocalInertiaDiagonal'] +_CHANGEDYNAMICSCOMMAND.oneofs_by_name['hasFrictionAnchor'].fields.append( + _CHANGEDYNAMICSCOMMAND.fields_by_name['frictionAnchor']) +_CHANGEDYNAMICSCOMMAND.fields_by_name['frictionAnchor'].containing_oneof = _CHANGEDYNAMICSCOMMAND.oneofs_by_name['hasFrictionAnchor'] +_CHANGEDYNAMICSCOMMAND.oneofs_by_name['hasccdSweptSphereRadius'].fields.append( + _CHANGEDYNAMICSCOMMAND.fields_by_name['ccdSweptSphereRadius']) +_CHANGEDYNAMICSCOMMAND.fields_by_name['ccdSweptSphereRadius'].containing_oneof = _CHANGEDYNAMICSCOMMAND.oneofs_by_name['hasccdSweptSphereRadius'] +_CHANGEDYNAMICSCOMMAND.oneofs_by_name['hasContactProcessingThreshold'].fields.append( + _CHANGEDYNAMICSCOMMAND.fields_by_name['contactProcessingThreshold']) +_CHANGEDYNAMICSCOMMAND.fields_by_name['contactProcessingThreshold'].containing_oneof = _CHANGEDYNAMICSCOMMAND.oneofs_by_name['hasContactProcessingThreshold'] +_CHANGEDYNAMICSCOMMAND.oneofs_by_name['hasActivationState'].fields.append( + _CHANGEDYNAMICSCOMMAND.fields_by_name['activationState']) +_CHANGEDYNAMICSCOMMAND.fields_by_name['activationState'].containing_oneof = _CHANGEDYNAMICSCOMMAND.oneofs_by_name['hasActivationState'] +_GETDYNAMICSSTATUS.fields_by_name['localInertiaDiagonal'].message_type = _VEC3 _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.fields_by_name['loadSdfCommand'].message_type = _LOADSDFCOMMAND +_PYBULLETCOMMAND.fields_by_name['loadMjcfCommand'].message_type = _LOADMJCFCOMMAND +_PYBULLETCOMMAND.fields_by_name['changeDynamicsCommand'].message_type = _CHANGEDYNAMICSCOMMAND +_PYBULLETCOMMAND.fields_by_name['getDynamicsCommand'].message_type = _GETDYNAMICSCOMMAND +_PYBULLETCOMMAND.fields_by_name['initPoseCommand'].message_type = _INITPOSECOMMAND +_PYBULLETCOMMAND.fields_by_name['requestActualStateCommand'].message_type = _REQUESTACTUALSTATECOMMAND _PYBULLETCOMMAND.oneofs_by_name['commands'].fields.append( _PYBULLETCOMMAND.fields_by_name['loadUrdfCommand']) _PYBULLETCOMMAND.fields_by_name['loadUrdfCommand'].containing_oneof = _PYBULLETCOMMAND.oneofs_by_name['commands'] @@ -408,16 +1235,60 @@ _PYBULLETCOMMAND.fields_by_name['terminateServerCommand'].containing_oneof = _PY _PYBULLETCOMMAND.oneofs_by_name['commands'].fields.append( _PYBULLETCOMMAND.fields_by_name['stepSimulationCommand']) _PYBULLETCOMMAND.fields_by_name['stepSimulationCommand'].containing_oneof = _PYBULLETCOMMAND.oneofs_by_name['commands'] +_PYBULLETCOMMAND.oneofs_by_name['commands'].fields.append( + _PYBULLETCOMMAND.fields_by_name['loadSdfCommand']) +_PYBULLETCOMMAND.fields_by_name['loadSdfCommand'].containing_oneof = _PYBULLETCOMMAND.oneofs_by_name['commands'] +_PYBULLETCOMMAND.oneofs_by_name['commands'].fields.append( + _PYBULLETCOMMAND.fields_by_name['loadMjcfCommand']) +_PYBULLETCOMMAND.fields_by_name['loadMjcfCommand'].containing_oneof = _PYBULLETCOMMAND.oneofs_by_name['commands'] +_PYBULLETCOMMAND.oneofs_by_name['commands'].fields.append( + _PYBULLETCOMMAND.fields_by_name['changeDynamicsCommand']) +_PYBULLETCOMMAND.fields_by_name['changeDynamicsCommand'].containing_oneof = _PYBULLETCOMMAND.oneofs_by_name['commands'] +_PYBULLETCOMMAND.oneofs_by_name['commands'].fields.append( + _PYBULLETCOMMAND.fields_by_name['getDynamicsCommand']) +_PYBULLETCOMMAND.fields_by_name['getDynamicsCommand'].containing_oneof = _PYBULLETCOMMAND.oneofs_by_name['commands'] +_PYBULLETCOMMAND.oneofs_by_name['commands'].fields.append( + _PYBULLETCOMMAND.fields_by_name['initPoseCommand']) +_PYBULLETCOMMAND.fields_by_name['initPoseCommand'].containing_oneof = _PYBULLETCOMMAND.oneofs_by_name['commands'] +_PYBULLETCOMMAND.oneofs_by_name['commands'].fields.append( + _PYBULLETCOMMAND.fields_by_name['requestActualStateCommand']) +_PYBULLETCOMMAND.fields_by_name['requestActualStateCommand'].containing_oneof = _PYBULLETCOMMAND.oneofs_by_name['commands'] _PYBULLETSTATUS.fields_by_name['urdfStatus'].message_type = _LOADURDFSTATUS +_PYBULLETSTATUS.fields_by_name['sdfStatus'].message_type = _SDFLOADEDSTATUS +_PYBULLETSTATUS.fields_by_name['mjcfStatus'].message_type = _MJCFLOADEDSTATUS +_PYBULLETSTATUS.fields_by_name['getDynamicsStatus'].message_type = _GETDYNAMICSSTATUS +_PYBULLETSTATUS.fields_by_name['actualStateStatus'].message_type = _SENDACTUALSTATESTATUS _PYBULLETSTATUS.oneofs_by_name['status'].fields.append( _PYBULLETSTATUS.fields_by_name['urdfStatus']) _PYBULLETSTATUS.fields_by_name['urdfStatus'].containing_oneof = _PYBULLETSTATUS.oneofs_by_name['status'] +_PYBULLETSTATUS.oneofs_by_name['status'].fields.append( + _PYBULLETSTATUS.fields_by_name['sdfStatus']) +_PYBULLETSTATUS.fields_by_name['sdfStatus'].containing_oneof = _PYBULLETSTATUS.oneofs_by_name['status'] +_PYBULLETSTATUS.oneofs_by_name['status'].fields.append( + _PYBULLETSTATUS.fields_by_name['mjcfStatus']) +_PYBULLETSTATUS.fields_by_name['mjcfStatus'].containing_oneof = _PYBULLETSTATUS.oneofs_by_name['status'] +_PYBULLETSTATUS.oneofs_by_name['status'].fields.append( + _PYBULLETSTATUS.fields_by_name['getDynamicsStatus']) +_PYBULLETSTATUS.fields_by_name['getDynamicsStatus'].containing_oneof = _PYBULLETSTATUS.oneofs_by_name['status'] +_PYBULLETSTATUS.oneofs_by_name['status'].fields.append( + _PYBULLETSTATUS.fields_by_name['actualStateStatus']) +_PYBULLETSTATUS.fields_by_name['actualStateStatus'].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['LoadSdfCommand'] = _LOADSDFCOMMAND +DESCRIPTOR.message_types_by_name['SdfLoadedStatus'] = _SDFLOADEDSTATUS +DESCRIPTOR.message_types_by_name['LoadMjcfCommand'] = _LOADMJCFCOMMAND +DESCRIPTOR.message_types_by_name['MjcfLoadedStatus'] = _MJCFLOADEDSTATUS +DESCRIPTOR.message_types_by_name['ChangeDynamicsCommand'] = _CHANGEDYNAMICSCOMMAND +DESCRIPTOR.message_types_by_name['GetDynamicsCommand'] = _GETDYNAMICSCOMMAND +DESCRIPTOR.message_types_by_name['GetDynamicsStatus'] = _GETDYNAMICSSTATUS +DESCRIPTOR.message_types_by_name['InitPoseCommand'] = _INITPOSECOMMAND +DESCRIPTOR.message_types_by_name['RequestActualStateCommand'] = _REQUESTACTUALSTATECOMMAND +DESCRIPTOR.message_types_by_name['SendActualStateStatus'] = _SENDACTUALSTATESTATUS DESCRIPTOR.message_types_by_name['PyBulletCommand'] = _PYBULLETCOMMAND DESCRIPTOR.message_types_by_name['PyBulletStatus'] = _PYBULLETSTATUS _sym_db.RegisterFileDescriptor(DESCRIPTOR) @@ -464,6 +1335,76 @@ LoadUrdfStatus = _reflection.GeneratedProtocolMessageType('LoadUrdfStatus', (_me )) _sym_db.RegisterMessage(LoadUrdfStatus) +LoadSdfCommand = _reflection.GeneratedProtocolMessageType('LoadSdfCommand', (_message.Message,), dict( + DESCRIPTOR = _LOADSDFCOMMAND, + __module__ = 'pybullet_pb2' + # @@protoc_insertion_point(class_scope:pybullet_grpc.LoadSdfCommand) + )) +_sym_db.RegisterMessage(LoadSdfCommand) + +SdfLoadedStatus = _reflection.GeneratedProtocolMessageType('SdfLoadedStatus', (_message.Message,), dict( + DESCRIPTOR = _SDFLOADEDSTATUS, + __module__ = 'pybullet_pb2' + # @@protoc_insertion_point(class_scope:pybullet_grpc.SdfLoadedStatus) + )) +_sym_db.RegisterMessage(SdfLoadedStatus) + +LoadMjcfCommand = _reflection.GeneratedProtocolMessageType('LoadMjcfCommand', (_message.Message,), dict( + DESCRIPTOR = _LOADMJCFCOMMAND, + __module__ = 'pybullet_pb2' + # @@protoc_insertion_point(class_scope:pybullet_grpc.LoadMjcfCommand) + )) +_sym_db.RegisterMessage(LoadMjcfCommand) + +MjcfLoadedStatus = _reflection.GeneratedProtocolMessageType('MjcfLoadedStatus', (_message.Message,), dict( + DESCRIPTOR = _MJCFLOADEDSTATUS, + __module__ = 'pybullet_pb2' + # @@protoc_insertion_point(class_scope:pybullet_grpc.MjcfLoadedStatus) + )) +_sym_db.RegisterMessage(MjcfLoadedStatus) + +ChangeDynamicsCommand = _reflection.GeneratedProtocolMessageType('ChangeDynamicsCommand', (_message.Message,), dict( + DESCRIPTOR = _CHANGEDYNAMICSCOMMAND, + __module__ = 'pybullet_pb2' + # @@protoc_insertion_point(class_scope:pybullet_grpc.ChangeDynamicsCommand) + )) +_sym_db.RegisterMessage(ChangeDynamicsCommand) + +GetDynamicsCommand = _reflection.GeneratedProtocolMessageType('GetDynamicsCommand', (_message.Message,), dict( + DESCRIPTOR = _GETDYNAMICSCOMMAND, + __module__ = 'pybullet_pb2' + # @@protoc_insertion_point(class_scope:pybullet_grpc.GetDynamicsCommand) + )) +_sym_db.RegisterMessage(GetDynamicsCommand) + +GetDynamicsStatus = _reflection.GeneratedProtocolMessageType('GetDynamicsStatus', (_message.Message,), dict( + DESCRIPTOR = _GETDYNAMICSSTATUS, + __module__ = 'pybullet_pb2' + # @@protoc_insertion_point(class_scope:pybullet_grpc.GetDynamicsStatus) + )) +_sym_db.RegisterMessage(GetDynamicsStatus) + +InitPoseCommand = _reflection.GeneratedProtocolMessageType('InitPoseCommand', (_message.Message,), dict( + DESCRIPTOR = _INITPOSECOMMAND, + __module__ = 'pybullet_pb2' + # @@protoc_insertion_point(class_scope:pybullet_grpc.InitPoseCommand) + )) +_sym_db.RegisterMessage(InitPoseCommand) + +RequestActualStateCommand = _reflection.GeneratedProtocolMessageType('RequestActualStateCommand', (_message.Message,), dict( + DESCRIPTOR = _REQUESTACTUALSTATECOMMAND, + __module__ = 'pybullet_pb2' + # @@protoc_insertion_point(class_scope:pybullet_grpc.RequestActualStateCommand) + )) +_sym_db.RegisterMessage(RequestActualStateCommand) + +SendActualStateStatus = _reflection.GeneratedProtocolMessageType('SendActualStateStatus', (_message.Message,), dict( + DESCRIPTOR = _SENDACTUALSTATESTATUS, + __module__ = 'pybullet_pb2' + # @@protoc_insertion_point(class_scope:pybullet_grpc.SendActualStateStatus) + )) +_sym_db.RegisterMessage(SendActualStateStatus) + PyBulletCommand = _reflection.GeneratedProtocolMessageType('PyBulletCommand', (_message.Message,), dict( DESCRIPTOR = _PYBULLETCOMMAND, __module__ = 'pybullet_pb2' @@ -488,8 +1429,8 @@ _PYBULLETAPI = _descriptor.ServiceDescriptor( file=DESCRIPTOR, index=0, options=None, - serialized_start=885, - serialized_end=980, + serialized_start=3604, + serialized_end=3699, methods=[ _descriptor.MethodDescriptor( name='SubmitCommand', From 9e2f6c79359ad0756b6e93569fe65d28ba522297 Mon Sep 17 00:00:00 2001 From: erwincoumans Date: Mon, 3 Sep 2018 23:13:15 -0700 Subject: [PATCH 2/3] more GRPC work --- build3/premake4.lua | 4 + build_visual_studio_vr_pybullet_double.bat | 1 + .../b3RobotSimulatorClientAPI.cpp | 13 +- examples/SharedMemory/PhysicsClientC_API.cpp | 116 +- examples/SharedMemory/PhysicsClientC_API.h | 7 + examples/SharedMemory/PhysicsClientTCP.h | 1 + examples/SharedMemory/PhysicsClientUDP.h | 2 + .../PhysicsCommandProcessorInterface.h | 3 +- examples/SharedMemory/PhysicsDirect.cpp | 3 +- .../SharedMemoryCommandProcessor.h | 1 + examples/SharedMemory/SharedMemoryPublic.h | 5 +- .../b3RobotSimulatorClientAPI_NoDirect.cpp | 18 +- .../SharedMemory/grpc/ConvertGRPCBullet.cpp | 1829 ++- .../SharedMemory/grpc/ConvertGRPCBullet.h | 6 +- examples/SharedMemory/grpc/main.cpp | 76 +- .../SharedMemory/grpc/proto/pybullet.proto | 292 +- examples/SharedMemory/grpc/pybullet.pb.cpp | 13210 +++++++++++++++- examples/SharedMemory/grpc/pybullet.pb.h | 6293 +++++++- examples/SharedMemory/grpc/pybullet_client.py | 18 +- examples/SharedMemory/grpc/pybullet_pb2.py | 1772 ++- examples/pybullet/pybullet.c | 16 +- 21 files changed, 22906 insertions(+), 780 deletions(-) diff --git a/build3/premake4.lua b/build3/premake4.lua index 44cf16114..324344c40 100644 --- a/build3/premake4.lua +++ b/build3/premake4.lua @@ -201,6 +201,10 @@ end defines {"BT_USE_DOUBLE_PRECISION"} end + if _OPTIONS["grpc"] then + defines {"BT_ENABLE_GRPC"} + end + configurations {"Release", "Debug"} configuration "Release" flags { "Optimize", "EnableSSE2","StaticRuntime", "NoMinimalRebuild", "FloatFast"} diff --git a/build_visual_studio_vr_pybullet_double.bat b/build_visual_studio_vr_pybullet_double.bat index 0211b7489..a5b824826 100644 --- a/build_visual_studio_vr_pybullet_double.bat +++ b/build_visual_studio_vr_pybullet_double.bat @@ -19,6 +19,7 @@ cd build3 premake4 --double --enable_multithreading --midi --enable_static_vr_plugin --enable_openvr --enable_pybullet --python_include_dir="%myvar%/include" --python_lib_dir="%myvar%/libs" --targetdir="../bin" vs2010 +#premake4 --double --grpc --enable_multithreading --midi --enable_static_vr_plugin --enable_openvr --enable_pybullet --python_include_dir="%myvar%/include" --python_lib_dir="%myvar%/libs" --targetdir="../binserver" vs2010 #premake4 --serial --audio --double --midi --enable_openvr --enable_pybullet --python_include_dir="%myvar%/include" --python_lib_dir="%myvar%/libs" --targetdir="../bin" vs2010 diff --git a/examples/RobotSimulator/b3RobotSimulatorClientAPI.cpp b/examples/RobotSimulator/b3RobotSimulatorClientAPI.cpp index 2ed58de09..e80ef8713 100644 --- a/examples/RobotSimulator/b3RobotSimulatorClientAPI.cpp +++ b/examples/RobotSimulator/b3RobotSimulatorClientAPI.cpp @@ -17,6 +17,9 @@ #include "../SharedMemory/SharedMemoryPublic.h" #include "Bullet3Common/b3Logging.h" +#ifdef BT_ENABLE_GRPC +#include "../SharedMemory/PhysicsClientGRPC_C_API.h" +#endif b3RobotSimulatorClientAPI::b3RobotSimulatorClientAPI() { @@ -170,7 +173,15 @@ bool b3RobotSimulatorClientAPI::connect(int mode, const std::string& hostName, i #endif //BT_ENABLE_CLSOCKET break; } - + case eCONNECT_GRPC: + { +#ifdef BT_ENABLE_GRPC + sm = b3ConnectPhysicsGRPC(hostName.c_str(), tcpPort); +#else + b3Warning("GRPC is not enabled in this pybullet build"); +#endif + break; + } default: { b3Warning("connectPhysicsServer unexpected argument"); diff --git a/examples/SharedMemory/PhysicsClientC_API.cpp b/examples/SharedMemory/PhysicsClientC_API.cpp index 454a2bfc6..ecff5f310 100644 --- a/examples/SharedMemory/PhysicsClientC_API.cpp +++ b/examples/SharedMemory/PhysicsClientC_API.cpp @@ -495,11 +495,18 @@ B3_SHARED_API b3SharedMemoryCommandHandle b3InitPhysicsParamCommand(b3Physic b3Assert(cl->canSubmitCommand()); struct SharedMemoryCommand* command = cl->getAvailableSharedMemoryCommand(); b3Assert(command); + return b3InitPhysicsParamCommand2((b3SharedMemoryCommandHandle) command); +} + +B3_SHARED_API b3SharedMemoryCommandHandle b3InitPhysicsParamCommand2(b3SharedMemoryCommandHandle commandHandle) +{ + struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; command->m_type = CMD_SEND_PHYSICS_SIMULATION_PARAMETERS; command->m_updateFlags = 0; - return (b3SharedMemoryCommandHandle) command; + return (b3SharedMemoryCommandHandle)command; } + B3_SHARED_API int b3PhysicsParamSetGravity(b3SharedMemoryCommandHandle commandHandle, double gravx,double gravy, double gravz) { struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; @@ -778,13 +785,21 @@ B3_SHARED_API b3SharedMemoryCommandHandle b3InitResetSimulationCommand(b3Phy b3Assert(cl->canSubmitCommand()); struct SharedMemoryCommand* command = cl->getAvailableSharedMemoryCommand(); b3Assert(command); - command->m_type = CMD_RESET_SIMULATION; - command->m_updateFlags = 0; - - return (b3SharedMemoryCommandHandle) command; - + return b3InitResetSimulationCommand2((b3SharedMemoryCommandHandle)command); + } +B3_SHARED_API b3SharedMemoryCommandHandle b3InitResetSimulationCommand2(b3SharedMemoryCommandHandle commandHandle) +{ + struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; + b3Assert(command); + command->m_type = CMD_RESET_SIMULATION; + command->m_updateFlags = 0; + return (b3SharedMemoryCommandHandle)command; +} + + + B3_SHARED_API b3SharedMemoryCommandHandle b3JointControlCommandInit(b3PhysicsClientHandle physClient, int controlMode) { @@ -798,15 +813,22 @@ B3_SHARED_API b3SharedMemoryCommandHandle b3JointControlCommandInit2( b3PhysicsC b3Assert(cl->canSubmitCommand()); struct SharedMemoryCommand* command = cl->getAvailableSharedMemoryCommand(); b3Assert(command); + return b3JointControlCommandInit2Internal((b3SharedMemoryCommandHandle)command, bodyUniqueId, controlMode); + +} + +B3_SHARED_API b3SharedMemoryCommandHandle b3JointControlCommandInit2Internal(b3SharedMemoryCommandHandle commandHandle, int bodyUniqueId, int controlMode) +{ + struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; command->m_type = CMD_SEND_DESIRED_STATE; - command->m_sendDesiredStateCommandArgument.m_controlMode = controlMode; + command->m_sendDesiredStateCommandArgument.m_controlMode = controlMode; command->m_sendDesiredStateCommandArgument.m_bodyUniqueId = bodyUniqueId; command->m_updateFlags = 0; - for (int i=0;im_sendDesiredStateCommandArgument.m_hasDesiredStateFlags[i] = 0; - } - return (b3SharedMemoryCommandHandle) command; + for (int i = 0; im_sendDesiredStateCommandArgument.m_hasDesiredStateFlags[i] = 0; + } + return (b3SharedMemoryCommandHandle)command; } B3_SHARED_API int b3JointControlSetDesiredPosition(b3SharedMemoryCommandHandle commandHandle, int qIndex, double value) @@ -2055,7 +2077,7 @@ B3_SHARED_API int b3GetStatusActualState2(b3SharedMemoryStatusHandle statusHandl { *linkWorldVelocities = args.m_linkWorldVelocities; } - + return 1; } B3_SHARED_API int b3GetStatusActualState(b3SharedMemoryStatusHandle statusHandle, @@ -2634,23 +2656,29 @@ B3_SHARED_API b3SharedMemoryCommandHandle b3InitCreateUserConstraintCommand(b3Ph b3Assert(cl->canSubmitCommand()); struct SharedMemoryCommand* command = cl->getAvailableSharedMemoryCommand(); b3Assert(command); - - command->m_type = CMD_USER_CONSTRAINT; + return b3InitCreateUserConstraintCommand2((b3SharedMemoryCommandHandle)command, parentBodyUniqueId, parentJointIndex, childBodyUniqueId, childJointIndex, info); + +} + +B3_SHARED_API b3SharedMemoryCommandHandle b3InitCreateUserConstraintCommand2(b3SharedMemoryCommandHandle commandHandle, int parentBodyUniqueId, int parentJointIndex, int childBodyUniqueId, int childJointIndex, struct b3JointInfo* info) +{ + struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; + command->m_type = CMD_USER_CONSTRAINT; command->m_updateFlags = USER_CONSTRAINT_ADD_CONSTRAINT; - command->m_userConstraintArguments.m_parentBodyIndex = parentBodyUniqueId; - command->m_userConstraintArguments.m_parentJointIndex = parentJointIndex; - command->m_userConstraintArguments.m_childBodyIndex = childBodyUniqueId; - command->m_userConstraintArguments.m_childJointIndex = childJointIndex; - for (int i = 0; i < 7; ++i) { - command->m_userConstraintArguments.m_parentFrame[i] = info->m_parentFrame[i]; - command->m_userConstraintArguments.m_childFrame[i] = info->m_childFrame[i]; - } - for (int i = 0; i < 3; ++i) { - command->m_userConstraintArguments.m_jointAxis[i] = info->m_jointAxis[i]; - } - command->m_userConstraintArguments.m_jointType = info->m_jointType; - return (b3SharedMemoryCommandHandle)command; + command->m_userConstraintArguments.m_parentBodyIndex = parentBodyUniqueId; + command->m_userConstraintArguments.m_parentJointIndex = parentJointIndex; + command->m_userConstraintArguments.m_childBodyIndex = childBodyUniqueId; + command->m_userConstraintArguments.m_childJointIndex = childJointIndex; + for (int i = 0; i < 7; ++i) { + command->m_userConstraintArguments.m_parentFrame[i] = info->m_parentFrame[i]; + command->m_userConstraintArguments.m_childFrame[i] = info->m_childFrame[i]; + } + for (int i = 0; i < 3; ++i) { + command->m_userConstraintArguments.m_jointAxis[i] = info->m_jointAxis[i]; + } + command->m_userConstraintArguments.m_jointType = info->m_jointType; + return (b3SharedMemoryCommandHandle)command; } B3_SHARED_API b3SharedMemoryCommandHandle b3InitChangeUserConstraintCommand(b3PhysicsClientHandle physClient, int userConstraintUniqueId) @@ -3392,10 +3420,16 @@ B3_SHARED_API b3SharedMemoryCommandHandle b3InitRequestCameraImage(b3PhysicsClie b3Assert(cl->canSubmitCommand()); struct SharedMemoryCommand* command = cl->getAvailableSharedMemoryCommand(); b3Assert(command); - command->m_type =CMD_REQUEST_CAMERA_IMAGE_DATA; + return b3InitRequestCameraImage2((b3SharedMemoryCommandHandle)command); +} + +B3_SHARED_API b3SharedMemoryCommandHandle b3InitRequestCameraImage2(b3SharedMemoryCommandHandle commandHandle) +{ + struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; + command->m_type = CMD_REQUEST_CAMERA_IMAGE_DATA; command->m_requestPixelDataArguments.m_startPixelIndex = 0; - command->m_updateFlags = 0;//REQUEST_PIXEL_ARGS_USE_HARDWARE_OPENGL; - return (b3SharedMemoryCommandHandle) command; + command->m_updateFlags = 0;//REQUEST_PIXEL_ARGS_USE_HARDWARE_OPENGL; + return (b3SharedMemoryCommandHandle)command; } B3_SHARED_API void b3RequestCameraImageSelectRenderer(b3SharedMemoryCommandHandle commandHandle, int renderer) @@ -4559,7 +4593,13 @@ B3_SHARED_API b3SharedMemoryCommandHandle b3RequestKeyboardEventsCommandInit(b3P b3Assert(cl->canSubmitCommand()); struct SharedMemoryCommand* command = cl->getAvailableSharedMemoryCommand(); b3Assert(command); + return b3RequestKeyboardEventsCommandInit2((b3SharedMemoryCommandHandle)command); + +} +B3_SHARED_API b3SharedMemoryCommandHandle b3RequestKeyboardEventsCommandInit2(b3SharedMemoryCommandHandle commandHandle) +{ + struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; command->m_type = CMD_REQUEST_KEYBOARD_EVENTS_DATA; command->m_updateFlags = 0; @@ -4836,10 +4876,16 @@ B3_SHARED_API b3SharedMemoryCommandHandle b3InitConfigureOpenGLVisualizer(b3Phys struct SharedMemoryCommand* command = cl->getAvailableSharedMemoryCommand(); b3Assert(command); - command->m_type = CMD_CONFIGURE_OPENGL_VISUALIZER; - command->m_updateFlags = 0; - - return (b3SharedMemoryCommandHandle)command; + return b3InitConfigureOpenGLVisualizer2((b3SharedMemoryCommandHandle)command); +} + +B3_SHARED_API b3SharedMemoryCommandHandle b3InitConfigureOpenGLVisualizer2(b3SharedMemoryCommandHandle commandHandle) +{ + struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; + command->m_type = CMD_CONFIGURE_OPENGL_VISUALIZER; + command->m_updateFlags = 0; + + return (b3SharedMemoryCommandHandle)command; } B3_SHARED_API void b3ConfigureOpenGLVisualizerSetVisualizationFlags(b3SharedMemoryCommandHandle commandHandle, int flag, int enabled) diff --git a/examples/SharedMemory/PhysicsClientC_API.h b/examples/SharedMemory/PhysicsClientC_API.h index 48b00990e..c93bd2a96 100644 --- a/examples/SharedMemory/PhysicsClientC_API.h +++ b/examples/SharedMemory/PhysicsClientC_API.h @@ -163,6 +163,7 @@ B3_SHARED_API int b3ChangeDynamicsInfoSetContactProcessingThreshold(b3SharedMemo B3_SHARED_API int b3ChangeDynamicsInfoSetActivationState(b3SharedMemoryCommandHandle commandHandle, int bodyUniqueId, int activationState); B3_SHARED_API b3SharedMemoryCommandHandle b3InitCreateUserConstraintCommand(b3PhysicsClientHandle physClient, int parentBodyUniqueId, int parentJointIndex, int childBodyUniqueId, int childJointIndex, struct b3JointInfo* info); +B3_SHARED_API b3SharedMemoryCommandHandle b3InitCreateUserConstraintCommand2(b3SharedMemoryCommandHandle commandHandle, int parentBodyUniqueId, int parentJointIndex, int childBodyUniqueId, int childJointIndex, struct b3JointInfo* info); ///return a unique id for the user constraint, after successful creation, or -1 for an invalid constraint id B3_SHARED_API int b3GetStatusUserConstraintUniqueId(b3SharedMemoryStatusHandle statusHandle); @@ -199,6 +200,7 @@ B3_SHARED_API void b3GetDebugLines(b3PhysicsClientHandle physClient, struct b ///configure the 3D OpenGL debug visualizer (enable/disable GUI widgets, shadows, position camera etc) B3_SHARED_API b3SharedMemoryCommandHandle b3InitConfigureOpenGLVisualizer(b3PhysicsClientHandle physClient); +B3_SHARED_API b3SharedMemoryCommandHandle b3InitConfigureOpenGLVisualizer2(b3SharedMemoryCommandHandle commandHandle); B3_SHARED_API void b3ConfigureOpenGLVisualizerSetVisualizationFlags(b3SharedMemoryCommandHandle commandHandle, int flag, int enabled); B3_SHARED_API void b3ConfigureOpenGLVisualizerSetViewMatrix(b3SharedMemoryCommandHandle commandHandle, float cameraDistance, float cameraPitch, float cameraYaw, const float cameraTargetPosition[/*3*/]); @@ -234,6 +236,7 @@ B3_SHARED_API int b3GetDebugItemUniqueId(b3SharedMemoryStatusHandle statusHandle ///request an image from a simulated camera, using a software renderer. B3_SHARED_API b3SharedMemoryCommandHandle b3InitRequestCameraImage(b3PhysicsClientHandle physClient); +B3_SHARED_API b3SharedMemoryCommandHandle b3InitRequestCameraImage2(b3SharedMemoryCommandHandle commandHandle); B3_SHARED_API void b3RequestCameraImageSetCameraMatrices(b3SharedMemoryCommandHandle commandHandle, float viewMatrix[/*16*/], float projectionMatrix[/*16*/]); B3_SHARED_API void b3RequestCameraImageSetPixelResolution(b3SharedMemoryCommandHandle commandHandle, int width, int height ); B3_SHARED_API void b3RequestCameraImageSetLightDirection(b3SharedMemoryCommandHandle commandHandle, const float lightDirection[/*3*/]); @@ -313,6 +316,7 @@ B3_SHARED_API void b3UpdateVisualShapeSpecularColor(b3SharedMemoryCommandHandle B3_SHARED_API b3SharedMemoryCommandHandle b3InitPhysicsParamCommand(b3PhysicsClientHandle physClient); +B3_SHARED_API b3SharedMemoryCommandHandle b3InitPhysicsParamCommand2(b3SharedMemoryCommandHandle commandHandle); B3_SHARED_API int b3PhysicsParamSetGravity(b3SharedMemoryCommandHandle commandHandle, double gravx,double gravy, double gravz); B3_SHARED_API int b3PhysicsParamSetTimeStep(b3SharedMemoryCommandHandle commandHandle, double timeStep); B3_SHARED_API int b3PhysicsParamSetDefaultContactERP(b3SharedMemoryCommandHandle commandHandle, double defaultContactERP); @@ -359,6 +363,7 @@ B3_SHARED_API b3SharedMemoryCommandHandle b3InitStepSimulationCommand(b3PhysicsC B3_SHARED_API b3SharedMemoryCommandHandle b3InitStepSimulationCommand2(b3SharedMemoryCommandHandle commandHandle); B3_SHARED_API b3SharedMemoryCommandHandle b3InitResetSimulationCommand(b3PhysicsClientHandle physClient); +B3_SHARED_API b3SharedMemoryCommandHandle b3InitResetSimulationCommand2(b3SharedMemoryCommandHandle commandHandle); ///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); @@ -444,6 +449,7 @@ B3_SHARED_API b3SharedMemoryCommandHandle b3JointControlCommandInit(b3PhysicsCl ///Set joint motor control variables such as desired position/angle, desired velocity, ///applied joint forces, dependent on the control mode (CONTROL_MODE_VELOCITY or CONTROL_MODE_TORQUE) B3_SHARED_API b3SharedMemoryCommandHandle b3JointControlCommandInit2(b3PhysicsClientHandle physClient, int bodyUniqueId, int controlMode); +B3_SHARED_API b3SharedMemoryCommandHandle b3JointControlCommandInit2Internal(b3SharedMemoryCommandHandle commandHandle, int bodyUniqueId, int controlMode); ///Only use when controlMode is CONTROL_MODE_POSITION_VELOCITY_PD B3_SHARED_API int b3JointControlSetDesiredPosition(b3SharedMemoryCommandHandle commandHandle, int qIndex, double value); @@ -609,6 +615,7 @@ B3_SHARED_API int b3SetVRCameraTrackingObject(b3SharedMemoryCommandHandle comman B3_SHARED_API int b3SetVRCameraTrackingObjectFlag(b3SharedMemoryCommandHandle commandHandle, int flag); B3_SHARED_API b3SharedMemoryCommandHandle b3RequestKeyboardEventsCommandInit(b3PhysicsClientHandle physClient); +B3_SHARED_API b3SharedMemoryCommandHandle b3RequestKeyboardEventsCommandInit2(b3SharedMemoryCommandHandle commandHandle); B3_SHARED_API void b3GetKeyboardEventsData(b3PhysicsClientHandle physClient, struct b3KeyboardEventsData* keyboardEventsData); B3_SHARED_API b3SharedMemoryCommandHandle b3RequestMouseEventsCommandInit(b3PhysicsClientHandle physClient); diff --git a/examples/SharedMemory/PhysicsClientTCP.h b/examples/SharedMemory/PhysicsClientTCP.h index c869cadb5..c378fc211 100644 --- a/examples/SharedMemory/PhysicsClientTCP.h +++ b/examples/SharedMemory/PhysicsClientTCP.h @@ -32,6 +32,7 @@ public: virtual void setTimeOut(double timeOutInSeconds); + virtual void reportNotifications() {} }; diff --git a/examples/SharedMemory/PhysicsClientUDP.h b/examples/SharedMemory/PhysicsClientUDP.h index b091bf89e..9b4825929 100644 --- a/examples/SharedMemory/PhysicsClientUDP.h +++ b/examples/SharedMemory/PhysicsClientUDP.h @@ -31,6 +31,8 @@ public: virtual void setGuiHelper(struct GUIHelperInterface* guiHelper); virtual void setTimeOut(double timeOutInSeconds); + + virtual void reportNotifications() {} }; diff --git a/examples/SharedMemory/PhysicsCommandProcessorInterface.h b/examples/SharedMemory/PhysicsCommandProcessorInterface.h index 4c5600581..69eef9513 100644 --- a/examples/SharedMemory/PhysicsCommandProcessorInterface.h +++ b/examples/SharedMemory/PhysicsCommandProcessorInterface.h @@ -27,6 +27,7 @@ public: virtual void setGuiHelper(struct GUIHelperInterface* guiHelper) = 0; virtual void setTimeOut(double timeOutInSeconds) = 0; + virtual void reportNotifications() = 0; }; @@ -44,7 +45,7 @@ public: virtual void enableRealTimeSimulation(bool enableRealTimeSim)=0; virtual bool isRealTimeSimulationEnabled() const=0; - virtual void reportNotifications() = 0; + virtual void enableCommandLogging(bool enable, const char* fileName)=0; virtual void replayFromLogFile(const char* fileName)=0; diff --git a/examples/SharedMemory/PhysicsDirect.cpp b/examples/SharedMemory/PhysicsDirect.cpp index 9e3e01831..fef537c62 100644 --- a/examples/SharedMemory/PhysicsDirect.cpp +++ b/examples/SharedMemory/PhysicsDirect.cpp @@ -1217,8 +1217,7 @@ bool PhysicsDirect::submitClientCommand(const struct SharedMemoryCommand& comman if (m_data->m_ownsCommandProcessor) { - CommandProcessorInterface *commandProcessor = (CommandProcessorInterface *)m_data->m_commandProcessor; - commandProcessor->reportNotifications(); + m_data->m_commandProcessor->reportNotifications(); } /*if (hasStatus) { diff --git a/examples/SharedMemory/SharedMemoryCommandProcessor.h b/examples/SharedMemory/SharedMemoryCommandProcessor.h index 6d75b87d9..f70d9749f 100644 --- a/examples/SharedMemory/SharedMemoryCommandProcessor.h +++ b/examples/SharedMemory/SharedMemoryCommandProcessor.h @@ -31,6 +31,7 @@ public: void setSharedMemoryKey(int key); virtual void setTimeOut(double timeOutInSeconds); + virtual void reportNotifications() {} }; #endif //SHARED_MEMORY_COMMAND_PROCESSOR_H diff --git a/examples/SharedMemory/SharedMemoryPublic.h b/examples/SharedMemory/SharedMemoryPublic.h index 5e7cc31d0..7129363f7 100644 --- a/examples/SharedMemory/SharedMemoryPublic.h +++ b/examples/SharedMemory/SharedMemoryPublic.h @@ -7,7 +7,8 @@ //Please don't replace an existing magic number: //instead, only ADD a new one at the top, comment-out previous one -#define SHARED_MEMORY_MAGIC_NUMBER 201809010 +#define SHARED_MEMORY_MAGIC_NUMBER 2018090300 +//#define SHARED_MEMORY_MAGIC_NUMBER 201809010 //#define SHARED_MEMORY_MAGIC_NUMBER 201807040 //#define SHARED_MEMORY_MAGIC_NUMBER 201806150 //#define SHARED_MEMORY_MAGIC_NUMBER 201806020 @@ -26,6 +27,7 @@ enum EnumSharedMemoryClientCommand { + CMD_INVALID=0, CMD_LOAD_SDF, CMD_LOAD_URDF, CMD_LOAD_BULLET, @@ -812,6 +814,7 @@ enum eCONNECT_METHOD { eCONNECT_SHARED_MEMORY_SERVER=9, eCONNECT_DART=10, eCONNECT_MUJOCO=11, + eCONNECT_GRPC=12, }; enum eURDF_Flags diff --git a/examples/SharedMemory/b3RobotSimulatorClientAPI_NoDirect.cpp b/examples/SharedMemory/b3RobotSimulatorClientAPI_NoDirect.cpp index 4b63c0997..56629f91d 100644 --- a/examples/SharedMemory/b3RobotSimulatorClientAPI_NoDirect.cpp +++ b/examples/SharedMemory/b3RobotSimulatorClientAPI_NoDirect.cpp @@ -789,10 +789,13 @@ void b3RobotSimulatorClientAPI_NoDirect::setJointMotorControl(int bodyUniqueId, b3JointInfo jointInfo; b3GetJointInfo(m_data->m_physicsClientHandle, bodyUniqueId, jointIndex, &jointInfo); int uIndex = jointInfo.m_uIndex; - b3JointControlSetKd(command, uIndex, args.m_kd); - b3JointControlSetDesiredVelocity(command, uIndex, args.m_targetVelocity); - b3JointControlSetMaximumForce(command, uIndex, args.m_maxTorqueValue); - statusHandle = b3SubmitClientCommandAndWaitStatus(m_data->m_physicsClientHandle, command); + if (uIndex >= 0) + { + b3JointControlSetKd(command, uIndex, args.m_kd); + b3JointControlSetDesiredVelocity(command, uIndex, args.m_targetVelocity); + b3JointControlSetMaximumForce(command, uIndex, args.m_maxTorqueValue); + statusHandle = b3SubmitClientCommandAndWaitStatus(m_data->m_physicsClientHandle, command); + } break; } case CONTROL_MODE_POSITION_VELOCITY_PD: @@ -817,8 +820,11 @@ void b3RobotSimulatorClientAPI_NoDirect::setJointMotorControl(int bodyUniqueId, b3JointInfo jointInfo; b3GetJointInfo(m_data->m_physicsClientHandle, bodyUniqueId, jointIndex, &jointInfo); int uIndex = jointInfo.m_uIndex; - b3JointControlSetDesiredForceTorque(command, uIndex, args.m_maxTorqueValue); - statusHandle = b3SubmitClientCommandAndWaitStatus(m_data->m_physicsClientHandle, command); + if (uIndex >= 0) + { + b3JointControlSetDesiredForceTorque(command, uIndex, args.m_maxTorqueValue); + statusHandle = b3SubmitClientCommandAndWaitStatus(m_data->m_physicsClientHandle, command); + } break; } case CONTROL_MODE_PD: diff --git a/examples/SharedMemory/grpc/ConvertGRPCBullet.cpp b/examples/SharedMemory/grpc/ConvertGRPCBullet.cpp index c6f4daabe..163aba08a 100644 --- a/examples/SharedMemory/grpc/ConvertGRPCBullet.cpp +++ b/examples/SharedMemory/grpc/ConvertGRPCBullet.cpp @@ -10,6 +10,9 @@ #include "pybullet.grpc.pb.h" #include "LinearMath/btMinMax.h" +//#define ALLOW_GRPC_COMMAND_CONVERSION +#define ALLOW_GRPC_STATUS_CONVERSION + using grpc::Server; using grpc::ServerAsyncResponseWriter; using grpc::ServerBuilder; @@ -20,265 +23,1613 @@ using pybullet_grpc::PyBulletCommand; using pybullet_grpc::PyBulletStatus; using pybullet_grpc::PyBulletAPI; +pybullet_grpc::PyBulletCommand* convertBulletToGRPCCommand(const struct SharedMemoryCommand& clientCmd, pybullet_grpc::PyBulletCommand& grpcCommand) +{ + pybullet_grpc::PyBulletCommand* grpcCmdPtr = 0; -SharedMemoryCommand* convertGRPCAndSubmitCommand(PyBulletCommand& grpcCommand, SharedMemoryCommand& cmd) + grpcCommand.set_commandtype(clientCmd.m_type); + + + switch (clientCmd.m_type) + { + + case CMD_RESET_SIMULATION: + { + grpcCmdPtr = &grpcCommand; + break; + } + case CMD_REQUEST_KEYBOARD_EVENTS_DATA: + { + grpcCmdPtr = &grpcCommand; + break; + } + + case CMD_USER_CONSTRAINT: + { + grpcCmdPtr = &grpcCommand; + ::pybullet_grpc::UserConstraintCommand* con = grpcCommand.mutable_userconstraintcommand(); + + con->set_updateflags(clientCmd.m_updateFlags); + con->mutable_childframe()->mutable_origin()->set_x(clientCmd.m_userConstraintArguments.m_childFrame[0]); + con->mutable_childframe()->mutable_origin()->set_y(clientCmd.m_userConstraintArguments.m_childFrame[1]); + con->mutable_childframe()->mutable_origin()->set_z(clientCmd.m_userConstraintArguments.m_childFrame[2]); + con->mutable_childframe()->mutable_orientation()->set_x(clientCmd.m_userConstraintArguments.m_childFrame[3]); + con->mutable_childframe()->mutable_orientation()->set_y(clientCmd.m_userConstraintArguments.m_childFrame[4]); + con->mutable_childframe()->mutable_orientation()->set_z(clientCmd.m_userConstraintArguments.m_childFrame[5]); + con->mutable_childframe()->mutable_orientation()->set_w(clientCmd.m_userConstraintArguments.m_childFrame[6]); + + con->mutable_parentframe()->mutable_origin()->set_x(clientCmd.m_userConstraintArguments.m_parentFrame[0]); + con->mutable_parentframe()->mutable_origin()->set_y(clientCmd.m_userConstraintArguments.m_parentFrame[1]); + con->mutable_parentframe()->mutable_origin()->set_z(clientCmd.m_userConstraintArguments.m_parentFrame[2]); + con->mutable_parentframe()->mutable_orientation()->set_x(clientCmd.m_userConstraintArguments.m_parentFrame[3]); + con->mutable_parentframe()->mutable_orientation()->set_y(clientCmd.m_userConstraintArguments.m_parentFrame[4]); + con->mutable_parentframe()->mutable_orientation()->set_z(clientCmd.m_userConstraintArguments.m_parentFrame[5]); + con->mutable_parentframe()->mutable_orientation()->set_w(clientCmd.m_userConstraintArguments.m_parentFrame[6]); + + con->mutable_jointaxis()->set_x(clientCmd.m_userConstraintArguments.m_jointAxis[0]); + con->mutable_jointaxis()->set_y(clientCmd.m_userConstraintArguments.m_jointAxis[1]); + con->mutable_jointaxis()->set_z(clientCmd.m_userConstraintArguments.m_jointAxis[2]); + + con->set_childbodyindex(clientCmd.m_userConstraintArguments.m_childBodyIndex); + con->set_childjointindex(clientCmd.m_userConstraintArguments.m_childJointIndex); + con->set_parentbodyindex(clientCmd.m_userConstraintArguments.m_parentBodyIndex); + con->set_parentjointindex(clientCmd.m_userConstraintArguments.m_parentJointIndex); + con->set_jointtype(clientCmd.m_userConstraintArguments.m_jointType); + + if (clientCmd.m_updateFlags&USER_CONSTRAINT_CHANGE_MAX_FORCE) + { + con->set_maxappliedforce(clientCmd.m_userConstraintArguments.m_maxAppliedForce); + } + if (clientCmd.m_updateFlags&USER_CONSTRAINT_CHANGE_GEAR_RATIO) + { + con->set_gearratio(clientCmd.m_userConstraintArguments.m_gearRatio); + } + + if (clientCmd.m_updateFlags&USER_CONSTRAINT_CHANGE_GEAR_AUX_LINK) + { + con->set_gearauxlink(clientCmd.m_userConstraintArguments.m_gearAuxLink); + } + if (clientCmd.m_updateFlags&USER_CONSTRAINT_CHANGE_RELATIVE_POSITION_TARGET) + { + con->set_relativepositiontarget(clientCmd.m_userConstraintArguments.m_relativePositionTarget); + } + if (clientCmd.m_updateFlags&USER_CONSTRAINT_CHANGE_ERP) + { + con->set_erp(clientCmd.m_userConstraintArguments.m_erp); + } + con->set_userconstraintuniqueid(-1); + + break; + } + case CMD_STEP_FORWARD_SIMULATION: + { + grpcCmdPtr = &grpcCommand; + break; + } + + case CMD_LOAD_URDF: + { + ::pybullet_grpc::LoadUrdfCommand* urdfCmd = grpcCommand.mutable_loadurdfcommand(); + grpcCmdPtr = &grpcCommand; + urdfCmd->set_filename(clientCmd.m_urdfArguments.m_urdfFileName); + if (clientCmd.m_updateFlags &URDF_ARGS_INITIAL_POSITION) + { + urdfCmd->mutable_initialposition()->set_x(clientCmd.m_urdfArguments.m_initialPosition[0]); + urdfCmd->mutable_initialposition()->set_y(clientCmd.m_urdfArguments.m_initialPosition[1]); + urdfCmd->mutable_initialposition()->set_z(clientCmd.m_urdfArguments.m_initialPosition[2]); + } + + if (clientCmd.m_updateFlags &URDF_ARGS_INITIAL_ORIENTATION) + { + urdfCmd->mutable_initialorientation()->set_x(clientCmd.m_urdfArguments.m_initialOrientation[0]); + urdfCmd->mutable_initialorientation()->set_y(clientCmd.m_urdfArguments.m_initialOrientation[1]); + urdfCmd->mutable_initialorientation()->set_z(clientCmd.m_urdfArguments.m_initialOrientation[2]); + urdfCmd->mutable_initialorientation()->set_w(clientCmd.m_urdfArguments.m_initialOrientation[3]); + } + + if (clientCmd.m_updateFlags &URDF_ARGS_USE_MULTIBODY) + { + urdfCmd->set_usemultibody(clientCmd.m_urdfArguments.m_useMultiBody); + } + if (clientCmd.m_updateFlags &URDF_ARGS_USE_FIXED_BASE) + { + urdfCmd->set_usefixedbase(clientCmd.m_urdfArguments.m_useFixedBase); + } + if (clientCmd.m_updateFlags &URDF_ARGS_USE_GLOBAL_SCALING) + { + urdfCmd->set_globalscaling(clientCmd.m_urdfArguments.m_globalScaling); + } + if (clientCmd.m_updateFlags &URDF_ARGS_HAS_CUSTOM_URDF_FLAGS) + { + urdfCmd->set_flags(clientCmd.m_urdfArguments.m_urdfFlags); + } + break; + } + + case CMD_INIT_POSE: + { + grpcCmdPtr = &grpcCommand; + ::pybullet_grpc::InitPoseCommand* pose = grpcCommand.mutable_initposecommand(); + { + pose->set_bodyuniqueid(clientCmd.m_initPoseArgs.m_bodyUniqueId); + pose->set_updateflags(clientCmd.m_updateFlags); + int maxQ = 0; + for (int q = 0; q < MAX_DEGREE_OF_FREEDOM; q++) + { + if (clientCmd.m_initPoseArgs.m_hasInitialStateQ[q]) + { + maxQ = q+1; + } + if (clientCmd.m_initPoseArgs.m_hasInitialStateQdot[q]) + { + maxQ = q+1; + } + } + for (int q = 0; q < maxQ; q++) + { + pose->add_hasinitialstateq(clientCmd.m_initPoseArgs.m_hasInitialStateQ[q]); + pose->add_hasinitialstateqdot(clientCmd.m_initPoseArgs.m_hasInitialStateQdot[q]); + pose->add_initialstateq(clientCmd.m_initPoseArgs.m_initialStateQ[q]); + + pose->add_initialstateqdot(clientCmd.m_initPoseArgs.m_initialStateQdot[q]); + } + + } + break; + } + + case CMD_REQUEST_ACTUAL_STATE: + { + grpcCmdPtr = &grpcCommand; + + ::pybullet_grpc::RequestActualStateCommand* grpcCmd = grpcCommand.mutable_requestactualstatecommand(); + grpcCmd->set_bodyuniqueid(clientCmd.m_requestActualStateInformationCommandArgument.m_bodyUniqueId); + if (clientCmd.m_updateFlags & ACTUAL_STATE_COMPUTE_FORWARD_KINEMATICS) + { + grpcCmd->set_computeforwardkinematics(true); + } + if (clientCmd.m_updateFlags & ACTUAL_STATE_COMPUTE_LINKVELOCITY) + { + grpcCmd->set_computelinkvelocities(true); + } + break; + } + + case CMD_SEND_DESIRED_STATE: + { + ::pybullet_grpc::JointMotorControlCommand* motor = grpcCommand.mutable_jointmotorcontrolcommand(); + motor->set_bodyuniqueid(clientCmd.m_sendDesiredStateCommandArgument.m_bodyUniqueId); + motor->set_controlmode(clientCmd.m_sendDesiredStateCommandArgument.m_controlMode); + motor->set_updateflags(clientCmd.m_updateFlags); + int maxQ = 0; + for (int q = 0; q < MAX_DEGREE_OF_FREEDOM; q++) + { + if (clientCmd.m_sendDesiredStateCommandArgument.m_hasDesiredStateFlags[q]) + { + maxQ = q + 1; + } + } + + for (int q = 0; q < maxQ; q++) + { + motor->add_desiredstateq(clientCmd.m_sendDesiredStateCommandArgument.m_desiredStateQ[q]); + motor->add_desiredstateqdot(clientCmd.m_sendDesiredStateCommandArgument.m_desiredStateQdot[q]); + motor->add_desiredstateforcetorque(clientCmd.m_sendDesiredStateCommandArgument.m_desiredStateForceTorque[q]); + motor->add_kd(clientCmd.m_sendDesiredStateCommandArgument.m_Kp[q]); + motor->add_kp(clientCmd.m_sendDesiredStateCommandArgument.m_Kp[q]); + motor->add_maxvelocity(clientCmd.m_sendDesiredStateCommandArgument.m_rhsClamp[q]); + motor->add_hasdesiredstateflags(clientCmd.m_sendDesiredStateCommandArgument.m_hasDesiredStateFlags[q]); + } + grpcCmdPtr = &grpcCommand; + //b3JointControlCommandInit2Internal + break; + } + + case CMD_SEND_PHYSICS_SIMULATION_PARAMETERS: + { + grpcCmdPtr = &grpcCommand; + ::pybullet_grpc::PhysicsSimulationParametersCommand* grpcCmd = grpcCommand.mutable_setphysicssimulationparameterscommand(); + grpcCmd->set_updateflags(clientCmd.m_updateFlags); + ::pybullet_grpc::PhysicsSimulationParameters* params = grpcCmd->mutable_params(); + + if (clientCmd.m_updateFlags&SIM_PARAM_UPDATE_DELTA_TIME) + { + params->set_deltatime(clientCmd.m_physSimParamArgs.m_deltaTime); + } + if (clientCmd.m_updateFlags&SIM_PARAM_UPDATE_GRAVITY) + { + ::pybullet_grpc::vec3* grav = params->mutable_gravityacceleration(); + grav->set_x(clientCmd.m_physSimParamArgs.m_gravityAcceleration[0]); + grav->set_y(clientCmd.m_physSimParamArgs.m_gravityAcceleration[1]); + grav->set_z(clientCmd.m_physSimParamArgs.m_gravityAcceleration[2]); + } + + if (clientCmd.m_updateFlags&SIM_PARAM_UPDATE_NUM_SOLVER_ITERATIONS) + { + params->set_numsolveriterations(clientCmd.m_physSimParamArgs.m_numSolverIterations); + } + if (clientCmd.m_updateFlags&SIM_PARAM_UPDATE_NUM_SIMULATION_SUB_STEPS) + { + params->set_numsimulationsubsteps(clientCmd.m_physSimParamArgs.m_numSimulationSubSteps); + } + + if (clientCmd.m_updateFlags&SIM_PARAM_UPDATE_REAL_TIME_SIMULATION) + { + params->set_userealtimesimulation(clientCmd.m_physSimParamArgs.m_useRealTimeSimulation); + } + if (clientCmd.m_updateFlags&SIM_PARAM_UPDATE_DEFAULT_CONTACT_ERP) + { + params->set_defaultcontacterp(clientCmd.m_physSimParamArgs.m_defaultContactERP); + } + if (clientCmd.m_updateFlags&SIM_PARAM_UPDATE_INTERNAL_SIMULATION_FLAGS) + { + params->set_internalsimflags(clientCmd.m_physSimParamArgs.m_internalSimFlags); + } + if (clientCmd.m_updateFlags&SIM_PARAM_UPDATE_USE_SPLIT_IMPULSE) + { + params->set_usesplitimpulse(clientCmd.m_physSimParamArgs.m_useSplitImpulse); + } + if (clientCmd.m_updateFlags&SIM_PARAM_UPDATE_SPLIT_IMPULSE_PENETRATION_THRESHOLD) + { + params->set_splitimpulsepenetrationthreshold(clientCmd.m_physSimParamArgs.m_splitImpulsePenetrationThreshold); + } + if (clientCmd.m_updateFlags&SIM_PARAM_UPDATE_COLLISION_FILTER_MODE) + { + params->set_collisionfiltermode(clientCmd.m_physSimParamArgs.m_collisionFilterMode); + } + if (clientCmd.m_updateFlags&SIM_PARAM_UPDATE_CONTACT_BREAKING_THRESHOLD) + { + params->set_contactbreakingthreshold(clientCmd.m_physSimParamArgs.m_contactBreakingThreshold); + } + + if (clientCmd.m_updateFlags&SIM_PARAM_ENABLE_CONE_FRICTION) + { + params->set_enableconefriction(clientCmd.m_physSimParamArgs.m_enableConeFriction); + } + + if (clientCmd.m_updateFlags&SIM_PARAM_ENABLE_FILE_CACHING) + { + params->set_enablefilecaching(clientCmd.m_physSimParamArgs.m_enableFileCaching); + } + + if (clientCmd.m_updateFlags&SIM_PARAM_UPDATE_RESTITUTION_VELOCITY_THRESHOLD) + { + params->set_restitutionvelocitythreshold(clientCmd.m_physSimParamArgs.m_restitutionVelocityThreshold); + } + if (clientCmd.m_updateFlags&SIM_PARAM_UPDATE_DEFAULT_NON_CONTACT_ERP) + { + params->set_defaultnoncontacterp(clientCmd.m_physSimParamArgs.m_defaultNonContactERP); + } + if (clientCmd.m_updateFlags&SIM_PARAM_UPDATE_DEFAULT_FRICTION_ERP) + { + params->set_frictionerp(clientCmd.m_physSimParamArgs.m_frictionERP); + } + if (clientCmd.m_updateFlags&SIM_PARAM_UPDATE_DETERMINISTIC_OVERLAPPING_PAIRS) + { + params->set_deterministicoverlappingpairs(clientCmd.m_physSimParamArgs.m_deterministicOverlappingPairs); + } + if (clientCmd.m_updateFlags&SIM_PARAM_UPDATE_CCD_ALLOWED_PENETRATION) + { + params->set_allowedccdpenetration(clientCmd.m_physSimParamArgs.m_allowedCcdPenetration); + } + if (clientCmd.m_updateFlags&SIM_PARAM_UPDATE_JOINT_FEEDBACK_MODE) + { + params->set_jointfeedbackmode(clientCmd.m_physSimParamArgs.m_jointFeedbackMode); + } + if (clientCmd.m_updateFlags&SIM_PARAM_UPDATE_DEFAULT_GLOBAL_CFM) + { + params->set_defaultglobalcfm(clientCmd.m_physSimParamArgs.m_defaultGlobalCFM); + } + if (clientCmd.m_updateFlags&SIM_PARAM_UPDATE_DEFAULT_FRICTION_CFM) + { + params->set_frictioncfm(clientCmd.m_physSimParamArgs.m_frictionCFM); + } + if (clientCmd.m_updateFlags&SIM_PARAM_UPDATE_SOLVER_RESIDULAL_THRESHOLD) + { + params->set_solverresidualthreshold(clientCmd.m_physSimParamArgs.m_solverResidualThreshold); + } + if (clientCmd.m_updateFlags&SIM_PARAM_UPDATE_CONTACT_SLOP) + { + params->set_contactslop(clientCmd.m_physSimParamArgs.m_contactSlop); + } + if (clientCmd.m_updateFlags&SIM_PARAM_ENABLE_SAT) + { + params->set_enablesat(clientCmd.m_physSimParamArgs.m_enableSAT); + } + if (clientCmd.m_updateFlags&SIM_PARAM_CONSTRAINT_SOLVER_TYPE) + { + params->set_constraintsolvertype(clientCmd.m_physSimParamArgs.m_constraintSolverType); + } + if (clientCmd.m_updateFlags&SIM_PARAM_CONSTRAINT_MIN_SOLVER_ISLAND_SIZE) + { + params->set_minimumsolverislandsize(clientCmd.m_physSimParamArgs.m_minimumSolverIslandSize); + } + + break; + } + + case CMD_REQUEST_BODY_INFO: + { + grpcCmdPtr = &grpcCommand; + ::pybullet_grpc::RequestBodyInfoCommand* grpcCmd = grpcCommand.mutable_requestbodyinfocommand(); + grpcCmd->set_bodyuniqueid(clientCmd.m_sdfRequestInfoArgs.m_bodyUniqueId); + break; + } + + case CMD_REQUEST_PHYSICS_SIMULATION_PARAMETERS: + { + grpcCmdPtr = &grpcCommand; + break; + } + + case CMD_SYNC_BODY_INFO: + { + grpcCmdPtr = &grpcCommand; + break; + } + case CMD_REQUEST_INTERNAL_DATA: + { + grpcCmdPtr = &grpcCommand; + break; + } + + case CMD_CONFIGURE_OPENGL_VISUALIZER: + { + grpcCmdPtr = &grpcCommand; + ::pybullet_grpc::ConfigureOpenGLVisualizerCommand* vizCmd = grpcCommand.mutable_configureopenglvisualizercommand(); + + vizCmd->set_updateflags(clientCmd.m_updateFlags); + vizCmd->set_cameradistance(clientCmd.m_configureOpenGLVisualizerArguments.m_cameraDistance); + vizCmd->set_camerapitch(clientCmd.m_configureOpenGLVisualizerArguments.m_cameraPitch); + vizCmd->set_camerayaw(clientCmd.m_configureOpenGLVisualizerArguments.m_cameraYaw); + vizCmd->set_setflag(clientCmd.m_configureOpenGLVisualizerArguments.m_setFlag); + vizCmd->set_setenabled(clientCmd.m_configureOpenGLVisualizerArguments.m_setEnabled); + ::pybullet_grpc::vec3* targetPos = vizCmd->mutable_cameratargetposition(); + targetPos->set_x(clientCmd.m_configureOpenGLVisualizerArguments.m_cameraTargetPosition[0]); + targetPos->set_y(clientCmd.m_configureOpenGLVisualizerArguments.m_cameraTargetPosition[1]); + targetPos->set_z(clientCmd.m_configureOpenGLVisualizerArguments.m_cameraTargetPosition[2]); + break; + } + + case CMD_REQUEST_CAMERA_IMAGE_DATA: + { + grpcCmdPtr = &grpcCommand; + ::pybullet_grpc::RequestCameraImageCommand* cam = grpcCommand.mutable_requestcameraimagecommand(); + + cam->set_updateflags(clientCmd.m_updateFlags); + cam->set_startpixelindex(clientCmd.m_requestPixelDataArguments.m_startPixelIndex); + + if (clientCmd.m_updateFlags&REQUEST_PIXEL_ARGS_SET_PIXEL_WIDTH_HEIGHT) + { + cam->set_pixelwidth(clientCmd.m_requestPixelDataArguments.m_pixelWidth); + cam->set_pixelheight(clientCmd.m_requestPixelDataArguments.m_pixelHeight); + } + if (clientCmd.m_updateFlags&REQUEST_PIXEL_ARGS_SET_SPECULAR_COEFF) + { + cam->set_lightspecularcoeff(clientCmd.m_requestPixelDataArguments.m_lightSpecularCoeff); + } + + if (clientCmd.m_updateFlags&REQUEST_PIXEL_ARGS_HAS_FLAGS) + { + cam->set_cameraflags(clientCmd.m_requestPixelDataArguments.m_flags); + } + if (clientCmd.m_updateFlags&REQUEST_PIXEL_ARGS_SET_SHADOW) + { + cam->set_hasshadow(clientCmd.m_requestPixelDataArguments.m_hasShadow); + } + if (clientCmd.m_updateFlags&REQUEST_PIXEL_ARGS_SET_AMBIENT_COEFF) + { + cam->set_lightambientcoeff(clientCmd.m_requestPixelDataArguments.m_lightAmbientCoeff); + } + if (clientCmd.m_updateFlags&REQUEST_PIXEL_ARGS_SET_DIFFUSE_COEFF) + { + cam->set_lightdiffusecoeff(clientCmd.m_requestPixelDataArguments.m_lightDiffuseCoeff); + } + if (clientCmd.m_updateFlags&REQUEST_PIXEL_ARGS_SET_LIGHT_DISTANCE) + { + cam->set_lightdistance(clientCmd.m_requestPixelDataArguments.m_lightDistance); + } + + if (clientCmd.m_updateFlags&REQUEST_PIXEL_ARGS_SET_LIGHT_COLOR) + { + ::pybullet_grpc::vec3* lightColor = cam->mutable_lightcolor(); + lightColor->set_x(clientCmd.m_requestPixelDataArguments.m_lightColor[0]); + lightColor->set_y(clientCmd.m_requestPixelDataArguments.m_lightColor[1]); + lightColor->set_z(clientCmd.m_requestPixelDataArguments.m_lightColor[2]); + } + if (clientCmd.m_updateFlags&REQUEST_PIXEL_ARGS_SET_LIGHT_DIRECTION) + { + ::pybullet_grpc::vec3* lightDir = cam->mutable_lightdirection(); + lightDir->set_x(clientCmd.m_requestPixelDataArguments.m_lightDirection[0]); + lightDir->set_y(clientCmd.m_requestPixelDataArguments.m_lightDirection[1]); + lightDir->set_z(clientCmd.m_requestPixelDataArguments.m_lightDirection[2]); + } + + if (clientCmd.m_updateFlags&REQUEST_PIXEL_ARGS_HAS_CAMERA_MATRICES) + { + ::pybullet_grpc::matrix4x4* projMat = cam->mutable_projectionmatrix(); + ::pybullet_grpc::matrix4x4* viewMat = cam->mutable_viewmatrix(); + for (int i = 0; i < 16; i++) + { + projMat->add_elems(clientCmd.m_requestPixelDataArguments.m_projectionMatrix[i]); + viewMat->add_elems(clientCmd.m_requestPixelDataArguments.m_viewMatrix[i]); + } + } + + if (clientCmd.m_updateFlags&REQUEST_PIXEL_ARGS_HAS_PROJECTIVE_TEXTURE_MATRICES) + { + ::pybullet_grpc::matrix4x4* projectiveProjMat = cam->mutable_projectivetextureprojectionmatrix(); + ::pybullet_grpc::matrix4x4* projectiveViewMat = cam->mutable_projectivetextureviewmatrix(); + for (int i = 0; i < 16; i++) + { + projectiveProjMat->add_elems(clientCmd.m_requestPixelDataArguments.m_projectiveTextureProjectionMatrix[i]); + projectiveViewMat->add_elems(clientCmd.m_requestPixelDataArguments.m_projectiveTextureViewMatrix[i]); + } + } + + break; + } + + default: + { + printf("convertBulletToGRPCCommand: Unknown command\n"); + //assert(0); + + } + }; + + + + if (0 == grpcCmdPtr) + { + grpcCmdPtr = &grpcCommand; + printf("Warning: slow fallback of convertBulletToGRPCCommand (%d)", clientCmd.m_type); + //convert an unknown command as binary blob + int sz = sizeof(SharedMemoryCommand); + if (sz > 0) + { + grpcCommand.add_unknowncommandbinaryblob((const char*)&clientCmd, sz); + } + } + btAssert(grpcCmdPtr); + return grpcCmdPtr; +} + + +SharedMemoryCommand* convertGRPCToBulletCommand(const PyBulletCommand& grpcCommand, SharedMemoryCommand& cmd) { SharedMemoryCommand* cmdPtr = 0; - if (grpcCommand.has_loadurdfcommand()) + + + cmd.m_type = grpcCommand.commandtype(); + if (cmd.m_type == CMD_INVALID) { - const ::pybullet_grpc::LoadUrdfCommand& grpcCmd = grpcCommand.loadurdfcommand(); - - std::string fileName = grpcCmd.filename(); - if (fileName.length()) + //derive it from the contents instead + if (grpcCommand.has_changedynamicscommand()) { - 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.flags()) - { - b3LoadUrdfCommandSetFlags(commandHandle, grpcCmd.flags()); - } - + cmd.m_type = CMD_CHANGE_DYNAMICS_INFO; } + if (grpcCommand.has_loadurdfcommand()) + { + cmd.m_type = CMD_LOAD_URDF; + } + if (grpcCommand.has_loadsdfcommand()) + { + cmd.m_type = CMD_LOAD_SDF; + } + if (grpcCommand.has_loadmjcfcommand()) + { + cmd.m_type = CMD_LOAD_MJCF; + } + if (grpcCommand.has_changedynamicscommand()) + { + cmd.m_type = CMD_CHANGE_DYNAMICS_INFO; + } + if (grpcCommand.has_getdynamicscommand()) + { + cmd.m_type = CMD_GET_DYNAMICS_INFO; + } + if (grpcCommand.has_initposecommand()) + { + cmd.m_type = CMD_INIT_POSE; + } + if (grpcCommand.has_requestactualstatecommand()) + { + cmd.m_type = CMD_REQUEST_ACTUAL_STATE; + } + if (grpcCommand.has_stepsimulationcommand()) + { + cmd.m_type = CMD_STEP_FORWARD_SIMULATION; + } + + } - if (grpcCommand.has_loadsdfcommand()) + int sz = grpcCommand.unknowncommandbinaryblob_size(); + if (sz) { - const ::pybullet_grpc::LoadSdfCommand& grpcCmd = grpcCommand.loadsdfcommand(); - - std::string fileName = grpcCmd.filename(); - if (fileName.length()) + if (sz == 1) { - cmdPtr = &cmd; - b3SharedMemoryCommandHandle commandHandle = (b3SharedMemoryCommandHandle)cmdPtr; - b3LoadSdfCommandInit2(commandHandle, fileName.c_str()); + const char* data = grpcCommand.unknowncommandbinaryblob().Get(0).c_str(); + int numBytes = grpcCommand.unknowncommandbinaryblob().Get(0).size(); - - if (grpcCmd.hasUseMultiBody_case() == ::pybullet_grpc::LoadSdfCommand::HasUseMultiBodyCase::kUseMultiBody) + btAssert(sizeof(SharedMemoryCommand) == numBytes); + if (sizeof(SharedMemoryCommand) == numBytes) { - b3LoadSdfCommandSetUseMultiBody(commandHandle, grpcCmd.usemultibody()); - } - if (grpcCmd.hasGlobalScaling_case() == ::pybullet_grpc::LoadSdfCommand::HasGlobalScalingCase::kGlobalScaling) - { - b3LoadSdfCommandSetUseGlobalScaling(commandHandle, grpcCmd.globalscaling()); - } - } - } - - if (grpcCommand.has_loadmjcfcommand()) - { - const pybullet_grpc::LoadMjcfCommand& grpcCmd = grpcCommand.loadmjcfcommand(); - - std::string fileName = grpcCmd.filename(); - if (fileName.length()) - { - cmdPtr = &cmd; - b3SharedMemoryCommandHandle commandHandle = (b3SharedMemoryCommandHandle)cmdPtr; - b3LoadMJCFCommandInit2(commandHandle, fileName.c_str()); - - if (grpcCmd.flags()) - { - b3LoadMJCFCommandSetFlags(commandHandle, grpcCmd.flags()); - } - } - } - - if (grpcCommand.has_changedynamicscommand()) - { - cmdPtr = &cmd; - b3SharedMemoryCommandHandle commandHandle = (b3SharedMemoryCommandHandle)cmdPtr; - const ::pybullet_grpc::ChangeDynamicsCommand& grpcCmd = grpcCommand.changedynamicscommand(); - int bodyUniqueId = grpcCmd.bodyuniqueid(); - int linkIndex = grpcCmd.linkindex(); - b3InitChangeDynamicsInfo2(commandHandle); - if (grpcCmd.hasMass_case() == ::pybullet_grpc::ChangeDynamicsCommand::HasMassCase::kMass) - { - b3ChangeDynamicsInfoSetMass(commandHandle, bodyUniqueId, linkIndex, grpcCmd.mass()); - } - if (grpcCmd.hasLateralFriction_case() == ::pybullet_grpc::ChangeDynamicsCommand::HasLateralFrictionCase::kLateralFriction) - { - b3ChangeDynamicsInfoSetLateralFriction(commandHandle, bodyUniqueId, linkIndex, grpcCmd.lateralfriction()); - } - if (grpcCmd.hasSpinningFriction_case() == ::pybullet_grpc::ChangeDynamicsCommand::HasSpinningFrictionCase::kSpinningFriction) - { - b3ChangeDynamicsInfoSetSpinningFriction(commandHandle, bodyUniqueId, linkIndex, grpcCmd.spinningfriction()); - } - if (grpcCmd.hasRollingFriction_case() == ::pybullet_grpc::ChangeDynamicsCommand::HasRollingFrictionCase::kRollingFriction) - { - b3ChangeDynamicsInfoSetRollingFriction(commandHandle, bodyUniqueId, linkIndex, grpcCmd.rollingfriction()); - } - - if (grpcCmd.hasRestitution_case() == ::pybullet_grpc::ChangeDynamicsCommand::HasRestitutionCase::kRestitution) - { - b3ChangeDynamicsInfoSetRestitution(commandHandle, bodyUniqueId, linkIndex, grpcCmd.restitution()); - } - if (grpcCmd.haslinearDamping_case() == ::pybullet_grpc::ChangeDynamicsCommand::HaslinearDampingCase::kLinearDamping) - { - b3ChangeDynamicsInfoSetLinearDamping(commandHandle, bodyUniqueId, grpcCmd.lineardamping()); - } - - if (grpcCmd.hasangularDamping_case() == ::pybullet_grpc::ChangeDynamicsCommand::HasangularDampingCase::kAngularDamping) - { - b3ChangeDynamicsInfoSetAngularDamping(commandHandle, bodyUniqueId, grpcCmd.angulardamping()); - } - - bool hasContactDamping = grpcCmd.hasContactDamping_case() == ::pybullet_grpc::ChangeDynamicsCommand::HasContactDampingCase::kContactDamping; - bool hasContactStiffness = grpcCmd.hasContactStiffness_case() == ::pybullet_grpc::ChangeDynamicsCommand::HasContactStiffnessCase::kContactStiffness; - if (hasContactDamping && hasContactStiffness) - { - b3ChangeDynamicsInfoSetContactStiffnessAndDamping(commandHandle, bodyUniqueId, linkIndex, grpcCmd.contactstiffness(), grpcCmd.contactdamping()); - } - if (grpcCmd.hasLocalInertiaDiagonal_case() == ::pybullet_grpc::ChangeDynamicsCommand::HasLocalInertiaDiagonalCase::kLocalInertiaDiagonal) - { - double localInertiaDiag[3] = { grpcCmd.localinertiadiagonal().x(), grpcCmd.localinertiadiagonal().y(), grpcCmd.localinertiadiagonal().z() }; - b3ChangeDynamicsInfoSetLocalInertiaDiagonal(commandHandle, bodyUniqueId, linkIndex, localInertiaDiag); - } - - if (grpcCmd.hasFrictionAnchor_case() == ::pybullet_grpc::ChangeDynamicsCommand::HasFrictionAnchorCase::kFrictionAnchor) - { - b3ChangeDynamicsInfoSetFrictionAnchor(commandHandle, bodyUniqueId, linkIndex, grpcCmd.frictionanchor()); - } - if (grpcCmd.hasccdSweptSphereRadius_case() == ::pybullet_grpc::ChangeDynamicsCommand::HasccdSweptSphereRadiusCase::kCcdSweptSphereRadius) - { - b3ChangeDynamicsInfoSetCcdSweptSphereRadius(commandHandle, bodyUniqueId, linkIndex, grpcCmd.ccdsweptsphereradius()); - } - - - if (grpcCmd.hasContactProcessingThreshold_case() == ::pybullet_grpc::ChangeDynamicsCommand::HasContactProcessingThresholdCase::kContactProcessingThreshold) - { - b3ChangeDynamicsInfoSetContactProcessingThreshold(commandHandle, bodyUniqueId, linkIndex, grpcCmd.contactprocessingthreshold()); - } - - if (grpcCmd.hasActivationState_case() == ::pybullet_grpc::ChangeDynamicsCommand::HasActivationStateCase::kActivationState) - { - b3ChangeDynamicsInfoSetActivationState(commandHandle, bodyUniqueId, grpcCmd.activationstate()); - } - - - } - if (grpcCommand.has_getdynamicscommand()) - { - cmdPtr = &cmd; - b3SharedMemoryCommandHandle commandHandle = (b3SharedMemoryCommandHandle)cmdPtr; - const ::pybullet_grpc::GetDynamicsCommand& grpcCmd = grpcCommand.getdynamicscommand(); - b3GetDynamicsInfoCommandInit2(commandHandle, grpcCmd.bodyuniqueid(), grpcCmd.linkindex()); - } - - if (grpcCommand.has_initposecommand()) - { - cmdPtr = &cmd; - b3SharedMemoryCommandHandle commandHandle = (b3SharedMemoryCommandHandle)cmdPtr; - - const ::pybullet_grpc::InitPoseCommand& grpcCmd = grpcCommand.initposecommand(); - b3CreatePoseCommandInit2(commandHandle, grpcCmd.bodyuniqueid()); - double initialQ[MAX_DEGREE_OF_FREEDOM] = { 0 }; - double initialQdot[MAX_DEGREE_OF_FREEDOM] = { 0 }; - int hasInitialQ[MAX_DEGREE_OF_FREEDOM] = { 0 }; - int hasInitialQdot[MAX_DEGREE_OF_FREEDOM] = { 0 }; - - if (grpcCmd.initialstateq_size() == grpcCmd.hasinitialstateq_size()) - { - int numInitial = btMin(grpcCmd.initialstateq_size(), MAX_DEGREE_OF_FREEDOM); - for (int i = 0; i < numInitial; i++) - { - initialQ[i] = grpcCmd.initialstateq(i); - hasInitialQ[i] = grpcCmd.hasinitialstateq(i); - } - if (numInitial) - { - b3CreatePoseCommandSetQ(commandHandle, numInitial, initialQ, hasInitialQ); + memcpy(&cmd, data, numBytes); } + printf("slow fallback on command type %d\n", cmd.m_type); } else { - printf("Error: if (grpcCmd.initialstateq_size() != grpcCmd.hasinitialstateq_size())\n"); + printf("Ignore unexpected unknowncommandbinaryblob\n"); } - if (grpcCmd.initialstateqdot_size() == grpcCmd.hasinitialstateqdot_size()) + cmdPtr = &cmd; + } + + + if (cmdPtr == 0) + { + switch (grpcCommand.commandtype()) { - int numInitial = btMin(grpcCmd.initialstateqdot_size(), MAX_DEGREE_OF_FREEDOM); - for (int i = 0; i < numInitial; i++) - { - initialQdot[i] = grpcCmd.initialstateqdot(i); - hasInitialQdot[i] = grpcCmd.hasinitialstateqdot(i); - } - if (numInitial) - { - b3CreatePoseCommandSetQdots(commandHandle, numInitial, initialQdot, hasInitialQdot); - } + + case CMD_RESET_SIMULATION: + { + cmdPtr = &cmd; + break; } - else + + case CMD_REQUEST_KEYBOARD_EVENTS_DATA: { - printf("Error: (grpcCmd.initialstateqdot_size() != grpcCmd.hasinitialstateqdot_size())\n"); + cmdPtr = &cmd; + b3SharedMemoryCommandHandle commandHandle = (b3SharedMemoryCommandHandle)cmdPtr; + b3RequestKeyboardEventsCommandInit2(commandHandle); + break; + } + + case CMD_USER_CONSTRAINT: + { + SharedMemoryCommand& clientCmd = cmd; + cmdPtr = &cmd; + b3SharedMemoryCommandHandle commandHandle = (b3SharedMemoryCommandHandle)cmdPtr; + + const ::pybullet_grpc::UserConstraintCommand* con = &grpcCommand.userconstraintcommand(); + + clientCmd.m_updateFlags = con->updateflags(); + clientCmd.m_userConstraintArguments.m_childFrame[0] = con->childframe().origin().x(); + clientCmd.m_userConstraintArguments.m_childFrame[1] = con->childframe().origin().y(); + clientCmd.m_userConstraintArguments.m_childFrame[2] = con->childframe().origin().z(); + clientCmd.m_userConstraintArguments.m_childFrame[3] = con->childframe().orientation().x(); + clientCmd.m_userConstraintArguments.m_childFrame[4] = con->childframe().orientation().y(); + clientCmd.m_userConstraintArguments.m_childFrame[5] = con->childframe().orientation().z(); + clientCmd.m_userConstraintArguments.m_childFrame[6] = con->childframe().orientation().w(); + + clientCmd.m_userConstraintArguments.m_parentFrame[0] = con->parentframe().origin().x(); + clientCmd.m_userConstraintArguments.m_parentFrame[1] = con->parentframe().origin().y(); + clientCmd.m_userConstraintArguments.m_parentFrame[2] = con->parentframe().origin().z(); + clientCmd.m_userConstraintArguments.m_parentFrame[3] = con->parentframe().orientation().x(); + clientCmd.m_userConstraintArguments.m_parentFrame[4] = con->parentframe().orientation().y(); + clientCmd.m_userConstraintArguments.m_parentFrame[5] = con->parentframe().orientation().z(); + clientCmd.m_userConstraintArguments.m_parentFrame[6] = con->parentframe().orientation().w(); + + clientCmd.m_userConstraintArguments.m_jointAxis[0] = con->jointaxis().x(); + clientCmd.m_userConstraintArguments.m_jointAxis[1] = con->jointaxis().y(); + clientCmd.m_userConstraintArguments.m_jointAxis[2] = con->jointaxis().z(); + + + clientCmd.m_userConstraintArguments.m_childBodyIndex = con->childbodyindex(); + clientCmd.m_userConstraintArguments.m_childJointIndex = con->childjointindex(); + clientCmd.m_userConstraintArguments.m_parentBodyIndex = con->parentbodyindex(); + clientCmd.m_userConstraintArguments.m_parentJointIndex = con->parentjointindex(); + clientCmd.m_userConstraintArguments.m_jointType = con->jointtype(); + + if (clientCmd.m_updateFlags&USER_CONSTRAINT_CHANGE_MAX_FORCE) + { + clientCmd.m_userConstraintArguments.m_maxAppliedForce = con->maxappliedforce(); + } + if (clientCmd.m_updateFlags&USER_CONSTRAINT_CHANGE_GEAR_RATIO) + { + clientCmd.m_userConstraintArguments.m_gearRatio = con->gearratio(); + } + + if (clientCmd.m_updateFlags&USER_CONSTRAINT_CHANGE_GEAR_AUX_LINK) + { + clientCmd.m_userConstraintArguments.m_gearAuxLink = con->gearauxlink(); + } + if (clientCmd.m_updateFlags&USER_CONSTRAINT_CHANGE_RELATIVE_POSITION_TARGET) + { + clientCmd.m_userConstraintArguments.m_relativePositionTarget = con->relativepositiontarget(); + } + if (clientCmd.m_updateFlags&USER_CONSTRAINT_CHANGE_ERP) + { + clientCmd.m_userConstraintArguments.m_erp = con->erp(); + } + + break; + } + + case CMD_STEP_FORWARD_SIMULATION: + { + + cmdPtr = &cmd; + b3SharedMemoryCommandHandle commandHandle = (b3SharedMemoryCommandHandle)cmdPtr; + b3InitStepSimulationCommand2(commandHandle); + + break; + } + + case CMD_LOAD_URDF: + { + btAssert(grpcCommand.has_loadurdfcommand()); + if (grpcCommand.has_loadurdfcommand()) + { + const ::pybullet_grpc::LoadUrdfCommand& grpcCmd = grpcCommand.loadurdfcommand(); + + std::string fileName = grpcCmd.filename(); + 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.flags()) + { + b3LoadUrdfCommandSetFlags(commandHandle, grpcCmd.flags()); + } + + } + } + break; + } + + case CMD_INIT_POSE: + { + btAssert(grpcCommand.has_initposecommand()); + if (grpcCommand.has_initposecommand()) + { + cmdPtr = &cmd; + b3SharedMemoryCommandHandle commandHandle = (b3SharedMemoryCommandHandle)cmdPtr; + + const ::pybullet_grpc::InitPoseCommand& grpcCmd = grpcCommand.initposecommand(); + b3CreatePoseCommandInit2(commandHandle, grpcCmd.bodyuniqueid()); + cmd.m_updateFlags = grpcCmd.updateflags(); + double initialQ[MAX_DEGREE_OF_FREEDOM] = { 0 }; + double initialQdot[MAX_DEGREE_OF_FREEDOM] = { 0 }; + int hasInitialQ[MAX_DEGREE_OF_FREEDOM] = { 0 }; + int hasInitialQdot[MAX_DEGREE_OF_FREEDOM] = { 0 }; + + if (grpcCmd.initialstateq_size() == grpcCmd.hasinitialstateq_size()) + { + int numInitial = btMin(grpcCmd.initialstateq_size(), MAX_DEGREE_OF_FREEDOM); + for (int i = 0; i < numInitial; i++) + { + initialQ[i] = grpcCmd.initialstateq(i); + hasInitialQ[i] = grpcCmd.hasinitialstateq(i); + } + if (numInitial) + { + b3CreatePoseCommandSetQ(commandHandle, numInitial, initialQ, hasInitialQ); + } + } + else + { + printf("Error: if (grpcCmd.initialstateq_size() != grpcCmd.hasinitialstateq_size())\n"); + } + if (grpcCmd.initialstateqdot_size() == grpcCmd.hasinitialstateqdot_size()) + { + int numInitial = btMin(grpcCmd.initialstateqdot_size(), MAX_DEGREE_OF_FREEDOM); + for (int i = 0; i < numInitial; i++) + { + initialQdot[i] = grpcCmd.initialstateqdot(i); + hasInitialQdot[i] = grpcCmd.hasinitialstateqdot(i); + } + if (numInitial) + { + b3CreatePoseCommandSetQdots(commandHandle, numInitial, initialQdot, hasInitialQdot); + } + } + else + { + printf("Error: (grpcCmd.initialstateqdot_size() != grpcCmd.hasinitialstateqdot_size())\n"); + } + } + break; + } + + case CMD_REQUEST_ACTUAL_STATE: + { + btAssert(grpcCommand.has_requestactualstatecommand()); + if (grpcCommand.has_requestactualstatecommand()) + { + cmdPtr = &cmd; + b3SharedMemoryCommandHandle commandHandle = (b3SharedMemoryCommandHandle)cmdPtr; + const ::pybullet_grpc::RequestActualStateCommand& grpcCmd = grpcCommand.requestactualstatecommand(); + b3RequestActualStateCommandInit2(commandHandle, grpcCmd.bodyuniqueid()); + if (grpcCmd.computeforwardkinematics()) + { + b3RequestActualStateCommandComputeForwardKinematics(commandHandle, grpcCmd.computeforwardkinematics()); + } + if (grpcCmd.computelinkvelocities()) + { + b3RequestActualStateCommandComputeLinkVelocity(commandHandle, grpcCmd.computelinkvelocities()); + } + } + break; + } + + case CMD_SEND_DESIRED_STATE: + { + cmdPtr = &cmd; + b3SharedMemoryCommandHandle commandHandle = (b3SharedMemoryCommandHandle)cmdPtr; + + const ::pybullet_grpc::JointMotorControlCommand* motor = &grpcCommand.jointmotorcontrolcommand(); + b3JointControlCommandInit2Internal(commandHandle, motor->bodyuniqueid(), motor->controlmode()); + + + int maxQ = motor->hasdesiredstateflags_size(); + for (int q = 0; q < maxQ; q++) + { + if (motor->hasdesiredstateflags(q)&SIM_DESIRED_STATE_HAS_Q) + { + b3JointControlSetDesiredPosition(commandHandle, q, motor->desiredstateq(q)); + } + if (motor->hasdesiredstateflags(q)&SIM_DESIRED_STATE_HAS_QDOT) + { + b3JointControlSetDesiredVelocity(commandHandle, q, motor->desiredstateqdot(q)); + } + if (motor->hasdesiredstateflags(q)&SIM_DESIRED_STATE_HAS_KD) + { + b3JointControlSetKd(commandHandle, q, motor->kd(q)); + } + if (motor->hasdesiredstateflags(q)&SIM_DESIRED_STATE_HAS_KP) + { + b3JointControlSetKd(commandHandle, q, motor->kp(q)); + } + if (motor->hasdesiredstateflags(q)&SIM_DESIRED_STATE_HAS_MAX_FORCE) + { + b3JointControlSetMaximumForce(commandHandle, q, motor->desiredstateforcetorque(q)); + } + if (motor->hasdesiredstateflags(q)&SIM_DESIRED_STATE_HAS_RHS_CLAMP) + { + b3JointControlSetMaximumVelocity(commandHandle, q, motor->maxvelocity(q)); + } + } + + //b3JointControlCommandInit2Internal + break; + } + + case CMD_SEND_PHYSICS_SIMULATION_PARAMETERS: + { + cmdPtr = &cmd; + b3SharedMemoryCommandHandle commandHandle = (b3SharedMemoryCommandHandle)cmdPtr; + b3InitPhysicsParamCommand2(commandHandle); + + int updateFlags = grpcCommand.setphysicssimulationparameterscommand().updateflags(); + const ::pybullet_grpc::PhysicsSimulationParameters* params = &grpcCommand.setphysicssimulationparameterscommand().params(); + + if (updateFlags&SIM_PARAM_UPDATE_DELTA_TIME) + { + b3PhysicsParamSetTimeStep(commandHandle, params->deltatime()); + } + if (updateFlags&SIM_PARAM_UPDATE_GRAVITY) + { + const ::pybullet_grpc::vec3* grav = ¶ms->gravityacceleration(); + b3PhysicsParamSetGravity(commandHandle, grav->x(), grav->y(), grav->z()); + } + + if (updateFlags&SIM_PARAM_UPDATE_NUM_SOLVER_ITERATIONS) + { + b3PhysicsParamSetNumSolverIterations(commandHandle, params->numsolveriterations()); + } + if (updateFlags&SIM_PARAM_UPDATE_NUM_SIMULATION_SUB_STEPS) + { + b3PhysicsParamSetNumSubSteps(commandHandle, params->numsimulationsubsteps()); + } + + if (updateFlags&SIM_PARAM_UPDATE_REAL_TIME_SIMULATION) + { + b3PhysicsParamSetRealTimeSimulation(commandHandle, params->userealtimesimulation()); + } + if (updateFlags&SIM_PARAM_UPDATE_DEFAULT_CONTACT_ERP) + { + b3PhysicsParamSetDefaultContactERP(commandHandle, params->defaultcontacterp()); + } + if (updateFlags&SIM_PARAM_UPDATE_INTERNAL_SIMULATION_FLAGS) + { + b3PhysicsParamSetInternalSimFlags(commandHandle, params->internalsimflags()); + } + if (updateFlags&SIM_PARAM_UPDATE_USE_SPLIT_IMPULSE) + { + b3PhysicsParamSetUseSplitImpulse(commandHandle, params->usesplitimpulse()); + } + if (updateFlags&SIM_PARAM_UPDATE_SPLIT_IMPULSE_PENETRATION_THRESHOLD) + { + b3PhysicsParamSetSplitImpulsePenetrationThreshold(commandHandle, params->splitimpulsepenetrationthreshold()); + } + if (updateFlags&SIM_PARAM_UPDATE_COLLISION_FILTER_MODE) + { + b3PhysicsParamSetCollisionFilterMode(commandHandle, params->collisionfiltermode()); + } + if (updateFlags&SIM_PARAM_UPDATE_CONTACT_BREAKING_THRESHOLD) + { + b3PhysicsParamSetContactBreakingThreshold(commandHandle, params->contactbreakingthreshold()); + } + + if (updateFlags&SIM_PARAM_ENABLE_CONE_FRICTION) + { + b3PhysicsParamSetEnableConeFriction(commandHandle, params->enableconefriction()); + } + + if (updateFlags&SIM_PARAM_ENABLE_FILE_CACHING) + { + b3PhysicsParamSetEnableFileCaching(commandHandle, params->enablefilecaching()); + } + + if (updateFlags&SIM_PARAM_UPDATE_RESTITUTION_VELOCITY_THRESHOLD) + { + b3PhysicsParamSetRestitutionVelocityThreshold(commandHandle, params->restitutionvelocitythreshold()); + } + if (updateFlags&SIM_PARAM_UPDATE_DEFAULT_NON_CONTACT_ERP) + { + b3PhysicsParamSetDefaultNonContactERP(commandHandle, params->defaultnoncontacterp()); + } + if (updateFlags&SIM_PARAM_UPDATE_DEFAULT_FRICTION_ERP) + { + b3PhysicsParamSetDefaultFrictionERP(commandHandle, params->frictionerp()); + } + if (updateFlags&SIM_PARAM_UPDATE_DETERMINISTIC_OVERLAPPING_PAIRS) + { + b3PhysicsParameterSetDeterministicOverlappingPairs(commandHandle, params->deterministicoverlappingpairs()); + } + if (updateFlags&SIM_PARAM_UPDATE_CCD_ALLOWED_PENETRATION) + { + b3PhysicsParameterSetAllowedCcdPenetration(commandHandle, params->allowedccdpenetration()); + } + if (updateFlags&SIM_PARAM_UPDATE_JOINT_FEEDBACK_MODE) + { + b3PhysicsParameterSetJointFeedbackMode(commandHandle, params->jointfeedbackmode()); + } + if (updateFlags&SIM_PARAM_UPDATE_DEFAULT_GLOBAL_CFM) + { + b3PhysicsParamSetDefaultGlobalCFM(commandHandle, params->defaultglobalcfm()); + } + if (updateFlags&SIM_PARAM_UPDATE_DEFAULT_FRICTION_CFM) + { + b3PhysicsParamSetDefaultFrictionCFM(commandHandle, params->frictioncfm()); + } + if (updateFlags&SIM_PARAM_UPDATE_SOLVER_RESIDULAL_THRESHOLD) + { + b3PhysicsParamSetSolverResidualThreshold(commandHandle, params->solverresidualthreshold()); + } + if (updateFlags&SIM_PARAM_UPDATE_CONTACT_SLOP) + { + b3PhysicsParamSetContactSlop(commandHandle, params->contactslop()); + } + if (updateFlags&SIM_PARAM_ENABLE_SAT) + { + b3PhysicsParameterSetEnableSAT(commandHandle, params->enablesat()); + } + if (updateFlags&SIM_PARAM_CONSTRAINT_SOLVER_TYPE) + { + b3PhysicsParameterSetConstraintSolverType(commandHandle, params->constraintsolvertype()); + } + if (updateFlags&SIM_PARAM_CONSTRAINT_MIN_SOLVER_ISLAND_SIZE) + { + b3PhysicsParameterSetMinimumSolverIslandSize(commandHandle, params->minimumsolverislandsize()); + } + + + break; + } + + case CMD_REQUEST_BODY_INFO: + { + cmdPtr = &cmd; + b3SharedMemoryCommandHandle commandHandle = (b3SharedMemoryCommandHandle)cmdPtr; + cmd.m_sdfRequestInfoArgs.m_bodyUniqueId = grpcCommand.requestbodyinfocommand().bodyuniqueid(); + break; + } + + case CMD_REQUEST_PHYSICS_SIMULATION_PARAMETERS: + { + cmdPtr = &cmd; + break; + } + + case CMD_SYNC_BODY_INFO: + { + cmdPtr = &cmd; + b3SharedMemoryCommandHandle commandHandle = (b3SharedMemoryCommandHandle)cmdPtr; + break; + } + + case CMD_REQUEST_INTERNAL_DATA: + { + cmdPtr = &cmd; + b3SharedMemoryCommandHandle commandHandle = (b3SharedMemoryCommandHandle)cmdPtr; + break; + } + + case CMD_CONFIGURE_OPENGL_VISUALIZER: + { + btAssert(grpcCommand.has_configureopenglvisualizercommand()); + if (grpcCommand.has_configureopenglvisualizercommand()) + { + cmdPtr = &cmd; + b3SharedMemoryCommandHandle commandHandle = (b3SharedMemoryCommandHandle)cmdPtr; + const ::pybullet_grpc::ConfigureOpenGLVisualizerCommand& grpcCmd = grpcCommand.configureopenglvisualizercommand(); + + b3InitConfigureOpenGLVisualizer2(commandHandle); + cmd.m_updateFlags = grpcCmd.updateflags(); + cmd.m_configureOpenGLVisualizerArguments.m_cameraDistance = grpcCmd.cameradistance(); + cmd.m_configureOpenGLVisualizerArguments.m_cameraPitch = grpcCmd.camerapitch(); + cmd.m_configureOpenGLVisualizerArguments.m_cameraYaw = grpcCmd.camerayaw(); + cmd.m_configureOpenGLVisualizerArguments.m_cameraTargetPosition[0] = grpcCmd.cameratargetposition().x(); + cmd.m_configureOpenGLVisualizerArguments.m_cameraTargetPosition[1] = grpcCmd.cameratargetposition().y(); + cmd.m_configureOpenGLVisualizerArguments.m_cameraTargetPosition[2] = grpcCmd.cameratargetposition().z(); + cmd.m_configureOpenGLVisualizerArguments.m_setEnabled = grpcCmd.setenabled(); + cmd.m_configureOpenGLVisualizerArguments.m_setFlag = grpcCmd.setflag(); + } + break; + } + + + + case CMD_REQUEST_CAMERA_IMAGE_DATA: + { + cmdPtr = &cmd; + b3SharedMemoryCommandHandle commandHandle = (b3SharedMemoryCommandHandle)cmdPtr; + SharedMemoryCommand& clientCmd = cmd; + + const ::pybullet_grpc::RequestCameraImageCommand* cam = &grpcCommand.requestcameraimagecommand(); + + b3InitRequestCameraImage2(commandHandle); + clientCmd.m_updateFlags = cam->updateflags(); + clientCmd.m_requestPixelDataArguments.m_startPixelIndex = cam->startpixelindex(); + + if (clientCmd.m_updateFlags&REQUEST_PIXEL_ARGS_SET_PIXEL_WIDTH_HEIGHT) + { + clientCmd.m_requestPixelDataArguments.m_pixelWidth = cam->pixelwidth(); + clientCmd.m_requestPixelDataArguments.m_pixelHeight = cam->pixelheight(); + } + if (clientCmd.m_updateFlags&REQUEST_PIXEL_ARGS_SET_SPECULAR_COEFF) + { + clientCmd.m_requestPixelDataArguments.m_lightSpecularCoeff = cam->lightspecularcoeff(); + } + + if (clientCmd.m_updateFlags&REQUEST_PIXEL_ARGS_HAS_FLAGS) + { + clientCmd.m_requestPixelDataArguments.m_flags = cam->cameraflags(); + } + if (clientCmd.m_updateFlags&REQUEST_PIXEL_ARGS_SET_SHADOW) + { + clientCmd.m_requestPixelDataArguments.m_hasShadow = cam->hasshadow(); + } + if (clientCmd.m_updateFlags&REQUEST_PIXEL_ARGS_SET_AMBIENT_COEFF) + { + clientCmd.m_requestPixelDataArguments.m_lightAmbientCoeff = cam->lightambientcoeff(); + } + if (clientCmd.m_updateFlags&REQUEST_PIXEL_ARGS_SET_DIFFUSE_COEFF) + { + clientCmd.m_requestPixelDataArguments.m_lightDiffuseCoeff = cam->lightdiffusecoeff(); + } + if (clientCmd.m_updateFlags&REQUEST_PIXEL_ARGS_SET_LIGHT_DISTANCE) + { + clientCmd.m_requestPixelDataArguments.m_lightDistance = cam->lightdistance(); + } + + if (clientCmd.m_updateFlags&REQUEST_PIXEL_ARGS_SET_LIGHT_COLOR) + { + const ::pybullet_grpc::vec3* lightColor = &cam->lightcolor(); + clientCmd.m_requestPixelDataArguments.m_lightColor[0] = lightColor->x(); + clientCmd.m_requestPixelDataArguments.m_lightColor[1] = lightColor->y(); + clientCmd.m_requestPixelDataArguments.m_lightColor[2] = lightColor->z(); + } + if (clientCmd.m_updateFlags&REQUEST_PIXEL_ARGS_SET_LIGHT_DIRECTION) + { + const ::pybullet_grpc::vec3* lightDir = &cam->lightdirection(); + clientCmd.m_requestPixelDataArguments.m_lightDirection[0] = lightDir->x(); + clientCmd.m_requestPixelDataArguments.m_lightDirection[1] = lightDir->y(); + clientCmd.m_requestPixelDataArguments.m_lightDirection[2] = lightDir->z(); + } + + if (clientCmd.m_updateFlags&REQUEST_PIXEL_ARGS_HAS_CAMERA_MATRICES) + { + const ::pybullet_grpc::matrix4x4* projMat = &cam->projectionmatrix(); + const ::pybullet_grpc::matrix4x4* viewMat = &cam->viewmatrix(); + for (int i = 0; i < 16; i++) + { + clientCmd.m_requestPixelDataArguments.m_projectionMatrix[i] = projMat->elems(i); + clientCmd.m_requestPixelDataArguments.m_viewMatrix[i] = viewMat->elems(i); + } + } + + if (clientCmd.m_updateFlags&REQUEST_PIXEL_ARGS_HAS_PROJECTIVE_TEXTURE_MATRICES) + { + const ::pybullet_grpc::matrix4x4* projectiveProjMat = &cam->projectivetextureprojectionmatrix(); + const ::pybullet_grpc::matrix4x4* projectiveViewMat = &cam->projectivetextureviewmatrix(); + for (int i = 0; i < 16; i++) + { + clientCmd.m_requestPixelDataArguments.m_projectiveTextureProjectionMatrix[i] = projectiveProjMat->elems(i); + clientCmd.m_requestPixelDataArguments.m_projectiveTextureViewMatrix[i] = projectiveViewMat->elems(i); + } + } + + break; + } + +#ifdef ALLOW_GRPC_COMMAND_CONVERSION + + + + + + + + + case CMD_LOAD_SDF: + { + btAssert(grpcCommand.has_loadsdfcommand()); + if (grpcCommand.has_loadsdfcommand()) + { + const ::pybullet_grpc::LoadSdfCommand& grpcCmd = grpcCommand.loadsdfcommand(); + + std::string fileName = grpcCmd.filename(); + if (fileName.length()) + { + cmdPtr = &cmd; + b3SharedMemoryCommandHandle commandHandle = (b3SharedMemoryCommandHandle)cmdPtr; + b3LoadSdfCommandInit2(commandHandle, fileName.c_str()); + + + if (grpcCmd.hasUseMultiBody_case() == ::pybullet_grpc::LoadSdfCommand::HasUseMultiBodyCase::kUseMultiBody) + { + b3LoadSdfCommandSetUseMultiBody(commandHandle, grpcCmd.usemultibody()); + } + if (grpcCmd.hasGlobalScaling_case() == ::pybullet_grpc::LoadSdfCommand::HasGlobalScalingCase::kGlobalScaling) + { + b3LoadSdfCommandSetUseGlobalScaling(commandHandle, grpcCmd.globalscaling()); + } + } + } + break; + } + case CMD_LOAD_MJCF: + { + btAssert(grpcCommand.has_loadmjcfcommand()); + if (grpcCommand.has_loadmjcfcommand()) + { + const pybullet_grpc::LoadMjcfCommand& grpcCmd = grpcCommand.loadmjcfcommand(); + + std::string fileName = grpcCmd.filename(); + if (fileName.length()) + { + cmdPtr = &cmd; + b3SharedMemoryCommandHandle commandHandle = (b3SharedMemoryCommandHandle)cmdPtr; + b3LoadMJCFCommandInit2(commandHandle, fileName.c_str()); + + if (grpcCmd.flags()) + { + b3LoadMJCFCommandSetFlags(commandHandle, grpcCmd.flags()); + } + } + } + break; + + } + + case CMD_CHANGE_DYNAMICS_INFO: + { + btAssert(grpcCommand.has_changedynamicscommand()); + if (grpcCommand.has_changedynamicscommand()) + { + cmdPtr = &cmd; + b3SharedMemoryCommandHandle commandHandle = (b3SharedMemoryCommandHandle)cmdPtr; + const ::pybullet_grpc::ChangeDynamicsCommand& grpcCmd = grpcCommand.changedynamicscommand(); + int bodyUniqueId = grpcCmd.bodyuniqueid(); + int linkIndex = grpcCmd.linkindex(); + b3InitChangeDynamicsInfo2(commandHandle); + if (grpcCmd.hasMass_case() == ::pybullet_grpc::ChangeDynamicsCommand::HasMassCase::kMass) + { + b3ChangeDynamicsInfoSetMass(commandHandle, bodyUniqueId, linkIndex, grpcCmd.mass()); + } + if (grpcCmd.hasLateralFriction_case() == ::pybullet_grpc::ChangeDynamicsCommand::HasLateralFrictionCase::kLateralFriction) + { + b3ChangeDynamicsInfoSetLateralFriction(commandHandle, bodyUniqueId, linkIndex, grpcCmd.lateralfriction()); + } + if (grpcCmd.hasSpinningFriction_case() == ::pybullet_grpc::ChangeDynamicsCommand::HasSpinningFrictionCase::kSpinningFriction) + { + b3ChangeDynamicsInfoSetSpinningFriction(commandHandle, bodyUniqueId, linkIndex, grpcCmd.spinningfriction()); + } + if (grpcCmd.hasRollingFriction_case() == ::pybullet_grpc::ChangeDynamicsCommand::HasRollingFrictionCase::kRollingFriction) + { + b3ChangeDynamicsInfoSetRollingFriction(commandHandle, bodyUniqueId, linkIndex, grpcCmd.rollingfriction()); + } + + if (grpcCmd.hasRestitution_case() == ::pybullet_grpc::ChangeDynamicsCommand::HasRestitutionCase::kRestitution) + { + b3ChangeDynamicsInfoSetRestitution(commandHandle, bodyUniqueId, linkIndex, grpcCmd.restitution()); + } + if (grpcCmd.haslinearDamping_case() == ::pybullet_grpc::ChangeDynamicsCommand::HaslinearDampingCase::kLinearDamping) + { + b3ChangeDynamicsInfoSetLinearDamping(commandHandle, bodyUniqueId, grpcCmd.lineardamping()); + } + + if (grpcCmd.hasangularDamping_case() == ::pybullet_grpc::ChangeDynamicsCommand::HasangularDampingCase::kAngularDamping) + { + b3ChangeDynamicsInfoSetAngularDamping(commandHandle, bodyUniqueId, grpcCmd.angulardamping()); + } + + bool hasContactDamping = grpcCmd.hasContactDamping_case() == ::pybullet_grpc::ChangeDynamicsCommand::HasContactDampingCase::kContactDamping; + bool hasContactStiffness = grpcCmd.hasContactStiffness_case() == ::pybullet_grpc::ChangeDynamicsCommand::HasContactStiffnessCase::kContactStiffness; + if (hasContactDamping && hasContactStiffness) + { + b3ChangeDynamicsInfoSetContactStiffnessAndDamping(commandHandle, bodyUniqueId, linkIndex, grpcCmd.contactstiffness(), grpcCmd.contactdamping()); + } + if (grpcCmd.hasLocalInertiaDiagonal_case() == ::pybullet_grpc::ChangeDynamicsCommand::HasLocalInertiaDiagonalCase::kLocalInertiaDiagonal) + { + double localInertiaDiag[3] = { grpcCmd.localinertiadiagonal().x(), grpcCmd.localinertiadiagonal().y(), grpcCmd.localinertiadiagonal().z() }; + b3ChangeDynamicsInfoSetLocalInertiaDiagonal(commandHandle, bodyUniqueId, linkIndex, localInertiaDiag); + } + + if (grpcCmd.hasFrictionAnchor_case() == ::pybullet_grpc::ChangeDynamicsCommand::HasFrictionAnchorCase::kFrictionAnchor) + { + b3ChangeDynamicsInfoSetFrictionAnchor(commandHandle, bodyUniqueId, linkIndex, grpcCmd.frictionanchor()); + } + if (grpcCmd.hasccdSweptSphereRadius_case() == ::pybullet_grpc::ChangeDynamicsCommand::HasccdSweptSphereRadiusCase::kCcdSweptSphereRadius) + { + b3ChangeDynamicsInfoSetCcdSweptSphereRadius(commandHandle, bodyUniqueId, linkIndex, grpcCmd.ccdsweptsphereradius()); + } + + + if (grpcCmd.hasContactProcessingThreshold_case() == ::pybullet_grpc::ChangeDynamicsCommand::HasContactProcessingThresholdCase::kContactProcessingThreshold) + { + b3ChangeDynamicsInfoSetContactProcessingThreshold(commandHandle, bodyUniqueId, linkIndex, grpcCmd.contactprocessingthreshold()); + } + + if (grpcCmd.hasActivationState_case() == ::pybullet_grpc::ChangeDynamicsCommand::HasActivationStateCase::kActivationState) + { + b3ChangeDynamicsInfoSetActivationState(commandHandle, bodyUniqueId, grpcCmd.activationstate()); + } + + + } + break; + } + case CMD_GET_DYNAMICS_INFO: + { + btAssert(grpcCommand.has_getdynamicscommand()); + if (grpcCommand.has_getdynamicscommand()) + { + cmdPtr = &cmd; + b3SharedMemoryCommandHandle commandHandle = (b3SharedMemoryCommandHandle)cmdPtr; + const ::pybullet_grpc::GetDynamicsCommand& grpcCmd = grpcCommand.getdynamicscommand(); + b3GetDynamicsInfoCommandInit2(commandHandle, grpcCmd.bodyuniqueid(), grpcCmd.linkindex()); + } + break; + + } + + + + + +#endif //ALLOW_GRPC_COMMAND_CONVERSION + default: + { + printf("unknown convertGRPCToBulletCommand"); + assert(0); + } } } - if (grpcCommand.has_requestactualstatecommand()) - { - cmdPtr = &cmd; - b3SharedMemoryCommandHandle commandHandle = (b3SharedMemoryCommandHandle)cmdPtr; - const ::pybullet_grpc::RequestActualStateCommand& grpcCmd = grpcCommand.requestactualstatecommand(); - b3RequestActualStateCommandInit2(commandHandle, grpcCmd.bodyuniqueid()); - if (grpcCmd.computeforwardkinematics()) - { - b3RequestActualStateCommandComputeForwardKinematics(commandHandle, grpcCmd.computeforwardkinematics()); - } - if (grpcCmd.computelinkvelocities()) - { - b3RequestActualStateCommandComputeLinkVelocity(commandHandle, grpcCmd.computelinkvelocities()); - } - } - if (grpcCommand.has_stepsimulationcommand()) + if (0 == cmdPtr) { - cmdPtr = &cmd; - b3SharedMemoryCommandHandle commandHandle = (b3SharedMemoryCommandHandle)cmdPtr; - b3InitStepSimulationCommand2(commandHandle); + printf("Error converting convertGRPCToBulletCommand"); } + btAssert(cmdPtr); return cmdPtr; } +bool convertGRPCToStatus(const PyBulletStatus& grpcReply, SharedMemoryStatus& serverStatus, char* bufferServerToClient, int bufferSizeInBytes) +{ + bool converted = false; + + serverStatus.m_type = grpcReply.statustype(); + + int sz = grpcReply.binaryblob().size(); + if (sz > 0) + { + if (sz == 1) + { + + const char* data = grpcReply.binaryblob().Get(0).c_str(); + int numBytes = grpcReply.binaryblob().Get(0).size(); + printf("copied binary blob of %d bytes\n", numBytes); + memcpy(bufferServerToClient, data, numBytes); + serverStatus.m_numDataStreamBytes = numBytes; + } + else + { + printf("Ignore unexpected binary blobs\n"); + } + } +#ifdef ALLOW_GRPC_STATUS_CONVERSION + switch (grpcReply.statustype()) + { + + case CMD_ACTUAL_STATE_UPDATE_COMPLETED: + { + converted = true; + const ::pybullet_grpc::SendActualStateStatus* stat = &grpcReply.actualstatestatus(); + serverStatus.m_sendActualStateArgs.m_bodyUniqueId = stat->bodyuniqueid(); + int numLinks = stat->numlinks(); + serverStatus.m_sendActualStateArgs.m_numLinks = numLinks; + + int numDegreeOfFreedomQ = stat->numdegreeoffreedomq(); + int numDegreeOfFreedomU = stat->numdegreeoffreedomu(); + serverStatus.m_sendActualStateArgs.m_numDegreeOfFreedomQ = numDegreeOfFreedomQ; + serverStatus.m_sendActualStateArgs.m_numDegreeOfFreedomU = numDegreeOfFreedomU; + + for (int i = 0; i < numDegreeOfFreedomQ; i++) + { + serverStatus.m_sendActualStateArgs.m_actualStateQ[i] = stat->actualstateq(i); + } + for (int i = 0; i < numDegreeOfFreedomU; i++) + { + serverStatus.m_sendActualStateArgs.m_actualStateQdot[i] = stat->actualstateqdot(i); + } + for (int i = 0; i < 7; i++) + { + serverStatus.m_sendActualStateArgs.m_rootLocalInertialFrame[i] = stat->rootlocalinertialframe(i); + } + for (int i = 0; i < numLinks * 6; i++) + { + serverStatus.m_sendActualStateArgs.m_linkLocalInertialFrames[i] = stat->linklocalinertialframes(i); + } + for (int i = 0; i < numLinks * 6; i++) + { + serverStatus.m_sendActualStateArgs.m_jointReactionForces[i] = stat->jointreactionforces(i); + } + for (int i = 0; i < numLinks; i++) + { + serverStatus.m_sendActualStateArgs.m_jointMotorForce[i] = stat->jointmotorforce(i); + } + for (int i = 0; i < numLinks * 7; i++) + { + serverStatus.m_sendActualStateArgs.m_linkState[i] = stat->linkstate(i); + } + for (int i = 0; i < numLinks * 6; i++) + { + serverStatus.m_sendActualStateArgs.m_linkWorldVelocities[i] = stat->linkworldvelocities(i); + } + + break; + } + + case CMD_REQUEST_KEYBOARD_EVENTS_DATA_COMPLETED: + { + converted = true; + const ::pybullet_grpc::KeyboardEventsStatus* keys = &grpcReply.keyboardeventsstatus(); + + serverStatus.m_sendKeyboardEvents.m_numKeyboardEvents = keys->keyboardevents_size(); + + for (int i = 0; i < serverStatus.m_sendKeyboardEvents.m_numKeyboardEvents; i++) + { + const ::pybullet_grpc::KeyboardEvent* key = &keys->keyboardevents(i); + serverStatus.m_sendKeyboardEvents.m_keyboardEvents[i].m_keyCode = key->keycode(); + serverStatus.m_sendKeyboardEvents.m_keyboardEvents[i].m_keyState = key->keystate(); + } + + break; + } + + case CMD_REQUEST_PHYSICS_SIMULATION_PARAMETERS_COMPLETED: + { + const ::pybullet_grpc::PhysicsSimulationParameters* params = &grpcReply.requestphysicssimulationparametersstatus(); + serverStatus.m_simulationParameterResultArgs.m_allowedCcdPenetration = params->allowedccdpenetration(); + serverStatus.m_simulationParameterResultArgs.m_collisionFilterMode = params->collisionfiltermode(); + serverStatus.m_simulationParameterResultArgs.m_constraintSolverType = params->constraintsolvertype(); + serverStatus.m_simulationParameterResultArgs.m_contactBreakingThreshold = params->contactbreakingthreshold(); + serverStatus.m_simulationParameterResultArgs.m_contactSlop = params->contactslop(); + serverStatus.m_simulationParameterResultArgs.m_defaultContactERP = params->defaultcontacterp(); + serverStatus.m_simulationParameterResultArgs.m_defaultGlobalCFM = params -> defaultglobalcfm(); + serverStatus.m_simulationParameterResultArgs.m_defaultNonContactERP = params->defaultnoncontacterp(); + serverStatus.m_simulationParameterResultArgs.m_deltaTime = params->deltatime(); + serverStatus.m_simulationParameterResultArgs.m_deterministicOverlappingPairs = params->deterministicoverlappingpairs(); + serverStatus.m_simulationParameterResultArgs.m_enableConeFriction = params->enableconefriction(); + serverStatus.m_simulationParameterResultArgs.m_enableFileCaching = params->enablefilecaching(); + serverStatus.m_simulationParameterResultArgs.m_enableSAT = params->enablesat(); + serverStatus.m_simulationParameterResultArgs.m_frictionCFM = params -> frictioncfm(); + serverStatus.m_simulationParameterResultArgs.m_frictionERP = params->frictionerp(); + serverStatus.m_simulationParameterResultArgs.m_gravityAcceleration[0] = params->gravityacceleration().x(); + serverStatus.m_simulationParameterResultArgs.m_gravityAcceleration[1] = params->gravityacceleration().y(); + serverStatus.m_simulationParameterResultArgs.m_gravityAcceleration[2] = params->gravityacceleration().z(); + serverStatus.m_simulationParameterResultArgs.m_internalSimFlags = params->internalsimflags(); + serverStatus.m_simulationParameterResultArgs.m_jointFeedbackMode = params->jointfeedbackmode(); + serverStatus.m_simulationParameterResultArgs.m_minimumSolverIslandSize = params->minimumsolverislandsize(); + serverStatus.m_simulationParameterResultArgs.m_numSimulationSubSteps = params->numsimulationsubsteps(); + serverStatus.m_simulationParameterResultArgs.m_numSolverIterations = params->numsolveriterations(); + serverStatus.m_simulationParameterResultArgs.m_restitutionVelocityThreshold = params->restitutionvelocitythreshold(); + serverStatus.m_simulationParameterResultArgs.m_solverResidualThreshold = params->solverresidualthreshold(); + serverStatus.m_simulationParameterResultArgs.m_splitImpulsePenetrationThreshold = params->splitimpulsepenetrationthreshold(); + serverStatus.m_simulationParameterResultArgs.m_useRealTimeSimulation = params->userealtimesimulation(); + serverStatus.m_simulationParameterResultArgs.m_useSplitImpulse = params->usesplitimpulse(); + + converted = true; + break; + } + case CMD_BODY_INFO_COMPLETED: + { + converted = true; + serverStatus.m_dataStreamArguments.m_bodyUniqueId = grpcReply.requestbodyinfostatus().bodyuniqueid(); + serverStatus.m_dataStreamArguments.m_bodyName[0] = 0; + serverStatus.m_dataStreamArguments.m_bulletFileName[0] = 0; + if (grpcReply.requestbodyinfostatus().bodyname().length()) + { + strcpy(serverStatus.m_dataStreamArguments.m_bodyName, grpcReply.requestbodyinfostatus().bodyname().c_str()); + } + + break; + } + case CMD_SYNC_BODY_INFO_COMPLETED: + { + serverStatus.m_sdfLoadedArgs.m_numBodies = grpcReply.syncbodiesstatus().bodyuniqueids_size(); + for (int i = 0; i < serverStatus.m_sdfLoadedArgs.m_numBodies; i++) + { + serverStatus.m_sdfLoadedArgs.m_bodyUniqueIds[i] = grpcReply.syncbodiesstatus().bodyuniqueids(i); + } + serverStatus.m_sdfLoadedArgs.m_numUserConstraints = grpcReply.syncbodiesstatus().userconstraintuniqueids_size(); + for (int i = 0; i < serverStatus.m_sdfLoadedArgs.m_numUserConstraints; i++) + { + serverStatus.m_sdfLoadedArgs.m_userConstraintUniqueIds[i] = grpcReply.syncbodiesstatus().userconstraintuniqueids(i); + } + + converted = true; + break; + } + case CMD_CLIENT_COMMAND_COMPLETED: + { + converted = true; + break; + } + case CMD_REQUEST_INTERNAL_DATA_COMPLETED: + { + converted = true; + break; + } + + case CMD_URDF_LOADING_COMPLETED: + { + converted = true; + serverStatus.m_dataStreamArguments.m_bodyUniqueId = grpcReply.urdfstatus().bodyuniqueid(); + if (grpcReply.urdfstatus().bodyname().length()>0 && grpcReply.urdfstatus().bodyname().length()<(MAX_FILENAME_LENGTH-1)) + { + strcpy(serverStatus.m_dataStreamArguments.m_bodyName, grpcReply.urdfstatus().bodyname().c_str()); + } + else + { + serverStatus.m_dataStreamArguments.m_bodyName[0] = 0; + } + if (grpcReply.urdfstatus().filename().length() > 0 && grpcReply.urdfstatus().filename().length() < (MAX_FILENAME_LENGTH - 1)) + { + strcpy(serverStatus.m_dataStreamArguments.m_bulletFileName, grpcReply.urdfstatus().filename().c_str()); + } + else + { + serverStatus.m_dataStreamArguments.m_bulletFileName[0] = 0; + } + + + + break; + } + case CMD_DESIRED_STATE_RECEIVED_COMPLETED: + { + converted = true; + break; + } + case CMD_USER_CONSTRAINT_COMPLETED: + { + const ::pybullet_grpc::UserConstraintStatus* con = &grpcReply.userconstraintstatus(); + serverStatus.m_userConstraintResultArgs.m_userConstraintUniqueId=con->userconstraintuniqueid(); + serverStatus.m_userConstraintResultArgs.m_maxAppliedForce = con->maxappliedforce(); + converted = true; + break; + } + case CMD_STEP_FORWARD_SIMULATION_COMPLETED: + { + converted = true; + break; + } + case CMD_RESET_SIMULATION_COMPLETED: + { + converted = true; + break; + } + case CMD_CAMERA_IMAGE_COMPLETED: + { + converted = true; + const ::pybullet_grpc::RequestCameraImageStatus* cam = &grpcReply.requestcameraimagestatus(); + serverStatus.m_sendPixelDataArguments.m_imageWidth = cam->imagewidth(); + serverStatus.m_sendPixelDataArguments.m_imageHeight = cam->imageheight(); + serverStatus.m_sendPixelDataArguments.m_numPixelsCopied = cam->numpixelscopied(); + serverStatus.m_sendPixelDataArguments.m_numRemainingPixels = cam->numremainingpixels(); + serverStatus.m_sendPixelDataArguments.m_startingPixelIndex = cam->startingpixelindex(); + break; + } + default: + { +#endif //ALLOW_GRPC_STATUS_CONVERSION + if (grpcReply.unknownstatusbinaryblob_size() > 0) + { + if (grpcReply.unknownstatusbinaryblob_size() == 1) + { + printf("convertStatusToGRPC: slow fallback status (%d), slow fallback", grpcReply.statustype()); + + const char* data = grpcReply.unknownstatusbinaryblob().Get(0).c_str(); + int numBytes = grpcReply.unknownstatusbinaryblob().Get(0).size(); + + btAssert(sizeof(SharedMemoryStatus)== numBytes); + if (sizeof(SharedMemoryStatus) == numBytes) + { + memcpy(&serverStatus, data, numBytes); + } + printf("slow fallback on command type %d\n", serverStatus.m_type); + btAssert(grpcReply.statustype() == serverStatus.m_type); + converted = true; + } + else + { + printf("unexpected unknownstatusbinaryblob_size\n"); + } + } + else + { + printf("unknown status and no slow fallback in convertStatusToGRPC %d\n", grpcReply.statustype()); + } + +#ifdef ALLOW_GRPC_STATUS_CONVERSION + } + + }; +#endif //ALLOW_GRPC_STATUS_CONVERSION + return converted; +} + + bool convertStatusToGRPC(const SharedMemoryStatus& serverStatus, char* bufferServerToClient, int bufferSizeInBytes, PyBulletStatus& grpcReply) { bool converted = false; grpcReply.set_statustype(serverStatus.m_type); + if (serverStatus.m_numDataStreamBytes) + { + grpcReply.add_binaryblob(bufferServerToClient, serverStatus.m_numDataStreamBytes); + } + +#ifdef ALLOW_GRPC_STATUS_CONVERSION switch (serverStatus.m_type) { + case CMD_REQUEST_KEYBOARD_EVENTS_DATA_COMPLETED: + { + converted = true; + ::pybullet_grpc::KeyboardEventsStatus* keys = grpcReply.mutable_keyboardeventsstatus(); + + for (int i = 0; i < serverStatus.m_sendKeyboardEvents.m_numKeyboardEvents; i++) + { + ::pybullet_grpc::KeyboardEvent* key = keys->add_keyboardevents(); + key->set_keycode(serverStatus.m_sendKeyboardEvents.m_keyboardEvents[i].m_keyCode); + key->set_keystate(serverStatus.m_sendKeyboardEvents.m_keyboardEvents[i].m_keyState); + } + + break; + } + case CMD_REQUEST_PHYSICS_SIMULATION_PARAMETERS_COMPLETED: + { + ::pybullet_grpc::PhysicsSimulationParameters* params = grpcReply.mutable_requestphysicssimulationparametersstatus(); + params->set_allowedccdpenetration(serverStatus.m_simulationParameterResultArgs.m_allowedCcdPenetration); + params->set_collisionfiltermode(serverStatus.m_simulationParameterResultArgs.m_collisionFilterMode); + params->set_constraintsolvertype(serverStatus.m_simulationParameterResultArgs.m_constraintSolverType); + params->set_contactbreakingthreshold(serverStatus.m_simulationParameterResultArgs.m_contactBreakingThreshold); + params->set_contactslop(serverStatus.m_simulationParameterResultArgs.m_contactSlop); + params->set_defaultcontacterp(serverStatus.m_simulationParameterResultArgs.m_defaultContactERP); + params->set_defaultglobalcfm(serverStatus.m_simulationParameterResultArgs.m_defaultGlobalCFM); + params->set_defaultnoncontacterp(serverStatus.m_simulationParameterResultArgs.m_defaultNonContactERP); + params->set_deltatime(serverStatus.m_simulationParameterResultArgs.m_deltaTime); + params->set_deterministicoverlappingpairs(serverStatus.m_simulationParameterResultArgs.m_deterministicOverlappingPairs); + params->set_enableconefriction(serverStatus.m_simulationParameterResultArgs.m_enableConeFriction); + params->set_enablefilecaching(serverStatus.m_simulationParameterResultArgs.m_enableFileCaching); + params->set_enablesat(serverStatus.m_simulationParameterResultArgs.m_enableSAT); + params->set_frictioncfm(serverStatus.m_simulationParameterResultArgs.m_frictionCFM); + params->set_frictionerp(serverStatus.m_simulationParameterResultArgs.m_frictionERP); + ::pybullet_grpc::vec3* grav = params->mutable_gravityacceleration(); + grav->set_x(serverStatus.m_simulationParameterResultArgs.m_gravityAcceleration[0]); + grav->set_y(serverStatus.m_simulationParameterResultArgs.m_gravityAcceleration[1]); + grav->set_z(serverStatus.m_simulationParameterResultArgs.m_gravityAcceleration[2]); + params->set_internalsimflags(serverStatus.m_simulationParameterResultArgs.m_internalSimFlags); + params->set_jointfeedbackmode(serverStatus.m_simulationParameterResultArgs.m_jointFeedbackMode); + params->set_minimumsolverislandsize(serverStatus.m_simulationParameterResultArgs.m_minimumSolverIslandSize); + params->set_numsimulationsubsteps(serverStatus.m_simulationParameterResultArgs.m_numSimulationSubSteps); + params->set_numsolveriterations(serverStatus.m_simulationParameterResultArgs.m_numSolverIterations); + params->set_restitutionvelocitythreshold(serverStatus.m_simulationParameterResultArgs.m_restitutionVelocityThreshold); + params->set_solverresidualthreshold(serverStatus.m_simulationParameterResultArgs.m_solverResidualThreshold); + params->set_splitimpulsepenetrationthreshold(serverStatus.m_simulationParameterResultArgs.m_splitImpulsePenetrationThreshold); + params->set_userealtimesimulation(serverStatus.m_simulationParameterResultArgs.m_useRealTimeSimulation); + params->set_usesplitimpulse(serverStatus.m_simulationParameterResultArgs.m_useSplitImpulse); + + converted = true; + break; + } + case CMD_BODY_INFO_COMPLETED: + { + converted = true; + ::pybullet_grpc::RequestBodyInfoStatus* stat = grpcReply.mutable_requestbodyinfostatus(); + stat->set_bodyuniqueid(serverStatus.m_dataStreamArguments.m_bodyUniqueId); + stat->set_bodyname(serverStatus.m_dataStreamArguments.m_bodyName); + break; + } + case CMD_SYNC_BODY_INFO_COMPLETED: + { + ::pybullet_grpc::SyncBodiesStatus* stat = grpcReply.mutable_syncbodiesstatus(); + + for (int i = 0; i < serverStatus.m_sdfLoadedArgs.m_numBodies; i++) + { + stat->add_bodyuniqueids(serverStatus.m_sdfLoadedArgs.m_bodyUniqueIds[i]); + } + for (int i = 0; i < serverStatus.m_sdfLoadedArgs.m_numUserConstraints; i++) + { + stat->add_userconstraintuniqueids(serverStatus.m_sdfLoadedArgs.m_userConstraintUniqueIds[i]); + } + + converted = true; + break; + } + + case CMD_REQUEST_INTERNAL_DATA_COMPLETED: + { + converted = true; + break; + } case CMD_URDF_LOADING_COMPLETED: { + converted = true; ::pybullet_grpc::LoadUrdfStatus* stat = grpcReply.mutable_urdfstatus(); b3SharedMemoryStatusHandle statusHandle = (b3SharedMemoryStatusHandle)&serverStatus; int objectUniqueId = b3GetStatusBodyIndex(statusHandle); stat->set_bodyuniqueid(objectUniqueId); + break; } case CMD_SDF_LOADING_COMPLETED: { + converted = true; int bodyIndicesOut[MAX_SDF_BODIES]; ::pybullet_grpc::SdfLoadedStatus* stat = grpcReply.mutable_sdfstatus(); b3SharedMemoryStatusHandle statusHandle = (b3SharedMemoryStatusHandle)&serverStatus; @@ -295,6 +1646,7 @@ bool convertStatusToGRPC(const SharedMemoryStatus& serverStatus, char* bufferSer } case CMD_MJCF_LOADING_COMPLETED: { + converted = true; int bodyIndicesOut[MAX_SDF_BODIES]; ::pybullet_grpc::MjcfLoadedStatus* stat = grpcReply.mutable_mjcfstatus(); b3SharedMemoryStatusHandle statusHandle = (b3SharedMemoryStatusHandle)&serverStatus; @@ -311,6 +1663,7 @@ bool convertStatusToGRPC(const SharedMemoryStatus& serverStatus, char* bufferSer } case CMD_GET_DYNAMICS_INFO_COMPLETED: { + converted = true; b3DynamicsInfo info; b3SharedMemoryStatusHandle statusHandle = (b3SharedMemoryStatusHandle)&serverStatus; if (b3GetDynamicsInfo(statusHandle, &info)) @@ -344,6 +1697,7 @@ bool convertStatusToGRPC(const SharedMemoryStatus& serverStatus, char* bufferSer } case CMD_ACTUAL_STATE_UPDATE_COMPLETED: { + converted = true; b3SharedMemoryStatusHandle statusHandle = (b3SharedMemoryStatusHandle)&serverStatus; int bodyUniqueId; int numLinks; @@ -418,15 +1772,64 @@ bool convertStatusToGRPC(const SharedMemoryStatus& serverStatus, char* bufferSer } case CMD_CLIENT_COMMAND_COMPLETED: { + converted = true; //no action needed? break; } + case CMD_DESIRED_STATE_RECEIVED_COMPLETED: + { + converted = true; + break; + } + case CMD_USER_CONSTRAINT_COMPLETED: + { + ::pybullet_grpc::UserConstraintStatus* con = grpcReply.mutable_userconstraintstatus(); + con->set_userconstraintuniqueid(serverStatus.m_userConstraintResultArgs.m_userConstraintUniqueId); + con->set_maxappliedforce(serverStatus.m_userConstraintResultArgs.m_maxAppliedForce); + converted = true; + break; + } + case CMD_STEP_FORWARD_SIMULATION_COMPLETED: + { + converted = true; + break; + } + case CMD_RESET_SIMULATION_COMPLETED: + { + converted = true; + break; + } + case CMD_CAMERA_IMAGE_COMPLETED: + { + converted = true; + ::pybullet_grpc::RequestCameraImageStatus* cam = grpcReply.mutable_requestcameraimagestatus(); + cam->set_imagewidth(serverStatus.m_sendPixelDataArguments.m_imageWidth); + cam->set_imageheight(serverStatus.m_sendPixelDataArguments.m_imageHeight); + cam->set_numpixelscopied(serverStatus.m_sendPixelDataArguments.m_numPixelsCopied); + cam->set_numremainingpixels(serverStatus.m_sendPixelDataArguments.m_numRemainingPixels); + cam->set_startingpixelindex(serverStatus.m_sendPixelDataArguments.m_startingPixelIndex); + break; + } + /* + case CMD_USER_CONSTRAINT_INFO_COMPLETED: + { + } + case CMD_USER_CONSTRAINT_REQUEST_STATE_COMPLETED: + { + } + */ + default: { - printf("convertStatusToGRPC: unknown status"); +#endif //ALLOW_GRPC_STATUS_CONVERSION + printf("convertStatusToGRPC: unknown status (%d), slow fallback", serverStatus.m_type); + int sz = sizeof(SharedMemoryStatus); + grpcReply.add_unknownstatusbinaryblob((const char*)&serverStatus, sz); + converted = true; +#ifdef ALLOW_GRPC_STATUS_CONVERSION } } - +#endif //ALLOW_GRPC_STATUS_CONVERSION return converted; } diff --git a/examples/SharedMemory/grpc/ConvertGRPCBullet.h b/examples/SharedMemory/grpc/ConvertGRPCBullet.h index 530c462b2..871c783fb 100644 --- a/examples/SharedMemory/grpc/ConvertGRPCBullet.h +++ b/examples/SharedMemory/grpc/ConvertGRPCBullet.h @@ -10,7 +10,11 @@ namespace pybullet_grpc class PyBulletStatus; }; -struct SharedMemoryCommand* convertGRPCAndSubmitCommand(pybullet_grpc::PyBulletCommand& grpcCommand, struct SharedMemoryCommand& cmd); +struct SharedMemoryCommand* convertGRPCToBulletCommand(const pybullet_grpc::PyBulletCommand& grpcCommand, struct SharedMemoryCommand& cmd); + +pybullet_grpc::PyBulletCommand* convertBulletToGRPCCommand(const struct SharedMemoryCommand& clientCmd, pybullet_grpc::PyBulletCommand& grpcCommand); + +bool convertGRPCToStatus(const pybullet_grpc::PyBulletStatus& grpcReply, struct SharedMemoryStatus& serverStatus, char* bufferServerToClient, int bufferSizeInBytes); bool convertStatusToGRPC(const struct SharedMemoryStatus& serverStatus, char* bufferServerToClient, int bufferSizeInBytes, pybullet_grpc::PyBulletStatus& grpcReply); diff --git a/examples/SharedMemory/grpc/main.cpp b/examples/SharedMemory/grpc/main.cpp index 751ef4373..8717238c7 100644 --- a/examples/SharedMemory/grpc/main.cpp +++ b/examples/SharedMemory/grpc/main.cpp @@ -53,12 +53,12 @@ public: } - void Run(MyCommandProcessor* comProc) { - std::string server_address("0.0.0.0:50051"); + void Run(MyCommandProcessor* comProc, const std::string& hostNamePort) { + ServerBuilder builder; // Listen on the given address without any authentication mechanism. - builder.AddListeningPort(server_address, grpc::InsecureServerCredentials()); + builder.AddListeningPort(hostNamePort, 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_); @@ -67,7 +67,7 @@ public: cq_ = builder.AddCompletionQueue(); // Finally assemble the server. server_ = builder.BuildAndStart(); - std::cout << "Server listening on " << server_address << std::endl; + std::cout << "Server listening on " << hostNamePort << std::endl; // Proceed to the server's main loop. HandleRpcs(comProc); @@ -121,41 +121,49 @@ private: m_status.set_statustype(CMD_UNKNOWN_COMMAND_FLUSHED); - cmdPtr = convertGRPCAndSubmitCommand(m_command, cmd); - - - if (cmdPtr) + + if (m_command.has_checkversioncommand()) { - bool hasStatus = m_comProc->processCommand(*cmdPtr, serverStatus, &buffer[0], buffer.size()); - double timeOutInSeconds = 10; - b3Clock clock; - double startTimeSeconds = clock.getTimeInSeconds(); - double curTimeSeconds = clock.getTimeInSeconds(); + m_status.set_statustype(CMD_CLIENT_COMMAND_COMPLETED); + m_status.mutable_checkversionstatus()->set_serverversion(SHARED_MEMORY_MAGIC_NUMBER); + } + else + { + cmdPtr = convertGRPCToBulletCommand(m_command, cmd); - while ((!hasStatus) && ((curTimeSeconds - startTimeSeconds) receiveStatus(serverStatus, &buffer[0], buffer.size()); - curTimeSeconds = clock.getTimeInSeconds(); + bool hasStatus = m_comProc->processCommand(*cmdPtr, serverStatus, &buffer[0], buffer.size()); + double timeOutInSeconds = 10; + b3Clock clock; + double startTimeSeconds = clock.getTimeInSeconds(); + double curTimeSeconds = clock.getTimeInSeconds(); + + while ((!hasStatus) && ((curTimeSeconds - startTimeSeconds) < timeOutInSeconds)) + { + hasStatus = m_comProc->receiveStatus(serverStatus, &buffer[0], buffer.size()); + curTimeSeconds = clock.getTimeInSeconds(); + } + if (gVerboseNetworkMessagesServer) + { + //printf("buffer.size = %d\n", buffer.size()); + printf("serverStatus.m_numDataStreamBytes = %d\n", serverStatus.m_numDataStreamBytes); + } + if (hasStatus) + { + b3AlignedObjectArray packetData; + unsigned char* statBytes = (unsigned char*)&serverStatus; + + convertStatusToGRPC(serverStatus, &buffer[0], buffer.size(), m_status); + } } - if (gVerboseNetworkMessagesServer) + + if (m_command.has_terminateservercommand()) { - //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); + status_ = TERMINATE; } } - - 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 @@ -245,6 +253,8 @@ int main(int argc, char** argv) int port = 6667; parseArgs.GetCmdLineArgument("port", port); + std::string hostName = "localhost"; + std::string hostNamePort = hostName + ":" + std::to_string(port); gVerboseNetworkMessagesServer = parseArgs.CheckCmdLineFlag("verbose"); @@ -263,7 +273,7 @@ int main(int argc, char** argv) { ServerImpl server; - server.Run(sm); + server.Run(sm, hostNamePort); } else { diff --git a/examples/SharedMemory/grpc/proto/pybullet.proto b/examples/SharedMemory/grpc/proto/pybullet.proto index cdedcfca0..9c9b6aebc 100644 --- a/examples/SharedMemory/grpc/proto/pybullet.proto +++ b/examples/SharedMemory/grpc/proto/pybullet.proto @@ -24,6 +24,7 @@ message vec3 double z=3; }; + message quat4 { double x=1; @@ -32,6 +33,38 @@ message quat4 double w=4; }; +message vec4 +{ + double x=1; + double y=2; + double z=3; + double w=4; +}; + + +message transform +{ + vec3 origin=1; + quat4 orientation=2; +}; + +message matrix4x4 +{ + //assume 16 elements, with translation in 12,13,14, + //'right' vector is elements 0,1,3 and 4 + repeated double elems=1; +}; + +message CheckVersionCommand +{ + int32 clientVersion=1; +}; + +message CheckVersionStatus +{ + int32 serverVersion=1; +}; + message TerminateServerCommand { @@ -42,6 +75,31 @@ message StepSimulationCommand { }; +message SyncBodiesCommand +{ + +}; + +message SyncBodiesStatus +{ + repeated int32 bodyUniqueIds=1; + repeated int32 userConstraintUniqueIds=2; +}; + + +message RequestBodyInfoCommand +{ + int32 bodyUniqueId=1; +}; + +message RequestBodyInfoStatus +{ + int32 bodyUniqueId=1; + string bodyName=2; +}; + + + message LoadUrdfCommand { string fileName=1; vec3 initialPosition=2; @@ -54,8 +112,11 @@ message LoadUrdfCommand { oneof hasGlobalScaling { double globalScaling=7; } }; + message LoadUrdfStatus { int32 bodyUniqueId=1; + string bodyName=2; + string fileName=3; } @@ -133,10 +194,11 @@ message GetDynamicsStatus message InitPoseCommand { int32 bodyUniqueId=1; - repeated int32 hasInitialStateQ=2; - repeated double initialStateQ=3; - repeated int32 hasInitialStateQdot=4; - repeated double initialStateQdot=5; + int32 updateflags=2; + repeated int32 hasInitialStateQ=3; + repeated double initialStateQ=4; + repeated int32 hasInitialStateQdot=5; + repeated double initialStateQdot=6; }; @@ -147,6 +209,7 @@ message RequestActualStateCommand bool computeLinkVelocities=3; }; + message SendActualStateStatus { int32 bodyUniqueId=1; @@ -171,37 +234,230 @@ message SendActualStateStatus }; +message ConfigureOpenGLVisualizerCommand +{ + int32 updateFlags=1; + + double cameraDistance=2; + double cameraPitch=3; + double cameraYaw=4; + vec3 cameraTargetPosition=5; + + int32 setFlag=6; + int32 setEnabled=7; +}; + + +message PhysicsSimulationParameters +{ + double deltaTime=1; + vec3 gravityAcceleration=2; + int32 numSimulationSubSteps=3; + int32 numSolverIterations=4; + int32 useRealTimeSimulation=5; + int32 useSplitImpulse=6; + double splitImpulsePenetrationThreshold=7; + double contactBreakingThreshold=8; + int32 internalSimFlags=9; + double defaultContactERP=10; + int32 collisionFilterMode=11; + int32 enableFileCaching=12; + double restitutionVelocityThreshold=13; + double defaultNonContactERP=14; + double frictionERP=15; + double defaultGlobalCFM=16; + double frictionCFM=17; + int32 enableConeFriction=18; + int32 deterministicOverlappingPairs=19; + double allowedCcdPenetration=20; + int32 jointFeedbackMode=21; + double solverResidualThreshold=22; + double contactSlop=23; + int32 enableSAT=24; + int32 constraintSolverType=25; + int32 minimumSolverIslandSize=26; +}; + + +message PhysicsSimulationParametersCommand +{ + int32 updateFlags=1; + PhysicsSimulationParameters params=2; +}; + + + +message JointMotorControlCommand +{ + int32 bodyUniqueId=1; + int32 controlMode=2; + int32 updateFlags=3; + + //PD parameters in case controlMode == CONTROL_MODE_POSITION_VELOCITY_PD + repeated double Kp=4;//indexed by degree of freedom, 6 for base, and then the dofs for each link + repeated double Kd=5;//indexed by degree of freedom, 6 for base, and then the dofs for each link + repeated double maxVelocity=6; + + repeated int32 hasDesiredStateFlags=7; + + //desired state is only written by the client, read-only access by server is expected + + //desiredStateQ is indexed by position variables, + //starting with 3 base position variables, 4 base orientation variables (quaternion), then link position variables + repeated double desiredStateQ=8; + + //desiredStateQdot is index by velocity degrees of freedom, 3 linear and 3 angular variables for the base and then link velocity variables + repeated double desiredStateQdot=9; + + //desiredStateForceTorque is either the actual applied force/torque (in CONTROL_MODE_TORQUE) or + //or the maximum applied force/torque for the PD/motor/constraint to reach the desired velocity in CONTROL_MODE_VELOCITY and CONTROL_MODE_POSITION_VELOCITY_PD mode + //indexed by degree of freedom, 6 dof base, and then dofs for each link + repeated double desiredStateForceTorque=10; +}; + + +message UserConstraintCommand +{ + int32 parentBodyIndex=1; + int32 parentJointIndex=2; + int32 childBodyIndex=3; + int32 childJointIndex=4; + transform parentFrame=5; + transform childFrame=6; + vec3 jointAxis=7; + int32 jointType=8; + double maxAppliedForce=9; + int32 userConstraintUniqueId=10; + double gearRatio=11; + int32 gearAuxLink=12; + double relativePositionTarget=13; + double erp=14; + int32 updateFlags=15; +}; + +message UserConstraintStatus +{ + double maxAppliedForce=9; + int32 userConstraintUniqueId=10; +}; + +message UserConstraintStateStatus +{ + vec3 appliedConstraintForcesLinear=1; + vec3 appliedConstraintForcesAngular=2; + int32 numDofs=3; +}; + + +message RequestKeyboardEventsCommand +{ + +}; + +message KeyboardEvent +{ + int32 keyCode=1;//ascii + int32 keyState=2;// see b3VRButtonInfo +}; + + +message KeyboardEventsStatus +{ + repeated KeyboardEvent keyboardEvents=1; +}; + + +message RequestCameraImageCommand +{ + int32 updateFlags=1; + int32 cameraFlags=2; + matrix4x4 viewMatrix=3; + matrix4x4 projectionMatrix=4; + int32 startPixelIndex=5; + int32 pixelWidth=6; + int32 pixelHeight=7; + vec3 lightDirection=8; + vec3 lightColor=9; + double lightDistance=10; + double lightAmbientCoeff=11; + double lightDiffuseCoeff=12; + double lightSpecularCoeff=13; + int32 hasShadow=14; + matrix4x4 projectiveTextureViewMatrix=15; + matrix4x4 projectiveTextureProjectionMatrix=16; +}; + +message RequestCameraImageStatus +{ + int32 imageWidth=1; + int32 imageHeight=2; + + int32 startingPixelIndex=3; + int32 numPixelsCopied=4; + int32 numRemainingPixels=5; +}; + // The request message containing the command message PyBulletCommand { int32 commandType=1; + repeated bytes binaryBlob=2; + + repeated bytes unknownCommandBinaryBlob=3; + oneof commands { - LoadUrdfCommand loadUrdfCommand = 3; - TerminateServerCommand terminateServerCommand=4; - StepSimulationCommand stepSimulationCommand= 5; - LoadSdfCommand loadSdfCommand=6; - LoadMjcfCommand loadMjcfCommand=7; - ChangeDynamicsCommand changeDynamicsCommand=8; - GetDynamicsCommand getDynamicsCommand=9; - InitPoseCommand initPoseCommand=10; - RequestActualStateCommand requestActualStateCommand=11; + + LoadUrdfCommand loadUrdfCommand = 4; + TerminateServerCommand terminateServerCommand=5; + StepSimulationCommand stepSimulationCommand= 6; + LoadSdfCommand loadSdfCommand=7; + LoadMjcfCommand loadMjcfCommand=8; + ChangeDynamicsCommand changeDynamicsCommand=9; + GetDynamicsCommand getDynamicsCommand=10; + InitPoseCommand initPoseCommand=11; + RequestActualStateCommand requestActualStateCommand=12; + ConfigureOpenGLVisualizerCommand configureOpenGLVisualizerCommand =13; + SyncBodiesCommand syncBodiesCommand=14; + RequestBodyInfoCommand requestBodyInfoCommand=15; + PhysicsSimulationParametersCommand setPhysicsSimulationParametersCommand=16; + JointMotorControlCommand jointMotorControlCommand=17; + UserConstraintCommand userConstraintCommand=18; + CheckVersionCommand checkVersionCommand=19; + RequestKeyboardEventsCommand requestKeyboardEventsCommand=20; + RequestCameraImageCommand requestCameraImageCommand=21; } + } // The response message containing the status message PyBulletStatus { int32 statusType=1; + repeated bytes binaryBlob=2; + + repeated bytes unknownStatusBinaryBlob=3; + oneof status { - LoadUrdfStatus urdfStatus = 2; - SdfLoadedStatus sdfStatus = 3; - MjcfLoadedStatus mjcfStatus = 4; - GetDynamicsStatus getDynamicsStatus = 5; - SendActualStateStatus actualStateStatus = 6; + + LoadUrdfStatus urdfStatus = 4; + SdfLoadedStatus sdfStatus = 5; + MjcfLoadedStatus mjcfStatus = 6; + GetDynamicsStatus getDynamicsStatus = 7; + SendActualStateStatus actualStateStatus = 8; + SyncBodiesStatus syncBodiesStatus=9; + RequestBodyInfoStatus requestBodyInfoStatus = 10; + PhysicsSimulationParameters requestPhysicsSimulationParametersStatus=11; + CheckVersionStatus checkVersionStatus=12; + UserConstraintStatus userConstraintStatus=13; + UserConstraintStateStatus userConstraintStateStatus=14; + KeyboardEventsStatus keyboardEventsStatus=15; + RequestCameraImageStatus requestCameraImageStatus=16; } + + } diff --git a/examples/SharedMemory/grpc/pybullet.pb.cpp b/examples/SharedMemory/grpc/pybullet.pb.cpp index 5a3df827a..ee70a400b 100644 --- a/examples/SharedMemory/grpc/pybullet.pb.cpp +++ b/examples/SharedMemory/grpc/pybullet.pb.cpp @@ -22,10 +22,28 @@ class vec3DefaultTypeInternal : public ::google::protobuf::internal::ExplicitlyC } _vec3_default_instance_; class quat4DefaultTypeInternal : public ::google::protobuf::internal::ExplicitlyConstructed { } _quat4_default_instance_; +class vec4DefaultTypeInternal : public ::google::protobuf::internal::ExplicitlyConstructed { +} _vec4_default_instance_; +class transformDefaultTypeInternal : public ::google::protobuf::internal::ExplicitlyConstructed { +} _transform_default_instance_; +class matrix4x4DefaultTypeInternal : public ::google::protobuf::internal::ExplicitlyConstructed { +} _matrix4x4_default_instance_; +class CheckVersionCommandDefaultTypeInternal : public ::google::protobuf::internal::ExplicitlyConstructed { +} _CheckVersionCommand_default_instance_; +class CheckVersionStatusDefaultTypeInternal : public ::google::protobuf::internal::ExplicitlyConstructed { +} _CheckVersionStatus_default_instance_; class TerminateServerCommandDefaultTypeInternal : public ::google::protobuf::internal::ExplicitlyConstructed { } _TerminateServerCommand_default_instance_; class StepSimulationCommandDefaultTypeInternal : public ::google::protobuf::internal::ExplicitlyConstructed { } _StepSimulationCommand_default_instance_; +class SyncBodiesCommandDefaultTypeInternal : public ::google::protobuf::internal::ExplicitlyConstructed { +} _SyncBodiesCommand_default_instance_; +class SyncBodiesStatusDefaultTypeInternal : public ::google::protobuf::internal::ExplicitlyConstructed { +} _SyncBodiesStatus_default_instance_; +class RequestBodyInfoCommandDefaultTypeInternal : public ::google::protobuf::internal::ExplicitlyConstructed { +} _RequestBodyInfoCommand_default_instance_; +class RequestBodyInfoStatusDefaultTypeInternal : public ::google::protobuf::internal::ExplicitlyConstructed { +} _RequestBodyInfoStatus_default_instance_; class LoadUrdfCommandDefaultTypeInternal : public ::google::protobuf::internal::ExplicitlyConstructed { public: ::google::protobuf::int32 usemultibody_; @@ -72,6 +90,30 @@ class RequestActualStateCommandDefaultTypeInternal : public ::google::protobuf:: } _RequestActualStateCommand_default_instance_; class SendActualStateStatusDefaultTypeInternal : public ::google::protobuf::internal::ExplicitlyConstructed { } _SendActualStateStatus_default_instance_; +class ConfigureOpenGLVisualizerCommandDefaultTypeInternal : public ::google::protobuf::internal::ExplicitlyConstructed { +} _ConfigureOpenGLVisualizerCommand_default_instance_; +class PhysicsSimulationParametersDefaultTypeInternal : public ::google::protobuf::internal::ExplicitlyConstructed { +} _PhysicsSimulationParameters_default_instance_; +class PhysicsSimulationParametersCommandDefaultTypeInternal : public ::google::protobuf::internal::ExplicitlyConstructed { +} _PhysicsSimulationParametersCommand_default_instance_; +class JointMotorControlCommandDefaultTypeInternal : public ::google::protobuf::internal::ExplicitlyConstructed { +} _JointMotorControlCommand_default_instance_; +class UserConstraintCommandDefaultTypeInternal : public ::google::protobuf::internal::ExplicitlyConstructed { +} _UserConstraintCommand_default_instance_; +class UserConstraintStatusDefaultTypeInternal : public ::google::protobuf::internal::ExplicitlyConstructed { +} _UserConstraintStatus_default_instance_; +class UserConstraintStateStatusDefaultTypeInternal : public ::google::protobuf::internal::ExplicitlyConstructed { +} _UserConstraintStateStatus_default_instance_; +class RequestKeyboardEventsCommandDefaultTypeInternal : public ::google::protobuf::internal::ExplicitlyConstructed { +} _RequestKeyboardEventsCommand_default_instance_; +class KeyboardEventDefaultTypeInternal : public ::google::protobuf::internal::ExplicitlyConstructed { +} _KeyboardEvent_default_instance_; +class KeyboardEventsStatusDefaultTypeInternal : public ::google::protobuf::internal::ExplicitlyConstructed { +} _KeyboardEventsStatus_default_instance_; +class RequestCameraImageCommandDefaultTypeInternal : public ::google::protobuf::internal::ExplicitlyConstructed { +} _RequestCameraImageCommand_default_instance_; +class RequestCameraImageStatusDefaultTypeInternal : public ::google::protobuf::internal::ExplicitlyConstructed { +} _RequestCameraImageStatus_default_instance_; class PyBulletCommandDefaultTypeInternal : public ::google::protobuf::internal::ExplicitlyConstructed { public: const ::pybullet_grpc::LoadUrdfCommand* loadurdfcommand_; @@ -83,6 +125,15 @@ class PyBulletCommandDefaultTypeInternal : public ::google::protobuf::internal:: const ::pybullet_grpc::GetDynamicsCommand* getdynamicscommand_; const ::pybullet_grpc::InitPoseCommand* initposecommand_; const ::pybullet_grpc::RequestActualStateCommand* requestactualstatecommand_; + const ::pybullet_grpc::ConfigureOpenGLVisualizerCommand* configureopenglvisualizercommand_; + const ::pybullet_grpc::SyncBodiesCommand* syncbodiescommand_; + const ::pybullet_grpc::RequestBodyInfoCommand* requestbodyinfocommand_; + const ::pybullet_grpc::PhysicsSimulationParametersCommand* setphysicssimulationparameterscommand_; + const ::pybullet_grpc::JointMotorControlCommand* jointmotorcontrolcommand_; + const ::pybullet_grpc::UserConstraintCommand* userconstraintcommand_; + const ::pybullet_grpc::CheckVersionCommand* checkversioncommand_; + const ::pybullet_grpc::RequestKeyboardEventsCommand* requestkeyboardeventscommand_; + const ::pybullet_grpc::RequestCameraImageCommand* requestcameraimagecommand_; } _PyBulletCommand_default_instance_; class PyBulletStatusDefaultTypeInternal : public ::google::protobuf::internal::ExplicitlyConstructed { public: @@ -91,6 +142,14 @@ class PyBulletStatusDefaultTypeInternal : public ::google::protobuf::internal::E const ::pybullet_grpc::MjcfLoadedStatus* mjcfstatus_; const ::pybullet_grpc::GetDynamicsStatus* getdynamicsstatus_; const ::pybullet_grpc::SendActualStateStatus* actualstatestatus_; + const ::pybullet_grpc::SyncBodiesStatus* syncbodiesstatus_; + const ::pybullet_grpc::RequestBodyInfoStatus* requestbodyinfostatus_; + const ::pybullet_grpc::PhysicsSimulationParameters* requestphysicssimulationparametersstatus_; + const ::pybullet_grpc::CheckVersionStatus* checkversionstatus_; + const ::pybullet_grpc::UserConstraintStatus* userconstraintstatus_; + const ::pybullet_grpc::UserConstraintStateStatus* userconstraintstatestatus_; + const ::pybullet_grpc::KeyboardEventsStatus* keyboardeventsstatus_; + const ::pybullet_grpc::RequestCameraImageStatus* requestcameraimagestatus_; } _PyBulletStatus_default_instance_; namespace protobuf_pybullet_2eproto { @@ -98,7 +157,7 @@ namespace protobuf_pybullet_2eproto { namespace { -::google::protobuf::Metadata file_level_metadata[18]; +::google::protobuf::Metadata file_level_metadata[39]; } // namespace @@ -119,6 +178,35 @@ const ::google::protobuf::uint32 TableStruct::offsets[] = { 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(vec4, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(vec4, x_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(vec4, y_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(vec4, z_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(vec4, w_), + ~0u, // no _has_bits_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(transform, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(transform, origin_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(transform, orientation_), + ~0u, // no _has_bits_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(matrix4x4, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(matrix4x4, elems_), + ~0u, // no _has_bits_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(CheckVersionCommand, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(CheckVersionCommand, clientversion_), + ~0u, // no _has_bits_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(CheckVersionStatus, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(CheckVersionStatus, serverversion_), + ~0u, // no _has_bits_ GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(TerminateServerCommand, _internal_metadata_), ~0u, // no _extensions_ ~0u, // no _oneof_case_ @@ -128,6 +216,27 @@ const ::google::protobuf::uint32 TableStruct::offsets[] = { ~0u, // no _extensions_ ~0u, // no _oneof_case_ ~0u, // no _has_bits_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(SyncBodiesCommand, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + ~0u, // no _has_bits_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(SyncBodiesStatus, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(SyncBodiesStatus, bodyuniqueids_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(SyncBodiesStatus, userconstraintuniqueids_), + ~0u, // no _has_bits_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(RequestBodyInfoCommand, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(RequestBodyInfoCommand, bodyuniqueid_), + ~0u, // no _has_bits_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(RequestBodyInfoStatus, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(RequestBodyInfoStatus, bodyuniqueid_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(RequestBodyInfoStatus, bodyname_), + ~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]), @@ -146,6 +255,8 @@ const ::google::protobuf::uint32 TableStruct::offsets[] = { ~0u, // no _extensions_ ~0u, // no _oneof_case_ GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(LoadUrdfStatus, bodyuniqueid_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(LoadUrdfStatus, bodyname_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(LoadUrdfStatus, filename_), ~0u, // no _has_bits_ GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(LoadSdfCommand, _internal_metadata_), ~0u, // no _extensions_ @@ -234,6 +345,7 @@ const ::google::protobuf::uint32 TableStruct::offsets[] = { ~0u, // no _extensions_ ~0u, // no _oneof_case_ GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(InitPoseCommand, bodyuniqueid_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(InitPoseCommand, updateflags_), GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(InitPoseCommand, hasinitialstateq_), GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(InitPoseCommand, initialstateq_), GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(InitPoseCommand, hasinitialstateqdot_), @@ -262,10 +374,149 @@ const ::google::protobuf::uint32 TableStruct::offsets[] = { GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(SendActualStateStatus, linkworldvelocities_), GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(SendActualStateStatus, linklocalinertialframes_), ~0u, // no _has_bits_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(ConfigureOpenGLVisualizerCommand, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(ConfigureOpenGLVisualizerCommand, updateflags_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(ConfigureOpenGLVisualizerCommand, cameradistance_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(ConfigureOpenGLVisualizerCommand, camerapitch_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(ConfigureOpenGLVisualizerCommand, camerayaw_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(ConfigureOpenGLVisualizerCommand, cameratargetposition_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(ConfigureOpenGLVisualizerCommand, setflag_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(ConfigureOpenGLVisualizerCommand, setenabled_), + ~0u, // no _has_bits_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(PhysicsSimulationParameters, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(PhysicsSimulationParameters, deltatime_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(PhysicsSimulationParameters, gravityacceleration_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(PhysicsSimulationParameters, numsimulationsubsteps_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(PhysicsSimulationParameters, numsolveriterations_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(PhysicsSimulationParameters, userealtimesimulation_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(PhysicsSimulationParameters, usesplitimpulse_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(PhysicsSimulationParameters, splitimpulsepenetrationthreshold_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(PhysicsSimulationParameters, contactbreakingthreshold_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(PhysicsSimulationParameters, internalsimflags_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(PhysicsSimulationParameters, defaultcontacterp_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(PhysicsSimulationParameters, collisionfiltermode_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(PhysicsSimulationParameters, enablefilecaching_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(PhysicsSimulationParameters, restitutionvelocitythreshold_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(PhysicsSimulationParameters, defaultnoncontacterp_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(PhysicsSimulationParameters, frictionerp_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(PhysicsSimulationParameters, defaultglobalcfm_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(PhysicsSimulationParameters, frictioncfm_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(PhysicsSimulationParameters, enableconefriction_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(PhysicsSimulationParameters, deterministicoverlappingpairs_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(PhysicsSimulationParameters, allowedccdpenetration_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(PhysicsSimulationParameters, jointfeedbackmode_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(PhysicsSimulationParameters, solverresidualthreshold_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(PhysicsSimulationParameters, contactslop_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(PhysicsSimulationParameters, enablesat_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(PhysicsSimulationParameters, constraintsolvertype_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(PhysicsSimulationParameters, minimumsolverislandsize_), + ~0u, // no _has_bits_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(PhysicsSimulationParametersCommand, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(PhysicsSimulationParametersCommand, updateflags_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(PhysicsSimulationParametersCommand, params_), + ~0u, // no _has_bits_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(JointMotorControlCommand, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(JointMotorControlCommand, bodyuniqueid_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(JointMotorControlCommand, controlmode_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(JointMotorControlCommand, updateflags_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(JointMotorControlCommand, kp_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(JointMotorControlCommand, kd_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(JointMotorControlCommand, maxvelocity_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(JointMotorControlCommand, hasdesiredstateflags_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(JointMotorControlCommand, desiredstateq_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(JointMotorControlCommand, desiredstateqdot_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(JointMotorControlCommand, desiredstateforcetorque_), + ~0u, // no _has_bits_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(UserConstraintCommand, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(UserConstraintCommand, parentbodyindex_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(UserConstraintCommand, parentjointindex_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(UserConstraintCommand, childbodyindex_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(UserConstraintCommand, childjointindex_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(UserConstraintCommand, parentframe_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(UserConstraintCommand, childframe_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(UserConstraintCommand, jointaxis_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(UserConstraintCommand, jointtype_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(UserConstraintCommand, maxappliedforce_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(UserConstraintCommand, userconstraintuniqueid_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(UserConstraintCommand, gearratio_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(UserConstraintCommand, gearauxlink_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(UserConstraintCommand, relativepositiontarget_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(UserConstraintCommand, erp_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(UserConstraintCommand, updateflags_), + ~0u, // no _has_bits_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(UserConstraintStatus, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(UserConstraintStatus, maxappliedforce_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(UserConstraintStatus, userconstraintuniqueid_), + ~0u, // no _has_bits_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(UserConstraintStateStatus, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(UserConstraintStateStatus, appliedconstraintforceslinear_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(UserConstraintStateStatus, appliedconstraintforcesangular_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(UserConstraintStateStatus, numdofs_), + ~0u, // no _has_bits_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(RequestKeyboardEventsCommand, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + ~0u, // no _has_bits_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(KeyboardEvent, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(KeyboardEvent, keycode_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(KeyboardEvent, keystate_), + ~0u, // no _has_bits_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(KeyboardEventsStatus, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(KeyboardEventsStatus, keyboardevents_), + ~0u, // no _has_bits_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(RequestCameraImageCommand, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(RequestCameraImageCommand, updateflags_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(RequestCameraImageCommand, cameraflags_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(RequestCameraImageCommand, viewmatrix_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(RequestCameraImageCommand, projectionmatrix_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(RequestCameraImageCommand, startpixelindex_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(RequestCameraImageCommand, pixelwidth_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(RequestCameraImageCommand, pixelheight_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(RequestCameraImageCommand, lightdirection_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(RequestCameraImageCommand, lightcolor_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(RequestCameraImageCommand, lightdistance_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(RequestCameraImageCommand, lightambientcoeff_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(RequestCameraImageCommand, lightdiffusecoeff_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(RequestCameraImageCommand, lightspecularcoeff_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(RequestCameraImageCommand, hasshadow_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(RequestCameraImageCommand, projectivetextureviewmatrix_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(RequestCameraImageCommand, projectivetextureprojectionmatrix_), + ~0u, // no _has_bits_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(RequestCameraImageStatus, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(RequestCameraImageStatus, imagewidth_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(RequestCameraImageStatus, imageheight_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(RequestCameraImageStatus, startingpixelindex_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(RequestCameraImageStatus, numpixelscopied_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(RequestCameraImageStatus, numremainingpixels_), + ~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_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(PyBulletCommand, binaryblob_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(PyBulletCommand, unknowncommandbinaryblob_), 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_), @@ -275,46 +526,95 @@ const ::google::protobuf::uint32 TableStruct::offsets[] = { PROTO2_GENERATED_DEFAULT_ONEOF_FIELD_OFFSET((&_PyBulletCommand_default_instance_), getdynamicscommand_), PROTO2_GENERATED_DEFAULT_ONEOF_FIELD_OFFSET((&_PyBulletCommand_default_instance_), initposecommand_), PROTO2_GENERATED_DEFAULT_ONEOF_FIELD_OFFSET((&_PyBulletCommand_default_instance_), requestactualstatecommand_), + PROTO2_GENERATED_DEFAULT_ONEOF_FIELD_OFFSET((&_PyBulletCommand_default_instance_), configureopenglvisualizercommand_), + PROTO2_GENERATED_DEFAULT_ONEOF_FIELD_OFFSET((&_PyBulletCommand_default_instance_), syncbodiescommand_), + PROTO2_GENERATED_DEFAULT_ONEOF_FIELD_OFFSET((&_PyBulletCommand_default_instance_), requestbodyinfocommand_), + PROTO2_GENERATED_DEFAULT_ONEOF_FIELD_OFFSET((&_PyBulletCommand_default_instance_), setphysicssimulationparameterscommand_), + PROTO2_GENERATED_DEFAULT_ONEOF_FIELD_OFFSET((&_PyBulletCommand_default_instance_), jointmotorcontrolcommand_), + PROTO2_GENERATED_DEFAULT_ONEOF_FIELD_OFFSET((&_PyBulletCommand_default_instance_), userconstraintcommand_), + PROTO2_GENERATED_DEFAULT_ONEOF_FIELD_OFFSET((&_PyBulletCommand_default_instance_), checkversioncommand_), + PROTO2_GENERATED_DEFAULT_ONEOF_FIELD_OFFSET((&_PyBulletCommand_default_instance_), requestkeyboardeventscommand_), + PROTO2_GENERATED_DEFAULT_ONEOF_FIELD_OFFSET((&_PyBulletCommand_default_instance_), requestcameraimagecommand_), 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_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(PyBulletStatus, binaryblob_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(PyBulletStatus, unknownstatusbinaryblob_), PROTO2_GENERATED_DEFAULT_ONEOF_FIELD_OFFSET((&_PyBulletStatus_default_instance_), urdfstatus_), PROTO2_GENERATED_DEFAULT_ONEOF_FIELD_OFFSET((&_PyBulletStatus_default_instance_), sdfstatus_), PROTO2_GENERATED_DEFAULT_ONEOF_FIELD_OFFSET((&_PyBulletStatus_default_instance_), mjcfstatus_), PROTO2_GENERATED_DEFAULT_ONEOF_FIELD_OFFSET((&_PyBulletStatus_default_instance_), getdynamicsstatus_), PROTO2_GENERATED_DEFAULT_ONEOF_FIELD_OFFSET((&_PyBulletStatus_default_instance_), actualstatestatus_), + PROTO2_GENERATED_DEFAULT_ONEOF_FIELD_OFFSET((&_PyBulletStatus_default_instance_), syncbodiesstatus_), + PROTO2_GENERATED_DEFAULT_ONEOF_FIELD_OFFSET((&_PyBulletStatus_default_instance_), requestbodyinfostatus_), + PROTO2_GENERATED_DEFAULT_ONEOF_FIELD_OFFSET((&_PyBulletStatus_default_instance_), requestphysicssimulationparametersstatus_), + PROTO2_GENERATED_DEFAULT_ONEOF_FIELD_OFFSET((&_PyBulletStatus_default_instance_), checkversionstatus_), + PROTO2_GENERATED_DEFAULT_ONEOF_FIELD_OFFSET((&_PyBulletStatus_default_instance_), userconstraintstatus_), + PROTO2_GENERATED_DEFAULT_ONEOF_FIELD_OFFSET((&_PyBulletStatus_default_instance_), userconstraintstatestatus_), + PROTO2_GENERATED_DEFAULT_ONEOF_FIELD_OFFSET((&_PyBulletStatus_default_instance_), keyboardeventsstatus_), + PROTO2_GENERATED_DEFAULT_ONEOF_FIELD_OFFSET((&_PyBulletStatus_default_instance_), requestcameraimagestatus_), 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(LoadSdfCommand)}, - { 52, -1, sizeof(SdfLoadedStatus)}, - { 57, -1, sizeof(LoadMjcfCommand)}, - { 63, -1, sizeof(MjcfLoadedStatus)}, - { 68, -1, sizeof(ChangeDynamicsCommand)}, - { 102, -1, sizeof(GetDynamicsCommand)}, - { 108, -1, sizeof(GetDynamicsStatus)}, - { 126, -1, sizeof(InitPoseCommand)}, - { 135, -1, sizeof(RequestActualStateCommand)}, - { 142, -1, sizeof(SendActualStateStatus)}, - { 158, -1, sizeof(PyBulletCommand)}, - { 173, -1, sizeof(PyBulletStatus)}, + { 15, -1, sizeof(vec4)}, + { 23, -1, sizeof(transform)}, + { 29, -1, sizeof(matrix4x4)}, + { 34, -1, sizeof(CheckVersionCommand)}, + { 39, -1, sizeof(CheckVersionStatus)}, + { 44, -1, sizeof(TerminateServerCommand)}, + { 49, -1, sizeof(StepSimulationCommand)}, + { 53, -1, sizeof(SyncBodiesCommand)}, + { 57, -1, sizeof(SyncBodiesStatus)}, + { 63, -1, sizeof(RequestBodyInfoCommand)}, + { 68, -1, sizeof(RequestBodyInfoStatus)}, + { 74, -1, sizeof(LoadUrdfCommand)}, + { 88, -1, sizeof(LoadUrdfStatus)}, + { 95, -1, sizeof(LoadSdfCommand)}, + { 104, -1, sizeof(SdfLoadedStatus)}, + { 109, -1, sizeof(LoadMjcfCommand)}, + { 115, -1, sizeof(MjcfLoadedStatus)}, + { 120, -1, sizeof(ChangeDynamicsCommand)}, + { 154, -1, sizeof(GetDynamicsCommand)}, + { 160, -1, sizeof(GetDynamicsStatus)}, + { 178, -1, sizeof(InitPoseCommand)}, + { 188, -1, sizeof(RequestActualStateCommand)}, + { 195, -1, sizeof(SendActualStateStatus)}, + { 211, -1, sizeof(ConfigureOpenGLVisualizerCommand)}, + { 222, -1, sizeof(PhysicsSimulationParameters)}, + { 252, -1, sizeof(PhysicsSimulationParametersCommand)}, + { 258, -1, sizeof(JointMotorControlCommand)}, + { 272, -1, sizeof(UserConstraintCommand)}, + { 291, -1, sizeof(UserConstraintStatus)}, + { 297, -1, sizeof(UserConstraintStateStatus)}, + { 304, -1, sizeof(RequestKeyboardEventsCommand)}, + { 308, -1, sizeof(KeyboardEvent)}, + { 314, -1, sizeof(KeyboardEventsStatus)}, + { 319, -1, sizeof(RequestCameraImageCommand)}, + { 339, -1, sizeof(RequestCameraImageStatus)}, + { 348, -1, sizeof(PyBulletCommand)}, + { 374, -1, sizeof(PyBulletStatus)}, }; static ::google::protobuf::Message const * const file_default_instances[] = { reinterpret_cast(&_vec3_default_instance_), reinterpret_cast(&_quat4_default_instance_), + reinterpret_cast(&_vec4_default_instance_), + reinterpret_cast(&_transform_default_instance_), + reinterpret_cast(&_matrix4x4_default_instance_), + reinterpret_cast(&_CheckVersionCommand_default_instance_), + reinterpret_cast(&_CheckVersionStatus_default_instance_), reinterpret_cast(&_TerminateServerCommand_default_instance_), reinterpret_cast(&_StepSimulationCommand_default_instance_), + reinterpret_cast(&_SyncBodiesCommand_default_instance_), + reinterpret_cast(&_SyncBodiesStatus_default_instance_), + reinterpret_cast(&_RequestBodyInfoCommand_default_instance_), + reinterpret_cast(&_RequestBodyInfoStatus_default_instance_), reinterpret_cast(&_LoadUrdfCommand_default_instance_), reinterpret_cast(&_LoadUrdfStatus_default_instance_), reinterpret_cast(&_LoadSdfCommand_default_instance_), @@ -327,6 +627,18 @@ static ::google::protobuf::Message const * const file_default_instances[] = { reinterpret_cast(&_InitPoseCommand_default_instance_), reinterpret_cast(&_RequestActualStateCommand_default_instance_), reinterpret_cast(&_SendActualStateStatus_default_instance_), + reinterpret_cast(&_ConfigureOpenGLVisualizerCommand_default_instance_), + reinterpret_cast(&_PhysicsSimulationParameters_default_instance_), + reinterpret_cast(&_PhysicsSimulationParametersCommand_default_instance_), + reinterpret_cast(&_JointMotorControlCommand_default_instance_), + reinterpret_cast(&_UserConstraintCommand_default_instance_), + reinterpret_cast(&_UserConstraintStatus_default_instance_), + reinterpret_cast(&_UserConstraintStateStatus_default_instance_), + reinterpret_cast(&_RequestKeyboardEventsCommand_default_instance_), + reinterpret_cast(&_KeyboardEvent_default_instance_), + reinterpret_cast(&_KeyboardEventsStatus_default_instance_), + reinterpret_cast(&_RequestCameraImageCommand_default_instance_), + reinterpret_cast(&_RequestCameraImageStatus_default_instance_), reinterpret_cast(&_PyBulletCommand_default_instance_), reinterpret_cast(&_PyBulletStatus_default_instance_), }; @@ -349,7 +661,7 @@ void protobuf_AssignDescriptorsOnce() { void protobuf_RegisterTypes(const ::std::string&) GOOGLE_ATTRIBUTE_COLD; void protobuf_RegisterTypes(const ::std::string&) { protobuf_AssignDescriptorsOnce(); - ::google::protobuf::internal::RegisterAllTypes(file_level_metadata, 18); + ::google::protobuf::internal::RegisterAllTypes(file_level_metadata, 39); } } // namespace @@ -359,38 +671,80 @@ void TableStruct::Shutdown() { delete file_level_metadata[0].reflection; _quat4_default_instance_.Shutdown(); delete file_level_metadata[1].reflection; - _TerminateServerCommand_default_instance_.Shutdown(); + _vec4_default_instance_.Shutdown(); delete file_level_metadata[2].reflection; - _StepSimulationCommand_default_instance_.Shutdown(); + _transform_default_instance_.Shutdown(); delete file_level_metadata[3].reflection; - _LoadUrdfCommand_default_instance_.Shutdown(); + _matrix4x4_default_instance_.Shutdown(); delete file_level_metadata[4].reflection; - _LoadUrdfStatus_default_instance_.Shutdown(); + _CheckVersionCommand_default_instance_.Shutdown(); delete file_level_metadata[5].reflection; - _LoadSdfCommand_default_instance_.Shutdown(); + _CheckVersionStatus_default_instance_.Shutdown(); delete file_level_metadata[6].reflection; - _SdfLoadedStatus_default_instance_.Shutdown(); + _TerminateServerCommand_default_instance_.Shutdown(); delete file_level_metadata[7].reflection; - _LoadMjcfCommand_default_instance_.Shutdown(); + _StepSimulationCommand_default_instance_.Shutdown(); delete file_level_metadata[8].reflection; - _MjcfLoadedStatus_default_instance_.Shutdown(); + _SyncBodiesCommand_default_instance_.Shutdown(); delete file_level_metadata[9].reflection; - _ChangeDynamicsCommand_default_instance_.Shutdown(); + _SyncBodiesStatus_default_instance_.Shutdown(); delete file_level_metadata[10].reflection; - _GetDynamicsCommand_default_instance_.Shutdown(); + _RequestBodyInfoCommand_default_instance_.Shutdown(); delete file_level_metadata[11].reflection; - _GetDynamicsStatus_default_instance_.Shutdown(); + _RequestBodyInfoStatus_default_instance_.Shutdown(); delete file_level_metadata[12].reflection; - _InitPoseCommand_default_instance_.Shutdown(); + _LoadUrdfCommand_default_instance_.Shutdown(); delete file_level_metadata[13].reflection; - _RequestActualStateCommand_default_instance_.Shutdown(); + _LoadUrdfStatus_default_instance_.Shutdown(); delete file_level_metadata[14].reflection; - _SendActualStateStatus_default_instance_.Shutdown(); + _LoadSdfCommand_default_instance_.Shutdown(); delete file_level_metadata[15].reflection; - _PyBulletCommand_default_instance_.Shutdown(); + _SdfLoadedStatus_default_instance_.Shutdown(); delete file_level_metadata[16].reflection; - _PyBulletStatus_default_instance_.Shutdown(); + _LoadMjcfCommand_default_instance_.Shutdown(); delete file_level_metadata[17].reflection; + _MjcfLoadedStatus_default_instance_.Shutdown(); + delete file_level_metadata[18].reflection; + _ChangeDynamicsCommand_default_instance_.Shutdown(); + delete file_level_metadata[19].reflection; + _GetDynamicsCommand_default_instance_.Shutdown(); + delete file_level_metadata[20].reflection; + _GetDynamicsStatus_default_instance_.Shutdown(); + delete file_level_metadata[21].reflection; + _InitPoseCommand_default_instance_.Shutdown(); + delete file_level_metadata[22].reflection; + _RequestActualStateCommand_default_instance_.Shutdown(); + delete file_level_metadata[23].reflection; + _SendActualStateStatus_default_instance_.Shutdown(); + delete file_level_metadata[24].reflection; + _ConfigureOpenGLVisualizerCommand_default_instance_.Shutdown(); + delete file_level_metadata[25].reflection; + _PhysicsSimulationParameters_default_instance_.Shutdown(); + delete file_level_metadata[26].reflection; + _PhysicsSimulationParametersCommand_default_instance_.Shutdown(); + delete file_level_metadata[27].reflection; + _JointMotorControlCommand_default_instance_.Shutdown(); + delete file_level_metadata[28].reflection; + _UserConstraintCommand_default_instance_.Shutdown(); + delete file_level_metadata[29].reflection; + _UserConstraintStatus_default_instance_.Shutdown(); + delete file_level_metadata[30].reflection; + _UserConstraintStateStatus_default_instance_.Shutdown(); + delete file_level_metadata[31].reflection; + _RequestKeyboardEventsCommand_default_instance_.Shutdown(); + delete file_level_metadata[32].reflection; + _KeyboardEvent_default_instance_.Shutdown(); + delete file_level_metadata[33].reflection; + _KeyboardEventsStatus_default_instance_.Shutdown(); + delete file_level_metadata[34].reflection; + _RequestCameraImageCommand_default_instance_.Shutdown(); + delete file_level_metadata[35].reflection; + _RequestCameraImageStatus_default_instance_.Shutdown(); + delete file_level_metadata[36].reflection; + _PyBulletCommand_default_instance_.Shutdown(); + delete file_level_metadata[37].reflection; + _PyBulletStatus_default_instance_.Shutdown(); + delete file_level_metadata[38].reflection; } void TableStruct::InitDefaultsImpl() { @@ -399,8 +753,17 @@ void TableStruct::InitDefaultsImpl() { ::google::protobuf::internal::InitProtobufDefaults(); _vec3_default_instance_.DefaultConstruct(); _quat4_default_instance_.DefaultConstruct(); + _vec4_default_instance_.DefaultConstruct(); + _transform_default_instance_.DefaultConstruct(); + _matrix4x4_default_instance_.DefaultConstruct(); + _CheckVersionCommand_default_instance_.DefaultConstruct(); + _CheckVersionStatus_default_instance_.DefaultConstruct(); _TerminateServerCommand_default_instance_.DefaultConstruct(); _StepSimulationCommand_default_instance_.DefaultConstruct(); + _SyncBodiesCommand_default_instance_.DefaultConstruct(); + _SyncBodiesStatus_default_instance_.DefaultConstruct(); + _RequestBodyInfoCommand_default_instance_.DefaultConstruct(); + _RequestBodyInfoStatus_default_instance_.DefaultConstruct(); _LoadUrdfCommand_default_instance_.DefaultConstruct(); _LoadUrdfStatus_default_instance_.DefaultConstruct(); _LoadSdfCommand_default_instance_.DefaultConstruct(); @@ -413,8 +776,24 @@ void TableStruct::InitDefaultsImpl() { _InitPoseCommand_default_instance_.DefaultConstruct(); _RequestActualStateCommand_default_instance_.DefaultConstruct(); _SendActualStateStatus_default_instance_.DefaultConstruct(); + _ConfigureOpenGLVisualizerCommand_default_instance_.DefaultConstruct(); + _PhysicsSimulationParameters_default_instance_.DefaultConstruct(); + _PhysicsSimulationParametersCommand_default_instance_.DefaultConstruct(); + _JointMotorControlCommand_default_instance_.DefaultConstruct(); + _UserConstraintCommand_default_instance_.DefaultConstruct(); + _UserConstraintStatus_default_instance_.DefaultConstruct(); + _UserConstraintStateStatus_default_instance_.DefaultConstruct(); + _RequestKeyboardEventsCommand_default_instance_.DefaultConstruct(); + _KeyboardEvent_default_instance_.DefaultConstruct(); + _KeyboardEventsStatus_default_instance_.DefaultConstruct(); + _RequestCameraImageCommand_default_instance_.DefaultConstruct(); + _RequestCameraImageStatus_default_instance_.DefaultConstruct(); _PyBulletCommand_default_instance_.DefaultConstruct(); _PyBulletStatus_default_instance_.DefaultConstruct(); + _transform_default_instance_.get_mutable()->origin_ = const_cast< ::pybullet_grpc::vec3*>( + ::pybullet_grpc::vec3::internal_default_instance()); + _transform_default_instance_.get_mutable()->orientation_ = const_cast< ::pybullet_grpc::quat4*>( + ::pybullet_grpc::quat4::internal_default_instance()); _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*>( @@ -441,6 +820,34 @@ void TableStruct::InitDefaultsImpl() { _ChangeDynamicsCommand_default_instance_.activationstate_ = 0; _GetDynamicsStatus_default_instance_.get_mutable()->localinertiadiagonal_ = const_cast< ::pybullet_grpc::vec3*>( ::pybullet_grpc::vec3::internal_default_instance()); + _ConfigureOpenGLVisualizerCommand_default_instance_.get_mutable()->cameratargetposition_ = const_cast< ::pybullet_grpc::vec3*>( + ::pybullet_grpc::vec3::internal_default_instance()); + _PhysicsSimulationParameters_default_instance_.get_mutable()->gravityacceleration_ = const_cast< ::pybullet_grpc::vec3*>( + ::pybullet_grpc::vec3::internal_default_instance()); + _PhysicsSimulationParametersCommand_default_instance_.get_mutable()->params_ = const_cast< ::pybullet_grpc::PhysicsSimulationParameters*>( + ::pybullet_grpc::PhysicsSimulationParameters::internal_default_instance()); + _UserConstraintCommand_default_instance_.get_mutable()->parentframe_ = const_cast< ::pybullet_grpc::transform*>( + ::pybullet_grpc::transform::internal_default_instance()); + _UserConstraintCommand_default_instance_.get_mutable()->childframe_ = const_cast< ::pybullet_grpc::transform*>( + ::pybullet_grpc::transform::internal_default_instance()); + _UserConstraintCommand_default_instance_.get_mutable()->jointaxis_ = const_cast< ::pybullet_grpc::vec3*>( + ::pybullet_grpc::vec3::internal_default_instance()); + _UserConstraintStateStatus_default_instance_.get_mutable()->appliedconstraintforceslinear_ = const_cast< ::pybullet_grpc::vec3*>( + ::pybullet_grpc::vec3::internal_default_instance()); + _UserConstraintStateStatus_default_instance_.get_mutable()->appliedconstraintforcesangular_ = const_cast< ::pybullet_grpc::vec3*>( + ::pybullet_grpc::vec3::internal_default_instance()); + _RequestCameraImageCommand_default_instance_.get_mutable()->viewmatrix_ = const_cast< ::pybullet_grpc::matrix4x4*>( + ::pybullet_grpc::matrix4x4::internal_default_instance()); + _RequestCameraImageCommand_default_instance_.get_mutable()->projectionmatrix_ = const_cast< ::pybullet_grpc::matrix4x4*>( + ::pybullet_grpc::matrix4x4::internal_default_instance()); + _RequestCameraImageCommand_default_instance_.get_mutable()->lightdirection_ = const_cast< ::pybullet_grpc::vec3*>( + ::pybullet_grpc::vec3::internal_default_instance()); + _RequestCameraImageCommand_default_instance_.get_mutable()->lightcolor_ = const_cast< ::pybullet_grpc::vec3*>( + ::pybullet_grpc::vec3::internal_default_instance()); + _RequestCameraImageCommand_default_instance_.get_mutable()->projectivetextureviewmatrix_ = const_cast< ::pybullet_grpc::matrix4x4*>( + ::pybullet_grpc::matrix4x4::internal_default_instance()); + _RequestCameraImageCommand_default_instance_.get_mutable()->projectivetextureprojectionmatrix_ = const_cast< ::pybullet_grpc::matrix4x4*>( + ::pybullet_grpc::matrix4x4::internal_default_instance()); _PyBulletCommand_default_instance_.loadurdfcommand_ = const_cast< ::pybullet_grpc::LoadUrdfCommand*>( ::pybullet_grpc::LoadUrdfCommand::internal_default_instance()); _PyBulletCommand_default_instance_.terminateservercommand_ = const_cast< ::pybullet_grpc::TerminateServerCommand*>( @@ -459,6 +866,24 @@ void TableStruct::InitDefaultsImpl() { ::pybullet_grpc::InitPoseCommand::internal_default_instance()); _PyBulletCommand_default_instance_.requestactualstatecommand_ = const_cast< ::pybullet_grpc::RequestActualStateCommand*>( ::pybullet_grpc::RequestActualStateCommand::internal_default_instance()); + _PyBulletCommand_default_instance_.configureopenglvisualizercommand_ = const_cast< ::pybullet_grpc::ConfigureOpenGLVisualizerCommand*>( + ::pybullet_grpc::ConfigureOpenGLVisualizerCommand::internal_default_instance()); + _PyBulletCommand_default_instance_.syncbodiescommand_ = const_cast< ::pybullet_grpc::SyncBodiesCommand*>( + ::pybullet_grpc::SyncBodiesCommand::internal_default_instance()); + _PyBulletCommand_default_instance_.requestbodyinfocommand_ = const_cast< ::pybullet_grpc::RequestBodyInfoCommand*>( + ::pybullet_grpc::RequestBodyInfoCommand::internal_default_instance()); + _PyBulletCommand_default_instance_.setphysicssimulationparameterscommand_ = const_cast< ::pybullet_grpc::PhysicsSimulationParametersCommand*>( + ::pybullet_grpc::PhysicsSimulationParametersCommand::internal_default_instance()); + _PyBulletCommand_default_instance_.jointmotorcontrolcommand_ = const_cast< ::pybullet_grpc::JointMotorControlCommand*>( + ::pybullet_grpc::JointMotorControlCommand::internal_default_instance()); + _PyBulletCommand_default_instance_.userconstraintcommand_ = const_cast< ::pybullet_grpc::UserConstraintCommand*>( + ::pybullet_grpc::UserConstraintCommand::internal_default_instance()); + _PyBulletCommand_default_instance_.checkversioncommand_ = const_cast< ::pybullet_grpc::CheckVersionCommand*>( + ::pybullet_grpc::CheckVersionCommand::internal_default_instance()); + _PyBulletCommand_default_instance_.requestkeyboardeventscommand_ = const_cast< ::pybullet_grpc::RequestKeyboardEventsCommand*>( + ::pybullet_grpc::RequestKeyboardEventsCommand::internal_default_instance()); + _PyBulletCommand_default_instance_.requestcameraimagecommand_ = const_cast< ::pybullet_grpc::RequestCameraImageCommand*>( + ::pybullet_grpc::RequestCameraImageCommand::internal_default_instance()); _PyBulletStatus_default_instance_.urdfstatus_ = const_cast< ::pybullet_grpc::LoadUrdfStatus*>( ::pybullet_grpc::LoadUrdfStatus::internal_default_instance()); _PyBulletStatus_default_instance_.sdfstatus_ = const_cast< ::pybullet_grpc::SdfLoadedStatus*>( @@ -469,6 +894,22 @@ void TableStruct::InitDefaultsImpl() { ::pybullet_grpc::GetDynamicsStatus::internal_default_instance()); _PyBulletStatus_default_instance_.actualstatestatus_ = const_cast< ::pybullet_grpc::SendActualStateStatus*>( ::pybullet_grpc::SendActualStateStatus::internal_default_instance()); + _PyBulletStatus_default_instance_.syncbodiesstatus_ = const_cast< ::pybullet_grpc::SyncBodiesStatus*>( + ::pybullet_grpc::SyncBodiesStatus::internal_default_instance()); + _PyBulletStatus_default_instance_.requestbodyinfostatus_ = const_cast< ::pybullet_grpc::RequestBodyInfoStatus*>( + ::pybullet_grpc::RequestBodyInfoStatus::internal_default_instance()); + _PyBulletStatus_default_instance_.requestphysicssimulationparametersstatus_ = const_cast< ::pybullet_grpc::PhysicsSimulationParameters*>( + ::pybullet_grpc::PhysicsSimulationParameters::internal_default_instance()); + _PyBulletStatus_default_instance_.checkversionstatus_ = const_cast< ::pybullet_grpc::CheckVersionStatus*>( + ::pybullet_grpc::CheckVersionStatus::internal_default_instance()); + _PyBulletStatus_default_instance_.userconstraintstatus_ = const_cast< ::pybullet_grpc::UserConstraintStatus*>( + ::pybullet_grpc::UserConstraintStatus::internal_default_instance()); + _PyBulletStatus_default_instance_.userconstraintstatestatus_ = const_cast< ::pybullet_grpc::UserConstraintStateStatus*>( + ::pybullet_grpc::UserConstraintStateStatus::internal_default_instance()); + _PyBulletStatus_default_instance_.keyboardeventsstatus_ = const_cast< ::pybullet_grpc::KeyboardEventsStatus*>( + ::pybullet_grpc::KeyboardEventsStatus::internal_default_instance()); + _PyBulletStatus_default_instance_.requestcameraimagestatus_ = const_cast< ::pybullet_grpc::RequestCameraImageStatus*>( + ::pybullet_grpc::RequestCameraImageStatus::internal_default_instance()); } void InitDefaults() { @@ -481,100 +922,223 @@ void AddDescriptorsImpl() { "\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\"\225\002\n" - "\017LoadUrdfCommand\022\020\n\010fileName\030\001 \001(\t\022,\n\017in" - "itialPosition\030\002 \001(\0132\023.pybullet_grpc.vec3" - "\0220\n\022initialOrientation\030\003 \001(\0132\024.pybullet_" - "grpc.quat4\022\026\n\014useMultiBody\030\004 \001(\005H\000\022\026\n\014us" - "eFixedBase\030\005 \001(\010H\001\022\r\n\005flags\030\006 \001(\005\022\027\n\rglo" - "balScaling\030\007 \001(\001H\002B\021\n\017hasUseMultiBodyB\021\n" - "\017hasUseFixedBaseB\022\n\020hasGlobalScaling\"&\n\016" - "LoadUrdfStatus\022\024\n\014bodyUniqueId\030\001 \001(\005\"z\n\016" - "LoadSdfCommand\022\020\n\010fileName\030\001 \001(\t\022\026\n\014useM" - "ultiBody\030\002 \001(\005H\000\022\027\n\rglobalScaling\030\003 \001(\001H" - "\001B\021\n\017hasUseMultiBodyB\022\n\020hasGlobalScaling" - "\"(\n\017SdfLoadedStatus\022\025\n\rbodyUniqueIds\030\002 \003" - "(\005\"2\n\017LoadMjcfCommand\022\020\n\010fileName\030\001 \001(\t\022" - "\r\n\005flags\030\002 \001(\005\")\n\020MjcfLoadedStatus\022\025\n\rbo" - "dyUniqueIds\030\002 \003(\005\"\211\006\n\025ChangeDynamicsComm" - "and\022\024\n\014bodyUniqueId\030\001 \001(\005\022\021\n\tlinkIndex\030\002" - " \001(\005\022\016\n\004mass\030\003 \001(\001H\000\022\031\n\017lateralFriction\030" - "\005 \001(\001H\001\022\032\n\020spinningFriction\030\006 \001(\001H\002\022\031\n\017r" - "ollingFriction\030\007 \001(\001H\003\022\025\n\013restitution\030\010 " - "\001(\001H\004\022\027\n\rlinearDamping\030\t \001(\001H\005\022\030\n\016angula" - "rDamping\030\n \001(\001H\006\022\032\n\020contactStiffness\030\013 \001" - "(\001H\007\022\030\n\016contactDamping\030\014 \001(\001H\010\0223\n\024localI" - "nertiaDiagonal\030\r \001(\0132\023.pybullet_grpc.vec" - "3H\t\022\030\n\016frictionAnchor\030\016 \001(\005H\n\022\036\n\024ccdSwep" - "tSphereRadius\030\017 \001(\001H\013\022$\n\032contactProcessi" - "ngThreshold\030\020 \001(\001H\014\022\031\n\017activationState\030\021" - " \001(\005H\rB\t\n\007hasMassB\024\n\022hasLateralFrictionB" - "\025\n\023hasSpinningFrictionB\024\n\022hasRollingFric" - "tionB\020\n\016hasRestitutionB\022\n\020haslinearDampi" - "ngB\023\n\021hasangularDampingB\025\n\023hasContactSti" - "ffnessB\023\n\021hasContactDampingB\031\n\027hasLocalI" - "nertiaDiagonalB\023\n\021hasFrictionAnchorB\031\n\027h" - "asccdSweptSphereRadiusB\037\n\035hasContactProc" - "essingThresholdB\024\n\022hasActivationState\"=\n" - "\022GetDynamicsCommand\022\024\n\014bodyUniqueId\030\001 \001(" - "\005\022\021\n\tlinkIndex\030\002 \001(\005\"\211\003\n\021GetDynamicsStat" - "us\022\014\n\004mass\030\003 \001(\001\022\027\n\017lateralFriction\030\005 \001(" - "\001\022\030\n\020spinningFriction\030\006 \001(\001\022\027\n\017rollingFr" - "iction\030\007 \001(\001\022\023\n\013restitution\030\010 \001(\001\022\025\n\rlin" - "earDamping\030\t \001(\001\022\026\n\016angularDamping\030\n \001(\001" - "\022\030\n\020contactStiffness\030\013 \001(\001\022\026\n\016contactDam" - "ping\030\014 \001(\001\0221\n\024localInertiaDiagonal\030\r \001(\013" - "2\023.pybullet_grpc.vec3\022\026\n\016frictionAnchor\030" - "\016 \001(\005\022\034\n\024ccdSweptSphereRadius\030\017 \001(\001\022\"\n\032c" - "ontactProcessingThreshold\030\020 \001(\001\022\027\n\017activ" - "ationState\030\021 \001(\005\"\217\001\n\017InitPoseCommand\022\024\n\014" - "bodyUniqueId\030\001 \001(\005\022\030\n\020hasInitialStateQ\030\002" - " \003(\005\022\025\n\rinitialStateQ\030\003 \003(\001\022\033\n\023hasInitia" - "lStateQdot\030\004 \003(\005\022\030\n\020initialStateQdot\030\005 \003" - "(\001\"r\n\031RequestActualStateCommand\022\024\n\014bodyU" - "niqueId\030\001 \001(\005\022 \n\030computeForwardKinematic" - "s\030\002 \001(\010\022\035\n\025computeLinkVelocities\030\003 \001(\010\"\317" - "\002\n\025SendActualStateStatus\022\024\n\014bodyUniqueId" - "\030\001 \001(\005\022\020\n\010numLinks\030\002 \001(\005\022\033\n\023numDegreeOfF" - "reedomQ\030\003 \001(\005\022\033\n\023numDegreeOfFreedomU\030\004 \001" - "(\005\022\036\n\026rootLocalInertialFrame\030\005 \003(\001\022\024\n\014ac" - "tualStateQ\030\006 \003(\001\022\027\n\017actualStateQdot\030\007 \003(" - "\001\022\033\n\023jointReactionForces\030\010 \003(\001\022\027\n\017jointM" - "otorForce\030\t \003(\001\022\021\n\tlinkState\030\n \003(\001\022\033\n\023li" - "nkWorldVelocities\030\013 \003(\001\022\037\n\027linkLocalIner" - "tialFrames\030\014 \003(\001\"\203\005\n\017PyBulletCommand\022\023\n\013" - "commandType\030\001 \001(\005\0229\n\017loadUrdfCommand\030\003 \001" - "(\0132\036.pybullet_grpc.LoadUrdfCommandH\000\022G\n\026" - "terminateServerCommand\030\004 \001(\0132%.pybullet_" - "grpc.TerminateServerCommandH\000\022E\n\025stepSim" - "ulationCommand\030\005 \001(\0132$.pybullet_grpc.Ste" - "pSimulationCommandH\000\0227\n\016loadSdfCommand\030\006" - " \001(\0132\035.pybullet_grpc.LoadSdfCommandH\000\0229\n" - "\017loadMjcfCommand\030\007 \001(\0132\036.pybullet_grpc.L" - "oadMjcfCommandH\000\022E\n\025changeDynamicsComman" - "d\030\010 \001(\0132$.pybullet_grpc.ChangeDynamicsCo" - "mmandH\000\022\?\n\022getDynamicsCommand\030\t \001(\0132!.py" - "bullet_grpc.GetDynamicsCommandH\000\0229\n\017init" - "PoseCommand\030\n \001(\0132\036.pybullet_grpc.InitPo" - "seCommandH\000\022M\n\031requestActualStateCommand" - "\030\013 \001(\0132(.pybullet_grpc.RequestActualStat" - "eCommandH\000B\n\n\010commands\"\321\002\n\016PyBulletStatu" - "s\022\022\n\nstatusType\030\001 \001(\005\0223\n\nurdfStatus\030\002 \001(" - "\0132\035.pybullet_grpc.LoadUrdfStatusH\000\0223\n\tsd" - "fStatus\030\003 \001(\0132\036.pybullet_grpc.SdfLoadedS" - "tatusH\000\0225\n\nmjcfStatus\030\004 \001(\0132\037.pybullet_g" - "rpc.MjcfLoadedStatusH\000\022=\n\021getDynamicsSta" - "tus\030\005 \001(\0132 .pybullet_grpc.GetDynamicsSta" - "tusH\000\022A\n\021actualStateStatus\030\006 \001(\0132$.pybul" - "let_grpc.SendActualStateStatusH\000B\010\n\006stat" - "us2_\n\013PyBulletAPI\022P\n\rSubmitCommand\022\036.pyb" - "ullet_grpc.PyBulletCommand\032\035.pybullet_gr" - "pc.PyBulletStatus\"\000B.\n\025io.grpc.pybullet_" - "grpcB\rPyBulletProtoP\001\242\002\003PBGb\006proto3" + "\004 \001(\001\"2\n\004vec4\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\ttransform\022#\n\006origin" + "\030\001 \001(\0132\023.pybullet_grpc.vec3\022)\n\013orientati" + "on\030\002 \001(\0132\024.pybullet_grpc.quat4\"\032\n\tmatrix" + "4x4\022\r\n\005elems\030\001 \003(\001\",\n\023CheckVersionComman" + "d\022\025\n\rclientVersion\030\001 \001(\005\"+\n\022CheckVersion" + "Status\022\025\n\rserverVersion\030\001 \001(\005\",\n\026Termina" + "teServerCommand\022\022\n\nexitReason\030\001 \001(\t\"\027\n\025S" + "tepSimulationCommand\"\023\n\021SyncBodiesComman" + "d\"J\n\020SyncBodiesStatus\022\025\n\rbodyUniqueIds\030\001" + " \003(\005\022\037\n\027userConstraintUniqueIds\030\002 \003(\005\".\n" + "\026RequestBodyInfoCommand\022\024\n\014bodyUniqueId\030" + "\001 \001(\005\"\?\n\025RequestBodyInfoStatus\022\024\n\014bodyUn" + "iqueId\030\001 \001(\005\022\020\n\010bodyName\030\002 \001(\t\"\225\002\n\017LoadU" + "rdfCommand\022\020\n\010fileName\030\001 \001(\t\022,\n\017initialP" + "osition\030\002 \001(\0132\023.pybullet_grpc.vec3\0220\n\022in" + "itialOrientation\030\003 \001(\0132\024.pybullet_grpc.q" + "uat4\022\026\n\014useMultiBody\030\004 \001(\005H\000\022\026\n\014useFixed" + "Base\030\005 \001(\010H\001\022\r\n\005flags\030\006 \001(\005\022\027\n\rglobalSca" + "ling\030\007 \001(\001H\002B\021\n\017hasUseMultiBodyB\021\n\017hasUs" + "eFixedBaseB\022\n\020hasGlobalScaling\"J\n\016LoadUr" + "dfStatus\022\024\n\014bodyUniqueId\030\001 \001(\005\022\020\n\010bodyNa" + "me\030\002 \001(\t\022\020\n\010fileName\030\003 \001(\t\"z\n\016LoadSdfCom" + "mand\022\020\n\010fileName\030\001 \001(\t\022\026\n\014useMultiBody\030\002" + " \001(\005H\000\022\027\n\rglobalScaling\030\003 \001(\001H\001B\021\n\017hasUs" + "eMultiBodyB\022\n\020hasGlobalScaling\"(\n\017SdfLoa" + "dedStatus\022\025\n\rbodyUniqueIds\030\002 \003(\005\"2\n\017Load" + "MjcfCommand\022\020\n\010fileName\030\001 \001(\t\022\r\n\005flags\030\002" + " \001(\005\")\n\020MjcfLoadedStatus\022\025\n\rbodyUniqueId" + "s\030\002 \003(\005\"\211\006\n\025ChangeDynamicsCommand\022\024\n\014bod" + "yUniqueId\030\001 \001(\005\022\021\n\tlinkIndex\030\002 \001(\005\022\016\n\004ma" + "ss\030\003 \001(\001H\000\022\031\n\017lateralFriction\030\005 \001(\001H\001\022\032\n" + "\020spinningFriction\030\006 \001(\001H\002\022\031\n\017rollingFric" + "tion\030\007 \001(\001H\003\022\025\n\013restitution\030\010 \001(\001H\004\022\027\n\rl" + "inearDamping\030\t \001(\001H\005\022\030\n\016angularDamping\030\n" + " \001(\001H\006\022\032\n\020contactStiffness\030\013 \001(\001H\007\022\030\n\016co" + "ntactDamping\030\014 \001(\001H\010\0223\n\024localInertiaDiag" + "onal\030\r \001(\0132\023.pybullet_grpc.vec3H\t\022\030\n\016fri" + "ctionAnchor\030\016 \001(\005H\n\022\036\n\024ccdSweptSphereRad" + "ius\030\017 \001(\001H\013\022$\n\032contactProcessingThreshol" + "d\030\020 \001(\001H\014\022\031\n\017activationState\030\021 \001(\005H\rB\t\n\007" + "hasMassB\024\n\022hasLateralFrictionB\025\n\023hasSpin" + "ningFrictionB\024\n\022hasRollingFrictionB\020\n\016ha" + "sRestitutionB\022\n\020haslinearDampingB\023\n\021hasa" + "ngularDampingB\025\n\023hasContactStiffnessB\023\n\021" + "hasContactDampingB\031\n\027hasLocalInertiaDiag" + "onalB\023\n\021hasFrictionAnchorB\031\n\027hasccdSwept" + "SphereRadiusB\037\n\035hasContactProcessingThre" + "sholdB\024\n\022hasActivationState\"=\n\022GetDynami" + "csCommand\022\024\n\014bodyUniqueId\030\001 \001(\005\022\021\n\tlinkI" + "ndex\030\002 \001(\005\"\211\003\n\021GetDynamicsStatus\022\014\n\004mass" + "\030\003 \001(\001\022\027\n\017lateralFriction\030\005 \001(\001\022\030\n\020spinn" + "ingFriction\030\006 \001(\001\022\027\n\017rollingFriction\030\007 \001" + "(\001\022\023\n\013restitution\030\010 \001(\001\022\025\n\rlinearDamping" + "\030\t \001(\001\022\026\n\016angularDamping\030\n \001(\001\022\030\n\020contac" + "tStiffness\030\013 \001(\001\022\026\n\016contactDamping\030\014 \001(\001" + "\0221\n\024localInertiaDiagonal\030\r \001(\0132\023.pybulle" + "t_grpc.vec3\022\026\n\016frictionAnchor\030\016 \001(\005\022\034\n\024c" + "cdSweptSphereRadius\030\017 \001(\001\022\"\n\032contactProc" + "essingThreshold\030\020 \001(\001\022\027\n\017activationState" + "\030\021 \001(\005\"\244\001\n\017InitPoseCommand\022\024\n\014bodyUnique" + "Id\030\001 \001(\005\022\023\n\013updateflags\030\002 \001(\005\022\030\n\020hasInit" + "ialStateQ\030\003 \003(\005\022\025\n\rinitialStateQ\030\004 \003(\001\022\033" + "\n\023hasInitialStateQdot\030\005 \003(\005\022\030\n\020initialSt" + "ateQdot\030\006 \003(\001\"r\n\031RequestActualStateComma" + "nd\022\024\n\014bodyUniqueId\030\001 \001(\005\022 \n\030computeForwa" + "rdKinematics\030\002 \001(\010\022\035\n\025computeLinkVelocit" + "ies\030\003 \001(\010\"\317\002\n\025SendActualStateStatus\022\024\n\014b" + "odyUniqueId\030\001 \001(\005\022\020\n\010numLinks\030\002 \001(\005\022\033\n\023n" + "umDegreeOfFreedomQ\030\003 \001(\005\022\033\n\023numDegreeOfF" + "reedomU\030\004 \001(\005\022\036\n\026rootLocalInertialFrame\030" + "\005 \003(\001\022\024\n\014actualStateQ\030\006 \003(\001\022\027\n\017actualSta" + "teQdot\030\007 \003(\001\022\033\n\023jointReactionForces\030\010 \003(" + "\001\022\027\n\017jointMotorForce\030\t \003(\001\022\021\n\tlinkState\030" + "\n \003(\001\022\033\n\023linkWorldVelocities\030\013 \003(\001\022\037\n\027li" + "nkLocalInertialFrames\030\014 \003(\001\"\317\001\n Configur" + "eOpenGLVisualizerCommand\022\023\n\013updateFlags\030" + "\001 \001(\005\022\026\n\016cameraDistance\030\002 \001(\001\022\023\n\013cameraP" + "itch\030\003 \001(\001\022\021\n\tcameraYaw\030\004 \001(\001\0221\n\024cameraT" + "argetPosition\030\005 \001(\0132\023.pybullet_grpc.vec3" + "\022\017\n\007setFlag\030\006 \001(\005\022\022\n\nsetEnabled\030\007 \001(\005\"\234\006" + "\n\033PhysicsSimulationParameters\022\021\n\tdeltaTi" + "me\030\001 \001(\001\0220\n\023gravityAcceleration\030\002 \001(\0132\023." + "pybullet_grpc.vec3\022\035\n\025numSimulationSubSt" + "eps\030\003 \001(\005\022\033\n\023numSolverIterations\030\004 \001(\005\022\035" + "\n\025useRealTimeSimulation\030\005 \001(\005\022\027\n\017useSpli" + "tImpulse\030\006 \001(\005\022(\n splitImpulsePenetratio" + "nThreshold\030\007 \001(\001\022 \n\030contactBreakingThres" + "hold\030\010 \001(\001\022\030\n\020internalSimFlags\030\t \001(\005\022\031\n\021" + "defaultContactERP\030\n \001(\001\022\033\n\023collisionFilt" + "erMode\030\013 \001(\005\022\031\n\021enableFileCaching\030\014 \001(\005\022" + "$\n\034restitutionVelocityThreshold\030\r \001(\001\022\034\n" + "\024defaultNonContactERP\030\016 \001(\001\022\023\n\013frictionE" + "RP\030\017 \001(\001\022\030\n\020defaultGlobalCFM\030\020 \001(\001\022\023\n\013fr" + "ictionCFM\030\021 \001(\001\022\032\n\022enableConeFriction\030\022 " + "\001(\005\022%\n\035deterministicOverlappingPairs\030\023 \001" + "(\005\022\035\n\025allowedCcdPenetration\030\024 \001(\001\022\031\n\021joi" + "ntFeedbackMode\030\025 \001(\005\022\037\n\027solverResidualTh" + "reshold\030\026 \001(\001\022\023\n\013contactSlop\030\027 \001(\001\022\021\n\ten" + "ableSAT\030\030 \001(\005\022\034\n\024constraintSolverType\030\031 " + "\001(\005\022\037\n\027minimumSolverIslandSize\030\032 \001(\005\"u\n\"" + "PhysicsSimulationParametersCommand\022\023\n\013up" + "dateFlags\030\001 \001(\005\022:\n\006params\030\002 \001(\0132*.pybull" + "et_grpc.PhysicsSimulationParameters\"\367\001\n\030" + "JointMotorControlCommand\022\024\n\014bodyUniqueId" + "\030\001 \001(\005\022\023\n\013controlMode\030\002 \001(\005\022\023\n\013updateFla" + "gs\030\003 \001(\005\022\n\n\002Kp\030\004 \003(\001\022\n\n\002Kd\030\005 \003(\001\022\023\n\013maxV" + "elocity\030\006 \003(\001\022\034\n\024hasDesiredStateFlags\030\007 " + "\003(\005\022\025\n\rdesiredStateQ\030\010 \003(\001\022\030\n\020desiredSta" + "teQdot\030\t \003(\001\022\037\n\027desiredStateForceTorque\030" + "\n \003(\001\"\266\003\n\025UserConstraintCommand\022\027\n\017paren" + "tBodyIndex\030\001 \001(\005\022\030\n\020parentJointIndex\030\002 \001" + "(\005\022\026\n\016childBodyIndex\030\003 \001(\005\022\027\n\017childJoint" + "Index\030\004 \001(\005\022-\n\013parentFrame\030\005 \001(\0132\030.pybul" + "let_grpc.transform\022,\n\nchildFrame\030\006 \001(\0132\030" + ".pybullet_grpc.transform\022&\n\tjointAxis\030\007 " + "\001(\0132\023.pybullet_grpc.vec3\022\021\n\tjointType\030\010 " + "\001(\005\022\027\n\017maxAppliedForce\030\t \001(\001\022\036\n\026userCons" + "traintUniqueId\030\n \001(\005\022\021\n\tgearRatio\030\013 \001(\001\022" + "\023\n\013gearAuxLink\030\014 \001(\005\022\036\n\026relativePosition" + "Target\030\r \001(\001\022\013\n\003erp\030\016 \001(\001\022\023\n\013updateFlags" + "\030\017 \001(\005\"O\n\024UserConstraintStatus\022\027\n\017maxApp" + "liedForce\030\t \001(\001\022\036\n\026userConstraintUniqueI" + "d\030\n \001(\005\"\245\001\n\031UserConstraintStateStatus\022:\n" + "\035appliedConstraintForcesLinear\030\001 \001(\0132\023.p" + "ybullet_grpc.vec3\022;\n\036appliedConstraintFo" + "rcesAngular\030\002 \001(\0132\023.pybullet_grpc.vec3\022\017" + "\n\007numDofs\030\003 \001(\005\"\036\n\034RequestKeyboardEvents" + "Command\"2\n\rKeyboardEvent\022\017\n\007keyCode\030\001 \001(" + "\005\022\020\n\010keyState\030\002 \001(\005\"L\n\024KeyboardEventsSta" + "tus\0224\n\016keyboardEvents\030\001 \003(\0132\034.pybullet_g" + "rpc.KeyboardEvent\"\277\004\n\031RequestCameraImage" + "Command\022\023\n\013updateFlags\030\001 \001(\005\022\023\n\013cameraFl" + "ags\030\002 \001(\005\022,\n\nviewMatrix\030\003 \001(\0132\030.pybullet" + "_grpc.matrix4x4\0222\n\020projectionMatrix\030\004 \001(" + "\0132\030.pybullet_grpc.matrix4x4\022\027\n\017startPixe" + "lIndex\030\005 \001(\005\022\022\n\npixelWidth\030\006 \001(\005\022\023\n\013pixe" + "lHeight\030\007 \001(\005\022+\n\016lightDirection\030\010 \001(\0132\023." + "pybullet_grpc.vec3\022\'\n\nlightColor\030\t \001(\0132\023" + ".pybullet_grpc.vec3\022\025\n\rlightDistance\030\n \001" + "(\001\022\031\n\021lightAmbientCoeff\030\013 \001(\001\022\031\n\021lightDi" + "ffuseCoeff\030\014 \001(\001\022\032\n\022lightSpecularCoeff\030\r" + " \001(\001\022\021\n\thasShadow\030\016 \001(\005\022=\n\033projectiveTex" + "tureViewMatrix\030\017 \001(\0132\030.pybullet_grpc.mat" + "rix4x4\022C\n!projectiveTextureProjectionMat" + "rix\030\020 \001(\0132\030.pybullet_grpc.matrix4x4\"\224\001\n\030" + "RequestCameraImageStatus\022\022\n\nimageWidth\030\001" + " \001(\005\022\023\n\013imageHeight\030\002 \001(\005\022\032\n\022startingPix" + "elIndex\030\003 \001(\005\022\027\n\017numPixelsCopied\030\004 \001(\005\022\032" + "\n\022numRemainingPixels\030\005 \001(\005\"\375\n\n\017PyBulletC" + "ommand\022\023\n\013commandType\030\001 \001(\005\022\022\n\nbinaryBlo" + "b\030\002 \003(\014\022 \n\030unknownCommandBinaryBlob\030\003 \003(" + "\014\0229\n\017loadUrdfCommand\030\004 \001(\0132\036.pybullet_gr" + "pc.LoadUrdfCommandH\000\022G\n\026terminateServerC" + "ommand\030\005 \001(\0132%.pybullet_grpc.TerminateSe" + "rverCommandH\000\022E\n\025stepSimulationCommand\030\006" + " \001(\0132$.pybullet_grpc.StepSimulationComma" + "ndH\000\0227\n\016loadSdfCommand\030\007 \001(\0132\035.pybullet_" + "grpc.LoadSdfCommandH\000\0229\n\017loadMjcfCommand" + "\030\010 \001(\0132\036.pybullet_grpc.LoadMjcfCommandH\000" + "\022E\n\025changeDynamicsCommand\030\t \001(\0132$.pybull" + "et_grpc.ChangeDynamicsCommandH\000\022\?\n\022getDy" + "namicsCommand\030\n \001(\0132!.pybullet_grpc.GetD" + "ynamicsCommandH\000\0229\n\017initPoseCommand\030\013 \001(" + "\0132\036.pybullet_grpc.InitPoseCommandH\000\022M\n\031r" + "equestActualStateCommand\030\014 \001(\0132(.pybulle" + "t_grpc.RequestActualStateCommandH\000\022[\n co" + "nfigureOpenGLVisualizerCommand\030\r \001(\0132/.p" + "ybullet_grpc.ConfigureOpenGLVisualizerCo" + "mmandH\000\022=\n\021syncBodiesCommand\030\016 \001(\0132 .pyb" + "ullet_grpc.SyncBodiesCommandH\000\022G\n\026reques" + "tBodyInfoCommand\030\017 \001(\0132%.pybullet_grpc.R" + "equestBodyInfoCommandH\000\022b\n%setPhysicsSim" + "ulationParametersCommand\030\020 \001(\01321.pybulle" + "t_grpc.PhysicsSimulationParametersComman" + "dH\000\022K\n\030jointMotorControlCommand\030\021 \001(\0132\'." + "pybullet_grpc.JointMotorControlCommandH\000" + "\022E\n\025userConstraintCommand\030\022 \001(\0132$.pybull" + "et_grpc.UserConstraintCommandH\000\022A\n\023check" + "VersionCommand\030\023 \001(\0132\".pybullet_grpc.Che" + "ckVersionCommandH\000\022S\n\034requestKeyboardEve" + "ntsCommand\030\024 \001(\0132+.pybullet_grpc.Request" + "KeyboardEventsCommandH\000\022M\n\031requestCamera" + "ImageCommand\030\025 \001(\0132(.pybullet_grpc.Reque" + "stCameraImageCommandH\000B\n\n\010commands\"\321\007\n\016P" + "yBulletStatus\022\022\n\nstatusType\030\001 \001(\005\022\022\n\nbin" + "aryBlob\030\002 \003(\014\022\037\n\027unknownStatusBinaryBlob" + "\030\003 \003(\014\0223\n\nurdfStatus\030\004 \001(\0132\035.pybullet_gr" + "pc.LoadUrdfStatusH\000\0223\n\tsdfStatus\030\005 \001(\0132\036" + ".pybullet_grpc.SdfLoadedStatusH\000\0225\n\nmjcf" + "Status\030\006 \001(\0132\037.pybullet_grpc.MjcfLoadedS" + "tatusH\000\022=\n\021getDynamicsStatus\030\007 \001(\0132 .pyb" + "ullet_grpc.GetDynamicsStatusH\000\022A\n\021actual" + "StateStatus\030\010 \001(\0132$.pybullet_grpc.SendAc" + "tualStateStatusH\000\022;\n\020syncBodiesStatus\030\t " + "\001(\0132\037.pybullet_grpc.SyncBodiesStatusH\000\022E" + "\n\025requestBodyInfoStatus\030\n \001(\0132$.pybullet" + "_grpc.RequestBodyInfoStatusH\000\022^\n(request" + "PhysicsSimulationParametersStatus\030\013 \001(\0132" + "*.pybullet_grpc.PhysicsSimulationParamet" + "ersH\000\022\?\n\022checkVersionStatus\030\014 \001(\0132!.pybu" + "llet_grpc.CheckVersionStatusH\000\022C\n\024userCo" + "nstraintStatus\030\r \001(\0132#.pybullet_grpc.Use" + "rConstraintStatusH\000\022M\n\031userConstraintSta" + "teStatus\030\016 \001(\0132(.pybullet_grpc.UserConst" + "raintStateStatusH\000\022C\n\024keyboardEventsStat" + "us\030\017 \001(\0132#.pybullet_grpc.KeyboardEventsS" + "tatusH\000\022K\n\030requestCameraImageStatus\030\020 \001(" + "\0132\'.pybullet_grpc.RequestCameraImageStat" + "usH\000B\010\n\006status2_\n\013PyBulletAPI\022P\n\rSubmitC" + "ommand\022\036.pybullet_grpc.PyBulletCommand\032\035" + ".pybullet_grpc.PyBulletStatus\"\000B.\n\025io.gr" + "pc.pybullet_grpcB\rPyBulletProtoP\001\242\002\003PBGb" + "\006proto3" }; ::google::protobuf::DescriptorPool::InternalAddGeneratedFile( - descriptor, 3755); + descriptor, 8647); ::google::protobuf::MessageFactory::InternalRegisterGeneratedFile( "pybullet.proto", &protobuf_RegisterTypes); ::google::protobuf::internal::OnShutdown(&TableStruct::Shutdown); @@ -1285,6 +1849,1434 @@ void quat4::set_w(double value) { // =================================================================== +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const int vec4::kXFieldNumber; +const int vec4::kYFieldNumber; +const int vec4::kZFieldNumber; +const int vec4::kWFieldNumber; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 + +vec4::vec4() + : ::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.vec4) +} +vec4::vec4(const vec4& 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.vec4) +} + +void vec4::SharedCtor() { + ::memset(&x_, 0, reinterpret_cast(&w_) - + reinterpret_cast(&x_) + sizeof(w_)); + _cached_size_ = 0; +} + +vec4::~vec4() { + // @@protoc_insertion_point(destructor:pybullet_grpc.vec4) + SharedDtor(); +} + +void vec4::SharedDtor() { +} + +void vec4::SetCachedSize(int size) const { + GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN(); + _cached_size_ = size; + GOOGLE_SAFE_CONCURRENT_WRITES_END(); +} +const ::google::protobuf::Descriptor* vec4::descriptor() { + protobuf_pybullet_2eproto::protobuf_AssignDescriptorsOnce(); + return protobuf_pybullet_2eproto::file_level_metadata[2].descriptor; +} + +const vec4& vec4::default_instance() { + protobuf_pybullet_2eproto::InitDefaults(); + return *internal_default_instance(); +} + +vec4* vec4::New(::google::protobuf::Arena* arena) const { + vec4* n = new vec4; + if (arena != NULL) { + arena->Own(n); + } + return n; +} + +void vec4::Clear() { +// @@protoc_insertion_point(message_clear_start:pybullet_grpc.vec4) + ::memset(&x_, 0, reinterpret_cast(&w_) - + reinterpret_cast(&x_) + sizeof(w_)); +} + +bool vec4::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.vec4) + 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.vec4) + return true; +failure: + // @@protoc_insertion_point(parse_failure:pybullet_grpc.vec4) + return false; +#undef DO_ +} + +void vec4::SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const { + // @@protoc_insertion_point(serialize_start:pybullet_grpc.vec4) + // 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.vec4) +} + +::google::protobuf::uint8* vec4::InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const { + (void)deterministic; // Unused + // @@protoc_insertion_point(serialize_to_array_start:pybullet_grpc.vec4) + // 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.vec4) + return target; +} + +size_t vec4::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:pybullet_grpc.vec4) + 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 vec4::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:pybullet_grpc.vec4) + GOOGLE_DCHECK_NE(&from, this); + const vec4* source = + ::google::protobuf::internal::DynamicCastToGenerated( + &from); + if (source == NULL) { + // @@protoc_insertion_point(generalized_merge_from_cast_fail:pybullet_grpc.vec4) + ::google::protobuf::internal::ReflectionOps::Merge(from, this); + } else { + // @@protoc_insertion_point(generalized_merge_from_cast_success:pybullet_grpc.vec4) + MergeFrom(*source); + } +} + +void vec4::MergeFrom(const vec4& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:pybullet_grpc.vec4) + 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 vec4::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:pybullet_grpc.vec4) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +void vec4::CopyFrom(const vec4& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:pybullet_grpc.vec4) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool vec4::IsInitialized() const { + return true; +} + +void vec4::Swap(vec4* other) { + if (other == this) return; + InternalSwap(other); +} +void vec4::InternalSwap(vec4* 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 vec4::GetMetadata() const { + protobuf_pybullet_2eproto::protobuf_AssignDescriptorsOnce(); + return protobuf_pybullet_2eproto::file_level_metadata[2]; +} + +#if PROTOBUF_INLINE_NOT_IN_HEADERS +// vec4 + +// double x = 1; +void vec4::clear_x() { + x_ = 0; +} +double vec4::x() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.vec4.x) + return x_; +} +void vec4::set_x(double value) { + + x_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.vec4.x) +} + +// double y = 2; +void vec4::clear_y() { + y_ = 0; +} +double vec4::y() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.vec4.y) + return y_; +} +void vec4::set_y(double value) { + + y_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.vec4.y) +} + +// double z = 3; +void vec4::clear_z() { + z_ = 0; +} +double vec4::z() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.vec4.z) + return z_; +} +void vec4::set_z(double value) { + + z_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.vec4.z) +} + +// double w = 4; +void vec4::clear_w() { + w_ = 0; +} +double vec4::w() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.vec4.w) + return w_; +} +void vec4::set_w(double value) { + + w_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.vec4.w) +} + +#endif // PROTOBUF_INLINE_NOT_IN_HEADERS + +// =================================================================== + +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const int transform::kOriginFieldNumber; +const int transform::kOrientationFieldNumber; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 + +transform::transform() + : ::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.transform) +} +transform::transform(const transform& from) + : ::google::protobuf::Message(), + _internal_metadata_(NULL), + _cached_size_(0) { + _internal_metadata_.MergeFrom(from._internal_metadata_); + if (from.has_origin()) { + origin_ = new ::pybullet_grpc::vec3(*from.origin_); + } else { + origin_ = NULL; + } + if (from.has_orientation()) { + orientation_ = new ::pybullet_grpc::quat4(*from.orientation_); + } else { + orientation_ = NULL; + } + // @@protoc_insertion_point(copy_constructor:pybullet_grpc.transform) +} + +void transform::SharedCtor() { + ::memset(&origin_, 0, reinterpret_cast(&orientation_) - + reinterpret_cast(&origin_) + sizeof(orientation_)); + _cached_size_ = 0; +} + +transform::~transform() { + // @@protoc_insertion_point(destructor:pybullet_grpc.transform) + SharedDtor(); +} + +void transform::SharedDtor() { + if (this != internal_default_instance()) { + delete origin_; + } + if (this != internal_default_instance()) { + delete orientation_; + } +} + +void transform::SetCachedSize(int size) const { + GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN(); + _cached_size_ = size; + GOOGLE_SAFE_CONCURRENT_WRITES_END(); +} +const ::google::protobuf::Descriptor* transform::descriptor() { + protobuf_pybullet_2eproto::protobuf_AssignDescriptorsOnce(); + return protobuf_pybullet_2eproto::file_level_metadata[3].descriptor; +} + +const transform& transform::default_instance() { + protobuf_pybullet_2eproto::InitDefaults(); + return *internal_default_instance(); +} + +transform* transform::New(::google::protobuf::Arena* arena) const { + transform* n = new transform; + if (arena != NULL) { + arena->Own(n); + } + return n; +} + +void transform::Clear() { +// @@protoc_insertion_point(message_clear_start:pybullet_grpc.transform) + if (GetArenaNoVirtual() == NULL && origin_ != NULL) { + delete origin_; + } + origin_ = NULL; + if (GetArenaNoVirtual() == NULL && orientation_ != NULL) { + delete orientation_; + } + orientation_ = NULL; +} + +bool transform::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.transform) + 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)) { + // .pybullet_grpc.vec3 origin = 1; + case 1: { + if (tag == 10u) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessageNoVirtual( + input, mutable_origin())); + } else { + goto handle_unusual; + } + break; + } + + // .pybullet_grpc.quat4 orientation = 2; + case 2: { + if (tag == 18u) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessageNoVirtual( + input, mutable_orientation())); + } 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.transform) + return true; +failure: + // @@protoc_insertion_point(parse_failure:pybullet_grpc.transform) + return false; +#undef DO_ +} + +void transform::SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const { + // @@protoc_insertion_point(serialize_start:pybullet_grpc.transform) + // .pybullet_grpc.vec3 origin = 1; + if (this->has_origin()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 1, *this->origin_, output); + } + + // .pybullet_grpc.quat4 orientation = 2; + if (this->has_orientation()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 2, *this->orientation_, output); + } + + // @@protoc_insertion_point(serialize_end:pybullet_grpc.transform) +} + +::google::protobuf::uint8* transform::InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const { + (void)deterministic; // Unused + // @@protoc_insertion_point(serialize_to_array_start:pybullet_grpc.transform) + // .pybullet_grpc.vec3 origin = 1; + if (this->has_origin()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageNoVirtualToArray( + 1, *this->origin_, false, target); + } + + // .pybullet_grpc.quat4 orientation = 2; + if (this->has_orientation()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageNoVirtualToArray( + 2, *this->orientation_, false, target); + } + + // @@protoc_insertion_point(serialize_to_array_end:pybullet_grpc.transform) + return target; +} + +size_t transform::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:pybullet_grpc.transform) + size_t total_size = 0; + + // .pybullet_grpc.vec3 origin = 1; + if (this->has_origin()) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSizeNoVirtual( + *this->origin_); + } + + // .pybullet_grpc.quat4 orientation = 2; + if (this->has_orientation()) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSizeNoVirtual( + *this->orientation_); + } + + 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 transform::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:pybullet_grpc.transform) + GOOGLE_DCHECK_NE(&from, this); + const transform* source = + ::google::protobuf::internal::DynamicCastToGenerated( + &from); + if (source == NULL) { + // @@protoc_insertion_point(generalized_merge_from_cast_fail:pybullet_grpc.transform) + ::google::protobuf::internal::ReflectionOps::Merge(from, this); + } else { + // @@protoc_insertion_point(generalized_merge_from_cast_success:pybullet_grpc.transform) + MergeFrom(*source); + } +} + +void transform::MergeFrom(const transform& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:pybullet_grpc.transform) + GOOGLE_DCHECK_NE(&from, this); + _internal_metadata_.MergeFrom(from._internal_metadata_); + if (from.has_origin()) { + mutable_origin()->::pybullet_grpc::vec3::MergeFrom(from.origin()); + } + if (from.has_orientation()) { + mutable_orientation()->::pybullet_grpc::quat4::MergeFrom(from.orientation()); + } +} + +void transform::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:pybullet_grpc.transform) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +void transform::CopyFrom(const transform& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:pybullet_grpc.transform) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool transform::IsInitialized() const { + return true; +} + +void transform::Swap(transform* other) { + if (other == this) return; + InternalSwap(other); +} +void transform::InternalSwap(transform* other) { + std::swap(origin_, other->origin_); + std::swap(orientation_, other->orientation_); + std::swap(_cached_size_, other->_cached_size_); +} + +::google::protobuf::Metadata transform::GetMetadata() const { + protobuf_pybullet_2eproto::protobuf_AssignDescriptorsOnce(); + return protobuf_pybullet_2eproto::file_level_metadata[3]; +} + +#if PROTOBUF_INLINE_NOT_IN_HEADERS +// transform + +// .pybullet_grpc.vec3 origin = 1; +bool transform::has_origin() const { + return this != internal_default_instance() && origin_ != NULL; +} +void transform::clear_origin() { + if (GetArenaNoVirtual() == NULL && origin_ != NULL) delete origin_; + origin_ = NULL; +} +const ::pybullet_grpc::vec3& transform::origin() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.transform.origin) + return origin_ != NULL ? *origin_ + : *::pybullet_grpc::vec3::internal_default_instance(); +} +::pybullet_grpc::vec3* transform::mutable_origin() { + + if (origin_ == NULL) { + origin_ = new ::pybullet_grpc::vec3; + } + // @@protoc_insertion_point(field_mutable:pybullet_grpc.transform.origin) + return origin_; +} +::pybullet_grpc::vec3* transform::release_origin() { + // @@protoc_insertion_point(field_release:pybullet_grpc.transform.origin) + + ::pybullet_grpc::vec3* temp = origin_; + origin_ = NULL; + return temp; +} +void transform::set_allocated_origin(::pybullet_grpc::vec3* origin) { + delete origin_; + origin_ = origin; + if (origin) { + + } else { + + } + // @@protoc_insertion_point(field_set_allocated:pybullet_grpc.transform.origin) +} + +// .pybullet_grpc.quat4 orientation = 2; +bool transform::has_orientation() const { + return this != internal_default_instance() && orientation_ != NULL; +} +void transform::clear_orientation() { + if (GetArenaNoVirtual() == NULL && orientation_ != NULL) delete orientation_; + orientation_ = NULL; +} +const ::pybullet_grpc::quat4& transform::orientation() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.transform.orientation) + return orientation_ != NULL ? *orientation_ + : *::pybullet_grpc::quat4::internal_default_instance(); +} +::pybullet_grpc::quat4* transform::mutable_orientation() { + + if (orientation_ == NULL) { + orientation_ = new ::pybullet_grpc::quat4; + } + // @@protoc_insertion_point(field_mutable:pybullet_grpc.transform.orientation) + return orientation_; +} +::pybullet_grpc::quat4* transform::release_orientation() { + // @@protoc_insertion_point(field_release:pybullet_grpc.transform.orientation) + + ::pybullet_grpc::quat4* temp = orientation_; + orientation_ = NULL; + return temp; +} +void transform::set_allocated_orientation(::pybullet_grpc::quat4* orientation) { + delete orientation_; + orientation_ = orientation; + if (orientation) { + + } else { + + } + // @@protoc_insertion_point(field_set_allocated:pybullet_grpc.transform.orientation) +} + +#endif // PROTOBUF_INLINE_NOT_IN_HEADERS + +// =================================================================== + +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const int matrix4x4::kElemsFieldNumber; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 + +matrix4x4::matrix4x4() + : ::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.matrix4x4) +} +matrix4x4::matrix4x4(const matrix4x4& from) + : ::google::protobuf::Message(), + _internal_metadata_(NULL), + elems_(from.elems_), + _cached_size_(0) { + _internal_metadata_.MergeFrom(from._internal_metadata_); + // @@protoc_insertion_point(copy_constructor:pybullet_grpc.matrix4x4) +} + +void matrix4x4::SharedCtor() { + _cached_size_ = 0; +} + +matrix4x4::~matrix4x4() { + // @@protoc_insertion_point(destructor:pybullet_grpc.matrix4x4) + SharedDtor(); +} + +void matrix4x4::SharedDtor() { +} + +void matrix4x4::SetCachedSize(int size) const { + GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN(); + _cached_size_ = size; + GOOGLE_SAFE_CONCURRENT_WRITES_END(); +} +const ::google::protobuf::Descriptor* matrix4x4::descriptor() { + protobuf_pybullet_2eproto::protobuf_AssignDescriptorsOnce(); + return protobuf_pybullet_2eproto::file_level_metadata[4].descriptor; +} + +const matrix4x4& matrix4x4::default_instance() { + protobuf_pybullet_2eproto::InitDefaults(); + return *internal_default_instance(); +} + +matrix4x4* matrix4x4::New(::google::protobuf::Arena* arena) const { + matrix4x4* n = new matrix4x4; + if (arena != NULL) { + arena->Own(n); + } + return n; +} + +void matrix4x4::Clear() { +// @@protoc_insertion_point(message_clear_start:pybullet_grpc.matrix4x4) + elems_.Clear(); +} + +bool matrix4x4::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.matrix4x4) + 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)) { + // repeated double elems = 1; + case 1: { + if (tag == 10u) { + DO_((::google::protobuf::internal::WireFormatLite::ReadPackedPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, this->mutable_elems()))); + } else if (tag == 9u) { + DO_((::google::protobuf::internal::WireFormatLite::ReadRepeatedPrimitiveNoInline< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + 1, 10u, input, this->mutable_elems()))); + } 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.matrix4x4) + return true; +failure: + // @@protoc_insertion_point(parse_failure:pybullet_grpc.matrix4x4) + return false; +#undef DO_ +} + +void matrix4x4::SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const { + // @@protoc_insertion_point(serialize_start:pybullet_grpc.matrix4x4) + // repeated double elems = 1; + if (this->elems_size() > 0) { + ::google::protobuf::internal::WireFormatLite::WriteTag(1, ::google::protobuf::internal::WireFormatLite::WIRETYPE_LENGTH_DELIMITED, output); + output->WriteVarint32(_elems_cached_byte_size_); + ::google::protobuf::internal::WireFormatLite::WriteDoubleArray( + this->elems().data(), this->elems_size(), output); + } + + // @@protoc_insertion_point(serialize_end:pybullet_grpc.matrix4x4) +} + +::google::protobuf::uint8* matrix4x4::InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const { + (void)deterministic; // Unused + // @@protoc_insertion_point(serialize_to_array_start:pybullet_grpc.matrix4x4) + // repeated double elems = 1; + if (this->elems_size() > 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteTagToArray( + 1, + ::google::protobuf::internal::WireFormatLite::WIRETYPE_LENGTH_DELIMITED, + target); + target = ::google::protobuf::io::CodedOutputStream::WriteVarint32ToArray( + _elems_cached_byte_size_, target); + } + for (int i = 0; i < this->elems_size(); i++) { + target = ::google::protobuf::internal::WireFormatLite:: + WriteDoubleNoTagToArray(this->elems(i), target); + } + + // @@protoc_insertion_point(serialize_to_array_end:pybullet_grpc.matrix4x4) + return target; +} + +size_t matrix4x4::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:pybullet_grpc.matrix4x4) + size_t total_size = 0; + + // repeated double elems = 1; + { + unsigned int count = this->elems_size(); + size_t data_size = 8UL * count; + if (data_size > 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::Int32Size(data_size); + } + int cached_size = ::google::protobuf::internal::ToCachedSize(data_size); + GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN(); + _elems_cached_byte_size_ = cached_size; + GOOGLE_SAFE_CONCURRENT_WRITES_END(); + total_size += data_size; + } + + 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 matrix4x4::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:pybullet_grpc.matrix4x4) + GOOGLE_DCHECK_NE(&from, this); + const matrix4x4* source = + ::google::protobuf::internal::DynamicCastToGenerated( + &from); + if (source == NULL) { + // @@protoc_insertion_point(generalized_merge_from_cast_fail:pybullet_grpc.matrix4x4) + ::google::protobuf::internal::ReflectionOps::Merge(from, this); + } else { + // @@protoc_insertion_point(generalized_merge_from_cast_success:pybullet_grpc.matrix4x4) + MergeFrom(*source); + } +} + +void matrix4x4::MergeFrom(const matrix4x4& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:pybullet_grpc.matrix4x4) + GOOGLE_DCHECK_NE(&from, this); + _internal_metadata_.MergeFrom(from._internal_metadata_); + elems_.MergeFrom(from.elems_); +} + +void matrix4x4::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:pybullet_grpc.matrix4x4) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +void matrix4x4::CopyFrom(const matrix4x4& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:pybullet_grpc.matrix4x4) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool matrix4x4::IsInitialized() const { + return true; +} + +void matrix4x4::Swap(matrix4x4* other) { + if (other == this) return; + InternalSwap(other); +} +void matrix4x4::InternalSwap(matrix4x4* other) { + elems_.UnsafeArenaSwap(&other->elems_); + std::swap(_cached_size_, other->_cached_size_); +} + +::google::protobuf::Metadata matrix4x4::GetMetadata() const { + protobuf_pybullet_2eproto::protobuf_AssignDescriptorsOnce(); + return protobuf_pybullet_2eproto::file_level_metadata[4]; +} + +#if PROTOBUF_INLINE_NOT_IN_HEADERS +// matrix4x4 + +// repeated double elems = 1; +int matrix4x4::elems_size() const { + return elems_.size(); +} +void matrix4x4::clear_elems() { + elems_.Clear(); +} +double matrix4x4::elems(int index) const { + // @@protoc_insertion_point(field_get:pybullet_grpc.matrix4x4.elems) + return elems_.Get(index); +} +void matrix4x4::set_elems(int index, double value) { + elems_.Set(index, value); + // @@protoc_insertion_point(field_set:pybullet_grpc.matrix4x4.elems) +} +void matrix4x4::add_elems(double value) { + elems_.Add(value); + // @@protoc_insertion_point(field_add:pybullet_grpc.matrix4x4.elems) +} +const ::google::protobuf::RepeatedField< double >& +matrix4x4::elems() const { + // @@protoc_insertion_point(field_list:pybullet_grpc.matrix4x4.elems) + return elems_; +} +::google::protobuf::RepeatedField< double >* +matrix4x4::mutable_elems() { + // @@protoc_insertion_point(field_mutable_list:pybullet_grpc.matrix4x4.elems) + return &elems_; +} + +#endif // PROTOBUF_INLINE_NOT_IN_HEADERS + +// =================================================================== + +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const int CheckVersionCommand::kClientVersionFieldNumber; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 + +CheckVersionCommand::CheckVersionCommand() + : ::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.CheckVersionCommand) +} +CheckVersionCommand::CheckVersionCommand(const CheckVersionCommand& from) + : ::google::protobuf::Message(), + _internal_metadata_(NULL), + _cached_size_(0) { + _internal_metadata_.MergeFrom(from._internal_metadata_); + clientversion_ = from.clientversion_; + // @@protoc_insertion_point(copy_constructor:pybullet_grpc.CheckVersionCommand) +} + +void CheckVersionCommand::SharedCtor() { + clientversion_ = 0; + _cached_size_ = 0; +} + +CheckVersionCommand::~CheckVersionCommand() { + // @@protoc_insertion_point(destructor:pybullet_grpc.CheckVersionCommand) + SharedDtor(); +} + +void CheckVersionCommand::SharedDtor() { +} + +void CheckVersionCommand::SetCachedSize(int size) const { + GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN(); + _cached_size_ = size; + GOOGLE_SAFE_CONCURRENT_WRITES_END(); +} +const ::google::protobuf::Descriptor* CheckVersionCommand::descriptor() { + protobuf_pybullet_2eproto::protobuf_AssignDescriptorsOnce(); + return protobuf_pybullet_2eproto::file_level_metadata[5].descriptor; +} + +const CheckVersionCommand& CheckVersionCommand::default_instance() { + protobuf_pybullet_2eproto::InitDefaults(); + return *internal_default_instance(); +} + +CheckVersionCommand* CheckVersionCommand::New(::google::protobuf::Arena* arena) const { + CheckVersionCommand* n = new CheckVersionCommand; + if (arena != NULL) { + arena->Own(n); + } + return n; +} + +void CheckVersionCommand::Clear() { +// @@protoc_insertion_point(message_clear_start:pybullet_grpc.CheckVersionCommand) + clientversion_ = 0; +} + +bool CheckVersionCommand::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.CheckVersionCommand) + 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 clientVersion = 1; + case 1: { + if (tag == 8u) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>( + input, &clientversion_))); + } 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.CheckVersionCommand) + return true; +failure: + // @@protoc_insertion_point(parse_failure:pybullet_grpc.CheckVersionCommand) + return false; +#undef DO_ +} + +void CheckVersionCommand::SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const { + // @@protoc_insertion_point(serialize_start:pybullet_grpc.CheckVersionCommand) + // int32 clientVersion = 1; + if (this->clientversion() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteInt32(1, this->clientversion(), output); + } + + // @@protoc_insertion_point(serialize_end:pybullet_grpc.CheckVersionCommand) +} + +::google::protobuf::uint8* CheckVersionCommand::InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const { + (void)deterministic; // Unused + // @@protoc_insertion_point(serialize_to_array_start:pybullet_grpc.CheckVersionCommand) + // int32 clientVersion = 1; + if (this->clientversion() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteInt32ToArray(1, this->clientversion(), target); + } + + // @@protoc_insertion_point(serialize_to_array_end:pybullet_grpc.CheckVersionCommand) + return target; +} + +size_t CheckVersionCommand::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:pybullet_grpc.CheckVersionCommand) + size_t total_size = 0; + + // int32 clientVersion = 1; + if (this->clientversion() != 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::Int32Size( + this->clientversion()); + } + + 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 CheckVersionCommand::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:pybullet_grpc.CheckVersionCommand) + GOOGLE_DCHECK_NE(&from, this); + const CheckVersionCommand* source = + ::google::protobuf::internal::DynamicCastToGenerated( + &from); + if (source == NULL) { + // @@protoc_insertion_point(generalized_merge_from_cast_fail:pybullet_grpc.CheckVersionCommand) + ::google::protobuf::internal::ReflectionOps::Merge(from, this); + } else { + // @@protoc_insertion_point(generalized_merge_from_cast_success:pybullet_grpc.CheckVersionCommand) + MergeFrom(*source); + } +} + +void CheckVersionCommand::MergeFrom(const CheckVersionCommand& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:pybullet_grpc.CheckVersionCommand) + GOOGLE_DCHECK_NE(&from, this); + _internal_metadata_.MergeFrom(from._internal_metadata_); + if (from.clientversion() != 0) { + set_clientversion(from.clientversion()); + } +} + +void CheckVersionCommand::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:pybullet_grpc.CheckVersionCommand) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +void CheckVersionCommand::CopyFrom(const CheckVersionCommand& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:pybullet_grpc.CheckVersionCommand) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool CheckVersionCommand::IsInitialized() const { + return true; +} + +void CheckVersionCommand::Swap(CheckVersionCommand* other) { + if (other == this) return; + InternalSwap(other); +} +void CheckVersionCommand::InternalSwap(CheckVersionCommand* other) { + std::swap(clientversion_, other->clientversion_); + std::swap(_cached_size_, other->_cached_size_); +} + +::google::protobuf::Metadata CheckVersionCommand::GetMetadata() const { + protobuf_pybullet_2eproto::protobuf_AssignDescriptorsOnce(); + return protobuf_pybullet_2eproto::file_level_metadata[5]; +} + +#if PROTOBUF_INLINE_NOT_IN_HEADERS +// CheckVersionCommand + +// int32 clientVersion = 1; +void CheckVersionCommand::clear_clientversion() { + clientversion_ = 0; +} +::google::protobuf::int32 CheckVersionCommand::clientversion() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.CheckVersionCommand.clientVersion) + return clientversion_; +} +void CheckVersionCommand::set_clientversion(::google::protobuf::int32 value) { + + clientversion_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.CheckVersionCommand.clientVersion) +} + +#endif // PROTOBUF_INLINE_NOT_IN_HEADERS + +// =================================================================== + +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const int CheckVersionStatus::kServerVersionFieldNumber; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 + +CheckVersionStatus::CheckVersionStatus() + : ::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.CheckVersionStatus) +} +CheckVersionStatus::CheckVersionStatus(const CheckVersionStatus& from) + : ::google::protobuf::Message(), + _internal_metadata_(NULL), + _cached_size_(0) { + _internal_metadata_.MergeFrom(from._internal_metadata_); + serverversion_ = from.serverversion_; + // @@protoc_insertion_point(copy_constructor:pybullet_grpc.CheckVersionStatus) +} + +void CheckVersionStatus::SharedCtor() { + serverversion_ = 0; + _cached_size_ = 0; +} + +CheckVersionStatus::~CheckVersionStatus() { + // @@protoc_insertion_point(destructor:pybullet_grpc.CheckVersionStatus) + SharedDtor(); +} + +void CheckVersionStatus::SharedDtor() { +} + +void CheckVersionStatus::SetCachedSize(int size) const { + GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN(); + _cached_size_ = size; + GOOGLE_SAFE_CONCURRENT_WRITES_END(); +} +const ::google::protobuf::Descriptor* CheckVersionStatus::descriptor() { + protobuf_pybullet_2eproto::protobuf_AssignDescriptorsOnce(); + return protobuf_pybullet_2eproto::file_level_metadata[6].descriptor; +} + +const CheckVersionStatus& CheckVersionStatus::default_instance() { + protobuf_pybullet_2eproto::InitDefaults(); + return *internal_default_instance(); +} + +CheckVersionStatus* CheckVersionStatus::New(::google::protobuf::Arena* arena) const { + CheckVersionStatus* n = new CheckVersionStatus; + if (arena != NULL) { + arena->Own(n); + } + return n; +} + +void CheckVersionStatus::Clear() { +// @@protoc_insertion_point(message_clear_start:pybullet_grpc.CheckVersionStatus) + serverversion_ = 0; +} + +bool CheckVersionStatus::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.CheckVersionStatus) + 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 serverVersion = 1; + case 1: { + if (tag == 8u) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>( + input, &serverversion_))); + } 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.CheckVersionStatus) + return true; +failure: + // @@protoc_insertion_point(parse_failure:pybullet_grpc.CheckVersionStatus) + return false; +#undef DO_ +} + +void CheckVersionStatus::SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const { + // @@protoc_insertion_point(serialize_start:pybullet_grpc.CheckVersionStatus) + // int32 serverVersion = 1; + if (this->serverversion() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteInt32(1, this->serverversion(), output); + } + + // @@protoc_insertion_point(serialize_end:pybullet_grpc.CheckVersionStatus) +} + +::google::protobuf::uint8* CheckVersionStatus::InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const { + (void)deterministic; // Unused + // @@protoc_insertion_point(serialize_to_array_start:pybullet_grpc.CheckVersionStatus) + // int32 serverVersion = 1; + if (this->serverversion() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteInt32ToArray(1, this->serverversion(), target); + } + + // @@protoc_insertion_point(serialize_to_array_end:pybullet_grpc.CheckVersionStatus) + return target; +} + +size_t CheckVersionStatus::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:pybullet_grpc.CheckVersionStatus) + size_t total_size = 0; + + // int32 serverVersion = 1; + if (this->serverversion() != 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::Int32Size( + this->serverversion()); + } + + 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 CheckVersionStatus::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:pybullet_grpc.CheckVersionStatus) + GOOGLE_DCHECK_NE(&from, this); + const CheckVersionStatus* source = + ::google::protobuf::internal::DynamicCastToGenerated( + &from); + if (source == NULL) { + // @@protoc_insertion_point(generalized_merge_from_cast_fail:pybullet_grpc.CheckVersionStatus) + ::google::protobuf::internal::ReflectionOps::Merge(from, this); + } else { + // @@protoc_insertion_point(generalized_merge_from_cast_success:pybullet_grpc.CheckVersionStatus) + MergeFrom(*source); + } +} + +void CheckVersionStatus::MergeFrom(const CheckVersionStatus& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:pybullet_grpc.CheckVersionStatus) + GOOGLE_DCHECK_NE(&from, this); + _internal_metadata_.MergeFrom(from._internal_metadata_); + if (from.serverversion() != 0) { + set_serverversion(from.serverversion()); + } +} + +void CheckVersionStatus::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:pybullet_grpc.CheckVersionStatus) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +void CheckVersionStatus::CopyFrom(const CheckVersionStatus& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:pybullet_grpc.CheckVersionStatus) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool CheckVersionStatus::IsInitialized() const { + return true; +} + +void CheckVersionStatus::Swap(CheckVersionStatus* other) { + if (other == this) return; + InternalSwap(other); +} +void CheckVersionStatus::InternalSwap(CheckVersionStatus* other) { + std::swap(serverversion_, other->serverversion_); + std::swap(_cached_size_, other->_cached_size_); +} + +::google::protobuf::Metadata CheckVersionStatus::GetMetadata() const { + protobuf_pybullet_2eproto::protobuf_AssignDescriptorsOnce(); + return protobuf_pybullet_2eproto::file_level_metadata[6]; +} + +#if PROTOBUF_INLINE_NOT_IN_HEADERS +// CheckVersionStatus + +// int32 serverVersion = 1; +void CheckVersionStatus::clear_serverversion() { + serverversion_ = 0; +} +::google::protobuf::int32 CheckVersionStatus::serverversion() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.CheckVersionStatus.serverVersion) + return serverversion_; +} +void CheckVersionStatus::set_serverversion(::google::protobuf::int32 value) { + + serverversion_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.CheckVersionStatus.serverVersion) +} + +#endif // PROTOBUF_INLINE_NOT_IN_HEADERS + +// =================================================================== + #if !defined(_MSC_VER) || _MSC_VER >= 1900 const int TerminateServerCommand::kExitReasonFieldNumber; #endif // !defined(_MSC_VER) || _MSC_VER >= 1900 @@ -1330,7 +3322,7 @@ void TerminateServerCommand::SetCachedSize(int size) const { } const ::google::protobuf::Descriptor* TerminateServerCommand::descriptor() { protobuf_pybullet_2eproto::protobuf_AssignDescriptorsOnce(); - return protobuf_pybullet_2eproto::file_level_metadata[2].descriptor; + return protobuf_pybullet_2eproto::file_level_metadata[7].descriptor; } const TerminateServerCommand& TerminateServerCommand::default_instance() { @@ -1504,7 +3496,7 @@ void TerminateServerCommand::InternalSwap(TerminateServerCommand* other) { ::google::protobuf::Metadata TerminateServerCommand::GetMetadata() const { protobuf_pybullet_2eproto::protobuf_AssignDescriptorsOnce(); - return protobuf_pybullet_2eproto::file_level_metadata[2]; + return protobuf_pybullet_2eproto::file_level_metadata[7]; } #if PROTOBUF_INLINE_NOT_IN_HEADERS @@ -1604,7 +3596,7 @@ void StepSimulationCommand::SetCachedSize(int size) const { } const ::google::protobuf::Descriptor* StepSimulationCommand::descriptor() { protobuf_pybullet_2eproto::protobuf_AssignDescriptorsOnce(); - return protobuf_pybullet_2eproto::file_level_metadata[3].descriptor; + return protobuf_pybullet_2eproto::file_level_metadata[8].descriptor; } const StepSimulationCommand& StepSimulationCommand::default_instance() { @@ -1724,7 +3716,7 @@ void StepSimulationCommand::InternalSwap(StepSimulationCommand* other) { ::google::protobuf::Metadata StepSimulationCommand::GetMetadata() const { protobuf_pybullet_2eproto::protobuf_AssignDescriptorsOnce(); - return protobuf_pybullet_2eproto::file_level_metadata[3]; + return protobuf_pybullet_2eproto::file_level_metadata[8]; } #if PROTOBUF_INLINE_NOT_IN_HEADERS @@ -1734,6 +3726,1085 @@ void StepSimulationCommand::InternalSwap(StepSimulationCommand* other) { // =================================================================== +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 + +SyncBodiesCommand::SyncBodiesCommand() + : ::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.SyncBodiesCommand) +} +SyncBodiesCommand::SyncBodiesCommand(const SyncBodiesCommand& from) + : ::google::protobuf::Message(), + _internal_metadata_(NULL), + _cached_size_(0) { + _internal_metadata_.MergeFrom(from._internal_metadata_); + // @@protoc_insertion_point(copy_constructor:pybullet_grpc.SyncBodiesCommand) +} + +void SyncBodiesCommand::SharedCtor() { + _cached_size_ = 0; +} + +SyncBodiesCommand::~SyncBodiesCommand() { + // @@protoc_insertion_point(destructor:pybullet_grpc.SyncBodiesCommand) + SharedDtor(); +} + +void SyncBodiesCommand::SharedDtor() { +} + +void SyncBodiesCommand::SetCachedSize(int size) const { + GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN(); + _cached_size_ = size; + GOOGLE_SAFE_CONCURRENT_WRITES_END(); +} +const ::google::protobuf::Descriptor* SyncBodiesCommand::descriptor() { + protobuf_pybullet_2eproto::protobuf_AssignDescriptorsOnce(); + return protobuf_pybullet_2eproto::file_level_metadata[9].descriptor; +} + +const SyncBodiesCommand& SyncBodiesCommand::default_instance() { + protobuf_pybullet_2eproto::InitDefaults(); + return *internal_default_instance(); +} + +SyncBodiesCommand* SyncBodiesCommand::New(::google::protobuf::Arena* arena) const { + SyncBodiesCommand* n = new SyncBodiesCommand; + if (arena != NULL) { + arena->Own(n); + } + return n; +} + +void SyncBodiesCommand::Clear() { +// @@protoc_insertion_point(message_clear_start:pybullet_grpc.SyncBodiesCommand) +} + +bool SyncBodiesCommand::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.SyncBodiesCommand) + 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.SyncBodiesCommand) + return true; +failure: + // @@protoc_insertion_point(parse_failure:pybullet_grpc.SyncBodiesCommand) + return false; +#undef DO_ +} + +void SyncBodiesCommand::SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const { + // @@protoc_insertion_point(serialize_start:pybullet_grpc.SyncBodiesCommand) + // @@protoc_insertion_point(serialize_end:pybullet_grpc.SyncBodiesCommand) +} + +::google::protobuf::uint8* SyncBodiesCommand::InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const { + (void)deterministic; // Unused + // @@protoc_insertion_point(serialize_to_array_start:pybullet_grpc.SyncBodiesCommand) + // @@protoc_insertion_point(serialize_to_array_end:pybullet_grpc.SyncBodiesCommand) + return target; +} + +size_t SyncBodiesCommand::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:pybullet_grpc.SyncBodiesCommand) + 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 SyncBodiesCommand::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:pybullet_grpc.SyncBodiesCommand) + GOOGLE_DCHECK_NE(&from, this); + const SyncBodiesCommand* source = + ::google::protobuf::internal::DynamicCastToGenerated( + &from); + if (source == NULL) { + // @@protoc_insertion_point(generalized_merge_from_cast_fail:pybullet_grpc.SyncBodiesCommand) + ::google::protobuf::internal::ReflectionOps::Merge(from, this); + } else { + // @@protoc_insertion_point(generalized_merge_from_cast_success:pybullet_grpc.SyncBodiesCommand) + MergeFrom(*source); + } +} + +void SyncBodiesCommand::MergeFrom(const SyncBodiesCommand& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:pybullet_grpc.SyncBodiesCommand) + GOOGLE_DCHECK_NE(&from, this); + _internal_metadata_.MergeFrom(from._internal_metadata_); +} + +void SyncBodiesCommand::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:pybullet_grpc.SyncBodiesCommand) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +void SyncBodiesCommand::CopyFrom(const SyncBodiesCommand& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:pybullet_grpc.SyncBodiesCommand) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool SyncBodiesCommand::IsInitialized() const { + return true; +} + +void SyncBodiesCommand::Swap(SyncBodiesCommand* other) { + if (other == this) return; + InternalSwap(other); +} +void SyncBodiesCommand::InternalSwap(SyncBodiesCommand* other) { + std::swap(_cached_size_, other->_cached_size_); +} + +::google::protobuf::Metadata SyncBodiesCommand::GetMetadata() const { + protobuf_pybullet_2eproto::protobuf_AssignDescriptorsOnce(); + return protobuf_pybullet_2eproto::file_level_metadata[9]; +} + +#if PROTOBUF_INLINE_NOT_IN_HEADERS +// SyncBodiesCommand + +#endif // PROTOBUF_INLINE_NOT_IN_HEADERS + +// =================================================================== + +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const int SyncBodiesStatus::kBodyUniqueIdsFieldNumber; +const int SyncBodiesStatus::kUserConstraintUniqueIdsFieldNumber; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 + +SyncBodiesStatus::SyncBodiesStatus() + : ::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.SyncBodiesStatus) +} +SyncBodiesStatus::SyncBodiesStatus(const SyncBodiesStatus& from) + : ::google::protobuf::Message(), + _internal_metadata_(NULL), + bodyuniqueids_(from.bodyuniqueids_), + userconstraintuniqueids_(from.userconstraintuniqueids_), + _cached_size_(0) { + _internal_metadata_.MergeFrom(from._internal_metadata_); + // @@protoc_insertion_point(copy_constructor:pybullet_grpc.SyncBodiesStatus) +} + +void SyncBodiesStatus::SharedCtor() { + _cached_size_ = 0; +} + +SyncBodiesStatus::~SyncBodiesStatus() { + // @@protoc_insertion_point(destructor:pybullet_grpc.SyncBodiesStatus) + SharedDtor(); +} + +void SyncBodiesStatus::SharedDtor() { +} + +void SyncBodiesStatus::SetCachedSize(int size) const { + GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN(); + _cached_size_ = size; + GOOGLE_SAFE_CONCURRENT_WRITES_END(); +} +const ::google::protobuf::Descriptor* SyncBodiesStatus::descriptor() { + protobuf_pybullet_2eproto::protobuf_AssignDescriptorsOnce(); + return protobuf_pybullet_2eproto::file_level_metadata[10].descriptor; +} + +const SyncBodiesStatus& SyncBodiesStatus::default_instance() { + protobuf_pybullet_2eproto::InitDefaults(); + return *internal_default_instance(); +} + +SyncBodiesStatus* SyncBodiesStatus::New(::google::protobuf::Arena* arena) const { + SyncBodiesStatus* n = new SyncBodiesStatus; + if (arena != NULL) { + arena->Own(n); + } + return n; +} + +void SyncBodiesStatus::Clear() { +// @@protoc_insertion_point(message_clear_start:pybullet_grpc.SyncBodiesStatus) + bodyuniqueids_.Clear(); + userconstraintuniqueids_.Clear(); +} + +bool SyncBodiesStatus::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.SyncBodiesStatus) + 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)) { + // repeated int32 bodyUniqueIds = 1; + case 1: { + if (tag == 10u) { + DO_((::google::protobuf::internal::WireFormatLite::ReadPackedPrimitive< + ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>( + input, this->mutable_bodyuniqueids()))); + } else if (tag == 8u) { + DO_((::google::protobuf::internal::WireFormatLite::ReadRepeatedPrimitiveNoInline< + ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>( + 1, 10u, input, this->mutable_bodyuniqueids()))); + } else { + goto handle_unusual; + } + break; + } + + // repeated int32 userConstraintUniqueIds = 2; + case 2: { + if (tag == 18u) { + DO_((::google::protobuf::internal::WireFormatLite::ReadPackedPrimitive< + ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>( + input, this->mutable_userconstraintuniqueids()))); + } else if (tag == 16u) { + DO_((::google::protobuf::internal::WireFormatLite::ReadRepeatedPrimitiveNoInline< + ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>( + 1, 18u, input, this->mutable_userconstraintuniqueids()))); + } 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.SyncBodiesStatus) + return true; +failure: + // @@protoc_insertion_point(parse_failure:pybullet_grpc.SyncBodiesStatus) + return false; +#undef DO_ +} + +void SyncBodiesStatus::SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const { + // @@protoc_insertion_point(serialize_start:pybullet_grpc.SyncBodiesStatus) + // repeated int32 bodyUniqueIds = 1; + if (this->bodyuniqueids_size() > 0) { + ::google::protobuf::internal::WireFormatLite::WriteTag(1, ::google::protobuf::internal::WireFormatLite::WIRETYPE_LENGTH_DELIMITED, output); + output->WriteVarint32(_bodyuniqueids_cached_byte_size_); + } + for (int i = 0; i < this->bodyuniqueids_size(); i++) { + ::google::protobuf::internal::WireFormatLite::WriteInt32NoTag( + this->bodyuniqueids(i), output); + } + + // repeated int32 userConstraintUniqueIds = 2; + if (this->userconstraintuniqueids_size() > 0) { + ::google::protobuf::internal::WireFormatLite::WriteTag(2, ::google::protobuf::internal::WireFormatLite::WIRETYPE_LENGTH_DELIMITED, output); + output->WriteVarint32(_userconstraintuniqueids_cached_byte_size_); + } + for (int i = 0; i < this->userconstraintuniqueids_size(); i++) { + ::google::protobuf::internal::WireFormatLite::WriteInt32NoTag( + this->userconstraintuniqueids(i), output); + } + + // @@protoc_insertion_point(serialize_end:pybullet_grpc.SyncBodiesStatus) +} + +::google::protobuf::uint8* SyncBodiesStatus::InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const { + (void)deterministic; // Unused + // @@protoc_insertion_point(serialize_to_array_start:pybullet_grpc.SyncBodiesStatus) + // repeated int32 bodyUniqueIds = 1; + if (this->bodyuniqueids_size() > 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteTagToArray( + 1, + ::google::protobuf::internal::WireFormatLite::WIRETYPE_LENGTH_DELIMITED, + target); + target = ::google::protobuf::io::CodedOutputStream::WriteVarint32ToArray( + _bodyuniqueids_cached_byte_size_, target); + } + for (int i = 0; i < this->bodyuniqueids_size(); i++) { + target = ::google::protobuf::internal::WireFormatLite:: + WriteInt32NoTagToArray(this->bodyuniqueids(i), target); + } + + // repeated int32 userConstraintUniqueIds = 2; + if (this->userconstraintuniqueids_size() > 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteTagToArray( + 2, + ::google::protobuf::internal::WireFormatLite::WIRETYPE_LENGTH_DELIMITED, + target); + target = ::google::protobuf::io::CodedOutputStream::WriteVarint32ToArray( + _userconstraintuniqueids_cached_byte_size_, target); + } + for (int i = 0; i < this->userconstraintuniqueids_size(); i++) { + target = ::google::protobuf::internal::WireFormatLite:: + WriteInt32NoTagToArray(this->userconstraintuniqueids(i), target); + } + + // @@protoc_insertion_point(serialize_to_array_end:pybullet_grpc.SyncBodiesStatus) + return target; +} + +size_t SyncBodiesStatus::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:pybullet_grpc.SyncBodiesStatus) + size_t total_size = 0; + + // repeated int32 bodyUniqueIds = 1; + { + size_t data_size = ::google::protobuf::internal::WireFormatLite:: + Int32Size(this->bodyuniqueids_); + if (data_size > 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::Int32Size(data_size); + } + int cached_size = ::google::protobuf::internal::ToCachedSize(data_size); + GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN(); + _bodyuniqueids_cached_byte_size_ = cached_size; + GOOGLE_SAFE_CONCURRENT_WRITES_END(); + total_size += data_size; + } + + // repeated int32 userConstraintUniqueIds = 2; + { + size_t data_size = ::google::protobuf::internal::WireFormatLite:: + Int32Size(this->userconstraintuniqueids_); + if (data_size > 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::Int32Size(data_size); + } + int cached_size = ::google::protobuf::internal::ToCachedSize(data_size); + GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN(); + _userconstraintuniqueids_cached_byte_size_ = cached_size; + GOOGLE_SAFE_CONCURRENT_WRITES_END(); + total_size += data_size; + } + + 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 SyncBodiesStatus::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:pybullet_grpc.SyncBodiesStatus) + GOOGLE_DCHECK_NE(&from, this); + const SyncBodiesStatus* source = + ::google::protobuf::internal::DynamicCastToGenerated( + &from); + if (source == NULL) { + // @@protoc_insertion_point(generalized_merge_from_cast_fail:pybullet_grpc.SyncBodiesStatus) + ::google::protobuf::internal::ReflectionOps::Merge(from, this); + } else { + // @@protoc_insertion_point(generalized_merge_from_cast_success:pybullet_grpc.SyncBodiesStatus) + MergeFrom(*source); + } +} + +void SyncBodiesStatus::MergeFrom(const SyncBodiesStatus& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:pybullet_grpc.SyncBodiesStatus) + GOOGLE_DCHECK_NE(&from, this); + _internal_metadata_.MergeFrom(from._internal_metadata_); + bodyuniqueids_.MergeFrom(from.bodyuniqueids_); + userconstraintuniqueids_.MergeFrom(from.userconstraintuniqueids_); +} + +void SyncBodiesStatus::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:pybullet_grpc.SyncBodiesStatus) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +void SyncBodiesStatus::CopyFrom(const SyncBodiesStatus& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:pybullet_grpc.SyncBodiesStatus) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool SyncBodiesStatus::IsInitialized() const { + return true; +} + +void SyncBodiesStatus::Swap(SyncBodiesStatus* other) { + if (other == this) return; + InternalSwap(other); +} +void SyncBodiesStatus::InternalSwap(SyncBodiesStatus* other) { + bodyuniqueids_.UnsafeArenaSwap(&other->bodyuniqueids_); + userconstraintuniqueids_.UnsafeArenaSwap(&other->userconstraintuniqueids_); + std::swap(_cached_size_, other->_cached_size_); +} + +::google::protobuf::Metadata SyncBodiesStatus::GetMetadata() const { + protobuf_pybullet_2eproto::protobuf_AssignDescriptorsOnce(); + return protobuf_pybullet_2eproto::file_level_metadata[10]; +} + +#if PROTOBUF_INLINE_NOT_IN_HEADERS +// SyncBodiesStatus + +// repeated int32 bodyUniqueIds = 1; +int SyncBodiesStatus::bodyuniqueids_size() const { + return bodyuniqueids_.size(); +} +void SyncBodiesStatus::clear_bodyuniqueids() { + bodyuniqueids_.Clear(); +} +::google::protobuf::int32 SyncBodiesStatus::bodyuniqueids(int index) const { + // @@protoc_insertion_point(field_get:pybullet_grpc.SyncBodiesStatus.bodyUniqueIds) + return bodyuniqueids_.Get(index); +} +void SyncBodiesStatus::set_bodyuniqueids(int index, ::google::protobuf::int32 value) { + bodyuniqueids_.Set(index, value); + // @@protoc_insertion_point(field_set:pybullet_grpc.SyncBodiesStatus.bodyUniqueIds) +} +void SyncBodiesStatus::add_bodyuniqueids(::google::protobuf::int32 value) { + bodyuniqueids_.Add(value); + // @@protoc_insertion_point(field_add:pybullet_grpc.SyncBodiesStatus.bodyUniqueIds) +} +const ::google::protobuf::RepeatedField< ::google::protobuf::int32 >& +SyncBodiesStatus::bodyuniqueids() const { + // @@protoc_insertion_point(field_list:pybullet_grpc.SyncBodiesStatus.bodyUniqueIds) + return bodyuniqueids_; +} +::google::protobuf::RepeatedField< ::google::protobuf::int32 >* +SyncBodiesStatus::mutable_bodyuniqueids() { + // @@protoc_insertion_point(field_mutable_list:pybullet_grpc.SyncBodiesStatus.bodyUniqueIds) + return &bodyuniqueids_; +} + +// repeated int32 userConstraintUniqueIds = 2; +int SyncBodiesStatus::userconstraintuniqueids_size() const { + return userconstraintuniqueids_.size(); +} +void SyncBodiesStatus::clear_userconstraintuniqueids() { + userconstraintuniqueids_.Clear(); +} +::google::protobuf::int32 SyncBodiesStatus::userconstraintuniqueids(int index) const { + // @@protoc_insertion_point(field_get:pybullet_grpc.SyncBodiesStatus.userConstraintUniqueIds) + return userconstraintuniqueids_.Get(index); +} +void SyncBodiesStatus::set_userconstraintuniqueids(int index, ::google::protobuf::int32 value) { + userconstraintuniqueids_.Set(index, value); + // @@protoc_insertion_point(field_set:pybullet_grpc.SyncBodiesStatus.userConstraintUniqueIds) +} +void SyncBodiesStatus::add_userconstraintuniqueids(::google::protobuf::int32 value) { + userconstraintuniqueids_.Add(value); + // @@protoc_insertion_point(field_add:pybullet_grpc.SyncBodiesStatus.userConstraintUniqueIds) +} +const ::google::protobuf::RepeatedField< ::google::protobuf::int32 >& +SyncBodiesStatus::userconstraintuniqueids() const { + // @@protoc_insertion_point(field_list:pybullet_grpc.SyncBodiesStatus.userConstraintUniqueIds) + return userconstraintuniqueids_; +} +::google::protobuf::RepeatedField< ::google::protobuf::int32 >* +SyncBodiesStatus::mutable_userconstraintuniqueids() { + // @@protoc_insertion_point(field_mutable_list:pybullet_grpc.SyncBodiesStatus.userConstraintUniqueIds) + return &userconstraintuniqueids_; +} + +#endif // PROTOBUF_INLINE_NOT_IN_HEADERS + +// =================================================================== + +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const int RequestBodyInfoCommand::kBodyUniqueIdFieldNumber; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 + +RequestBodyInfoCommand::RequestBodyInfoCommand() + : ::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.RequestBodyInfoCommand) +} +RequestBodyInfoCommand::RequestBodyInfoCommand(const RequestBodyInfoCommand& from) + : ::google::protobuf::Message(), + _internal_metadata_(NULL), + _cached_size_(0) { + _internal_metadata_.MergeFrom(from._internal_metadata_); + bodyuniqueid_ = from.bodyuniqueid_; + // @@protoc_insertion_point(copy_constructor:pybullet_grpc.RequestBodyInfoCommand) +} + +void RequestBodyInfoCommand::SharedCtor() { + bodyuniqueid_ = 0; + _cached_size_ = 0; +} + +RequestBodyInfoCommand::~RequestBodyInfoCommand() { + // @@protoc_insertion_point(destructor:pybullet_grpc.RequestBodyInfoCommand) + SharedDtor(); +} + +void RequestBodyInfoCommand::SharedDtor() { +} + +void RequestBodyInfoCommand::SetCachedSize(int size) const { + GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN(); + _cached_size_ = size; + GOOGLE_SAFE_CONCURRENT_WRITES_END(); +} +const ::google::protobuf::Descriptor* RequestBodyInfoCommand::descriptor() { + protobuf_pybullet_2eproto::protobuf_AssignDescriptorsOnce(); + return protobuf_pybullet_2eproto::file_level_metadata[11].descriptor; +} + +const RequestBodyInfoCommand& RequestBodyInfoCommand::default_instance() { + protobuf_pybullet_2eproto::InitDefaults(); + return *internal_default_instance(); +} + +RequestBodyInfoCommand* RequestBodyInfoCommand::New(::google::protobuf::Arena* arena) const { + RequestBodyInfoCommand* n = new RequestBodyInfoCommand; + if (arena != NULL) { + arena->Own(n); + } + return n; +} + +void RequestBodyInfoCommand::Clear() { +// @@protoc_insertion_point(message_clear_start:pybullet_grpc.RequestBodyInfoCommand) + bodyuniqueid_ = 0; +} + +bool RequestBodyInfoCommand::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.RequestBodyInfoCommand) + 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 bodyUniqueId = 1; + case 1: { + if (tag == 8u) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>( + input, &bodyuniqueid_))); + } 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.RequestBodyInfoCommand) + return true; +failure: + // @@protoc_insertion_point(parse_failure:pybullet_grpc.RequestBodyInfoCommand) + return false; +#undef DO_ +} + +void RequestBodyInfoCommand::SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const { + // @@protoc_insertion_point(serialize_start:pybullet_grpc.RequestBodyInfoCommand) + // int32 bodyUniqueId = 1; + if (this->bodyuniqueid() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteInt32(1, this->bodyuniqueid(), output); + } + + // @@protoc_insertion_point(serialize_end:pybullet_grpc.RequestBodyInfoCommand) +} + +::google::protobuf::uint8* RequestBodyInfoCommand::InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const { + (void)deterministic; // Unused + // @@protoc_insertion_point(serialize_to_array_start:pybullet_grpc.RequestBodyInfoCommand) + // int32 bodyUniqueId = 1; + if (this->bodyuniqueid() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteInt32ToArray(1, this->bodyuniqueid(), target); + } + + // @@protoc_insertion_point(serialize_to_array_end:pybullet_grpc.RequestBodyInfoCommand) + return target; +} + +size_t RequestBodyInfoCommand::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:pybullet_grpc.RequestBodyInfoCommand) + size_t total_size = 0; + + // int32 bodyUniqueId = 1; + if (this->bodyuniqueid() != 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::Int32Size( + this->bodyuniqueid()); + } + + 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 RequestBodyInfoCommand::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:pybullet_grpc.RequestBodyInfoCommand) + GOOGLE_DCHECK_NE(&from, this); + const RequestBodyInfoCommand* source = + ::google::protobuf::internal::DynamicCastToGenerated( + &from); + if (source == NULL) { + // @@protoc_insertion_point(generalized_merge_from_cast_fail:pybullet_grpc.RequestBodyInfoCommand) + ::google::protobuf::internal::ReflectionOps::Merge(from, this); + } else { + // @@protoc_insertion_point(generalized_merge_from_cast_success:pybullet_grpc.RequestBodyInfoCommand) + MergeFrom(*source); + } +} + +void RequestBodyInfoCommand::MergeFrom(const RequestBodyInfoCommand& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:pybullet_grpc.RequestBodyInfoCommand) + GOOGLE_DCHECK_NE(&from, this); + _internal_metadata_.MergeFrom(from._internal_metadata_); + if (from.bodyuniqueid() != 0) { + set_bodyuniqueid(from.bodyuniqueid()); + } +} + +void RequestBodyInfoCommand::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:pybullet_grpc.RequestBodyInfoCommand) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +void RequestBodyInfoCommand::CopyFrom(const RequestBodyInfoCommand& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:pybullet_grpc.RequestBodyInfoCommand) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool RequestBodyInfoCommand::IsInitialized() const { + return true; +} + +void RequestBodyInfoCommand::Swap(RequestBodyInfoCommand* other) { + if (other == this) return; + InternalSwap(other); +} +void RequestBodyInfoCommand::InternalSwap(RequestBodyInfoCommand* other) { + std::swap(bodyuniqueid_, other->bodyuniqueid_); + std::swap(_cached_size_, other->_cached_size_); +} + +::google::protobuf::Metadata RequestBodyInfoCommand::GetMetadata() const { + protobuf_pybullet_2eproto::protobuf_AssignDescriptorsOnce(); + return protobuf_pybullet_2eproto::file_level_metadata[11]; +} + +#if PROTOBUF_INLINE_NOT_IN_HEADERS +// RequestBodyInfoCommand + +// int32 bodyUniqueId = 1; +void RequestBodyInfoCommand::clear_bodyuniqueid() { + bodyuniqueid_ = 0; +} +::google::protobuf::int32 RequestBodyInfoCommand::bodyuniqueid() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.RequestBodyInfoCommand.bodyUniqueId) + return bodyuniqueid_; +} +void RequestBodyInfoCommand::set_bodyuniqueid(::google::protobuf::int32 value) { + + bodyuniqueid_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.RequestBodyInfoCommand.bodyUniqueId) +} + +#endif // PROTOBUF_INLINE_NOT_IN_HEADERS + +// =================================================================== + +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const int RequestBodyInfoStatus::kBodyUniqueIdFieldNumber; +const int RequestBodyInfoStatus::kBodyNameFieldNumber; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 + +RequestBodyInfoStatus::RequestBodyInfoStatus() + : ::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.RequestBodyInfoStatus) +} +RequestBodyInfoStatus::RequestBodyInfoStatus(const RequestBodyInfoStatus& from) + : ::google::protobuf::Message(), + _internal_metadata_(NULL), + _cached_size_(0) { + _internal_metadata_.MergeFrom(from._internal_metadata_); + bodyname_.UnsafeSetDefault(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); + if (from.bodyname().size() > 0) { + bodyname_.AssignWithDefault(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), from.bodyname_); + } + bodyuniqueid_ = from.bodyuniqueid_; + // @@protoc_insertion_point(copy_constructor:pybullet_grpc.RequestBodyInfoStatus) +} + +void RequestBodyInfoStatus::SharedCtor() { + bodyname_.UnsafeSetDefault(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); + bodyuniqueid_ = 0; + _cached_size_ = 0; +} + +RequestBodyInfoStatus::~RequestBodyInfoStatus() { + // @@protoc_insertion_point(destructor:pybullet_grpc.RequestBodyInfoStatus) + SharedDtor(); +} + +void RequestBodyInfoStatus::SharedDtor() { + bodyname_.DestroyNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); +} + +void RequestBodyInfoStatus::SetCachedSize(int size) const { + GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN(); + _cached_size_ = size; + GOOGLE_SAFE_CONCURRENT_WRITES_END(); +} +const ::google::protobuf::Descriptor* RequestBodyInfoStatus::descriptor() { + protobuf_pybullet_2eproto::protobuf_AssignDescriptorsOnce(); + return protobuf_pybullet_2eproto::file_level_metadata[12].descriptor; +} + +const RequestBodyInfoStatus& RequestBodyInfoStatus::default_instance() { + protobuf_pybullet_2eproto::InitDefaults(); + return *internal_default_instance(); +} + +RequestBodyInfoStatus* RequestBodyInfoStatus::New(::google::protobuf::Arena* arena) const { + RequestBodyInfoStatus* n = new RequestBodyInfoStatus; + if (arena != NULL) { + arena->Own(n); + } + return n; +} + +void RequestBodyInfoStatus::Clear() { +// @@protoc_insertion_point(message_clear_start:pybullet_grpc.RequestBodyInfoStatus) + bodyname_.ClearToEmptyNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); + bodyuniqueid_ = 0; +} + +bool RequestBodyInfoStatus::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.RequestBodyInfoStatus) + 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 bodyUniqueId = 1; + case 1: { + if (tag == 8u) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>( + input, &bodyuniqueid_))); + } else { + goto handle_unusual; + } + break; + } + + // string bodyName = 2; + case 2: { + if (tag == 18u) { + DO_(::google::protobuf::internal::WireFormatLite::ReadString( + input, this->mutable_bodyname())); + DO_(::google::protobuf::internal::WireFormatLite::VerifyUtf8String( + this->bodyname().data(), this->bodyname().length(), + ::google::protobuf::internal::WireFormatLite::PARSE, + "pybullet_grpc.RequestBodyInfoStatus.bodyName")); + } 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.RequestBodyInfoStatus) + return true; +failure: + // @@protoc_insertion_point(parse_failure:pybullet_grpc.RequestBodyInfoStatus) + return false; +#undef DO_ +} + +void RequestBodyInfoStatus::SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const { + // @@protoc_insertion_point(serialize_start:pybullet_grpc.RequestBodyInfoStatus) + // int32 bodyUniqueId = 1; + if (this->bodyuniqueid() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteInt32(1, this->bodyuniqueid(), output); + } + + // string bodyName = 2; + if (this->bodyname().size() > 0) { + ::google::protobuf::internal::WireFormatLite::VerifyUtf8String( + this->bodyname().data(), this->bodyname().length(), + ::google::protobuf::internal::WireFormatLite::SERIALIZE, + "pybullet_grpc.RequestBodyInfoStatus.bodyName"); + ::google::protobuf::internal::WireFormatLite::WriteStringMaybeAliased( + 2, this->bodyname(), output); + } + + // @@protoc_insertion_point(serialize_end:pybullet_grpc.RequestBodyInfoStatus) +} + +::google::protobuf::uint8* RequestBodyInfoStatus::InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const { + (void)deterministic; // Unused + // @@protoc_insertion_point(serialize_to_array_start:pybullet_grpc.RequestBodyInfoStatus) + // int32 bodyUniqueId = 1; + if (this->bodyuniqueid() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteInt32ToArray(1, this->bodyuniqueid(), target); + } + + // string bodyName = 2; + if (this->bodyname().size() > 0) { + ::google::protobuf::internal::WireFormatLite::VerifyUtf8String( + this->bodyname().data(), this->bodyname().length(), + ::google::protobuf::internal::WireFormatLite::SERIALIZE, + "pybullet_grpc.RequestBodyInfoStatus.bodyName"); + target = + ::google::protobuf::internal::WireFormatLite::WriteStringToArray( + 2, this->bodyname(), target); + } + + // @@protoc_insertion_point(serialize_to_array_end:pybullet_grpc.RequestBodyInfoStatus) + return target; +} + +size_t RequestBodyInfoStatus::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:pybullet_grpc.RequestBodyInfoStatus) + size_t total_size = 0; + + // string bodyName = 2; + if (this->bodyname().size() > 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::StringSize( + this->bodyname()); + } + + // int32 bodyUniqueId = 1; + if (this->bodyuniqueid() != 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::Int32Size( + this->bodyuniqueid()); + } + + 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 RequestBodyInfoStatus::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:pybullet_grpc.RequestBodyInfoStatus) + GOOGLE_DCHECK_NE(&from, this); + const RequestBodyInfoStatus* source = + ::google::protobuf::internal::DynamicCastToGenerated( + &from); + if (source == NULL) { + // @@protoc_insertion_point(generalized_merge_from_cast_fail:pybullet_grpc.RequestBodyInfoStatus) + ::google::protobuf::internal::ReflectionOps::Merge(from, this); + } else { + // @@protoc_insertion_point(generalized_merge_from_cast_success:pybullet_grpc.RequestBodyInfoStatus) + MergeFrom(*source); + } +} + +void RequestBodyInfoStatus::MergeFrom(const RequestBodyInfoStatus& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:pybullet_grpc.RequestBodyInfoStatus) + GOOGLE_DCHECK_NE(&from, this); + _internal_metadata_.MergeFrom(from._internal_metadata_); + if (from.bodyname().size() > 0) { + + bodyname_.AssignWithDefault(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), from.bodyname_); + } + if (from.bodyuniqueid() != 0) { + set_bodyuniqueid(from.bodyuniqueid()); + } +} + +void RequestBodyInfoStatus::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:pybullet_grpc.RequestBodyInfoStatus) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +void RequestBodyInfoStatus::CopyFrom(const RequestBodyInfoStatus& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:pybullet_grpc.RequestBodyInfoStatus) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool RequestBodyInfoStatus::IsInitialized() const { + return true; +} + +void RequestBodyInfoStatus::Swap(RequestBodyInfoStatus* other) { + if (other == this) return; + InternalSwap(other); +} +void RequestBodyInfoStatus::InternalSwap(RequestBodyInfoStatus* other) { + bodyname_.Swap(&other->bodyname_); + std::swap(bodyuniqueid_, other->bodyuniqueid_); + std::swap(_cached_size_, other->_cached_size_); +} + +::google::protobuf::Metadata RequestBodyInfoStatus::GetMetadata() const { + protobuf_pybullet_2eproto::protobuf_AssignDescriptorsOnce(); + return protobuf_pybullet_2eproto::file_level_metadata[12]; +} + +#if PROTOBUF_INLINE_NOT_IN_HEADERS +// RequestBodyInfoStatus + +// int32 bodyUniqueId = 1; +void RequestBodyInfoStatus::clear_bodyuniqueid() { + bodyuniqueid_ = 0; +} +::google::protobuf::int32 RequestBodyInfoStatus::bodyuniqueid() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.RequestBodyInfoStatus.bodyUniqueId) + return bodyuniqueid_; +} +void RequestBodyInfoStatus::set_bodyuniqueid(::google::protobuf::int32 value) { + + bodyuniqueid_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.RequestBodyInfoStatus.bodyUniqueId) +} + +// string bodyName = 2; +void RequestBodyInfoStatus::clear_bodyname() { + bodyname_.ClearToEmptyNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); +} +const ::std::string& RequestBodyInfoStatus::bodyname() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.RequestBodyInfoStatus.bodyName) + return bodyname_.GetNoArena(); +} +void RequestBodyInfoStatus::set_bodyname(const ::std::string& value) { + + bodyname_.SetNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), value); + // @@protoc_insertion_point(field_set:pybullet_grpc.RequestBodyInfoStatus.bodyName) +} +#if LANG_CXX11 +void RequestBodyInfoStatus::set_bodyname(::std::string&& value) { + + bodyname_.SetNoArena( + &::google::protobuf::internal::GetEmptyStringAlreadyInited(), std::move(value)); + // @@protoc_insertion_point(field_set_rvalue:pybullet_grpc.RequestBodyInfoStatus.bodyName) +} +#endif +void RequestBodyInfoStatus::set_bodyname(const char* value) { + + bodyname_.SetNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), ::std::string(value)); + // @@protoc_insertion_point(field_set_char:pybullet_grpc.RequestBodyInfoStatus.bodyName) +} +void RequestBodyInfoStatus::set_bodyname(const char* value, size_t size) { + + bodyname_.SetNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), + ::std::string(reinterpret_cast(value), size)); + // @@protoc_insertion_point(field_set_pointer:pybullet_grpc.RequestBodyInfoStatus.bodyName) +} +::std::string* RequestBodyInfoStatus::mutable_bodyname() { + + // @@protoc_insertion_point(field_mutable:pybullet_grpc.RequestBodyInfoStatus.bodyName) + return bodyname_.MutableNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); +} +::std::string* RequestBodyInfoStatus::release_bodyname() { + // @@protoc_insertion_point(field_release:pybullet_grpc.RequestBodyInfoStatus.bodyName) + + return bodyname_.ReleaseNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); +} +void RequestBodyInfoStatus::set_allocated_bodyname(::std::string* bodyname) { + if (bodyname != NULL) { + + } else { + + } + bodyname_.SetAllocatedNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), bodyname); + // @@protoc_insertion_point(field_set_allocated:pybullet_grpc.RequestBodyInfoStatus.bodyName) +} + +#endif // PROTOBUF_INLINE_NOT_IN_HEADERS + +// =================================================================== + #if !defined(_MSC_VER) || _MSC_VER >= 1900 const int LoadUrdfCommand::kFileNameFieldNumber; const int LoadUrdfCommand::kInitialPositionFieldNumber; @@ -1846,7 +4917,7 @@ void LoadUrdfCommand::SetCachedSize(int size) const { } const ::google::protobuf::Descriptor* LoadUrdfCommand::descriptor() { protobuf_pybullet_2eproto::protobuf_AssignDescriptorsOnce(); - return protobuf_pybullet_2eproto::file_level_metadata[4].descriptor; + return protobuf_pybullet_2eproto::file_level_metadata[13].descriptor; } const LoadUrdfCommand& LoadUrdfCommand::default_instance() { @@ -2316,7 +5387,7 @@ void LoadUrdfCommand::InternalSwap(LoadUrdfCommand* other) { ::google::protobuf::Metadata LoadUrdfCommand::GetMetadata() const { protobuf_pybullet_2eproto::protobuf_AssignDescriptorsOnce(); - return protobuf_pybullet_2eproto::file_level_metadata[4]; + return protobuf_pybullet_2eproto::file_level_metadata[13]; } #if PROTOBUF_INLINE_NOT_IN_HEADERS @@ -2586,6 +5657,8 @@ LoadUrdfCommand::HasGlobalScalingCase LoadUrdfCommand::hasGlobalScaling_case() c #if !defined(_MSC_VER) || _MSC_VER >= 1900 const int LoadUrdfStatus::kBodyUniqueIdFieldNumber; +const int LoadUrdfStatus::kBodyNameFieldNumber; +const int LoadUrdfStatus::kFileNameFieldNumber; #endif // !defined(_MSC_VER) || _MSC_VER >= 1900 LoadUrdfStatus::LoadUrdfStatus() @@ -2601,11 +5674,21 @@ LoadUrdfStatus::LoadUrdfStatus(const LoadUrdfStatus& from) _internal_metadata_(NULL), _cached_size_(0) { _internal_metadata_.MergeFrom(from._internal_metadata_); + bodyname_.UnsafeSetDefault(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); + if (from.bodyname().size() > 0) { + bodyname_.AssignWithDefault(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), from.bodyname_); + } + filename_.UnsafeSetDefault(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); + if (from.filename().size() > 0) { + filename_.AssignWithDefault(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), from.filename_); + } bodyuniqueid_ = from.bodyuniqueid_; // @@protoc_insertion_point(copy_constructor:pybullet_grpc.LoadUrdfStatus) } void LoadUrdfStatus::SharedCtor() { + bodyname_.UnsafeSetDefault(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); + filename_.UnsafeSetDefault(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); bodyuniqueid_ = 0; _cached_size_ = 0; } @@ -2616,6 +5699,8 @@ LoadUrdfStatus::~LoadUrdfStatus() { } void LoadUrdfStatus::SharedDtor() { + bodyname_.DestroyNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); + filename_.DestroyNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); } void LoadUrdfStatus::SetCachedSize(int size) const { @@ -2625,7 +5710,7 @@ void LoadUrdfStatus::SetCachedSize(int size) const { } const ::google::protobuf::Descriptor* LoadUrdfStatus::descriptor() { protobuf_pybullet_2eproto::protobuf_AssignDescriptorsOnce(); - return protobuf_pybullet_2eproto::file_level_metadata[5].descriptor; + return protobuf_pybullet_2eproto::file_level_metadata[14].descriptor; } const LoadUrdfStatus& LoadUrdfStatus::default_instance() { @@ -2643,6 +5728,8 @@ LoadUrdfStatus* LoadUrdfStatus::New(::google::protobuf::Arena* arena) const { void LoadUrdfStatus::Clear() { // @@protoc_insertion_point(message_clear_start:pybullet_grpc.LoadUrdfStatus) + bodyname_.ClearToEmptyNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); + filename_.ClearToEmptyNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); bodyuniqueid_ = 0; } @@ -2669,6 +5756,36 @@ bool LoadUrdfStatus::MergePartialFromCodedStream( break; } + // string bodyName = 2; + case 2: { + if (tag == 18u) { + DO_(::google::protobuf::internal::WireFormatLite::ReadString( + input, this->mutable_bodyname())); + DO_(::google::protobuf::internal::WireFormatLite::VerifyUtf8String( + this->bodyname().data(), this->bodyname().length(), + ::google::protobuf::internal::WireFormatLite::PARSE, + "pybullet_grpc.LoadUrdfStatus.bodyName")); + } else { + goto handle_unusual; + } + break; + } + + // string fileName = 3; + case 3: { + if (tag == 26u) { + DO_(::google::protobuf::internal::WireFormatLite::ReadString( + input, this->mutable_filename())); + DO_(::google::protobuf::internal::WireFormatLite::VerifyUtf8String( + this->filename().data(), this->filename().length(), + ::google::protobuf::internal::WireFormatLite::PARSE, + "pybullet_grpc.LoadUrdfStatus.fileName")); + } else { + goto handle_unusual; + } + break; + } + default: { handle_unusual: if (tag == 0 || @@ -2698,6 +5815,26 @@ void LoadUrdfStatus::SerializeWithCachedSizes( ::google::protobuf::internal::WireFormatLite::WriteInt32(1, this->bodyuniqueid(), output); } + // string bodyName = 2; + if (this->bodyname().size() > 0) { + ::google::protobuf::internal::WireFormatLite::VerifyUtf8String( + this->bodyname().data(), this->bodyname().length(), + ::google::protobuf::internal::WireFormatLite::SERIALIZE, + "pybullet_grpc.LoadUrdfStatus.bodyName"); + ::google::protobuf::internal::WireFormatLite::WriteStringMaybeAliased( + 2, this->bodyname(), output); + } + + // string fileName = 3; + if (this->filename().size() > 0) { + ::google::protobuf::internal::WireFormatLite::VerifyUtf8String( + this->filename().data(), this->filename().length(), + ::google::protobuf::internal::WireFormatLite::SERIALIZE, + "pybullet_grpc.LoadUrdfStatus.fileName"); + ::google::protobuf::internal::WireFormatLite::WriteStringMaybeAliased( + 3, this->filename(), output); + } + // @@protoc_insertion_point(serialize_end:pybullet_grpc.LoadUrdfStatus) } @@ -2710,6 +5847,28 @@ void LoadUrdfStatus::SerializeWithCachedSizes( target = ::google::protobuf::internal::WireFormatLite::WriteInt32ToArray(1, this->bodyuniqueid(), target); } + // string bodyName = 2; + if (this->bodyname().size() > 0) { + ::google::protobuf::internal::WireFormatLite::VerifyUtf8String( + this->bodyname().data(), this->bodyname().length(), + ::google::protobuf::internal::WireFormatLite::SERIALIZE, + "pybullet_grpc.LoadUrdfStatus.bodyName"); + target = + ::google::protobuf::internal::WireFormatLite::WriteStringToArray( + 2, this->bodyname(), target); + } + + // string fileName = 3; + if (this->filename().size() > 0) { + ::google::protobuf::internal::WireFormatLite::VerifyUtf8String( + this->filename().data(), this->filename().length(), + ::google::protobuf::internal::WireFormatLite::SERIALIZE, + "pybullet_grpc.LoadUrdfStatus.fileName"); + target = + ::google::protobuf::internal::WireFormatLite::WriteStringToArray( + 3, this->filename(), target); + } + // @@protoc_insertion_point(serialize_to_array_end:pybullet_grpc.LoadUrdfStatus) return target; } @@ -2718,6 +5877,20 @@ size_t LoadUrdfStatus::ByteSizeLong() const { // @@protoc_insertion_point(message_byte_size_start:pybullet_grpc.LoadUrdfStatus) size_t total_size = 0; + // string bodyName = 2; + if (this->bodyname().size() > 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::StringSize( + this->bodyname()); + } + + // string fileName = 3; + if (this->filename().size() > 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::StringSize( + this->filename()); + } + // int32 bodyUniqueId = 1; if (this->bodyuniqueid() != 0) { total_size += 1 + @@ -2751,6 +5924,14 @@ 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.bodyname().size() > 0) { + + bodyname_.AssignWithDefault(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), from.bodyname_); + } + if (from.filename().size() > 0) { + + filename_.AssignWithDefault(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), from.filename_); + } if (from.bodyuniqueid() != 0) { set_bodyuniqueid(from.bodyuniqueid()); } @@ -2779,13 +5960,15 @@ void LoadUrdfStatus::Swap(LoadUrdfStatus* other) { InternalSwap(other); } void LoadUrdfStatus::InternalSwap(LoadUrdfStatus* other) { + bodyname_.Swap(&other->bodyname_); + filename_.Swap(&other->filename_); std::swap(bodyuniqueid_, other->bodyuniqueid_); 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]; + return protobuf_pybullet_2eproto::file_level_metadata[14]; } #if PROTOBUF_INLINE_NOT_IN_HEADERS @@ -2805,6 +5988,110 @@ void LoadUrdfStatus::set_bodyuniqueid(::google::protobuf::int32 value) { // @@protoc_insertion_point(field_set:pybullet_grpc.LoadUrdfStatus.bodyUniqueId) } +// string bodyName = 2; +void LoadUrdfStatus::clear_bodyname() { + bodyname_.ClearToEmptyNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); +} +const ::std::string& LoadUrdfStatus::bodyname() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.LoadUrdfStatus.bodyName) + return bodyname_.GetNoArena(); +} +void LoadUrdfStatus::set_bodyname(const ::std::string& value) { + + bodyname_.SetNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), value); + // @@protoc_insertion_point(field_set:pybullet_grpc.LoadUrdfStatus.bodyName) +} +#if LANG_CXX11 +void LoadUrdfStatus::set_bodyname(::std::string&& value) { + + bodyname_.SetNoArena( + &::google::protobuf::internal::GetEmptyStringAlreadyInited(), std::move(value)); + // @@protoc_insertion_point(field_set_rvalue:pybullet_grpc.LoadUrdfStatus.bodyName) +} +#endif +void LoadUrdfStatus::set_bodyname(const char* value) { + + bodyname_.SetNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), ::std::string(value)); + // @@protoc_insertion_point(field_set_char:pybullet_grpc.LoadUrdfStatus.bodyName) +} +void LoadUrdfStatus::set_bodyname(const char* value, size_t size) { + + bodyname_.SetNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), + ::std::string(reinterpret_cast(value), size)); + // @@protoc_insertion_point(field_set_pointer:pybullet_grpc.LoadUrdfStatus.bodyName) +} +::std::string* LoadUrdfStatus::mutable_bodyname() { + + // @@protoc_insertion_point(field_mutable:pybullet_grpc.LoadUrdfStatus.bodyName) + return bodyname_.MutableNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); +} +::std::string* LoadUrdfStatus::release_bodyname() { + // @@protoc_insertion_point(field_release:pybullet_grpc.LoadUrdfStatus.bodyName) + + return bodyname_.ReleaseNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); +} +void LoadUrdfStatus::set_allocated_bodyname(::std::string* bodyname) { + if (bodyname != NULL) { + + } else { + + } + bodyname_.SetAllocatedNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), bodyname); + // @@protoc_insertion_point(field_set_allocated:pybullet_grpc.LoadUrdfStatus.bodyName) +} + +// string fileName = 3; +void LoadUrdfStatus::clear_filename() { + filename_.ClearToEmptyNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); +} +const ::std::string& LoadUrdfStatus::filename() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.LoadUrdfStatus.fileName) + return filename_.GetNoArena(); +} +void LoadUrdfStatus::set_filename(const ::std::string& value) { + + filename_.SetNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), value); + // @@protoc_insertion_point(field_set:pybullet_grpc.LoadUrdfStatus.fileName) +} +#if LANG_CXX11 +void LoadUrdfStatus::set_filename(::std::string&& value) { + + filename_.SetNoArena( + &::google::protobuf::internal::GetEmptyStringAlreadyInited(), std::move(value)); + // @@protoc_insertion_point(field_set_rvalue:pybullet_grpc.LoadUrdfStatus.fileName) +} +#endif +void LoadUrdfStatus::set_filename(const char* value) { + + filename_.SetNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), ::std::string(value)); + // @@protoc_insertion_point(field_set_char:pybullet_grpc.LoadUrdfStatus.fileName) +} +void LoadUrdfStatus::set_filename(const char* value, size_t size) { + + filename_.SetNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), + ::std::string(reinterpret_cast(value), size)); + // @@protoc_insertion_point(field_set_pointer:pybullet_grpc.LoadUrdfStatus.fileName) +} +::std::string* LoadUrdfStatus::mutable_filename() { + + // @@protoc_insertion_point(field_mutable:pybullet_grpc.LoadUrdfStatus.fileName) + return filename_.MutableNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); +} +::std::string* LoadUrdfStatus::release_filename() { + // @@protoc_insertion_point(field_release:pybullet_grpc.LoadUrdfStatus.fileName) + + return filename_.ReleaseNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); +} +void LoadUrdfStatus::set_allocated_filename(::std::string* filename) { + if (filename != NULL) { + + } else { + + } + filename_.SetAllocatedNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), filename); + // @@protoc_insertion_point(field_set_allocated:pybullet_grpc.LoadUrdfStatus.fileName) +} + #endif // PROTOBUF_INLINE_NOT_IN_HEADERS // =================================================================== @@ -2884,7 +6171,7 @@ void LoadSdfCommand::SetCachedSize(int size) const { } const ::google::protobuf::Descriptor* LoadSdfCommand::descriptor() { protobuf_pybullet_2eproto::protobuf_AssignDescriptorsOnce(); - return protobuf_pybullet_2eproto::file_level_metadata[6].descriptor; + return protobuf_pybullet_2eproto::file_level_metadata[15].descriptor; } const LoadSdfCommand& LoadSdfCommand::default_instance() { @@ -3181,7 +6468,7 @@ void LoadSdfCommand::InternalSwap(LoadSdfCommand* other) { ::google::protobuf::Metadata LoadSdfCommand::GetMetadata() const { protobuf_pybullet_2eproto::protobuf_AssignDescriptorsOnce(); - return protobuf_pybullet_2eproto::file_level_metadata[6]; + return protobuf_pybullet_2eproto::file_level_metadata[15]; } #if PROTOBUF_INLINE_NOT_IN_HEADERS @@ -3359,7 +6646,7 @@ void SdfLoadedStatus::SetCachedSize(int size) const { } const ::google::protobuf::Descriptor* SdfLoadedStatus::descriptor() { protobuf_pybullet_2eproto::protobuf_AssignDescriptorsOnce(); - return protobuf_pybullet_2eproto::file_level_metadata[7].descriptor; + return protobuf_pybullet_2eproto::file_level_metadata[16].descriptor; } const SdfLoadedStatus& SdfLoadedStatus::default_instance() { @@ -3542,7 +6829,7 @@ void SdfLoadedStatus::InternalSwap(SdfLoadedStatus* other) { ::google::protobuf::Metadata SdfLoadedStatus::GetMetadata() const { protobuf_pybullet_2eproto::protobuf_AssignDescriptorsOnce(); - return protobuf_pybullet_2eproto::file_level_metadata[7]; + return protobuf_pybullet_2eproto::file_level_metadata[16]; } #if PROTOBUF_INLINE_NOT_IN_HEADERS @@ -3630,7 +6917,7 @@ void LoadMjcfCommand::SetCachedSize(int size) const { } const ::google::protobuf::Descriptor* LoadMjcfCommand::descriptor() { protobuf_pybullet_2eproto::protobuf_AssignDescriptorsOnce(); - return protobuf_pybullet_2eproto::file_level_metadata[8].descriptor; + return protobuf_pybullet_2eproto::file_level_metadata[17].descriptor; } const LoadMjcfCommand& LoadMjcfCommand::default_instance() { @@ -3839,7 +7126,7 @@ void LoadMjcfCommand::InternalSwap(LoadMjcfCommand* other) { ::google::protobuf::Metadata LoadMjcfCommand::GetMetadata() const { protobuf_pybullet_2eproto::protobuf_AssignDescriptorsOnce(); - return protobuf_pybullet_2eproto::file_level_metadata[8]; + return protobuf_pybullet_2eproto::file_level_metadata[17]; } #if PROTOBUF_INLINE_NOT_IN_HEADERS @@ -3955,7 +7242,7 @@ void MjcfLoadedStatus::SetCachedSize(int size) const { } const ::google::protobuf::Descriptor* MjcfLoadedStatus::descriptor() { protobuf_pybullet_2eproto::protobuf_AssignDescriptorsOnce(); - return protobuf_pybullet_2eproto::file_level_metadata[9].descriptor; + return protobuf_pybullet_2eproto::file_level_metadata[18].descriptor; } const MjcfLoadedStatus& MjcfLoadedStatus::default_instance() { @@ -4138,7 +7425,7 @@ void MjcfLoadedStatus::InternalSwap(MjcfLoadedStatus* other) { ::google::protobuf::Metadata MjcfLoadedStatus::GetMetadata() const { protobuf_pybullet_2eproto::protobuf_AssignDescriptorsOnce(); - return protobuf_pybullet_2eproto::file_level_metadata[9]; + return protobuf_pybullet_2eproto::file_level_metadata[18]; } #if PROTOBUF_INLINE_NOT_IN_HEADERS @@ -4433,7 +7720,7 @@ void ChangeDynamicsCommand::SetCachedSize(int size) const { } const ::google::protobuf::Descriptor* ChangeDynamicsCommand::descriptor() { protobuf_pybullet_2eproto::protobuf_AssignDescriptorsOnce(); - return protobuf_pybullet_2eproto::file_level_metadata[10].descriptor; + return protobuf_pybullet_2eproto::file_level_metadata[19].descriptor; } const ChangeDynamicsCommand& ChangeDynamicsCommand::default_instance() { @@ -5475,7 +8762,7 @@ void ChangeDynamicsCommand::InternalSwap(ChangeDynamicsCommand* other) { ::google::protobuf::Metadata ChangeDynamicsCommand::GetMetadata() const { protobuf_pybullet_2eproto::protobuf_AssignDescriptorsOnce(); - return protobuf_pybullet_2eproto::file_level_metadata[10]; + return protobuf_pybullet_2eproto::file_level_metadata[19]; } #if PROTOBUF_INLINE_NOT_IN_HEADERS @@ -6109,7 +9396,7 @@ void GetDynamicsCommand::SetCachedSize(int size) const { } const ::google::protobuf::Descriptor* GetDynamicsCommand::descriptor() { protobuf_pybullet_2eproto::protobuf_AssignDescriptorsOnce(); - return protobuf_pybullet_2eproto::file_level_metadata[11].descriptor; + return protobuf_pybullet_2eproto::file_level_metadata[20].descriptor; } const GetDynamicsCommand& GetDynamicsCommand::default_instance() { @@ -6304,7 +9591,7 @@ void GetDynamicsCommand::InternalSwap(GetDynamicsCommand* other) { ::google::protobuf::Metadata GetDynamicsCommand::GetMetadata() const { protobuf_pybullet_2eproto::protobuf_AssignDescriptorsOnce(); - return protobuf_pybullet_2eproto::file_level_metadata[11]; + return protobuf_pybullet_2eproto::file_level_metadata[20]; } #if PROTOBUF_INLINE_NOT_IN_HEADERS @@ -6407,7 +9694,7 @@ void GetDynamicsStatus::SetCachedSize(int size) const { } const ::google::protobuf::Descriptor* GetDynamicsStatus::descriptor() { protobuf_pybullet_2eproto::protobuf_AssignDescriptorsOnce(); - return protobuf_pybullet_2eproto::file_level_metadata[12].descriptor; + return protobuf_pybullet_2eproto::file_level_metadata[21].descriptor; } const GetDynamicsStatus& GetDynamicsStatus::default_instance() { @@ -6993,7 +10280,7 @@ void GetDynamicsStatus::InternalSwap(GetDynamicsStatus* other) { ::google::protobuf::Metadata GetDynamicsStatus::GetMetadata() const { protobuf_pybullet_2eproto::protobuf_AssignDescriptorsOnce(); - return protobuf_pybullet_2eproto::file_level_metadata[12]; + return protobuf_pybullet_2eproto::file_level_metadata[21]; } #if PROTOBUF_INLINE_NOT_IN_HEADERS @@ -7226,6 +10513,7 @@ void GetDynamicsStatus::set_activationstate(::google::protobuf::int32 value) { #if !defined(_MSC_VER) || _MSC_VER >= 1900 const int InitPoseCommand::kBodyUniqueIdFieldNumber; +const int InitPoseCommand::kUpdateflagsFieldNumber; const int InitPoseCommand::kHasInitialStateQFieldNumber; const int InitPoseCommand::kInitialStateQFieldNumber; const int InitPoseCommand::kHasInitialStateQdotFieldNumber; @@ -7249,12 +10537,15 @@ InitPoseCommand::InitPoseCommand(const InitPoseCommand& from) initialstateqdot_(from.initialstateqdot_), _cached_size_(0) { _internal_metadata_.MergeFrom(from._internal_metadata_); - bodyuniqueid_ = from.bodyuniqueid_; + ::memcpy(&bodyuniqueid_, &from.bodyuniqueid_, + reinterpret_cast(&updateflags_) - + reinterpret_cast(&bodyuniqueid_) + sizeof(updateflags_)); // @@protoc_insertion_point(copy_constructor:pybullet_grpc.InitPoseCommand) } void InitPoseCommand::SharedCtor() { - bodyuniqueid_ = 0; + ::memset(&bodyuniqueid_, 0, reinterpret_cast(&updateflags_) - + reinterpret_cast(&bodyuniqueid_) + sizeof(updateflags_)); _cached_size_ = 0; } @@ -7273,7 +10564,7 @@ void InitPoseCommand::SetCachedSize(int size) const { } const ::google::protobuf::Descriptor* InitPoseCommand::descriptor() { protobuf_pybullet_2eproto::protobuf_AssignDescriptorsOnce(); - return protobuf_pybullet_2eproto::file_level_metadata[13].descriptor; + return protobuf_pybullet_2eproto::file_level_metadata[22].descriptor; } const InitPoseCommand& InitPoseCommand::default_instance() { @@ -7295,7 +10586,8 @@ void InitPoseCommand::Clear() { initialstateq_.Clear(); hasinitialstateqdot_.Clear(); initialstateqdot_.Clear(); - bodyuniqueid_ = 0; + ::memset(&bodyuniqueid_, 0, reinterpret_cast(&updateflags_) - + reinterpret_cast(&bodyuniqueid_) + sizeof(updateflags_)); } bool InitPoseCommand::MergePartialFromCodedStream( @@ -7321,64 +10613,77 @@ bool InitPoseCommand::MergePartialFromCodedStream( break; } - // repeated int32 hasInitialStateQ = 2; + // int32 updateflags = 2; case 2: { - if (tag == 18u) { - DO_((::google::protobuf::internal::WireFormatLite::ReadPackedPrimitive< + if (tag == 16u) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>( - input, this->mutable_hasinitialstateq()))); - } else if (tag == 16u) { - DO_((::google::protobuf::internal::WireFormatLite::ReadRepeatedPrimitiveNoInline< - ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>( - 1, 18u, input, this->mutable_hasinitialstateq()))); + input, &updateflags_))); } else { goto handle_unusual; } break; } - // repeated double initialStateQ = 3; + // repeated int32 hasInitialStateQ = 3; case 3: { if (tag == 26u) { DO_((::google::protobuf::internal::WireFormatLite::ReadPackedPrimitive< - double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( - input, this->mutable_initialstateq()))); - } else if (tag == 25u) { + ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>( + input, this->mutable_hasinitialstateq()))); + } else if (tag == 24u) { DO_((::google::protobuf::internal::WireFormatLite::ReadRepeatedPrimitiveNoInline< - double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( - 1, 26u, input, this->mutable_initialstateq()))); + ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>( + 1, 26u, input, this->mutable_hasinitialstateq()))); } else { goto handle_unusual; } break; } - // repeated int32 hasInitialStateQdot = 4; + // repeated double initialStateQ = 4; case 4: { if (tag == 34u) { DO_((::google::protobuf::internal::WireFormatLite::ReadPackedPrimitive< - ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>( - input, this->mutable_hasinitialstateqdot()))); - } else if (tag == 32u) { + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, this->mutable_initialstateq()))); + } else if (tag == 33u) { DO_((::google::protobuf::internal::WireFormatLite::ReadRepeatedPrimitiveNoInline< - ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>( - 1, 34u, input, this->mutable_hasinitialstateqdot()))); + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + 1, 34u, input, this->mutable_initialstateq()))); } else { goto handle_unusual; } break; } - // repeated double initialStateQdot = 5; + // repeated int32 hasInitialStateQdot = 5; case 5: { if (tag == 42u) { + DO_((::google::protobuf::internal::WireFormatLite::ReadPackedPrimitive< + ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>( + input, this->mutable_hasinitialstateqdot()))); + } else if (tag == 40u) { + DO_((::google::protobuf::internal::WireFormatLite::ReadRepeatedPrimitiveNoInline< + ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>( + 1, 42u, input, this->mutable_hasinitialstateqdot()))); + } else { + goto handle_unusual; + } + break; + } + + // repeated double initialStateQdot = 6; + case 6: { + if (tag == 50u) { DO_((::google::protobuf::internal::WireFormatLite::ReadPackedPrimitive< double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( input, this->mutable_initialstateqdot()))); - } else if (tag == 41u) { + } else if (tag == 49u) { DO_((::google::protobuf::internal::WireFormatLite::ReadRepeatedPrimitiveNoInline< double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( - 1, 42u, input, this->mutable_initialstateqdot()))); + 1, 50u, input, this->mutable_initialstateqdot()))); } else { goto handle_unusual; } @@ -7414,9 +10719,14 @@ void InitPoseCommand::SerializeWithCachedSizes( ::google::protobuf::internal::WireFormatLite::WriteInt32(1, this->bodyuniqueid(), output); } - // repeated int32 hasInitialStateQ = 2; + // int32 updateflags = 2; + if (this->updateflags() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteInt32(2, this->updateflags(), output); + } + + // repeated int32 hasInitialStateQ = 3; if (this->hasinitialstateq_size() > 0) { - ::google::protobuf::internal::WireFormatLite::WriteTag(2, ::google::protobuf::internal::WireFormatLite::WIRETYPE_LENGTH_DELIMITED, output); + ::google::protobuf::internal::WireFormatLite::WriteTag(3, ::google::protobuf::internal::WireFormatLite::WIRETYPE_LENGTH_DELIMITED, output); output->WriteVarint32(_hasinitialstateq_cached_byte_size_); } for (int i = 0; i < this->hasinitialstateq_size(); i++) { @@ -7424,17 +10734,17 @@ void InitPoseCommand::SerializeWithCachedSizes( this->hasinitialstateq(i), output); } - // repeated double initialStateQ = 3; + // repeated double initialStateQ = 4; if (this->initialstateq_size() > 0) { - ::google::protobuf::internal::WireFormatLite::WriteTag(3, ::google::protobuf::internal::WireFormatLite::WIRETYPE_LENGTH_DELIMITED, output); + ::google::protobuf::internal::WireFormatLite::WriteTag(4, ::google::protobuf::internal::WireFormatLite::WIRETYPE_LENGTH_DELIMITED, output); output->WriteVarint32(_initialstateq_cached_byte_size_); ::google::protobuf::internal::WireFormatLite::WriteDoubleArray( this->initialstateq().data(), this->initialstateq_size(), output); } - // repeated int32 hasInitialStateQdot = 4; + // repeated int32 hasInitialStateQdot = 5; if (this->hasinitialstateqdot_size() > 0) { - ::google::protobuf::internal::WireFormatLite::WriteTag(4, ::google::protobuf::internal::WireFormatLite::WIRETYPE_LENGTH_DELIMITED, output); + ::google::protobuf::internal::WireFormatLite::WriteTag(5, ::google::protobuf::internal::WireFormatLite::WIRETYPE_LENGTH_DELIMITED, output); output->WriteVarint32(_hasinitialstateqdot_cached_byte_size_); } for (int i = 0; i < this->hasinitialstateqdot_size(); i++) { @@ -7442,9 +10752,9 @@ void InitPoseCommand::SerializeWithCachedSizes( this->hasinitialstateqdot(i), output); } - // repeated double initialStateQdot = 5; + // repeated double initialStateQdot = 6; if (this->initialstateqdot_size() > 0) { - ::google::protobuf::internal::WireFormatLite::WriteTag(5, ::google::protobuf::internal::WireFormatLite::WIRETYPE_LENGTH_DELIMITED, output); + ::google::protobuf::internal::WireFormatLite::WriteTag(6, ::google::protobuf::internal::WireFormatLite::WIRETYPE_LENGTH_DELIMITED, output); output->WriteVarint32(_initialstateqdot_cached_byte_size_); ::google::protobuf::internal::WireFormatLite::WriteDoubleArray( this->initialstateqdot().data(), this->initialstateqdot_size(), output); @@ -7462,10 +10772,15 @@ void InitPoseCommand::SerializeWithCachedSizes( target = ::google::protobuf::internal::WireFormatLite::WriteInt32ToArray(1, this->bodyuniqueid(), target); } - // repeated int32 hasInitialStateQ = 2; + // int32 updateflags = 2; + if (this->updateflags() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteInt32ToArray(2, this->updateflags(), target); + } + + // repeated int32 hasInitialStateQ = 3; if (this->hasinitialstateq_size() > 0) { target = ::google::protobuf::internal::WireFormatLite::WriteTagToArray( - 2, + 3, ::google::protobuf::internal::WireFormatLite::WIRETYPE_LENGTH_DELIMITED, target); target = ::google::protobuf::io::CodedOutputStream::WriteVarint32ToArray( @@ -7476,10 +10791,10 @@ void InitPoseCommand::SerializeWithCachedSizes( WriteInt32NoTagToArray(this->hasinitialstateq(i), target); } - // repeated double initialStateQ = 3; + // repeated double initialStateQ = 4; if (this->initialstateq_size() > 0) { target = ::google::protobuf::internal::WireFormatLite::WriteTagToArray( - 3, + 4, ::google::protobuf::internal::WireFormatLite::WIRETYPE_LENGTH_DELIMITED, target); target = ::google::protobuf::io::CodedOutputStream::WriteVarint32ToArray( @@ -7490,10 +10805,10 @@ void InitPoseCommand::SerializeWithCachedSizes( WriteDoubleNoTagToArray(this->initialstateq(i), target); } - // repeated int32 hasInitialStateQdot = 4; + // repeated int32 hasInitialStateQdot = 5; if (this->hasinitialstateqdot_size() > 0) { target = ::google::protobuf::internal::WireFormatLite::WriteTagToArray( - 4, + 5, ::google::protobuf::internal::WireFormatLite::WIRETYPE_LENGTH_DELIMITED, target); target = ::google::protobuf::io::CodedOutputStream::WriteVarint32ToArray( @@ -7504,10 +10819,10 @@ void InitPoseCommand::SerializeWithCachedSizes( WriteInt32NoTagToArray(this->hasinitialstateqdot(i), target); } - // repeated double initialStateQdot = 5; + // repeated double initialStateQdot = 6; if (this->initialstateqdot_size() > 0) { target = ::google::protobuf::internal::WireFormatLite::WriteTagToArray( - 5, + 6, ::google::protobuf::internal::WireFormatLite::WIRETYPE_LENGTH_DELIMITED, target); target = ::google::protobuf::io::CodedOutputStream::WriteVarint32ToArray( @@ -7526,7 +10841,7 @@ size_t InitPoseCommand::ByteSizeLong() const { // @@protoc_insertion_point(message_byte_size_start:pybullet_grpc.InitPoseCommand) size_t total_size = 0; - // repeated int32 hasInitialStateQ = 2; + // repeated int32 hasInitialStateQ = 3; { size_t data_size = ::google::protobuf::internal::WireFormatLite:: Int32Size(this->hasinitialstateq_); @@ -7541,7 +10856,7 @@ size_t InitPoseCommand::ByteSizeLong() const { total_size += data_size; } - // repeated double initialStateQ = 3; + // repeated double initialStateQ = 4; { unsigned int count = this->initialstateq_size(); size_t data_size = 8UL * count; @@ -7556,7 +10871,7 @@ size_t InitPoseCommand::ByteSizeLong() const { total_size += data_size; } - // repeated int32 hasInitialStateQdot = 4; + // repeated int32 hasInitialStateQdot = 5; { size_t data_size = ::google::protobuf::internal::WireFormatLite:: Int32Size(this->hasinitialstateqdot_); @@ -7571,7 +10886,7 @@ size_t InitPoseCommand::ByteSizeLong() const { total_size += data_size; } - // repeated double initialStateQdot = 5; + // repeated double initialStateQdot = 6; { unsigned int count = this->initialstateqdot_size(); size_t data_size = 8UL * count; @@ -7593,6 +10908,13 @@ size_t InitPoseCommand::ByteSizeLong() const { this->bodyuniqueid()); } + // int32 updateflags = 2; + if (this->updateflags() != 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::Int32Size( + this->updateflags()); + } + int cached_size = ::google::protobuf::internal::ToCachedSize(total_size); GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN(); _cached_size_ = cached_size; @@ -7626,6 +10948,9 @@ void InitPoseCommand::MergeFrom(const InitPoseCommand& from) { if (from.bodyuniqueid() != 0) { set_bodyuniqueid(from.bodyuniqueid()); } + if (from.updateflags() != 0) { + set_updateflags(from.updateflags()); + } } void InitPoseCommand::CopyFrom(const ::google::protobuf::Message& from) { @@ -7656,12 +10981,13 @@ void InitPoseCommand::InternalSwap(InitPoseCommand* other) { hasinitialstateqdot_.UnsafeArenaSwap(&other->hasinitialstateqdot_); initialstateqdot_.UnsafeArenaSwap(&other->initialstateqdot_); std::swap(bodyuniqueid_, other->bodyuniqueid_); + std::swap(updateflags_, other->updateflags_); std::swap(_cached_size_, other->_cached_size_); } ::google::protobuf::Metadata InitPoseCommand::GetMetadata() const { protobuf_pybullet_2eproto::protobuf_AssignDescriptorsOnce(); - return protobuf_pybullet_2eproto::file_level_metadata[13]; + return protobuf_pybullet_2eproto::file_level_metadata[22]; } #if PROTOBUF_INLINE_NOT_IN_HEADERS @@ -7681,7 +11007,21 @@ void InitPoseCommand::set_bodyuniqueid(::google::protobuf::int32 value) { // @@protoc_insertion_point(field_set:pybullet_grpc.InitPoseCommand.bodyUniqueId) } -// repeated int32 hasInitialStateQ = 2; +// int32 updateflags = 2; +void InitPoseCommand::clear_updateflags() { + updateflags_ = 0; +} +::google::protobuf::int32 InitPoseCommand::updateflags() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.InitPoseCommand.updateflags) + return updateflags_; +} +void InitPoseCommand::set_updateflags(::google::protobuf::int32 value) { + + updateflags_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.InitPoseCommand.updateflags) +} + +// repeated int32 hasInitialStateQ = 3; int InitPoseCommand::hasinitialstateq_size() const { return hasinitialstateq_.size(); } @@ -7711,7 +11051,7 @@ InitPoseCommand::mutable_hasinitialstateq() { return &hasinitialstateq_; } -// repeated double initialStateQ = 3; +// repeated double initialStateQ = 4; int InitPoseCommand::initialstateq_size() const { return initialstateq_.size(); } @@ -7741,7 +11081,7 @@ InitPoseCommand::mutable_initialstateq() { return &initialstateq_; } -// repeated int32 hasInitialStateQdot = 4; +// repeated int32 hasInitialStateQdot = 5; int InitPoseCommand::hasinitialstateqdot_size() const { return hasinitialstateqdot_.size(); } @@ -7771,7 +11111,7 @@ InitPoseCommand::mutable_hasinitialstateqdot() { return &hasinitialstateqdot_; } -// repeated double initialStateQdot = 5; +// repeated double initialStateQdot = 6; int InitPoseCommand::initialstateqdot_size() const { return initialstateqdot_.size(); } @@ -7851,7 +11191,7 @@ void RequestActualStateCommand::SetCachedSize(int size) const { } const ::google::protobuf::Descriptor* RequestActualStateCommand::descriptor() { protobuf_pybullet_2eproto::protobuf_AssignDescriptorsOnce(); - return protobuf_pybullet_2eproto::file_level_metadata[14].descriptor; + return protobuf_pybullet_2eproto::file_level_metadata[23].descriptor; } const RequestActualStateCommand& RequestActualStateCommand::default_instance() { @@ -8076,7 +11416,7 @@ void RequestActualStateCommand::InternalSwap(RequestActualStateCommand* other) { ::google::protobuf::Metadata RequestActualStateCommand::GetMetadata() const { protobuf_pybullet_2eproto::protobuf_AssignDescriptorsOnce(); - return protobuf_pybullet_2eproto::file_level_metadata[14]; + return protobuf_pybullet_2eproto::file_level_metadata[23]; } #if PROTOBUF_INLINE_NOT_IN_HEADERS @@ -8191,7 +11531,7 @@ void SendActualStateStatus::SetCachedSize(int size) const { } const ::google::protobuf::Descriptor* SendActualStateStatus::descriptor() { protobuf_pybullet_2eproto::protobuf_AssignDescriptorsOnce(); - return protobuf_pybullet_2eproto::file_level_metadata[15].descriptor; + return protobuf_pybullet_2eproto::file_level_metadata[24].descriptor; } const SendActualStateStatus& SendActualStateStatus::default_instance() { @@ -8902,7 +12242,7 @@ void SendActualStateStatus::InternalSwap(SendActualStateStatus* other) { ::google::protobuf::Metadata SendActualStateStatus::GetMetadata() const { protobuf_pybullet_2eproto::protobuf_AssignDescriptorsOnce(); - return protobuf_pybullet_2eproto::file_level_metadata[15]; + return protobuf_pybullet_2eproto::file_level_metadata[24]; } #if PROTOBUF_INLINE_NOT_IN_HEADERS @@ -9208,8 +12548,7288 @@ SendActualStateStatus::mutable_linklocalinertialframes() { // =================================================================== +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const int ConfigureOpenGLVisualizerCommand::kUpdateFlagsFieldNumber; +const int ConfigureOpenGLVisualizerCommand::kCameraDistanceFieldNumber; +const int ConfigureOpenGLVisualizerCommand::kCameraPitchFieldNumber; +const int ConfigureOpenGLVisualizerCommand::kCameraYawFieldNumber; +const int ConfigureOpenGLVisualizerCommand::kCameraTargetPositionFieldNumber; +const int ConfigureOpenGLVisualizerCommand::kSetFlagFieldNumber; +const int ConfigureOpenGLVisualizerCommand::kSetEnabledFieldNumber; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 + +ConfigureOpenGLVisualizerCommand::ConfigureOpenGLVisualizerCommand() + : ::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.ConfigureOpenGLVisualizerCommand) +} +ConfigureOpenGLVisualizerCommand::ConfigureOpenGLVisualizerCommand(const ConfigureOpenGLVisualizerCommand& from) + : ::google::protobuf::Message(), + _internal_metadata_(NULL), + _cached_size_(0) { + _internal_metadata_.MergeFrom(from._internal_metadata_); + if (from.has_cameratargetposition()) { + cameratargetposition_ = new ::pybullet_grpc::vec3(*from.cameratargetposition_); + } else { + cameratargetposition_ = NULL; + } + ::memcpy(&cameradistance_, &from.cameradistance_, + reinterpret_cast(&setenabled_) - + reinterpret_cast(&cameradistance_) + sizeof(setenabled_)); + // @@protoc_insertion_point(copy_constructor:pybullet_grpc.ConfigureOpenGLVisualizerCommand) +} + +void ConfigureOpenGLVisualizerCommand::SharedCtor() { + ::memset(&cameratargetposition_, 0, reinterpret_cast(&setenabled_) - + reinterpret_cast(&cameratargetposition_) + sizeof(setenabled_)); + _cached_size_ = 0; +} + +ConfigureOpenGLVisualizerCommand::~ConfigureOpenGLVisualizerCommand() { + // @@protoc_insertion_point(destructor:pybullet_grpc.ConfigureOpenGLVisualizerCommand) + SharedDtor(); +} + +void ConfigureOpenGLVisualizerCommand::SharedDtor() { + if (this != internal_default_instance()) { + delete cameratargetposition_; + } +} + +void ConfigureOpenGLVisualizerCommand::SetCachedSize(int size) const { + GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN(); + _cached_size_ = size; + GOOGLE_SAFE_CONCURRENT_WRITES_END(); +} +const ::google::protobuf::Descriptor* ConfigureOpenGLVisualizerCommand::descriptor() { + protobuf_pybullet_2eproto::protobuf_AssignDescriptorsOnce(); + return protobuf_pybullet_2eproto::file_level_metadata[25].descriptor; +} + +const ConfigureOpenGLVisualizerCommand& ConfigureOpenGLVisualizerCommand::default_instance() { + protobuf_pybullet_2eproto::InitDefaults(); + return *internal_default_instance(); +} + +ConfigureOpenGLVisualizerCommand* ConfigureOpenGLVisualizerCommand::New(::google::protobuf::Arena* arena) const { + ConfigureOpenGLVisualizerCommand* n = new ConfigureOpenGLVisualizerCommand; + if (arena != NULL) { + arena->Own(n); + } + return n; +} + +void ConfigureOpenGLVisualizerCommand::Clear() { +// @@protoc_insertion_point(message_clear_start:pybullet_grpc.ConfigureOpenGLVisualizerCommand) + if (GetArenaNoVirtual() == NULL && cameratargetposition_ != NULL) { + delete cameratargetposition_; + } + cameratargetposition_ = NULL; + ::memset(&cameradistance_, 0, reinterpret_cast(&setenabled_) - + reinterpret_cast(&cameradistance_) + sizeof(setenabled_)); +} + +bool ConfigureOpenGLVisualizerCommand::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.ConfigureOpenGLVisualizerCommand) + 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 updateFlags = 1; + case 1: { + if (tag == 8u) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>( + input, &updateflags_))); + } else { + goto handle_unusual; + } + break; + } + + // double cameraDistance = 2; + case 2: { + if (tag == 17u) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &cameradistance_))); + } else { + goto handle_unusual; + } + break; + } + + // double cameraPitch = 3; + case 3: { + if (tag == 25u) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &camerapitch_))); + } else { + goto handle_unusual; + } + break; + } + + // double cameraYaw = 4; + case 4: { + if (tag == 33u) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &camerayaw_))); + } else { + goto handle_unusual; + } + break; + } + + // .pybullet_grpc.vec3 cameraTargetPosition = 5; + case 5: { + if (tag == 42u) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessageNoVirtual( + input, mutable_cameratargetposition())); + } else { + goto handle_unusual; + } + break; + } + + // int32 setFlag = 6; + case 6: { + if (tag == 48u) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>( + input, &setflag_))); + } else { + goto handle_unusual; + } + break; + } + + // int32 setEnabled = 7; + case 7: { + if (tag == 56u) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>( + input, &setenabled_))); + } 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.ConfigureOpenGLVisualizerCommand) + return true; +failure: + // @@protoc_insertion_point(parse_failure:pybullet_grpc.ConfigureOpenGLVisualizerCommand) + return false; +#undef DO_ +} + +void ConfigureOpenGLVisualizerCommand::SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const { + // @@protoc_insertion_point(serialize_start:pybullet_grpc.ConfigureOpenGLVisualizerCommand) + // int32 updateFlags = 1; + if (this->updateflags() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteInt32(1, this->updateflags(), output); + } + + // double cameraDistance = 2; + if (this->cameradistance() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(2, this->cameradistance(), output); + } + + // double cameraPitch = 3; + if (this->camerapitch() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(3, this->camerapitch(), output); + } + + // double cameraYaw = 4; + if (this->camerayaw() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(4, this->camerayaw(), output); + } + + // .pybullet_grpc.vec3 cameraTargetPosition = 5; + if (this->has_cameratargetposition()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 5, *this->cameratargetposition_, output); + } + + // int32 setFlag = 6; + if (this->setflag() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteInt32(6, this->setflag(), output); + } + + // int32 setEnabled = 7; + if (this->setenabled() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteInt32(7, this->setenabled(), output); + } + + // @@protoc_insertion_point(serialize_end:pybullet_grpc.ConfigureOpenGLVisualizerCommand) +} + +::google::protobuf::uint8* ConfigureOpenGLVisualizerCommand::InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const { + (void)deterministic; // Unused + // @@protoc_insertion_point(serialize_to_array_start:pybullet_grpc.ConfigureOpenGLVisualizerCommand) + // int32 updateFlags = 1; + if (this->updateflags() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteInt32ToArray(1, this->updateflags(), target); + } + + // double cameraDistance = 2; + if (this->cameradistance() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(2, this->cameradistance(), target); + } + + // double cameraPitch = 3; + if (this->camerapitch() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(3, this->camerapitch(), target); + } + + // double cameraYaw = 4; + if (this->camerayaw() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(4, this->camerayaw(), target); + } + + // .pybullet_grpc.vec3 cameraTargetPosition = 5; + if (this->has_cameratargetposition()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageNoVirtualToArray( + 5, *this->cameratargetposition_, false, target); + } + + // int32 setFlag = 6; + if (this->setflag() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteInt32ToArray(6, this->setflag(), target); + } + + // int32 setEnabled = 7; + if (this->setenabled() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteInt32ToArray(7, this->setenabled(), target); + } + + // @@protoc_insertion_point(serialize_to_array_end:pybullet_grpc.ConfigureOpenGLVisualizerCommand) + return target; +} + +size_t ConfigureOpenGLVisualizerCommand::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:pybullet_grpc.ConfigureOpenGLVisualizerCommand) + size_t total_size = 0; + + // .pybullet_grpc.vec3 cameraTargetPosition = 5; + if (this->has_cameratargetposition()) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSizeNoVirtual( + *this->cameratargetposition_); + } + + // double cameraDistance = 2; + if (this->cameradistance() != 0) { + total_size += 1 + 8; + } + + // double cameraPitch = 3; + if (this->camerapitch() != 0) { + total_size += 1 + 8; + } + + // int32 updateFlags = 1; + if (this->updateflags() != 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::Int32Size( + this->updateflags()); + } + + // int32 setFlag = 6; + if (this->setflag() != 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::Int32Size( + this->setflag()); + } + + // double cameraYaw = 4; + if (this->camerayaw() != 0) { + total_size += 1 + 8; + } + + // int32 setEnabled = 7; + if (this->setenabled() != 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::Int32Size( + this->setenabled()); + } + + 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 ConfigureOpenGLVisualizerCommand::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:pybullet_grpc.ConfigureOpenGLVisualizerCommand) + GOOGLE_DCHECK_NE(&from, this); + const ConfigureOpenGLVisualizerCommand* source = + ::google::protobuf::internal::DynamicCastToGenerated( + &from); + if (source == NULL) { + // @@protoc_insertion_point(generalized_merge_from_cast_fail:pybullet_grpc.ConfigureOpenGLVisualizerCommand) + ::google::protobuf::internal::ReflectionOps::Merge(from, this); + } else { + // @@protoc_insertion_point(generalized_merge_from_cast_success:pybullet_grpc.ConfigureOpenGLVisualizerCommand) + MergeFrom(*source); + } +} + +void ConfigureOpenGLVisualizerCommand::MergeFrom(const ConfigureOpenGLVisualizerCommand& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:pybullet_grpc.ConfigureOpenGLVisualizerCommand) + GOOGLE_DCHECK_NE(&from, this); + _internal_metadata_.MergeFrom(from._internal_metadata_); + if (from.has_cameratargetposition()) { + mutable_cameratargetposition()->::pybullet_grpc::vec3::MergeFrom(from.cameratargetposition()); + } + if (from.cameradistance() != 0) { + set_cameradistance(from.cameradistance()); + } + if (from.camerapitch() != 0) { + set_camerapitch(from.camerapitch()); + } + if (from.updateflags() != 0) { + set_updateflags(from.updateflags()); + } + if (from.setflag() != 0) { + set_setflag(from.setflag()); + } + if (from.camerayaw() != 0) { + set_camerayaw(from.camerayaw()); + } + if (from.setenabled() != 0) { + set_setenabled(from.setenabled()); + } +} + +void ConfigureOpenGLVisualizerCommand::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:pybullet_grpc.ConfigureOpenGLVisualizerCommand) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +void ConfigureOpenGLVisualizerCommand::CopyFrom(const ConfigureOpenGLVisualizerCommand& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:pybullet_grpc.ConfigureOpenGLVisualizerCommand) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool ConfigureOpenGLVisualizerCommand::IsInitialized() const { + return true; +} + +void ConfigureOpenGLVisualizerCommand::Swap(ConfigureOpenGLVisualizerCommand* other) { + if (other == this) return; + InternalSwap(other); +} +void ConfigureOpenGLVisualizerCommand::InternalSwap(ConfigureOpenGLVisualizerCommand* other) { + std::swap(cameratargetposition_, other->cameratargetposition_); + std::swap(cameradistance_, other->cameradistance_); + std::swap(camerapitch_, other->camerapitch_); + std::swap(updateflags_, other->updateflags_); + std::swap(setflag_, other->setflag_); + std::swap(camerayaw_, other->camerayaw_); + std::swap(setenabled_, other->setenabled_); + std::swap(_cached_size_, other->_cached_size_); +} + +::google::protobuf::Metadata ConfigureOpenGLVisualizerCommand::GetMetadata() const { + protobuf_pybullet_2eproto::protobuf_AssignDescriptorsOnce(); + return protobuf_pybullet_2eproto::file_level_metadata[25]; +} + +#if PROTOBUF_INLINE_NOT_IN_HEADERS +// ConfigureOpenGLVisualizerCommand + +// int32 updateFlags = 1; +void ConfigureOpenGLVisualizerCommand::clear_updateflags() { + updateflags_ = 0; +} +::google::protobuf::int32 ConfigureOpenGLVisualizerCommand::updateflags() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.ConfigureOpenGLVisualizerCommand.updateFlags) + return updateflags_; +} +void ConfigureOpenGLVisualizerCommand::set_updateflags(::google::protobuf::int32 value) { + + updateflags_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.ConfigureOpenGLVisualizerCommand.updateFlags) +} + +// double cameraDistance = 2; +void ConfigureOpenGLVisualizerCommand::clear_cameradistance() { + cameradistance_ = 0; +} +double ConfigureOpenGLVisualizerCommand::cameradistance() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.ConfigureOpenGLVisualizerCommand.cameraDistance) + return cameradistance_; +} +void ConfigureOpenGLVisualizerCommand::set_cameradistance(double value) { + + cameradistance_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.ConfigureOpenGLVisualizerCommand.cameraDistance) +} + +// double cameraPitch = 3; +void ConfigureOpenGLVisualizerCommand::clear_camerapitch() { + camerapitch_ = 0; +} +double ConfigureOpenGLVisualizerCommand::camerapitch() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.ConfigureOpenGLVisualizerCommand.cameraPitch) + return camerapitch_; +} +void ConfigureOpenGLVisualizerCommand::set_camerapitch(double value) { + + camerapitch_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.ConfigureOpenGLVisualizerCommand.cameraPitch) +} + +// double cameraYaw = 4; +void ConfigureOpenGLVisualizerCommand::clear_camerayaw() { + camerayaw_ = 0; +} +double ConfigureOpenGLVisualizerCommand::camerayaw() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.ConfigureOpenGLVisualizerCommand.cameraYaw) + return camerayaw_; +} +void ConfigureOpenGLVisualizerCommand::set_camerayaw(double value) { + + camerayaw_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.ConfigureOpenGLVisualizerCommand.cameraYaw) +} + +// .pybullet_grpc.vec3 cameraTargetPosition = 5; +bool ConfigureOpenGLVisualizerCommand::has_cameratargetposition() const { + return this != internal_default_instance() && cameratargetposition_ != NULL; +} +void ConfigureOpenGLVisualizerCommand::clear_cameratargetposition() { + if (GetArenaNoVirtual() == NULL && cameratargetposition_ != NULL) delete cameratargetposition_; + cameratargetposition_ = NULL; +} +const ::pybullet_grpc::vec3& ConfigureOpenGLVisualizerCommand::cameratargetposition() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.ConfigureOpenGLVisualizerCommand.cameraTargetPosition) + return cameratargetposition_ != NULL ? *cameratargetposition_ + : *::pybullet_grpc::vec3::internal_default_instance(); +} +::pybullet_grpc::vec3* ConfigureOpenGLVisualizerCommand::mutable_cameratargetposition() { + + if (cameratargetposition_ == NULL) { + cameratargetposition_ = new ::pybullet_grpc::vec3; + } + // @@protoc_insertion_point(field_mutable:pybullet_grpc.ConfigureOpenGLVisualizerCommand.cameraTargetPosition) + return cameratargetposition_; +} +::pybullet_grpc::vec3* ConfigureOpenGLVisualizerCommand::release_cameratargetposition() { + // @@protoc_insertion_point(field_release:pybullet_grpc.ConfigureOpenGLVisualizerCommand.cameraTargetPosition) + + ::pybullet_grpc::vec3* temp = cameratargetposition_; + cameratargetposition_ = NULL; + return temp; +} +void ConfigureOpenGLVisualizerCommand::set_allocated_cameratargetposition(::pybullet_grpc::vec3* cameratargetposition) { + delete cameratargetposition_; + cameratargetposition_ = cameratargetposition; + if (cameratargetposition) { + + } else { + + } + // @@protoc_insertion_point(field_set_allocated:pybullet_grpc.ConfigureOpenGLVisualizerCommand.cameraTargetPosition) +} + +// int32 setFlag = 6; +void ConfigureOpenGLVisualizerCommand::clear_setflag() { + setflag_ = 0; +} +::google::protobuf::int32 ConfigureOpenGLVisualizerCommand::setflag() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.ConfigureOpenGLVisualizerCommand.setFlag) + return setflag_; +} +void ConfigureOpenGLVisualizerCommand::set_setflag(::google::protobuf::int32 value) { + + setflag_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.ConfigureOpenGLVisualizerCommand.setFlag) +} + +// int32 setEnabled = 7; +void ConfigureOpenGLVisualizerCommand::clear_setenabled() { + setenabled_ = 0; +} +::google::protobuf::int32 ConfigureOpenGLVisualizerCommand::setenabled() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.ConfigureOpenGLVisualizerCommand.setEnabled) + return setenabled_; +} +void ConfigureOpenGLVisualizerCommand::set_setenabled(::google::protobuf::int32 value) { + + setenabled_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.ConfigureOpenGLVisualizerCommand.setEnabled) +} + +#endif // PROTOBUF_INLINE_NOT_IN_HEADERS + +// =================================================================== + +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const int PhysicsSimulationParameters::kDeltaTimeFieldNumber; +const int PhysicsSimulationParameters::kGravityAccelerationFieldNumber; +const int PhysicsSimulationParameters::kNumSimulationSubStepsFieldNumber; +const int PhysicsSimulationParameters::kNumSolverIterationsFieldNumber; +const int PhysicsSimulationParameters::kUseRealTimeSimulationFieldNumber; +const int PhysicsSimulationParameters::kUseSplitImpulseFieldNumber; +const int PhysicsSimulationParameters::kSplitImpulsePenetrationThresholdFieldNumber; +const int PhysicsSimulationParameters::kContactBreakingThresholdFieldNumber; +const int PhysicsSimulationParameters::kInternalSimFlagsFieldNumber; +const int PhysicsSimulationParameters::kDefaultContactERPFieldNumber; +const int PhysicsSimulationParameters::kCollisionFilterModeFieldNumber; +const int PhysicsSimulationParameters::kEnableFileCachingFieldNumber; +const int PhysicsSimulationParameters::kRestitutionVelocityThresholdFieldNumber; +const int PhysicsSimulationParameters::kDefaultNonContactERPFieldNumber; +const int PhysicsSimulationParameters::kFrictionERPFieldNumber; +const int PhysicsSimulationParameters::kDefaultGlobalCFMFieldNumber; +const int PhysicsSimulationParameters::kFrictionCFMFieldNumber; +const int PhysicsSimulationParameters::kEnableConeFrictionFieldNumber; +const int PhysicsSimulationParameters::kDeterministicOverlappingPairsFieldNumber; +const int PhysicsSimulationParameters::kAllowedCcdPenetrationFieldNumber; +const int PhysicsSimulationParameters::kJointFeedbackModeFieldNumber; +const int PhysicsSimulationParameters::kSolverResidualThresholdFieldNumber; +const int PhysicsSimulationParameters::kContactSlopFieldNumber; +const int PhysicsSimulationParameters::kEnableSATFieldNumber; +const int PhysicsSimulationParameters::kConstraintSolverTypeFieldNumber; +const int PhysicsSimulationParameters::kMinimumSolverIslandSizeFieldNumber; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 + +PhysicsSimulationParameters::PhysicsSimulationParameters() + : ::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.PhysicsSimulationParameters) +} +PhysicsSimulationParameters::PhysicsSimulationParameters(const PhysicsSimulationParameters& from) + : ::google::protobuf::Message(), + _internal_metadata_(NULL), + _cached_size_(0) { + _internal_metadata_.MergeFrom(from._internal_metadata_); + if (from.has_gravityacceleration()) { + gravityacceleration_ = new ::pybullet_grpc::vec3(*from.gravityacceleration_); + } else { + gravityacceleration_ = NULL; + } + ::memcpy(&deltatime_, &from.deltatime_, + reinterpret_cast(&minimumsolverislandsize_) - + reinterpret_cast(&deltatime_) + sizeof(minimumsolverislandsize_)); + // @@protoc_insertion_point(copy_constructor:pybullet_grpc.PhysicsSimulationParameters) +} + +void PhysicsSimulationParameters::SharedCtor() { + ::memset(&gravityacceleration_, 0, reinterpret_cast(&minimumsolverislandsize_) - + reinterpret_cast(&gravityacceleration_) + sizeof(minimumsolverislandsize_)); + _cached_size_ = 0; +} + +PhysicsSimulationParameters::~PhysicsSimulationParameters() { + // @@protoc_insertion_point(destructor:pybullet_grpc.PhysicsSimulationParameters) + SharedDtor(); +} + +void PhysicsSimulationParameters::SharedDtor() { + if (this != internal_default_instance()) { + delete gravityacceleration_; + } +} + +void PhysicsSimulationParameters::SetCachedSize(int size) const { + GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN(); + _cached_size_ = size; + GOOGLE_SAFE_CONCURRENT_WRITES_END(); +} +const ::google::protobuf::Descriptor* PhysicsSimulationParameters::descriptor() { + protobuf_pybullet_2eproto::protobuf_AssignDescriptorsOnce(); + return protobuf_pybullet_2eproto::file_level_metadata[26].descriptor; +} + +const PhysicsSimulationParameters& PhysicsSimulationParameters::default_instance() { + protobuf_pybullet_2eproto::InitDefaults(); + return *internal_default_instance(); +} + +PhysicsSimulationParameters* PhysicsSimulationParameters::New(::google::protobuf::Arena* arena) const { + PhysicsSimulationParameters* n = new PhysicsSimulationParameters; + if (arena != NULL) { + arena->Own(n); + } + return n; +} + +void PhysicsSimulationParameters::Clear() { +// @@protoc_insertion_point(message_clear_start:pybullet_grpc.PhysicsSimulationParameters) + if (GetArenaNoVirtual() == NULL && gravityacceleration_ != NULL) { + delete gravityacceleration_; + } + gravityacceleration_ = NULL; + ::memset(&deltatime_, 0, reinterpret_cast(&minimumsolverislandsize_) - + reinterpret_cast(&deltatime_) + sizeof(minimumsolverislandsize_)); +} + +bool PhysicsSimulationParameters::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.PhysicsSimulationParameters) + for (;;) { + ::std::pair< ::google::protobuf::uint32, bool> p = input->ReadTagWithCutoffNoLastTag(16383u); + tag = p.first; + if (!p.second) goto handle_unusual; + switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { + // double deltaTime = 1; + case 1: { + if (tag == 9u) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &deltatime_))); + } else { + goto handle_unusual; + } + break; + } + + // .pybullet_grpc.vec3 gravityAcceleration = 2; + case 2: { + if (tag == 18u) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessageNoVirtual( + input, mutable_gravityacceleration())); + } else { + goto handle_unusual; + } + break; + } + + // int32 numSimulationSubSteps = 3; + case 3: { + if (tag == 24u) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>( + input, &numsimulationsubsteps_))); + } else { + goto handle_unusual; + } + break; + } + + // int32 numSolverIterations = 4; + case 4: { + if (tag == 32u) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>( + input, &numsolveriterations_))); + } else { + goto handle_unusual; + } + break; + } + + // int32 useRealTimeSimulation = 5; + case 5: { + if (tag == 40u) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>( + input, &userealtimesimulation_))); + } else { + goto handle_unusual; + } + break; + } + + // int32 useSplitImpulse = 6; + case 6: { + if (tag == 48u) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>( + input, &usesplitimpulse_))); + } else { + goto handle_unusual; + } + break; + } + + // double splitImpulsePenetrationThreshold = 7; + case 7: { + if (tag == 57u) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &splitimpulsepenetrationthreshold_))); + } else { + goto handle_unusual; + } + break; + } + + // double contactBreakingThreshold = 8; + case 8: { + if (tag == 65u) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &contactbreakingthreshold_))); + } else { + goto handle_unusual; + } + break; + } + + // int32 internalSimFlags = 9; + case 9: { + if (tag == 72u) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>( + input, &internalsimflags_))); + } else { + goto handle_unusual; + } + break; + } + + // double defaultContactERP = 10; + case 10: { + if (tag == 81u) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &defaultcontacterp_))); + } else { + goto handle_unusual; + } + break; + } + + // int32 collisionFilterMode = 11; + case 11: { + if (tag == 88u) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>( + input, &collisionfiltermode_))); + } else { + goto handle_unusual; + } + break; + } + + // int32 enableFileCaching = 12; + case 12: { + if (tag == 96u) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>( + input, &enablefilecaching_))); + } else { + goto handle_unusual; + } + break; + } + + // double restitutionVelocityThreshold = 13; + case 13: { + if (tag == 105u) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &restitutionvelocitythreshold_))); + } else { + goto handle_unusual; + } + break; + } + + // double defaultNonContactERP = 14; + case 14: { + if (tag == 113u) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &defaultnoncontacterp_))); + } else { + goto handle_unusual; + } + break; + } + + // double frictionERP = 15; + case 15: { + if (tag == 121u) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &frictionerp_))); + } else { + goto handle_unusual; + } + break; + } + + // double defaultGlobalCFM = 16; + case 16: { + if (tag == 129u) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &defaultglobalcfm_))); + } else { + goto handle_unusual; + } + break; + } + + // double frictionCFM = 17; + case 17: { + if (tag == 137u) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &frictioncfm_))); + } else { + goto handle_unusual; + } + break; + } + + // int32 enableConeFriction = 18; + case 18: { + if (tag == 144u) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>( + input, &enableconefriction_))); + } else { + goto handle_unusual; + } + break; + } + + // int32 deterministicOverlappingPairs = 19; + case 19: { + if (tag == 152u) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>( + input, &deterministicoverlappingpairs_))); + } else { + goto handle_unusual; + } + break; + } + + // double allowedCcdPenetration = 20; + case 20: { + if (tag == 161u) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &allowedccdpenetration_))); + } else { + goto handle_unusual; + } + break; + } + + // int32 jointFeedbackMode = 21; + case 21: { + if (tag == 168u) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>( + input, &jointfeedbackmode_))); + } else { + goto handle_unusual; + } + break; + } + + // double solverResidualThreshold = 22; + case 22: { + if (tag == 177u) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &solverresidualthreshold_))); + } else { + goto handle_unusual; + } + break; + } + + // double contactSlop = 23; + case 23: { + if (tag == 185u) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &contactslop_))); + } else { + goto handle_unusual; + } + break; + } + + // int32 enableSAT = 24; + case 24: { + if (tag == 192u) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>( + input, &enablesat_))); + } else { + goto handle_unusual; + } + break; + } + + // int32 constraintSolverType = 25; + case 25: { + if (tag == 200u) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>( + input, &constraintsolvertype_))); + } else { + goto handle_unusual; + } + break; + } + + // int32 minimumSolverIslandSize = 26; + case 26: { + if (tag == 208u) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>( + input, &minimumsolverislandsize_))); + } 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.PhysicsSimulationParameters) + return true; +failure: + // @@protoc_insertion_point(parse_failure:pybullet_grpc.PhysicsSimulationParameters) + return false; +#undef DO_ +} + +void PhysicsSimulationParameters::SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const { + // @@protoc_insertion_point(serialize_start:pybullet_grpc.PhysicsSimulationParameters) + // double deltaTime = 1; + if (this->deltatime() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(1, this->deltatime(), output); + } + + // .pybullet_grpc.vec3 gravityAcceleration = 2; + if (this->has_gravityacceleration()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 2, *this->gravityacceleration_, output); + } + + // int32 numSimulationSubSteps = 3; + if (this->numsimulationsubsteps() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteInt32(3, this->numsimulationsubsteps(), output); + } + + // int32 numSolverIterations = 4; + if (this->numsolveriterations() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteInt32(4, this->numsolveriterations(), output); + } + + // int32 useRealTimeSimulation = 5; + if (this->userealtimesimulation() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteInt32(5, this->userealtimesimulation(), output); + } + + // int32 useSplitImpulse = 6; + if (this->usesplitimpulse() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteInt32(6, this->usesplitimpulse(), output); + } + + // double splitImpulsePenetrationThreshold = 7; + if (this->splitimpulsepenetrationthreshold() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(7, this->splitimpulsepenetrationthreshold(), output); + } + + // double contactBreakingThreshold = 8; + if (this->contactbreakingthreshold() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(8, this->contactbreakingthreshold(), output); + } + + // int32 internalSimFlags = 9; + if (this->internalsimflags() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteInt32(9, this->internalsimflags(), output); + } + + // double defaultContactERP = 10; + if (this->defaultcontacterp() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(10, this->defaultcontacterp(), output); + } + + // int32 collisionFilterMode = 11; + if (this->collisionfiltermode() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteInt32(11, this->collisionfiltermode(), output); + } + + // int32 enableFileCaching = 12; + if (this->enablefilecaching() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteInt32(12, this->enablefilecaching(), output); + } + + // double restitutionVelocityThreshold = 13; + if (this->restitutionvelocitythreshold() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(13, this->restitutionvelocitythreshold(), output); + } + + // double defaultNonContactERP = 14; + if (this->defaultnoncontacterp() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(14, this->defaultnoncontacterp(), output); + } + + // double frictionERP = 15; + if (this->frictionerp() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(15, this->frictionerp(), output); + } + + // double defaultGlobalCFM = 16; + if (this->defaultglobalcfm() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(16, this->defaultglobalcfm(), output); + } + + // double frictionCFM = 17; + if (this->frictioncfm() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(17, this->frictioncfm(), output); + } + + // int32 enableConeFriction = 18; + if (this->enableconefriction() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteInt32(18, this->enableconefriction(), output); + } + + // int32 deterministicOverlappingPairs = 19; + if (this->deterministicoverlappingpairs() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteInt32(19, this->deterministicoverlappingpairs(), output); + } + + // double allowedCcdPenetration = 20; + if (this->allowedccdpenetration() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(20, this->allowedccdpenetration(), output); + } + + // int32 jointFeedbackMode = 21; + if (this->jointfeedbackmode() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteInt32(21, this->jointfeedbackmode(), output); + } + + // double solverResidualThreshold = 22; + if (this->solverresidualthreshold() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(22, this->solverresidualthreshold(), output); + } + + // double contactSlop = 23; + if (this->contactslop() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(23, this->contactslop(), output); + } + + // int32 enableSAT = 24; + if (this->enablesat() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteInt32(24, this->enablesat(), output); + } + + // int32 constraintSolverType = 25; + if (this->constraintsolvertype() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteInt32(25, this->constraintsolvertype(), output); + } + + // int32 minimumSolverIslandSize = 26; + if (this->minimumsolverislandsize() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteInt32(26, this->minimumsolverislandsize(), output); + } + + // @@protoc_insertion_point(serialize_end:pybullet_grpc.PhysicsSimulationParameters) +} + +::google::protobuf::uint8* PhysicsSimulationParameters::InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const { + (void)deterministic; // Unused + // @@protoc_insertion_point(serialize_to_array_start:pybullet_grpc.PhysicsSimulationParameters) + // double deltaTime = 1; + if (this->deltatime() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(1, this->deltatime(), target); + } + + // .pybullet_grpc.vec3 gravityAcceleration = 2; + if (this->has_gravityacceleration()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageNoVirtualToArray( + 2, *this->gravityacceleration_, false, target); + } + + // int32 numSimulationSubSteps = 3; + if (this->numsimulationsubsteps() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteInt32ToArray(3, this->numsimulationsubsteps(), target); + } + + // int32 numSolverIterations = 4; + if (this->numsolveriterations() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteInt32ToArray(4, this->numsolveriterations(), target); + } + + // int32 useRealTimeSimulation = 5; + if (this->userealtimesimulation() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteInt32ToArray(5, this->userealtimesimulation(), target); + } + + // int32 useSplitImpulse = 6; + if (this->usesplitimpulse() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteInt32ToArray(6, this->usesplitimpulse(), target); + } + + // double splitImpulsePenetrationThreshold = 7; + if (this->splitimpulsepenetrationthreshold() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(7, this->splitimpulsepenetrationthreshold(), target); + } + + // double contactBreakingThreshold = 8; + if (this->contactbreakingthreshold() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(8, this->contactbreakingthreshold(), target); + } + + // int32 internalSimFlags = 9; + if (this->internalsimflags() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteInt32ToArray(9, this->internalsimflags(), target); + } + + // double defaultContactERP = 10; + if (this->defaultcontacterp() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(10, this->defaultcontacterp(), target); + } + + // int32 collisionFilterMode = 11; + if (this->collisionfiltermode() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteInt32ToArray(11, this->collisionfiltermode(), target); + } + + // int32 enableFileCaching = 12; + if (this->enablefilecaching() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteInt32ToArray(12, this->enablefilecaching(), target); + } + + // double restitutionVelocityThreshold = 13; + if (this->restitutionvelocitythreshold() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(13, this->restitutionvelocitythreshold(), target); + } + + // double defaultNonContactERP = 14; + if (this->defaultnoncontacterp() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(14, this->defaultnoncontacterp(), target); + } + + // double frictionERP = 15; + if (this->frictionerp() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(15, this->frictionerp(), target); + } + + // double defaultGlobalCFM = 16; + if (this->defaultglobalcfm() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(16, this->defaultglobalcfm(), target); + } + + // double frictionCFM = 17; + if (this->frictioncfm() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(17, this->frictioncfm(), target); + } + + // int32 enableConeFriction = 18; + if (this->enableconefriction() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteInt32ToArray(18, this->enableconefriction(), target); + } + + // int32 deterministicOverlappingPairs = 19; + if (this->deterministicoverlappingpairs() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteInt32ToArray(19, this->deterministicoverlappingpairs(), target); + } + + // double allowedCcdPenetration = 20; + if (this->allowedccdpenetration() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(20, this->allowedccdpenetration(), target); + } + + // int32 jointFeedbackMode = 21; + if (this->jointfeedbackmode() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteInt32ToArray(21, this->jointfeedbackmode(), target); + } + + // double solverResidualThreshold = 22; + if (this->solverresidualthreshold() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(22, this->solverresidualthreshold(), target); + } + + // double contactSlop = 23; + if (this->contactslop() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(23, this->contactslop(), target); + } + + // int32 enableSAT = 24; + if (this->enablesat() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteInt32ToArray(24, this->enablesat(), target); + } + + // int32 constraintSolverType = 25; + if (this->constraintsolvertype() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteInt32ToArray(25, this->constraintsolvertype(), target); + } + + // int32 minimumSolverIslandSize = 26; + if (this->minimumsolverislandsize() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteInt32ToArray(26, this->minimumsolverislandsize(), target); + } + + // @@protoc_insertion_point(serialize_to_array_end:pybullet_grpc.PhysicsSimulationParameters) + return target; +} + +size_t PhysicsSimulationParameters::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:pybullet_grpc.PhysicsSimulationParameters) + size_t total_size = 0; + + // .pybullet_grpc.vec3 gravityAcceleration = 2; + if (this->has_gravityacceleration()) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSizeNoVirtual( + *this->gravityacceleration_); + } + + // double deltaTime = 1; + if (this->deltatime() != 0) { + total_size += 1 + 8; + } + + // int32 numSimulationSubSteps = 3; + if (this->numsimulationsubsteps() != 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::Int32Size( + this->numsimulationsubsteps()); + } + + // int32 numSolverIterations = 4; + if (this->numsolveriterations() != 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::Int32Size( + this->numsolveriterations()); + } + + // int32 useRealTimeSimulation = 5; + if (this->userealtimesimulation() != 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::Int32Size( + this->userealtimesimulation()); + } + + // int32 useSplitImpulse = 6; + if (this->usesplitimpulse() != 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::Int32Size( + this->usesplitimpulse()); + } + + // double splitImpulsePenetrationThreshold = 7; + if (this->splitimpulsepenetrationthreshold() != 0) { + total_size += 1 + 8; + } + + // double contactBreakingThreshold = 8; + if (this->contactbreakingthreshold() != 0) { + total_size += 1 + 8; + } + + // double defaultContactERP = 10; + if (this->defaultcontacterp() != 0) { + total_size += 1 + 8; + } + + // int32 internalSimFlags = 9; + if (this->internalsimflags() != 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::Int32Size( + this->internalsimflags()); + } + + // int32 collisionFilterMode = 11; + if (this->collisionfiltermode() != 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::Int32Size( + this->collisionfiltermode()); + } + + // double restitutionVelocityThreshold = 13; + if (this->restitutionvelocitythreshold() != 0) { + total_size += 1 + 8; + } + + // double defaultNonContactERP = 14; + if (this->defaultnoncontacterp() != 0) { + total_size += 1 + 8; + } + + // double frictionERP = 15; + if (this->frictionerp() != 0) { + total_size += 1 + 8; + } + + // int32 enableFileCaching = 12; + if (this->enablefilecaching() != 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::Int32Size( + this->enablefilecaching()); + } + + // int32 enableConeFriction = 18; + if (this->enableconefriction() != 0) { + total_size += 2 + + ::google::protobuf::internal::WireFormatLite::Int32Size( + this->enableconefriction()); + } + + // double defaultGlobalCFM = 16; + if (this->defaultglobalcfm() != 0) { + total_size += 2 + 8; + } + + // double frictionCFM = 17; + if (this->frictioncfm() != 0) { + total_size += 2 + 8; + } + + // double allowedCcdPenetration = 20; + if (this->allowedccdpenetration() != 0) { + total_size += 2 + 8; + } + + // int32 deterministicOverlappingPairs = 19; + if (this->deterministicoverlappingpairs() != 0) { + total_size += 2 + + ::google::protobuf::internal::WireFormatLite::Int32Size( + this->deterministicoverlappingpairs()); + } + + // int32 jointFeedbackMode = 21; + if (this->jointfeedbackmode() != 0) { + total_size += 2 + + ::google::protobuf::internal::WireFormatLite::Int32Size( + this->jointfeedbackmode()); + } + + // double solverResidualThreshold = 22; + if (this->solverresidualthreshold() != 0) { + total_size += 2 + 8; + } + + // double contactSlop = 23; + if (this->contactslop() != 0) { + total_size += 2 + 8; + } + + // int32 enableSAT = 24; + if (this->enablesat() != 0) { + total_size += 2 + + ::google::protobuf::internal::WireFormatLite::Int32Size( + this->enablesat()); + } + + // int32 constraintSolverType = 25; + if (this->constraintsolvertype() != 0) { + total_size += 2 + + ::google::protobuf::internal::WireFormatLite::Int32Size( + this->constraintsolvertype()); + } + + // int32 minimumSolverIslandSize = 26; + if (this->minimumsolverislandsize() != 0) { + total_size += 2 + + ::google::protobuf::internal::WireFormatLite::Int32Size( + this->minimumsolverislandsize()); + } + + 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 PhysicsSimulationParameters::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:pybullet_grpc.PhysicsSimulationParameters) + GOOGLE_DCHECK_NE(&from, this); + const PhysicsSimulationParameters* source = + ::google::protobuf::internal::DynamicCastToGenerated( + &from); + if (source == NULL) { + // @@protoc_insertion_point(generalized_merge_from_cast_fail:pybullet_grpc.PhysicsSimulationParameters) + ::google::protobuf::internal::ReflectionOps::Merge(from, this); + } else { + // @@protoc_insertion_point(generalized_merge_from_cast_success:pybullet_grpc.PhysicsSimulationParameters) + MergeFrom(*source); + } +} + +void PhysicsSimulationParameters::MergeFrom(const PhysicsSimulationParameters& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:pybullet_grpc.PhysicsSimulationParameters) + GOOGLE_DCHECK_NE(&from, this); + _internal_metadata_.MergeFrom(from._internal_metadata_); + if (from.has_gravityacceleration()) { + mutable_gravityacceleration()->::pybullet_grpc::vec3::MergeFrom(from.gravityacceleration()); + } + if (from.deltatime() != 0) { + set_deltatime(from.deltatime()); + } + if (from.numsimulationsubsteps() != 0) { + set_numsimulationsubsteps(from.numsimulationsubsteps()); + } + if (from.numsolveriterations() != 0) { + set_numsolveriterations(from.numsolveriterations()); + } + if (from.userealtimesimulation() != 0) { + set_userealtimesimulation(from.userealtimesimulation()); + } + if (from.usesplitimpulse() != 0) { + set_usesplitimpulse(from.usesplitimpulse()); + } + if (from.splitimpulsepenetrationthreshold() != 0) { + set_splitimpulsepenetrationthreshold(from.splitimpulsepenetrationthreshold()); + } + if (from.contactbreakingthreshold() != 0) { + set_contactbreakingthreshold(from.contactbreakingthreshold()); + } + if (from.defaultcontacterp() != 0) { + set_defaultcontacterp(from.defaultcontacterp()); + } + if (from.internalsimflags() != 0) { + set_internalsimflags(from.internalsimflags()); + } + if (from.collisionfiltermode() != 0) { + set_collisionfiltermode(from.collisionfiltermode()); + } + if (from.restitutionvelocitythreshold() != 0) { + set_restitutionvelocitythreshold(from.restitutionvelocitythreshold()); + } + if (from.defaultnoncontacterp() != 0) { + set_defaultnoncontacterp(from.defaultnoncontacterp()); + } + if (from.frictionerp() != 0) { + set_frictionerp(from.frictionerp()); + } + if (from.enablefilecaching() != 0) { + set_enablefilecaching(from.enablefilecaching()); + } + if (from.enableconefriction() != 0) { + set_enableconefriction(from.enableconefriction()); + } + if (from.defaultglobalcfm() != 0) { + set_defaultglobalcfm(from.defaultglobalcfm()); + } + if (from.frictioncfm() != 0) { + set_frictioncfm(from.frictioncfm()); + } + if (from.allowedccdpenetration() != 0) { + set_allowedccdpenetration(from.allowedccdpenetration()); + } + if (from.deterministicoverlappingpairs() != 0) { + set_deterministicoverlappingpairs(from.deterministicoverlappingpairs()); + } + if (from.jointfeedbackmode() != 0) { + set_jointfeedbackmode(from.jointfeedbackmode()); + } + if (from.solverresidualthreshold() != 0) { + set_solverresidualthreshold(from.solverresidualthreshold()); + } + if (from.contactslop() != 0) { + set_contactslop(from.contactslop()); + } + if (from.enablesat() != 0) { + set_enablesat(from.enablesat()); + } + if (from.constraintsolvertype() != 0) { + set_constraintsolvertype(from.constraintsolvertype()); + } + if (from.minimumsolverislandsize() != 0) { + set_minimumsolverislandsize(from.minimumsolverislandsize()); + } +} + +void PhysicsSimulationParameters::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:pybullet_grpc.PhysicsSimulationParameters) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +void PhysicsSimulationParameters::CopyFrom(const PhysicsSimulationParameters& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:pybullet_grpc.PhysicsSimulationParameters) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool PhysicsSimulationParameters::IsInitialized() const { + return true; +} + +void PhysicsSimulationParameters::Swap(PhysicsSimulationParameters* other) { + if (other == this) return; + InternalSwap(other); +} +void PhysicsSimulationParameters::InternalSwap(PhysicsSimulationParameters* other) { + std::swap(gravityacceleration_, other->gravityacceleration_); + std::swap(deltatime_, other->deltatime_); + std::swap(numsimulationsubsteps_, other->numsimulationsubsteps_); + std::swap(numsolveriterations_, other->numsolveriterations_); + std::swap(userealtimesimulation_, other->userealtimesimulation_); + std::swap(usesplitimpulse_, other->usesplitimpulse_); + std::swap(splitimpulsepenetrationthreshold_, other->splitimpulsepenetrationthreshold_); + std::swap(contactbreakingthreshold_, other->contactbreakingthreshold_); + std::swap(defaultcontacterp_, other->defaultcontacterp_); + std::swap(internalsimflags_, other->internalsimflags_); + std::swap(collisionfiltermode_, other->collisionfiltermode_); + std::swap(restitutionvelocitythreshold_, other->restitutionvelocitythreshold_); + std::swap(defaultnoncontacterp_, other->defaultnoncontacterp_); + std::swap(frictionerp_, other->frictionerp_); + std::swap(enablefilecaching_, other->enablefilecaching_); + std::swap(enableconefriction_, other->enableconefriction_); + std::swap(defaultglobalcfm_, other->defaultglobalcfm_); + std::swap(frictioncfm_, other->frictioncfm_); + std::swap(allowedccdpenetration_, other->allowedccdpenetration_); + std::swap(deterministicoverlappingpairs_, other->deterministicoverlappingpairs_); + std::swap(jointfeedbackmode_, other->jointfeedbackmode_); + std::swap(solverresidualthreshold_, other->solverresidualthreshold_); + std::swap(contactslop_, other->contactslop_); + std::swap(enablesat_, other->enablesat_); + std::swap(constraintsolvertype_, other->constraintsolvertype_); + std::swap(minimumsolverislandsize_, other->minimumsolverislandsize_); + std::swap(_cached_size_, other->_cached_size_); +} + +::google::protobuf::Metadata PhysicsSimulationParameters::GetMetadata() const { + protobuf_pybullet_2eproto::protobuf_AssignDescriptorsOnce(); + return protobuf_pybullet_2eproto::file_level_metadata[26]; +} + +#if PROTOBUF_INLINE_NOT_IN_HEADERS +// PhysicsSimulationParameters + +// double deltaTime = 1; +void PhysicsSimulationParameters::clear_deltatime() { + deltatime_ = 0; +} +double PhysicsSimulationParameters::deltatime() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.PhysicsSimulationParameters.deltaTime) + return deltatime_; +} +void PhysicsSimulationParameters::set_deltatime(double value) { + + deltatime_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.PhysicsSimulationParameters.deltaTime) +} + +// .pybullet_grpc.vec3 gravityAcceleration = 2; +bool PhysicsSimulationParameters::has_gravityacceleration() const { + return this != internal_default_instance() && gravityacceleration_ != NULL; +} +void PhysicsSimulationParameters::clear_gravityacceleration() { + if (GetArenaNoVirtual() == NULL && gravityacceleration_ != NULL) delete gravityacceleration_; + gravityacceleration_ = NULL; +} +const ::pybullet_grpc::vec3& PhysicsSimulationParameters::gravityacceleration() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.PhysicsSimulationParameters.gravityAcceleration) + return gravityacceleration_ != NULL ? *gravityacceleration_ + : *::pybullet_grpc::vec3::internal_default_instance(); +} +::pybullet_grpc::vec3* PhysicsSimulationParameters::mutable_gravityacceleration() { + + if (gravityacceleration_ == NULL) { + gravityacceleration_ = new ::pybullet_grpc::vec3; + } + // @@protoc_insertion_point(field_mutable:pybullet_grpc.PhysicsSimulationParameters.gravityAcceleration) + return gravityacceleration_; +} +::pybullet_grpc::vec3* PhysicsSimulationParameters::release_gravityacceleration() { + // @@protoc_insertion_point(field_release:pybullet_grpc.PhysicsSimulationParameters.gravityAcceleration) + + ::pybullet_grpc::vec3* temp = gravityacceleration_; + gravityacceleration_ = NULL; + return temp; +} +void PhysicsSimulationParameters::set_allocated_gravityacceleration(::pybullet_grpc::vec3* gravityacceleration) { + delete gravityacceleration_; + gravityacceleration_ = gravityacceleration; + if (gravityacceleration) { + + } else { + + } + // @@protoc_insertion_point(field_set_allocated:pybullet_grpc.PhysicsSimulationParameters.gravityAcceleration) +} + +// int32 numSimulationSubSteps = 3; +void PhysicsSimulationParameters::clear_numsimulationsubsteps() { + numsimulationsubsteps_ = 0; +} +::google::protobuf::int32 PhysicsSimulationParameters::numsimulationsubsteps() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.PhysicsSimulationParameters.numSimulationSubSteps) + return numsimulationsubsteps_; +} +void PhysicsSimulationParameters::set_numsimulationsubsteps(::google::protobuf::int32 value) { + + numsimulationsubsteps_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.PhysicsSimulationParameters.numSimulationSubSteps) +} + +// int32 numSolverIterations = 4; +void PhysicsSimulationParameters::clear_numsolveriterations() { + numsolveriterations_ = 0; +} +::google::protobuf::int32 PhysicsSimulationParameters::numsolveriterations() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.PhysicsSimulationParameters.numSolverIterations) + return numsolveriterations_; +} +void PhysicsSimulationParameters::set_numsolveriterations(::google::protobuf::int32 value) { + + numsolveriterations_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.PhysicsSimulationParameters.numSolverIterations) +} + +// int32 useRealTimeSimulation = 5; +void PhysicsSimulationParameters::clear_userealtimesimulation() { + userealtimesimulation_ = 0; +} +::google::protobuf::int32 PhysicsSimulationParameters::userealtimesimulation() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.PhysicsSimulationParameters.useRealTimeSimulation) + return userealtimesimulation_; +} +void PhysicsSimulationParameters::set_userealtimesimulation(::google::protobuf::int32 value) { + + userealtimesimulation_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.PhysicsSimulationParameters.useRealTimeSimulation) +} + +// int32 useSplitImpulse = 6; +void PhysicsSimulationParameters::clear_usesplitimpulse() { + usesplitimpulse_ = 0; +} +::google::protobuf::int32 PhysicsSimulationParameters::usesplitimpulse() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.PhysicsSimulationParameters.useSplitImpulse) + return usesplitimpulse_; +} +void PhysicsSimulationParameters::set_usesplitimpulse(::google::protobuf::int32 value) { + + usesplitimpulse_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.PhysicsSimulationParameters.useSplitImpulse) +} + +// double splitImpulsePenetrationThreshold = 7; +void PhysicsSimulationParameters::clear_splitimpulsepenetrationthreshold() { + splitimpulsepenetrationthreshold_ = 0; +} +double PhysicsSimulationParameters::splitimpulsepenetrationthreshold() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.PhysicsSimulationParameters.splitImpulsePenetrationThreshold) + return splitimpulsepenetrationthreshold_; +} +void PhysicsSimulationParameters::set_splitimpulsepenetrationthreshold(double value) { + + splitimpulsepenetrationthreshold_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.PhysicsSimulationParameters.splitImpulsePenetrationThreshold) +} + +// double contactBreakingThreshold = 8; +void PhysicsSimulationParameters::clear_contactbreakingthreshold() { + contactbreakingthreshold_ = 0; +} +double PhysicsSimulationParameters::contactbreakingthreshold() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.PhysicsSimulationParameters.contactBreakingThreshold) + return contactbreakingthreshold_; +} +void PhysicsSimulationParameters::set_contactbreakingthreshold(double value) { + + contactbreakingthreshold_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.PhysicsSimulationParameters.contactBreakingThreshold) +} + +// int32 internalSimFlags = 9; +void PhysicsSimulationParameters::clear_internalsimflags() { + internalsimflags_ = 0; +} +::google::protobuf::int32 PhysicsSimulationParameters::internalsimflags() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.PhysicsSimulationParameters.internalSimFlags) + return internalsimflags_; +} +void PhysicsSimulationParameters::set_internalsimflags(::google::protobuf::int32 value) { + + internalsimflags_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.PhysicsSimulationParameters.internalSimFlags) +} + +// double defaultContactERP = 10; +void PhysicsSimulationParameters::clear_defaultcontacterp() { + defaultcontacterp_ = 0; +} +double PhysicsSimulationParameters::defaultcontacterp() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.PhysicsSimulationParameters.defaultContactERP) + return defaultcontacterp_; +} +void PhysicsSimulationParameters::set_defaultcontacterp(double value) { + + defaultcontacterp_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.PhysicsSimulationParameters.defaultContactERP) +} + +// int32 collisionFilterMode = 11; +void PhysicsSimulationParameters::clear_collisionfiltermode() { + collisionfiltermode_ = 0; +} +::google::protobuf::int32 PhysicsSimulationParameters::collisionfiltermode() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.PhysicsSimulationParameters.collisionFilterMode) + return collisionfiltermode_; +} +void PhysicsSimulationParameters::set_collisionfiltermode(::google::protobuf::int32 value) { + + collisionfiltermode_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.PhysicsSimulationParameters.collisionFilterMode) +} + +// int32 enableFileCaching = 12; +void PhysicsSimulationParameters::clear_enablefilecaching() { + enablefilecaching_ = 0; +} +::google::protobuf::int32 PhysicsSimulationParameters::enablefilecaching() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.PhysicsSimulationParameters.enableFileCaching) + return enablefilecaching_; +} +void PhysicsSimulationParameters::set_enablefilecaching(::google::protobuf::int32 value) { + + enablefilecaching_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.PhysicsSimulationParameters.enableFileCaching) +} + +// double restitutionVelocityThreshold = 13; +void PhysicsSimulationParameters::clear_restitutionvelocitythreshold() { + restitutionvelocitythreshold_ = 0; +} +double PhysicsSimulationParameters::restitutionvelocitythreshold() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.PhysicsSimulationParameters.restitutionVelocityThreshold) + return restitutionvelocitythreshold_; +} +void PhysicsSimulationParameters::set_restitutionvelocitythreshold(double value) { + + restitutionvelocitythreshold_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.PhysicsSimulationParameters.restitutionVelocityThreshold) +} + +// double defaultNonContactERP = 14; +void PhysicsSimulationParameters::clear_defaultnoncontacterp() { + defaultnoncontacterp_ = 0; +} +double PhysicsSimulationParameters::defaultnoncontacterp() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.PhysicsSimulationParameters.defaultNonContactERP) + return defaultnoncontacterp_; +} +void PhysicsSimulationParameters::set_defaultnoncontacterp(double value) { + + defaultnoncontacterp_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.PhysicsSimulationParameters.defaultNonContactERP) +} + +// double frictionERP = 15; +void PhysicsSimulationParameters::clear_frictionerp() { + frictionerp_ = 0; +} +double PhysicsSimulationParameters::frictionerp() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.PhysicsSimulationParameters.frictionERP) + return frictionerp_; +} +void PhysicsSimulationParameters::set_frictionerp(double value) { + + frictionerp_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.PhysicsSimulationParameters.frictionERP) +} + +// double defaultGlobalCFM = 16; +void PhysicsSimulationParameters::clear_defaultglobalcfm() { + defaultglobalcfm_ = 0; +} +double PhysicsSimulationParameters::defaultglobalcfm() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.PhysicsSimulationParameters.defaultGlobalCFM) + return defaultglobalcfm_; +} +void PhysicsSimulationParameters::set_defaultglobalcfm(double value) { + + defaultglobalcfm_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.PhysicsSimulationParameters.defaultGlobalCFM) +} + +// double frictionCFM = 17; +void PhysicsSimulationParameters::clear_frictioncfm() { + frictioncfm_ = 0; +} +double PhysicsSimulationParameters::frictioncfm() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.PhysicsSimulationParameters.frictionCFM) + return frictioncfm_; +} +void PhysicsSimulationParameters::set_frictioncfm(double value) { + + frictioncfm_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.PhysicsSimulationParameters.frictionCFM) +} + +// int32 enableConeFriction = 18; +void PhysicsSimulationParameters::clear_enableconefriction() { + enableconefriction_ = 0; +} +::google::protobuf::int32 PhysicsSimulationParameters::enableconefriction() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.PhysicsSimulationParameters.enableConeFriction) + return enableconefriction_; +} +void PhysicsSimulationParameters::set_enableconefriction(::google::protobuf::int32 value) { + + enableconefriction_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.PhysicsSimulationParameters.enableConeFriction) +} + +// int32 deterministicOverlappingPairs = 19; +void PhysicsSimulationParameters::clear_deterministicoverlappingpairs() { + deterministicoverlappingpairs_ = 0; +} +::google::protobuf::int32 PhysicsSimulationParameters::deterministicoverlappingpairs() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.PhysicsSimulationParameters.deterministicOverlappingPairs) + return deterministicoverlappingpairs_; +} +void PhysicsSimulationParameters::set_deterministicoverlappingpairs(::google::protobuf::int32 value) { + + deterministicoverlappingpairs_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.PhysicsSimulationParameters.deterministicOverlappingPairs) +} + +// double allowedCcdPenetration = 20; +void PhysicsSimulationParameters::clear_allowedccdpenetration() { + allowedccdpenetration_ = 0; +} +double PhysicsSimulationParameters::allowedccdpenetration() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.PhysicsSimulationParameters.allowedCcdPenetration) + return allowedccdpenetration_; +} +void PhysicsSimulationParameters::set_allowedccdpenetration(double value) { + + allowedccdpenetration_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.PhysicsSimulationParameters.allowedCcdPenetration) +} + +// int32 jointFeedbackMode = 21; +void PhysicsSimulationParameters::clear_jointfeedbackmode() { + jointfeedbackmode_ = 0; +} +::google::protobuf::int32 PhysicsSimulationParameters::jointfeedbackmode() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.PhysicsSimulationParameters.jointFeedbackMode) + return jointfeedbackmode_; +} +void PhysicsSimulationParameters::set_jointfeedbackmode(::google::protobuf::int32 value) { + + jointfeedbackmode_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.PhysicsSimulationParameters.jointFeedbackMode) +} + +// double solverResidualThreshold = 22; +void PhysicsSimulationParameters::clear_solverresidualthreshold() { + solverresidualthreshold_ = 0; +} +double PhysicsSimulationParameters::solverresidualthreshold() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.PhysicsSimulationParameters.solverResidualThreshold) + return solverresidualthreshold_; +} +void PhysicsSimulationParameters::set_solverresidualthreshold(double value) { + + solverresidualthreshold_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.PhysicsSimulationParameters.solverResidualThreshold) +} + +// double contactSlop = 23; +void PhysicsSimulationParameters::clear_contactslop() { + contactslop_ = 0; +} +double PhysicsSimulationParameters::contactslop() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.PhysicsSimulationParameters.contactSlop) + return contactslop_; +} +void PhysicsSimulationParameters::set_contactslop(double value) { + + contactslop_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.PhysicsSimulationParameters.contactSlop) +} + +// int32 enableSAT = 24; +void PhysicsSimulationParameters::clear_enablesat() { + enablesat_ = 0; +} +::google::protobuf::int32 PhysicsSimulationParameters::enablesat() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.PhysicsSimulationParameters.enableSAT) + return enablesat_; +} +void PhysicsSimulationParameters::set_enablesat(::google::protobuf::int32 value) { + + enablesat_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.PhysicsSimulationParameters.enableSAT) +} + +// int32 constraintSolverType = 25; +void PhysicsSimulationParameters::clear_constraintsolvertype() { + constraintsolvertype_ = 0; +} +::google::protobuf::int32 PhysicsSimulationParameters::constraintsolvertype() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.PhysicsSimulationParameters.constraintSolverType) + return constraintsolvertype_; +} +void PhysicsSimulationParameters::set_constraintsolvertype(::google::protobuf::int32 value) { + + constraintsolvertype_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.PhysicsSimulationParameters.constraintSolverType) +} + +// int32 minimumSolverIslandSize = 26; +void PhysicsSimulationParameters::clear_minimumsolverislandsize() { + minimumsolverislandsize_ = 0; +} +::google::protobuf::int32 PhysicsSimulationParameters::minimumsolverislandsize() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.PhysicsSimulationParameters.minimumSolverIslandSize) + return minimumsolverislandsize_; +} +void PhysicsSimulationParameters::set_minimumsolverislandsize(::google::protobuf::int32 value) { + + minimumsolverislandsize_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.PhysicsSimulationParameters.minimumSolverIslandSize) +} + +#endif // PROTOBUF_INLINE_NOT_IN_HEADERS + +// =================================================================== + +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const int PhysicsSimulationParametersCommand::kUpdateFlagsFieldNumber; +const int PhysicsSimulationParametersCommand::kParamsFieldNumber; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 + +PhysicsSimulationParametersCommand::PhysicsSimulationParametersCommand() + : ::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.PhysicsSimulationParametersCommand) +} +PhysicsSimulationParametersCommand::PhysicsSimulationParametersCommand(const PhysicsSimulationParametersCommand& from) + : ::google::protobuf::Message(), + _internal_metadata_(NULL), + _cached_size_(0) { + _internal_metadata_.MergeFrom(from._internal_metadata_); + if (from.has_params()) { + params_ = new ::pybullet_grpc::PhysicsSimulationParameters(*from.params_); + } else { + params_ = NULL; + } + updateflags_ = from.updateflags_; + // @@protoc_insertion_point(copy_constructor:pybullet_grpc.PhysicsSimulationParametersCommand) +} + +void PhysicsSimulationParametersCommand::SharedCtor() { + ::memset(¶ms_, 0, reinterpret_cast(&updateflags_) - + reinterpret_cast(¶ms_) + sizeof(updateflags_)); + _cached_size_ = 0; +} + +PhysicsSimulationParametersCommand::~PhysicsSimulationParametersCommand() { + // @@protoc_insertion_point(destructor:pybullet_grpc.PhysicsSimulationParametersCommand) + SharedDtor(); +} + +void PhysicsSimulationParametersCommand::SharedDtor() { + if (this != internal_default_instance()) { + delete params_; + } +} + +void PhysicsSimulationParametersCommand::SetCachedSize(int size) const { + GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN(); + _cached_size_ = size; + GOOGLE_SAFE_CONCURRENT_WRITES_END(); +} +const ::google::protobuf::Descriptor* PhysicsSimulationParametersCommand::descriptor() { + protobuf_pybullet_2eproto::protobuf_AssignDescriptorsOnce(); + return protobuf_pybullet_2eproto::file_level_metadata[27].descriptor; +} + +const PhysicsSimulationParametersCommand& PhysicsSimulationParametersCommand::default_instance() { + protobuf_pybullet_2eproto::InitDefaults(); + return *internal_default_instance(); +} + +PhysicsSimulationParametersCommand* PhysicsSimulationParametersCommand::New(::google::protobuf::Arena* arena) const { + PhysicsSimulationParametersCommand* n = new PhysicsSimulationParametersCommand; + if (arena != NULL) { + arena->Own(n); + } + return n; +} + +void PhysicsSimulationParametersCommand::Clear() { +// @@protoc_insertion_point(message_clear_start:pybullet_grpc.PhysicsSimulationParametersCommand) + if (GetArenaNoVirtual() == NULL && params_ != NULL) { + delete params_; + } + params_ = NULL; + updateflags_ = 0; +} + +bool PhysicsSimulationParametersCommand::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.PhysicsSimulationParametersCommand) + 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 updateFlags = 1; + case 1: { + if (tag == 8u) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>( + input, &updateflags_))); + } else { + goto handle_unusual; + } + break; + } + + // .pybullet_grpc.PhysicsSimulationParameters params = 2; + case 2: { + if (tag == 18u) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessageNoVirtual( + input, mutable_params())); + } 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.PhysicsSimulationParametersCommand) + return true; +failure: + // @@protoc_insertion_point(parse_failure:pybullet_grpc.PhysicsSimulationParametersCommand) + return false; +#undef DO_ +} + +void PhysicsSimulationParametersCommand::SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const { + // @@protoc_insertion_point(serialize_start:pybullet_grpc.PhysicsSimulationParametersCommand) + // int32 updateFlags = 1; + if (this->updateflags() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteInt32(1, this->updateflags(), output); + } + + // .pybullet_grpc.PhysicsSimulationParameters params = 2; + if (this->has_params()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 2, *this->params_, output); + } + + // @@protoc_insertion_point(serialize_end:pybullet_grpc.PhysicsSimulationParametersCommand) +} + +::google::protobuf::uint8* PhysicsSimulationParametersCommand::InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const { + (void)deterministic; // Unused + // @@protoc_insertion_point(serialize_to_array_start:pybullet_grpc.PhysicsSimulationParametersCommand) + // int32 updateFlags = 1; + if (this->updateflags() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteInt32ToArray(1, this->updateflags(), target); + } + + // .pybullet_grpc.PhysicsSimulationParameters params = 2; + if (this->has_params()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageNoVirtualToArray( + 2, *this->params_, false, target); + } + + // @@protoc_insertion_point(serialize_to_array_end:pybullet_grpc.PhysicsSimulationParametersCommand) + return target; +} + +size_t PhysicsSimulationParametersCommand::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:pybullet_grpc.PhysicsSimulationParametersCommand) + size_t total_size = 0; + + // .pybullet_grpc.PhysicsSimulationParameters params = 2; + if (this->has_params()) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSizeNoVirtual( + *this->params_); + } + + // int32 updateFlags = 1; + if (this->updateflags() != 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::Int32Size( + this->updateflags()); + } + + 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 PhysicsSimulationParametersCommand::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:pybullet_grpc.PhysicsSimulationParametersCommand) + GOOGLE_DCHECK_NE(&from, this); + const PhysicsSimulationParametersCommand* source = + ::google::protobuf::internal::DynamicCastToGenerated( + &from); + if (source == NULL) { + // @@protoc_insertion_point(generalized_merge_from_cast_fail:pybullet_grpc.PhysicsSimulationParametersCommand) + ::google::protobuf::internal::ReflectionOps::Merge(from, this); + } else { + // @@protoc_insertion_point(generalized_merge_from_cast_success:pybullet_grpc.PhysicsSimulationParametersCommand) + MergeFrom(*source); + } +} + +void PhysicsSimulationParametersCommand::MergeFrom(const PhysicsSimulationParametersCommand& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:pybullet_grpc.PhysicsSimulationParametersCommand) + GOOGLE_DCHECK_NE(&from, this); + _internal_metadata_.MergeFrom(from._internal_metadata_); + if (from.has_params()) { + mutable_params()->::pybullet_grpc::PhysicsSimulationParameters::MergeFrom(from.params()); + } + if (from.updateflags() != 0) { + set_updateflags(from.updateflags()); + } +} + +void PhysicsSimulationParametersCommand::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:pybullet_grpc.PhysicsSimulationParametersCommand) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +void PhysicsSimulationParametersCommand::CopyFrom(const PhysicsSimulationParametersCommand& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:pybullet_grpc.PhysicsSimulationParametersCommand) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool PhysicsSimulationParametersCommand::IsInitialized() const { + return true; +} + +void PhysicsSimulationParametersCommand::Swap(PhysicsSimulationParametersCommand* other) { + if (other == this) return; + InternalSwap(other); +} +void PhysicsSimulationParametersCommand::InternalSwap(PhysicsSimulationParametersCommand* other) { + std::swap(params_, other->params_); + std::swap(updateflags_, other->updateflags_); + std::swap(_cached_size_, other->_cached_size_); +} + +::google::protobuf::Metadata PhysicsSimulationParametersCommand::GetMetadata() const { + protobuf_pybullet_2eproto::protobuf_AssignDescriptorsOnce(); + return protobuf_pybullet_2eproto::file_level_metadata[27]; +} + +#if PROTOBUF_INLINE_NOT_IN_HEADERS +// PhysicsSimulationParametersCommand + +// int32 updateFlags = 1; +void PhysicsSimulationParametersCommand::clear_updateflags() { + updateflags_ = 0; +} +::google::protobuf::int32 PhysicsSimulationParametersCommand::updateflags() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.PhysicsSimulationParametersCommand.updateFlags) + return updateflags_; +} +void PhysicsSimulationParametersCommand::set_updateflags(::google::protobuf::int32 value) { + + updateflags_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.PhysicsSimulationParametersCommand.updateFlags) +} + +// .pybullet_grpc.PhysicsSimulationParameters params = 2; +bool PhysicsSimulationParametersCommand::has_params() const { + return this != internal_default_instance() && params_ != NULL; +} +void PhysicsSimulationParametersCommand::clear_params() { + if (GetArenaNoVirtual() == NULL && params_ != NULL) delete params_; + params_ = NULL; +} +const ::pybullet_grpc::PhysicsSimulationParameters& PhysicsSimulationParametersCommand::params() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.PhysicsSimulationParametersCommand.params) + return params_ != NULL ? *params_ + : *::pybullet_grpc::PhysicsSimulationParameters::internal_default_instance(); +} +::pybullet_grpc::PhysicsSimulationParameters* PhysicsSimulationParametersCommand::mutable_params() { + + if (params_ == NULL) { + params_ = new ::pybullet_grpc::PhysicsSimulationParameters; + } + // @@protoc_insertion_point(field_mutable:pybullet_grpc.PhysicsSimulationParametersCommand.params) + return params_; +} +::pybullet_grpc::PhysicsSimulationParameters* PhysicsSimulationParametersCommand::release_params() { + // @@protoc_insertion_point(field_release:pybullet_grpc.PhysicsSimulationParametersCommand.params) + + ::pybullet_grpc::PhysicsSimulationParameters* temp = params_; + params_ = NULL; + return temp; +} +void PhysicsSimulationParametersCommand::set_allocated_params(::pybullet_grpc::PhysicsSimulationParameters* params) { + delete params_; + params_ = params; + if (params) { + + } else { + + } + // @@protoc_insertion_point(field_set_allocated:pybullet_grpc.PhysicsSimulationParametersCommand.params) +} + +#endif // PROTOBUF_INLINE_NOT_IN_HEADERS + +// =================================================================== + +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const int JointMotorControlCommand::kBodyUniqueIdFieldNumber; +const int JointMotorControlCommand::kControlModeFieldNumber; +const int JointMotorControlCommand::kUpdateFlagsFieldNumber; +const int JointMotorControlCommand::kKpFieldNumber; +const int JointMotorControlCommand::kKdFieldNumber; +const int JointMotorControlCommand::kMaxVelocityFieldNumber; +const int JointMotorControlCommand::kHasDesiredStateFlagsFieldNumber; +const int JointMotorControlCommand::kDesiredStateQFieldNumber; +const int JointMotorControlCommand::kDesiredStateQdotFieldNumber; +const int JointMotorControlCommand::kDesiredStateForceTorqueFieldNumber; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 + +JointMotorControlCommand::JointMotorControlCommand() + : ::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.JointMotorControlCommand) +} +JointMotorControlCommand::JointMotorControlCommand(const JointMotorControlCommand& from) + : ::google::protobuf::Message(), + _internal_metadata_(NULL), + kp_(from.kp_), + kd_(from.kd_), + maxvelocity_(from.maxvelocity_), + hasdesiredstateflags_(from.hasdesiredstateflags_), + desiredstateq_(from.desiredstateq_), + desiredstateqdot_(from.desiredstateqdot_), + desiredstateforcetorque_(from.desiredstateforcetorque_), + _cached_size_(0) { + _internal_metadata_.MergeFrom(from._internal_metadata_); + ::memcpy(&bodyuniqueid_, &from.bodyuniqueid_, + reinterpret_cast(&updateflags_) - + reinterpret_cast(&bodyuniqueid_) + sizeof(updateflags_)); + // @@protoc_insertion_point(copy_constructor:pybullet_grpc.JointMotorControlCommand) +} + +void JointMotorControlCommand::SharedCtor() { + ::memset(&bodyuniqueid_, 0, reinterpret_cast(&updateflags_) - + reinterpret_cast(&bodyuniqueid_) + sizeof(updateflags_)); + _cached_size_ = 0; +} + +JointMotorControlCommand::~JointMotorControlCommand() { + // @@protoc_insertion_point(destructor:pybullet_grpc.JointMotorControlCommand) + SharedDtor(); +} + +void JointMotorControlCommand::SharedDtor() { +} + +void JointMotorControlCommand::SetCachedSize(int size) const { + GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN(); + _cached_size_ = size; + GOOGLE_SAFE_CONCURRENT_WRITES_END(); +} +const ::google::protobuf::Descriptor* JointMotorControlCommand::descriptor() { + protobuf_pybullet_2eproto::protobuf_AssignDescriptorsOnce(); + return protobuf_pybullet_2eproto::file_level_metadata[28].descriptor; +} + +const JointMotorControlCommand& JointMotorControlCommand::default_instance() { + protobuf_pybullet_2eproto::InitDefaults(); + return *internal_default_instance(); +} + +JointMotorControlCommand* JointMotorControlCommand::New(::google::protobuf::Arena* arena) const { + JointMotorControlCommand* n = new JointMotorControlCommand; + if (arena != NULL) { + arena->Own(n); + } + return n; +} + +void JointMotorControlCommand::Clear() { +// @@protoc_insertion_point(message_clear_start:pybullet_grpc.JointMotorControlCommand) + kp_.Clear(); + kd_.Clear(); + maxvelocity_.Clear(); + hasdesiredstateflags_.Clear(); + desiredstateq_.Clear(); + desiredstateqdot_.Clear(); + desiredstateforcetorque_.Clear(); + ::memset(&bodyuniqueid_, 0, reinterpret_cast(&updateflags_) - + reinterpret_cast(&bodyuniqueid_) + sizeof(updateflags_)); +} + +bool JointMotorControlCommand::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.JointMotorControlCommand) + 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 bodyUniqueId = 1; + case 1: { + if (tag == 8u) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>( + input, &bodyuniqueid_))); + } else { + goto handle_unusual; + } + break; + } + + // int32 controlMode = 2; + case 2: { + if (tag == 16u) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>( + input, &controlmode_))); + } else { + goto handle_unusual; + } + break; + } + + // int32 updateFlags = 3; + case 3: { + if (tag == 24u) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>( + input, &updateflags_))); + } else { + goto handle_unusual; + } + break; + } + + // repeated double Kp = 4; + case 4: { + if (tag == 34u) { + DO_((::google::protobuf::internal::WireFormatLite::ReadPackedPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, this->mutable_kp()))); + } else if (tag == 33u) { + DO_((::google::protobuf::internal::WireFormatLite::ReadRepeatedPrimitiveNoInline< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + 1, 34u, input, this->mutable_kp()))); + } else { + goto handle_unusual; + } + break; + } + + // repeated double Kd = 5; + case 5: { + if (tag == 42u) { + DO_((::google::protobuf::internal::WireFormatLite::ReadPackedPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, this->mutable_kd()))); + } else if (tag == 41u) { + DO_((::google::protobuf::internal::WireFormatLite::ReadRepeatedPrimitiveNoInline< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + 1, 42u, input, this->mutable_kd()))); + } else { + goto handle_unusual; + } + break; + } + + // repeated double maxVelocity = 6; + case 6: { + if (tag == 50u) { + DO_((::google::protobuf::internal::WireFormatLite::ReadPackedPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, this->mutable_maxvelocity()))); + } else if (tag == 49u) { + DO_((::google::protobuf::internal::WireFormatLite::ReadRepeatedPrimitiveNoInline< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + 1, 50u, input, this->mutable_maxvelocity()))); + } else { + goto handle_unusual; + } + break; + } + + // repeated int32 hasDesiredStateFlags = 7; + case 7: { + if (tag == 58u) { + DO_((::google::protobuf::internal::WireFormatLite::ReadPackedPrimitive< + ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>( + input, this->mutable_hasdesiredstateflags()))); + } else if (tag == 56u) { + DO_((::google::protobuf::internal::WireFormatLite::ReadRepeatedPrimitiveNoInline< + ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>( + 1, 58u, input, this->mutable_hasdesiredstateflags()))); + } else { + goto handle_unusual; + } + break; + } + + // repeated double desiredStateQ = 8; + case 8: { + if (tag == 66u) { + DO_((::google::protobuf::internal::WireFormatLite::ReadPackedPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, this->mutable_desiredstateq()))); + } else if (tag == 65u) { + DO_((::google::protobuf::internal::WireFormatLite::ReadRepeatedPrimitiveNoInline< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + 1, 66u, input, this->mutable_desiredstateq()))); + } else { + goto handle_unusual; + } + break; + } + + // repeated double desiredStateQdot = 9; + case 9: { + if (tag == 74u) { + DO_((::google::protobuf::internal::WireFormatLite::ReadPackedPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, this->mutable_desiredstateqdot()))); + } else if (tag == 73u) { + DO_((::google::protobuf::internal::WireFormatLite::ReadRepeatedPrimitiveNoInline< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + 1, 74u, input, this->mutable_desiredstateqdot()))); + } else { + goto handle_unusual; + } + break; + } + + // repeated double desiredStateForceTorque = 10; + case 10: { + if (tag == 82u) { + DO_((::google::protobuf::internal::WireFormatLite::ReadPackedPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, this->mutable_desiredstateforcetorque()))); + } else if (tag == 81u) { + DO_((::google::protobuf::internal::WireFormatLite::ReadRepeatedPrimitiveNoInline< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + 1, 82u, input, this->mutable_desiredstateforcetorque()))); + } 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.JointMotorControlCommand) + return true; +failure: + // @@protoc_insertion_point(parse_failure:pybullet_grpc.JointMotorControlCommand) + return false; +#undef DO_ +} + +void JointMotorControlCommand::SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const { + // @@protoc_insertion_point(serialize_start:pybullet_grpc.JointMotorControlCommand) + // int32 bodyUniqueId = 1; + if (this->bodyuniqueid() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteInt32(1, this->bodyuniqueid(), output); + } + + // int32 controlMode = 2; + if (this->controlmode() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteInt32(2, this->controlmode(), output); + } + + // int32 updateFlags = 3; + if (this->updateflags() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteInt32(3, this->updateflags(), output); + } + + // repeated double Kp = 4; + if (this->kp_size() > 0) { + ::google::protobuf::internal::WireFormatLite::WriteTag(4, ::google::protobuf::internal::WireFormatLite::WIRETYPE_LENGTH_DELIMITED, output); + output->WriteVarint32(_kp_cached_byte_size_); + ::google::protobuf::internal::WireFormatLite::WriteDoubleArray( + this->kp().data(), this->kp_size(), output); + } + + // repeated double Kd = 5; + if (this->kd_size() > 0) { + ::google::protobuf::internal::WireFormatLite::WriteTag(5, ::google::protobuf::internal::WireFormatLite::WIRETYPE_LENGTH_DELIMITED, output); + output->WriteVarint32(_kd_cached_byte_size_); + ::google::protobuf::internal::WireFormatLite::WriteDoubleArray( + this->kd().data(), this->kd_size(), output); + } + + // repeated double maxVelocity = 6; + if (this->maxvelocity_size() > 0) { + ::google::protobuf::internal::WireFormatLite::WriteTag(6, ::google::protobuf::internal::WireFormatLite::WIRETYPE_LENGTH_DELIMITED, output); + output->WriteVarint32(_maxvelocity_cached_byte_size_); + ::google::protobuf::internal::WireFormatLite::WriteDoubleArray( + this->maxvelocity().data(), this->maxvelocity_size(), output); + } + + // repeated int32 hasDesiredStateFlags = 7; + if (this->hasdesiredstateflags_size() > 0) { + ::google::protobuf::internal::WireFormatLite::WriteTag(7, ::google::protobuf::internal::WireFormatLite::WIRETYPE_LENGTH_DELIMITED, output); + output->WriteVarint32(_hasdesiredstateflags_cached_byte_size_); + } + for (int i = 0; i < this->hasdesiredstateflags_size(); i++) { + ::google::protobuf::internal::WireFormatLite::WriteInt32NoTag( + this->hasdesiredstateflags(i), output); + } + + // repeated double desiredStateQ = 8; + if (this->desiredstateq_size() > 0) { + ::google::protobuf::internal::WireFormatLite::WriteTag(8, ::google::protobuf::internal::WireFormatLite::WIRETYPE_LENGTH_DELIMITED, output); + output->WriteVarint32(_desiredstateq_cached_byte_size_); + ::google::protobuf::internal::WireFormatLite::WriteDoubleArray( + this->desiredstateq().data(), this->desiredstateq_size(), output); + } + + // repeated double desiredStateQdot = 9; + if (this->desiredstateqdot_size() > 0) { + ::google::protobuf::internal::WireFormatLite::WriteTag(9, ::google::protobuf::internal::WireFormatLite::WIRETYPE_LENGTH_DELIMITED, output); + output->WriteVarint32(_desiredstateqdot_cached_byte_size_); + ::google::protobuf::internal::WireFormatLite::WriteDoubleArray( + this->desiredstateqdot().data(), this->desiredstateqdot_size(), output); + } + + // repeated double desiredStateForceTorque = 10; + if (this->desiredstateforcetorque_size() > 0) { + ::google::protobuf::internal::WireFormatLite::WriteTag(10, ::google::protobuf::internal::WireFormatLite::WIRETYPE_LENGTH_DELIMITED, output); + output->WriteVarint32(_desiredstateforcetorque_cached_byte_size_); + ::google::protobuf::internal::WireFormatLite::WriteDoubleArray( + this->desiredstateforcetorque().data(), this->desiredstateforcetorque_size(), output); + } + + // @@protoc_insertion_point(serialize_end:pybullet_grpc.JointMotorControlCommand) +} + +::google::protobuf::uint8* JointMotorControlCommand::InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const { + (void)deterministic; // Unused + // @@protoc_insertion_point(serialize_to_array_start:pybullet_grpc.JointMotorControlCommand) + // int32 bodyUniqueId = 1; + if (this->bodyuniqueid() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteInt32ToArray(1, this->bodyuniqueid(), target); + } + + // int32 controlMode = 2; + if (this->controlmode() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteInt32ToArray(2, this->controlmode(), target); + } + + // int32 updateFlags = 3; + if (this->updateflags() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteInt32ToArray(3, this->updateflags(), target); + } + + // repeated double Kp = 4; + if (this->kp_size() > 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteTagToArray( + 4, + ::google::protobuf::internal::WireFormatLite::WIRETYPE_LENGTH_DELIMITED, + target); + target = ::google::protobuf::io::CodedOutputStream::WriteVarint32ToArray( + _kp_cached_byte_size_, target); + } + for (int i = 0; i < this->kp_size(); i++) { + target = ::google::protobuf::internal::WireFormatLite:: + WriteDoubleNoTagToArray(this->kp(i), target); + } + + // repeated double Kd = 5; + if (this->kd_size() > 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteTagToArray( + 5, + ::google::protobuf::internal::WireFormatLite::WIRETYPE_LENGTH_DELIMITED, + target); + target = ::google::protobuf::io::CodedOutputStream::WriteVarint32ToArray( + _kd_cached_byte_size_, target); + } + for (int i = 0; i < this->kd_size(); i++) { + target = ::google::protobuf::internal::WireFormatLite:: + WriteDoubleNoTagToArray(this->kd(i), target); + } + + // repeated double maxVelocity = 6; + if (this->maxvelocity_size() > 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteTagToArray( + 6, + ::google::protobuf::internal::WireFormatLite::WIRETYPE_LENGTH_DELIMITED, + target); + target = ::google::protobuf::io::CodedOutputStream::WriteVarint32ToArray( + _maxvelocity_cached_byte_size_, target); + } + for (int i = 0; i < this->maxvelocity_size(); i++) { + target = ::google::protobuf::internal::WireFormatLite:: + WriteDoubleNoTagToArray(this->maxvelocity(i), target); + } + + // repeated int32 hasDesiredStateFlags = 7; + if (this->hasdesiredstateflags_size() > 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteTagToArray( + 7, + ::google::protobuf::internal::WireFormatLite::WIRETYPE_LENGTH_DELIMITED, + target); + target = ::google::protobuf::io::CodedOutputStream::WriteVarint32ToArray( + _hasdesiredstateflags_cached_byte_size_, target); + } + for (int i = 0; i < this->hasdesiredstateflags_size(); i++) { + target = ::google::protobuf::internal::WireFormatLite:: + WriteInt32NoTagToArray(this->hasdesiredstateflags(i), target); + } + + // repeated double desiredStateQ = 8; + if (this->desiredstateq_size() > 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteTagToArray( + 8, + ::google::protobuf::internal::WireFormatLite::WIRETYPE_LENGTH_DELIMITED, + target); + target = ::google::protobuf::io::CodedOutputStream::WriteVarint32ToArray( + _desiredstateq_cached_byte_size_, target); + } + for (int i = 0; i < this->desiredstateq_size(); i++) { + target = ::google::protobuf::internal::WireFormatLite:: + WriteDoubleNoTagToArray(this->desiredstateq(i), target); + } + + // repeated double desiredStateQdot = 9; + if (this->desiredstateqdot_size() > 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteTagToArray( + 9, + ::google::protobuf::internal::WireFormatLite::WIRETYPE_LENGTH_DELIMITED, + target); + target = ::google::protobuf::io::CodedOutputStream::WriteVarint32ToArray( + _desiredstateqdot_cached_byte_size_, target); + } + for (int i = 0; i < this->desiredstateqdot_size(); i++) { + target = ::google::protobuf::internal::WireFormatLite:: + WriteDoubleNoTagToArray(this->desiredstateqdot(i), target); + } + + // repeated double desiredStateForceTorque = 10; + if (this->desiredstateforcetorque_size() > 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteTagToArray( + 10, + ::google::protobuf::internal::WireFormatLite::WIRETYPE_LENGTH_DELIMITED, + target); + target = ::google::protobuf::io::CodedOutputStream::WriteVarint32ToArray( + _desiredstateforcetorque_cached_byte_size_, target); + } + for (int i = 0; i < this->desiredstateforcetorque_size(); i++) { + target = ::google::protobuf::internal::WireFormatLite:: + WriteDoubleNoTagToArray(this->desiredstateforcetorque(i), target); + } + + // @@protoc_insertion_point(serialize_to_array_end:pybullet_grpc.JointMotorControlCommand) + return target; +} + +size_t JointMotorControlCommand::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:pybullet_grpc.JointMotorControlCommand) + size_t total_size = 0; + + // repeated double Kp = 4; + { + unsigned int count = this->kp_size(); + size_t data_size = 8UL * count; + if (data_size > 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::Int32Size(data_size); + } + int cached_size = ::google::protobuf::internal::ToCachedSize(data_size); + GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN(); + _kp_cached_byte_size_ = cached_size; + GOOGLE_SAFE_CONCURRENT_WRITES_END(); + total_size += data_size; + } + + // repeated double Kd = 5; + { + unsigned int count = this->kd_size(); + size_t data_size = 8UL * count; + if (data_size > 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::Int32Size(data_size); + } + int cached_size = ::google::protobuf::internal::ToCachedSize(data_size); + GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN(); + _kd_cached_byte_size_ = cached_size; + GOOGLE_SAFE_CONCURRENT_WRITES_END(); + total_size += data_size; + } + + // repeated double maxVelocity = 6; + { + unsigned int count = this->maxvelocity_size(); + size_t data_size = 8UL * count; + if (data_size > 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::Int32Size(data_size); + } + int cached_size = ::google::protobuf::internal::ToCachedSize(data_size); + GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN(); + _maxvelocity_cached_byte_size_ = cached_size; + GOOGLE_SAFE_CONCURRENT_WRITES_END(); + total_size += data_size; + } + + // repeated int32 hasDesiredStateFlags = 7; + { + size_t data_size = ::google::protobuf::internal::WireFormatLite:: + Int32Size(this->hasdesiredstateflags_); + if (data_size > 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::Int32Size(data_size); + } + int cached_size = ::google::protobuf::internal::ToCachedSize(data_size); + GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN(); + _hasdesiredstateflags_cached_byte_size_ = cached_size; + GOOGLE_SAFE_CONCURRENT_WRITES_END(); + total_size += data_size; + } + + // repeated double desiredStateQ = 8; + { + unsigned int count = this->desiredstateq_size(); + size_t data_size = 8UL * count; + if (data_size > 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::Int32Size(data_size); + } + int cached_size = ::google::protobuf::internal::ToCachedSize(data_size); + GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN(); + _desiredstateq_cached_byte_size_ = cached_size; + GOOGLE_SAFE_CONCURRENT_WRITES_END(); + total_size += data_size; + } + + // repeated double desiredStateQdot = 9; + { + unsigned int count = this->desiredstateqdot_size(); + size_t data_size = 8UL * count; + if (data_size > 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::Int32Size(data_size); + } + int cached_size = ::google::protobuf::internal::ToCachedSize(data_size); + GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN(); + _desiredstateqdot_cached_byte_size_ = cached_size; + GOOGLE_SAFE_CONCURRENT_WRITES_END(); + total_size += data_size; + } + + // repeated double desiredStateForceTorque = 10; + { + unsigned int count = this->desiredstateforcetorque_size(); + size_t data_size = 8UL * count; + if (data_size > 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::Int32Size(data_size); + } + int cached_size = ::google::protobuf::internal::ToCachedSize(data_size); + GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN(); + _desiredstateforcetorque_cached_byte_size_ = cached_size; + GOOGLE_SAFE_CONCURRENT_WRITES_END(); + total_size += data_size; + } + + // int32 bodyUniqueId = 1; + if (this->bodyuniqueid() != 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::Int32Size( + this->bodyuniqueid()); + } + + // int32 controlMode = 2; + if (this->controlmode() != 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::Int32Size( + this->controlmode()); + } + + // int32 updateFlags = 3; + if (this->updateflags() != 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::Int32Size( + this->updateflags()); + } + + 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 JointMotorControlCommand::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:pybullet_grpc.JointMotorControlCommand) + GOOGLE_DCHECK_NE(&from, this); + const JointMotorControlCommand* source = + ::google::protobuf::internal::DynamicCastToGenerated( + &from); + if (source == NULL) { + // @@protoc_insertion_point(generalized_merge_from_cast_fail:pybullet_grpc.JointMotorControlCommand) + ::google::protobuf::internal::ReflectionOps::Merge(from, this); + } else { + // @@protoc_insertion_point(generalized_merge_from_cast_success:pybullet_grpc.JointMotorControlCommand) + MergeFrom(*source); + } +} + +void JointMotorControlCommand::MergeFrom(const JointMotorControlCommand& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:pybullet_grpc.JointMotorControlCommand) + GOOGLE_DCHECK_NE(&from, this); + _internal_metadata_.MergeFrom(from._internal_metadata_); + kp_.MergeFrom(from.kp_); + kd_.MergeFrom(from.kd_); + maxvelocity_.MergeFrom(from.maxvelocity_); + hasdesiredstateflags_.MergeFrom(from.hasdesiredstateflags_); + desiredstateq_.MergeFrom(from.desiredstateq_); + desiredstateqdot_.MergeFrom(from.desiredstateqdot_); + desiredstateforcetorque_.MergeFrom(from.desiredstateforcetorque_); + if (from.bodyuniqueid() != 0) { + set_bodyuniqueid(from.bodyuniqueid()); + } + if (from.controlmode() != 0) { + set_controlmode(from.controlmode()); + } + if (from.updateflags() != 0) { + set_updateflags(from.updateflags()); + } +} + +void JointMotorControlCommand::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:pybullet_grpc.JointMotorControlCommand) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +void JointMotorControlCommand::CopyFrom(const JointMotorControlCommand& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:pybullet_grpc.JointMotorControlCommand) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool JointMotorControlCommand::IsInitialized() const { + return true; +} + +void JointMotorControlCommand::Swap(JointMotorControlCommand* other) { + if (other == this) return; + InternalSwap(other); +} +void JointMotorControlCommand::InternalSwap(JointMotorControlCommand* other) { + kp_.UnsafeArenaSwap(&other->kp_); + kd_.UnsafeArenaSwap(&other->kd_); + maxvelocity_.UnsafeArenaSwap(&other->maxvelocity_); + hasdesiredstateflags_.UnsafeArenaSwap(&other->hasdesiredstateflags_); + desiredstateq_.UnsafeArenaSwap(&other->desiredstateq_); + desiredstateqdot_.UnsafeArenaSwap(&other->desiredstateqdot_); + desiredstateforcetorque_.UnsafeArenaSwap(&other->desiredstateforcetorque_); + std::swap(bodyuniqueid_, other->bodyuniqueid_); + std::swap(controlmode_, other->controlmode_); + std::swap(updateflags_, other->updateflags_); + std::swap(_cached_size_, other->_cached_size_); +} + +::google::protobuf::Metadata JointMotorControlCommand::GetMetadata() const { + protobuf_pybullet_2eproto::protobuf_AssignDescriptorsOnce(); + return protobuf_pybullet_2eproto::file_level_metadata[28]; +} + +#if PROTOBUF_INLINE_NOT_IN_HEADERS +// JointMotorControlCommand + +// int32 bodyUniqueId = 1; +void JointMotorControlCommand::clear_bodyuniqueid() { + bodyuniqueid_ = 0; +} +::google::protobuf::int32 JointMotorControlCommand::bodyuniqueid() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.JointMotorControlCommand.bodyUniqueId) + return bodyuniqueid_; +} +void JointMotorControlCommand::set_bodyuniqueid(::google::protobuf::int32 value) { + + bodyuniqueid_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.JointMotorControlCommand.bodyUniqueId) +} + +// int32 controlMode = 2; +void JointMotorControlCommand::clear_controlmode() { + controlmode_ = 0; +} +::google::protobuf::int32 JointMotorControlCommand::controlmode() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.JointMotorControlCommand.controlMode) + return controlmode_; +} +void JointMotorControlCommand::set_controlmode(::google::protobuf::int32 value) { + + controlmode_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.JointMotorControlCommand.controlMode) +} + +// int32 updateFlags = 3; +void JointMotorControlCommand::clear_updateflags() { + updateflags_ = 0; +} +::google::protobuf::int32 JointMotorControlCommand::updateflags() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.JointMotorControlCommand.updateFlags) + return updateflags_; +} +void JointMotorControlCommand::set_updateflags(::google::protobuf::int32 value) { + + updateflags_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.JointMotorControlCommand.updateFlags) +} + +// repeated double Kp = 4; +int JointMotorControlCommand::kp_size() const { + return kp_.size(); +} +void JointMotorControlCommand::clear_kp() { + kp_.Clear(); +} +double JointMotorControlCommand::kp(int index) const { + // @@protoc_insertion_point(field_get:pybullet_grpc.JointMotorControlCommand.Kp) + return kp_.Get(index); +} +void JointMotorControlCommand::set_kp(int index, double value) { + kp_.Set(index, value); + // @@protoc_insertion_point(field_set:pybullet_grpc.JointMotorControlCommand.Kp) +} +void JointMotorControlCommand::add_kp(double value) { + kp_.Add(value); + // @@protoc_insertion_point(field_add:pybullet_grpc.JointMotorControlCommand.Kp) +} +const ::google::protobuf::RepeatedField< double >& +JointMotorControlCommand::kp() const { + // @@protoc_insertion_point(field_list:pybullet_grpc.JointMotorControlCommand.Kp) + return kp_; +} +::google::protobuf::RepeatedField< double >* +JointMotorControlCommand::mutable_kp() { + // @@protoc_insertion_point(field_mutable_list:pybullet_grpc.JointMotorControlCommand.Kp) + return &kp_; +} + +// repeated double Kd = 5; +int JointMotorControlCommand::kd_size() const { + return kd_.size(); +} +void JointMotorControlCommand::clear_kd() { + kd_.Clear(); +} +double JointMotorControlCommand::kd(int index) const { + // @@protoc_insertion_point(field_get:pybullet_grpc.JointMotorControlCommand.Kd) + return kd_.Get(index); +} +void JointMotorControlCommand::set_kd(int index, double value) { + kd_.Set(index, value); + // @@protoc_insertion_point(field_set:pybullet_grpc.JointMotorControlCommand.Kd) +} +void JointMotorControlCommand::add_kd(double value) { + kd_.Add(value); + // @@protoc_insertion_point(field_add:pybullet_grpc.JointMotorControlCommand.Kd) +} +const ::google::protobuf::RepeatedField< double >& +JointMotorControlCommand::kd() const { + // @@protoc_insertion_point(field_list:pybullet_grpc.JointMotorControlCommand.Kd) + return kd_; +} +::google::protobuf::RepeatedField< double >* +JointMotorControlCommand::mutable_kd() { + // @@protoc_insertion_point(field_mutable_list:pybullet_grpc.JointMotorControlCommand.Kd) + return &kd_; +} + +// repeated double maxVelocity = 6; +int JointMotorControlCommand::maxvelocity_size() const { + return maxvelocity_.size(); +} +void JointMotorControlCommand::clear_maxvelocity() { + maxvelocity_.Clear(); +} +double JointMotorControlCommand::maxvelocity(int index) const { + // @@protoc_insertion_point(field_get:pybullet_grpc.JointMotorControlCommand.maxVelocity) + return maxvelocity_.Get(index); +} +void JointMotorControlCommand::set_maxvelocity(int index, double value) { + maxvelocity_.Set(index, value); + // @@protoc_insertion_point(field_set:pybullet_grpc.JointMotorControlCommand.maxVelocity) +} +void JointMotorControlCommand::add_maxvelocity(double value) { + maxvelocity_.Add(value); + // @@protoc_insertion_point(field_add:pybullet_grpc.JointMotorControlCommand.maxVelocity) +} +const ::google::protobuf::RepeatedField< double >& +JointMotorControlCommand::maxvelocity() const { + // @@protoc_insertion_point(field_list:pybullet_grpc.JointMotorControlCommand.maxVelocity) + return maxvelocity_; +} +::google::protobuf::RepeatedField< double >* +JointMotorControlCommand::mutable_maxvelocity() { + // @@protoc_insertion_point(field_mutable_list:pybullet_grpc.JointMotorControlCommand.maxVelocity) + return &maxvelocity_; +} + +// repeated int32 hasDesiredStateFlags = 7; +int JointMotorControlCommand::hasdesiredstateflags_size() const { + return hasdesiredstateflags_.size(); +} +void JointMotorControlCommand::clear_hasdesiredstateflags() { + hasdesiredstateflags_.Clear(); +} +::google::protobuf::int32 JointMotorControlCommand::hasdesiredstateflags(int index) const { + // @@protoc_insertion_point(field_get:pybullet_grpc.JointMotorControlCommand.hasDesiredStateFlags) + return hasdesiredstateflags_.Get(index); +} +void JointMotorControlCommand::set_hasdesiredstateflags(int index, ::google::protobuf::int32 value) { + hasdesiredstateflags_.Set(index, value); + // @@protoc_insertion_point(field_set:pybullet_grpc.JointMotorControlCommand.hasDesiredStateFlags) +} +void JointMotorControlCommand::add_hasdesiredstateflags(::google::protobuf::int32 value) { + hasdesiredstateflags_.Add(value); + // @@protoc_insertion_point(field_add:pybullet_grpc.JointMotorControlCommand.hasDesiredStateFlags) +} +const ::google::protobuf::RepeatedField< ::google::protobuf::int32 >& +JointMotorControlCommand::hasdesiredstateflags() const { + // @@protoc_insertion_point(field_list:pybullet_grpc.JointMotorControlCommand.hasDesiredStateFlags) + return hasdesiredstateflags_; +} +::google::protobuf::RepeatedField< ::google::protobuf::int32 >* +JointMotorControlCommand::mutable_hasdesiredstateflags() { + // @@protoc_insertion_point(field_mutable_list:pybullet_grpc.JointMotorControlCommand.hasDesiredStateFlags) + return &hasdesiredstateflags_; +} + +// repeated double desiredStateQ = 8; +int JointMotorControlCommand::desiredstateq_size() const { + return desiredstateq_.size(); +} +void JointMotorControlCommand::clear_desiredstateq() { + desiredstateq_.Clear(); +} +double JointMotorControlCommand::desiredstateq(int index) const { + // @@protoc_insertion_point(field_get:pybullet_grpc.JointMotorControlCommand.desiredStateQ) + return desiredstateq_.Get(index); +} +void JointMotorControlCommand::set_desiredstateq(int index, double value) { + desiredstateq_.Set(index, value); + // @@protoc_insertion_point(field_set:pybullet_grpc.JointMotorControlCommand.desiredStateQ) +} +void JointMotorControlCommand::add_desiredstateq(double value) { + desiredstateq_.Add(value); + // @@protoc_insertion_point(field_add:pybullet_grpc.JointMotorControlCommand.desiredStateQ) +} +const ::google::protobuf::RepeatedField< double >& +JointMotorControlCommand::desiredstateq() const { + // @@protoc_insertion_point(field_list:pybullet_grpc.JointMotorControlCommand.desiredStateQ) + return desiredstateq_; +} +::google::protobuf::RepeatedField< double >* +JointMotorControlCommand::mutable_desiredstateq() { + // @@protoc_insertion_point(field_mutable_list:pybullet_grpc.JointMotorControlCommand.desiredStateQ) + return &desiredstateq_; +} + +// repeated double desiredStateQdot = 9; +int JointMotorControlCommand::desiredstateqdot_size() const { + return desiredstateqdot_.size(); +} +void JointMotorControlCommand::clear_desiredstateqdot() { + desiredstateqdot_.Clear(); +} +double JointMotorControlCommand::desiredstateqdot(int index) const { + // @@protoc_insertion_point(field_get:pybullet_grpc.JointMotorControlCommand.desiredStateQdot) + return desiredstateqdot_.Get(index); +} +void JointMotorControlCommand::set_desiredstateqdot(int index, double value) { + desiredstateqdot_.Set(index, value); + // @@protoc_insertion_point(field_set:pybullet_grpc.JointMotorControlCommand.desiredStateQdot) +} +void JointMotorControlCommand::add_desiredstateqdot(double value) { + desiredstateqdot_.Add(value); + // @@protoc_insertion_point(field_add:pybullet_grpc.JointMotorControlCommand.desiredStateQdot) +} +const ::google::protobuf::RepeatedField< double >& +JointMotorControlCommand::desiredstateqdot() const { + // @@protoc_insertion_point(field_list:pybullet_grpc.JointMotorControlCommand.desiredStateQdot) + return desiredstateqdot_; +} +::google::protobuf::RepeatedField< double >* +JointMotorControlCommand::mutable_desiredstateqdot() { + // @@protoc_insertion_point(field_mutable_list:pybullet_grpc.JointMotorControlCommand.desiredStateQdot) + return &desiredstateqdot_; +} + +// repeated double desiredStateForceTorque = 10; +int JointMotorControlCommand::desiredstateforcetorque_size() const { + return desiredstateforcetorque_.size(); +} +void JointMotorControlCommand::clear_desiredstateforcetorque() { + desiredstateforcetorque_.Clear(); +} +double JointMotorControlCommand::desiredstateforcetorque(int index) const { + // @@protoc_insertion_point(field_get:pybullet_grpc.JointMotorControlCommand.desiredStateForceTorque) + return desiredstateforcetorque_.Get(index); +} +void JointMotorControlCommand::set_desiredstateforcetorque(int index, double value) { + desiredstateforcetorque_.Set(index, value); + // @@protoc_insertion_point(field_set:pybullet_grpc.JointMotorControlCommand.desiredStateForceTorque) +} +void JointMotorControlCommand::add_desiredstateforcetorque(double value) { + desiredstateforcetorque_.Add(value); + // @@protoc_insertion_point(field_add:pybullet_grpc.JointMotorControlCommand.desiredStateForceTorque) +} +const ::google::protobuf::RepeatedField< double >& +JointMotorControlCommand::desiredstateforcetorque() const { + // @@protoc_insertion_point(field_list:pybullet_grpc.JointMotorControlCommand.desiredStateForceTorque) + return desiredstateforcetorque_; +} +::google::protobuf::RepeatedField< double >* +JointMotorControlCommand::mutable_desiredstateforcetorque() { + // @@protoc_insertion_point(field_mutable_list:pybullet_grpc.JointMotorControlCommand.desiredStateForceTorque) + return &desiredstateforcetorque_; +} + +#endif // PROTOBUF_INLINE_NOT_IN_HEADERS + +// =================================================================== + +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const int UserConstraintCommand::kParentBodyIndexFieldNumber; +const int UserConstraintCommand::kParentJointIndexFieldNumber; +const int UserConstraintCommand::kChildBodyIndexFieldNumber; +const int UserConstraintCommand::kChildJointIndexFieldNumber; +const int UserConstraintCommand::kParentFrameFieldNumber; +const int UserConstraintCommand::kChildFrameFieldNumber; +const int UserConstraintCommand::kJointAxisFieldNumber; +const int UserConstraintCommand::kJointTypeFieldNumber; +const int UserConstraintCommand::kMaxAppliedForceFieldNumber; +const int UserConstraintCommand::kUserConstraintUniqueIdFieldNumber; +const int UserConstraintCommand::kGearRatioFieldNumber; +const int UserConstraintCommand::kGearAuxLinkFieldNumber; +const int UserConstraintCommand::kRelativePositionTargetFieldNumber; +const int UserConstraintCommand::kErpFieldNumber; +const int UserConstraintCommand::kUpdateFlagsFieldNumber; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 + +UserConstraintCommand::UserConstraintCommand() + : ::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.UserConstraintCommand) +} +UserConstraintCommand::UserConstraintCommand(const UserConstraintCommand& from) + : ::google::protobuf::Message(), + _internal_metadata_(NULL), + _cached_size_(0) { + _internal_metadata_.MergeFrom(from._internal_metadata_); + if (from.has_parentframe()) { + parentframe_ = new ::pybullet_grpc::transform(*from.parentframe_); + } else { + parentframe_ = NULL; + } + if (from.has_childframe()) { + childframe_ = new ::pybullet_grpc::transform(*from.childframe_); + } else { + childframe_ = NULL; + } + if (from.has_jointaxis()) { + jointaxis_ = new ::pybullet_grpc::vec3(*from.jointaxis_); + } else { + jointaxis_ = NULL; + } + ::memcpy(&parentbodyindex_, &from.parentbodyindex_, + reinterpret_cast(&erp_) - + reinterpret_cast(&parentbodyindex_) + sizeof(erp_)); + // @@protoc_insertion_point(copy_constructor:pybullet_grpc.UserConstraintCommand) +} + +void UserConstraintCommand::SharedCtor() { + ::memset(&parentframe_, 0, reinterpret_cast(&erp_) - + reinterpret_cast(&parentframe_) + sizeof(erp_)); + _cached_size_ = 0; +} + +UserConstraintCommand::~UserConstraintCommand() { + // @@protoc_insertion_point(destructor:pybullet_grpc.UserConstraintCommand) + SharedDtor(); +} + +void UserConstraintCommand::SharedDtor() { + if (this != internal_default_instance()) { + delete parentframe_; + } + if (this != internal_default_instance()) { + delete childframe_; + } + if (this != internal_default_instance()) { + delete jointaxis_; + } +} + +void UserConstraintCommand::SetCachedSize(int size) const { + GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN(); + _cached_size_ = size; + GOOGLE_SAFE_CONCURRENT_WRITES_END(); +} +const ::google::protobuf::Descriptor* UserConstraintCommand::descriptor() { + protobuf_pybullet_2eproto::protobuf_AssignDescriptorsOnce(); + return protobuf_pybullet_2eproto::file_level_metadata[29].descriptor; +} + +const UserConstraintCommand& UserConstraintCommand::default_instance() { + protobuf_pybullet_2eproto::InitDefaults(); + return *internal_default_instance(); +} + +UserConstraintCommand* UserConstraintCommand::New(::google::protobuf::Arena* arena) const { + UserConstraintCommand* n = new UserConstraintCommand; + if (arena != NULL) { + arena->Own(n); + } + return n; +} + +void UserConstraintCommand::Clear() { +// @@protoc_insertion_point(message_clear_start:pybullet_grpc.UserConstraintCommand) + if (GetArenaNoVirtual() == NULL && parentframe_ != NULL) { + delete parentframe_; + } + parentframe_ = NULL; + if (GetArenaNoVirtual() == NULL && childframe_ != NULL) { + delete childframe_; + } + childframe_ = NULL; + if (GetArenaNoVirtual() == NULL && jointaxis_ != NULL) { + delete jointaxis_; + } + jointaxis_ = NULL; + ::memset(&parentbodyindex_, 0, reinterpret_cast(&erp_) - + reinterpret_cast(&parentbodyindex_) + sizeof(erp_)); +} + +bool UserConstraintCommand::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.UserConstraintCommand) + 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 parentBodyIndex = 1; + case 1: { + if (tag == 8u) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>( + input, &parentbodyindex_))); + } else { + goto handle_unusual; + } + break; + } + + // int32 parentJointIndex = 2; + case 2: { + if (tag == 16u) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>( + input, &parentjointindex_))); + } else { + goto handle_unusual; + } + break; + } + + // int32 childBodyIndex = 3; + case 3: { + if (tag == 24u) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>( + input, &childbodyindex_))); + } else { + goto handle_unusual; + } + break; + } + + // int32 childJointIndex = 4; + case 4: { + if (tag == 32u) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>( + input, &childjointindex_))); + } else { + goto handle_unusual; + } + break; + } + + // .pybullet_grpc.transform parentFrame = 5; + case 5: { + if (tag == 42u) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessageNoVirtual( + input, mutable_parentframe())); + } else { + goto handle_unusual; + } + break; + } + + // .pybullet_grpc.transform childFrame = 6; + case 6: { + if (tag == 50u) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessageNoVirtual( + input, mutable_childframe())); + } else { + goto handle_unusual; + } + break; + } + + // .pybullet_grpc.vec3 jointAxis = 7; + case 7: { + if (tag == 58u) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessageNoVirtual( + input, mutable_jointaxis())); + } else { + goto handle_unusual; + } + break; + } + + // int32 jointType = 8; + case 8: { + if (tag == 64u) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>( + input, &jointtype_))); + } else { + goto handle_unusual; + } + break; + } + + // double maxAppliedForce = 9; + case 9: { + if (tag == 73u) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &maxappliedforce_))); + } else { + goto handle_unusual; + } + break; + } + + // int32 userConstraintUniqueId = 10; + case 10: { + if (tag == 80u) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>( + input, &userconstraintuniqueid_))); + } else { + goto handle_unusual; + } + break; + } + + // double gearRatio = 11; + case 11: { + if (tag == 89u) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &gearratio_))); + } else { + goto handle_unusual; + } + break; + } + + // int32 gearAuxLink = 12; + case 12: { + if (tag == 96u) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>( + input, &gearauxlink_))); + } else { + goto handle_unusual; + } + break; + } + + // double relativePositionTarget = 13; + case 13: { + if (tag == 105u) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &relativepositiontarget_))); + } else { + goto handle_unusual; + } + break; + } + + // double erp = 14; + case 14: { + if (tag == 113u) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &erp_))); + } else { + goto handle_unusual; + } + break; + } + + // int32 updateFlags = 15; + case 15: { + if (tag == 120u) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>( + input, &updateflags_))); + } 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.UserConstraintCommand) + return true; +failure: + // @@protoc_insertion_point(parse_failure:pybullet_grpc.UserConstraintCommand) + return false; +#undef DO_ +} + +void UserConstraintCommand::SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const { + // @@protoc_insertion_point(serialize_start:pybullet_grpc.UserConstraintCommand) + // int32 parentBodyIndex = 1; + if (this->parentbodyindex() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteInt32(1, this->parentbodyindex(), output); + } + + // int32 parentJointIndex = 2; + if (this->parentjointindex() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteInt32(2, this->parentjointindex(), output); + } + + // int32 childBodyIndex = 3; + if (this->childbodyindex() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteInt32(3, this->childbodyindex(), output); + } + + // int32 childJointIndex = 4; + if (this->childjointindex() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteInt32(4, this->childjointindex(), output); + } + + // .pybullet_grpc.transform parentFrame = 5; + if (this->has_parentframe()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 5, *this->parentframe_, output); + } + + // .pybullet_grpc.transform childFrame = 6; + if (this->has_childframe()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 6, *this->childframe_, output); + } + + // .pybullet_grpc.vec3 jointAxis = 7; + if (this->has_jointaxis()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 7, *this->jointaxis_, output); + } + + // int32 jointType = 8; + if (this->jointtype() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteInt32(8, this->jointtype(), output); + } + + // double maxAppliedForce = 9; + if (this->maxappliedforce() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(9, this->maxappliedforce(), output); + } + + // int32 userConstraintUniqueId = 10; + if (this->userconstraintuniqueid() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteInt32(10, this->userconstraintuniqueid(), output); + } + + // double gearRatio = 11; + if (this->gearratio() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(11, this->gearratio(), output); + } + + // int32 gearAuxLink = 12; + if (this->gearauxlink() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteInt32(12, this->gearauxlink(), output); + } + + // double relativePositionTarget = 13; + if (this->relativepositiontarget() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(13, this->relativepositiontarget(), output); + } + + // double erp = 14; + if (this->erp() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(14, this->erp(), output); + } + + // int32 updateFlags = 15; + if (this->updateflags() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteInt32(15, this->updateflags(), output); + } + + // @@protoc_insertion_point(serialize_end:pybullet_grpc.UserConstraintCommand) +} + +::google::protobuf::uint8* UserConstraintCommand::InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const { + (void)deterministic; // Unused + // @@protoc_insertion_point(serialize_to_array_start:pybullet_grpc.UserConstraintCommand) + // int32 parentBodyIndex = 1; + if (this->parentbodyindex() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteInt32ToArray(1, this->parentbodyindex(), target); + } + + // int32 parentJointIndex = 2; + if (this->parentjointindex() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteInt32ToArray(2, this->parentjointindex(), target); + } + + // int32 childBodyIndex = 3; + if (this->childbodyindex() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteInt32ToArray(3, this->childbodyindex(), target); + } + + // int32 childJointIndex = 4; + if (this->childjointindex() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteInt32ToArray(4, this->childjointindex(), target); + } + + // .pybullet_grpc.transform parentFrame = 5; + if (this->has_parentframe()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageNoVirtualToArray( + 5, *this->parentframe_, false, target); + } + + // .pybullet_grpc.transform childFrame = 6; + if (this->has_childframe()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageNoVirtualToArray( + 6, *this->childframe_, false, target); + } + + // .pybullet_grpc.vec3 jointAxis = 7; + if (this->has_jointaxis()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageNoVirtualToArray( + 7, *this->jointaxis_, false, target); + } + + // int32 jointType = 8; + if (this->jointtype() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteInt32ToArray(8, this->jointtype(), target); + } + + // double maxAppliedForce = 9; + if (this->maxappliedforce() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(9, this->maxappliedforce(), target); + } + + // int32 userConstraintUniqueId = 10; + if (this->userconstraintuniqueid() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteInt32ToArray(10, this->userconstraintuniqueid(), target); + } + + // double gearRatio = 11; + if (this->gearratio() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(11, this->gearratio(), target); + } + + // int32 gearAuxLink = 12; + if (this->gearauxlink() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteInt32ToArray(12, this->gearauxlink(), target); + } + + // double relativePositionTarget = 13; + if (this->relativepositiontarget() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(13, this->relativepositiontarget(), target); + } + + // double erp = 14; + if (this->erp() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(14, this->erp(), target); + } + + // int32 updateFlags = 15; + if (this->updateflags() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteInt32ToArray(15, this->updateflags(), target); + } + + // @@protoc_insertion_point(serialize_to_array_end:pybullet_grpc.UserConstraintCommand) + return target; +} + +size_t UserConstraintCommand::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:pybullet_grpc.UserConstraintCommand) + size_t total_size = 0; + + // .pybullet_grpc.transform parentFrame = 5; + if (this->has_parentframe()) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSizeNoVirtual( + *this->parentframe_); + } + + // .pybullet_grpc.transform childFrame = 6; + if (this->has_childframe()) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSizeNoVirtual( + *this->childframe_); + } + + // .pybullet_grpc.vec3 jointAxis = 7; + if (this->has_jointaxis()) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSizeNoVirtual( + *this->jointaxis_); + } + + // int32 parentBodyIndex = 1; + if (this->parentbodyindex() != 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::Int32Size( + this->parentbodyindex()); + } + + // int32 parentJointIndex = 2; + if (this->parentjointindex() != 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::Int32Size( + this->parentjointindex()); + } + + // int32 childBodyIndex = 3; + if (this->childbodyindex() != 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::Int32Size( + this->childbodyindex()); + } + + // int32 childJointIndex = 4; + if (this->childjointindex() != 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::Int32Size( + this->childjointindex()); + } + + // double maxAppliedForce = 9; + if (this->maxappliedforce() != 0) { + total_size += 1 + 8; + } + + // int32 jointType = 8; + if (this->jointtype() != 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::Int32Size( + this->jointtype()); + } + + // int32 userConstraintUniqueId = 10; + if (this->userconstraintuniqueid() != 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::Int32Size( + this->userconstraintuniqueid()); + } + + // double gearRatio = 11; + if (this->gearratio() != 0) { + total_size += 1 + 8; + } + + // double relativePositionTarget = 13; + if (this->relativepositiontarget() != 0) { + total_size += 1 + 8; + } + + // int32 gearAuxLink = 12; + if (this->gearauxlink() != 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::Int32Size( + this->gearauxlink()); + } + + // int32 updateFlags = 15; + if (this->updateflags() != 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::Int32Size( + this->updateflags()); + } + + // double erp = 14; + if (this->erp() != 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 UserConstraintCommand::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:pybullet_grpc.UserConstraintCommand) + GOOGLE_DCHECK_NE(&from, this); + const UserConstraintCommand* source = + ::google::protobuf::internal::DynamicCastToGenerated( + &from); + if (source == NULL) { + // @@protoc_insertion_point(generalized_merge_from_cast_fail:pybullet_grpc.UserConstraintCommand) + ::google::protobuf::internal::ReflectionOps::Merge(from, this); + } else { + // @@protoc_insertion_point(generalized_merge_from_cast_success:pybullet_grpc.UserConstraintCommand) + MergeFrom(*source); + } +} + +void UserConstraintCommand::MergeFrom(const UserConstraintCommand& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:pybullet_grpc.UserConstraintCommand) + GOOGLE_DCHECK_NE(&from, this); + _internal_metadata_.MergeFrom(from._internal_metadata_); + if (from.has_parentframe()) { + mutable_parentframe()->::pybullet_grpc::transform::MergeFrom(from.parentframe()); + } + if (from.has_childframe()) { + mutable_childframe()->::pybullet_grpc::transform::MergeFrom(from.childframe()); + } + if (from.has_jointaxis()) { + mutable_jointaxis()->::pybullet_grpc::vec3::MergeFrom(from.jointaxis()); + } + if (from.parentbodyindex() != 0) { + set_parentbodyindex(from.parentbodyindex()); + } + if (from.parentjointindex() != 0) { + set_parentjointindex(from.parentjointindex()); + } + if (from.childbodyindex() != 0) { + set_childbodyindex(from.childbodyindex()); + } + if (from.childjointindex() != 0) { + set_childjointindex(from.childjointindex()); + } + if (from.maxappliedforce() != 0) { + set_maxappliedforce(from.maxappliedforce()); + } + if (from.jointtype() != 0) { + set_jointtype(from.jointtype()); + } + if (from.userconstraintuniqueid() != 0) { + set_userconstraintuniqueid(from.userconstraintuniqueid()); + } + if (from.gearratio() != 0) { + set_gearratio(from.gearratio()); + } + if (from.relativepositiontarget() != 0) { + set_relativepositiontarget(from.relativepositiontarget()); + } + if (from.gearauxlink() != 0) { + set_gearauxlink(from.gearauxlink()); + } + if (from.updateflags() != 0) { + set_updateflags(from.updateflags()); + } + if (from.erp() != 0) { + set_erp(from.erp()); + } +} + +void UserConstraintCommand::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:pybullet_grpc.UserConstraintCommand) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +void UserConstraintCommand::CopyFrom(const UserConstraintCommand& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:pybullet_grpc.UserConstraintCommand) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool UserConstraintCommand::IsInitialized() const { + return true; +} + +void UserConstraintCommand::Swap(UserConstraintCommand* other) { + if (other == this) return; + InternalSwap(other); +} +void UserConstraintCommand::InternalSwap(UserConstraintCommand* other) { + std::swap(parentframe_, other->parentframe_); + std::swap(childframe_, other->childframe_); + std::swap(jointaxis_, other->jointaxis_); + std::swap(parentbodyindex_, other->parentbodyindex_); + std::swap(parentjointindex_, other->parentjointindex_); + std::swap(childbodyindex_, other->childbodyindex_); + std::swap(childjointindex_, other->childjointindex_); + std::swap(maxappliedforce_, other->maxappliedforce_); + std::swap(jointtype_, other->jointtype_); + std::swap(userconstraintuniqueid_, other->userconstraintuniqueid_); + std::swap(gearratio_, other->gearratio_); + std::swap(relativepositiontarget_, other->relativepositiontarget_); + std::swap(gearauxlink_, other->gearauxlink_); + std::swap(updateflags_, other->updateflags_); + std::swap(erp_, other->erp_); + std::swap(_cached_size_, other->_cached_size_); +} + +::google::protobuf::Metadata UserConstraintCommand::GetMetadata() const { + protobuf_pybullet_2eproto::protobuf_AssignDescriptorsOnce(); + return protobuf_pybullet_2eproto::file_level_metadata[29]; +} + +#if PROTOBUF_INLINE_NOT_IN_HEADERS +// UserConstraintCommand + +// int32 parentBodyIndex = 1; +void UserConstraintCommand::clear_parentbodyindex() { + parentbodyindex_ = 0; +} +::google::protobuf::int32 UserConstraintCommand::parentbodyindex() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.UserConstraintCommand.parentBodyIndex) + return parentbodyindex_; +} +void UserConstraintCommand::set_parentbodyindex(::google::protobuf::int32 value) { + + parentbodyindex_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.UserConstraintCommand.parentBodyIndex) +} + +// int32 parentJointIndex = 2; +void UserConstraintCommand::clear_parentjointindex() { + parentjointindex_ = 0; +} +::google::protobuf::int32 UserConstraintCommand::parentjointindex() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.UserConstraintCommand.parentJointIndex) + return parentjointindex_; +} +void UserConstraintCommand::set_parentjointindex(::google::protobuf::int32 value) { + + parentjointindex_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.UserConstraintCommand.parentJointIndex) +} + +// int32 childBodyIndex = 3; +void UserConstraintCommand::clear_childbodyindex() { + childbodyindex_ = 0; +} +::google::protobuf::int32 UserConstraintCommand::childbodyindex() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.UserConstraintCommand.childBodyIndex) + return childbodyindex_; +} +void UserConstraintCommand::set_childbodyindex(::google::protobuf::int32 value) { + + childbodyindex_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.UserConstraintCommand.childBodyIndex) +} + +// int32 childJointIndex = 4; +void UserConstraintCommand::clear_childjointindex() { + childjointindex_ = 0; +} +::google::protobuf::int32 UserConstraintCommand::childjointindex() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.UserConstraintCommand.childJointIndex) + return childjointindex_; +} +void UserConstraintCommand::set_childjointindex(::google::protobuf::int32 value) { + + childjointindex_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.UserConstraintCommand.childJointIndex) +} + +// .pybullet_grpc.transform parentFrame = 5; +bool UserConstraintCommand::has_parentframe() const { + return this != internal_default_instance() && parentframe_ != NULL; +} +void UserConstraintCommand::clear_parentframe() { + if (GetArenaNoVirtual() == NULL && parentframe_ != NULL) delete parentframe_; + parentframe_ = NULL; +} +const ::pybullet_grpc::transform& UserConstraintCommand::parentframe() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.UserConstraintCommand.parentFrame) + return parentframe_ != NULL ? *parentframe_ + : *::pybullet_grpc::transform::internal_default_instance(); +} +::pybullet_grpc::transform* UserConstraintCommand::mutable_parentframe() { + + if (parentframe_ == NULL) { + parentframe_ = new ::pybullet_grpc::transform; + } + // @@protoc_insertion_point(field_mutable:pybullet_grpc.UserConstraintCommand.parentFrame) + return parentframe_; +} +::pybullet_grpc::transform* UserConstraintCommand::release_parentframe() { + // @@protoc_insertion_point(field_release:pybullet_grpc.UserConstraintCommand.parentFrame) + + ::pybullet_grpc::transform* temp = parentframe_; + parentframe_ = NULL; + return temp; +} +void UserConstraintCommand::set_allocated_parentframe(::pybullet_grpc::transform* parentframe) { + delete parentframe_; + parentframe_ = parentframe; + if (parentframe) { + + } else { + + } + // @@protoc_insertion_point(field_set_allocated:pybullet_grpc.UserConstraintCommand.parentFrame) +} + +// .pybullet_grpc.transform childFrame = 6; +bool UserConstraintCommand::has_childframe() const { + return this != internal_default_instance() && childframe_ != NULL; +} +void UserConstraintCommand::clear_childframe() { + if (GetArenaNoVirtual() == NULL && childframe_ != NULL) delete childframe_; + childframe_ = NULL; +} +const ::pybullet_grpc::transform& UserConstraintCommand::childframe() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.UserConstraintCommand.childFrame) + return childframe_ != NULL ? *childframe_ + : *::pybullet_grpc::transform::internal_default_instance(); +} +::pybullet_grpc::transform* UserConstraintCommand::mutable_childframe() { + + if (childframe_ == NULL) { + childframe_ = new ::pybullet_grpc::transform; + } + // @@protoc_insertion_point(field_mutable:pybullet_grpc.UserConstraintCommand.childFrame) + return childframe_; +} +::pybullet_grpc::transform* UserConstraintCommand::release_childframe() { + // @@protoc_insertion_point(field_release:pybullet_grpc.UserConstraintCommand.childFrame) + + ::pybullet_grpc::transform* temp = childframe_; + childframe_ = NULL; + return temp; +} +void UserConstraintCommand::set_allocated_childframe(::pybullet_grpc::transform* childframe) { + delete childframe_; + childframe_ = childframe; + if (childframe) { + + } else { + + } + // @@protoc_insertion_point(field_set_allocated:pybullet_grpc.UserConstraintCommand.childFrame) +} + +// .pybullet_grpc.vec3 jointAxis = 7; +bool UserConstraintCommand::has_jointaxis() const { + return this != internal_default_instance() && jointaxis_ != NULL; +} +void UserConstraintCommand::clear_jointaxis() { + if (GetArenaNoVirtual() == NULL && jointaxis_ != NULL) delete jointaxis_; + jointaxis_ = NULL; +} +const ::pybullet_grpc::vec3& UserConstraintCommand::jointaxis() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.UserConstraintCommand.jointAxis) + return jointaxis_ != NULL ? *jointaxis_ + : *::pybullet_grpc::vec3::internal_default_instance(); +} +::pybullet_grpc::vec3* UserConstraintCommand::mutable_jointaxis() { + + if (jointaxis_ == NULL) { + jointaxis_ = new ::pybullet_grpc::vec3; + } + // @@protoc_insertion_point(field_mutable:pybullet_grpc.UserConstraintCommand.jointAxis) + return jointaxis_; +} +::pybullet_grpc::vec3* UserConstraintCommand::release_jointaxis() { + // @@protoc_insertion_point(field_release:pybullet_grpc.UserConstraintCommand.jointAxis) + + ::pybullet_grpc::vec3* temp = jointaxis_; + jointaxis_ = NULL; + return temp; +} +void UserConstraintCommand::set_allocated_jointaxis(::pybullet_grpc::vec3* jointaxis) { + delete jointaxis_; + jointaxis_ = jointaxis; + if (jointaxis) { + + } else { + + } + // @@protoc_insertion_point(field_set_allocated:pybullet_grpc.UserConstraintCommand.jointAxis) +} + +// int32 jointType = 8; +void UserConstraintCommand::clear_jointtype() { + jointtype_ = 0; +} +::google::protobuf::int32 UserConstraintCommand::jointtype() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.UserConstraintCommand.jointType) + return jointtype_; +} +void UserConstraintCommand::set_jointtype(::google::protobuf::int32 value) { + + jointtype_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.UserConstraintCommand.jointType) +} + +// double maxAppliedForce = 9; +void UserConstraintCommand::clear_maxappliedforce() { + maxappliedforce_ = 0; +} +double UserConstraintCommand::maxappliedforce() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.UserConstraintCommand.maxAppliedForce) + return maxappliedforce_; +} +void UserConstraintCommand::set_maxappliedforce(double value) { + + maxappliedforce_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.UserConstraintCommand.maxAppliedForce) +} + +// int32 userConstraintUniqueId = 10; +void UserConstraintCommand::clear_userconstraintuniqueid() { + userconstraintuniqueid_ = 0; +} +::google::protobuf::int32 UserConstraintCommand::userconstraintuniqueid() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.UserConstraintCommand.userConstraintUniqueId) + return userconstraintuniqueid_; +} +void UserConstraintCommand::set_userconstraintuniqueid(::google::protobuf::int32 value) { + + userconstraintuniqueid_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.UserConstraintCommand.userConstraintUniqueId) +} + +// double gearRatio = 11; +void UserConstraintCommand::clear_gearratio() { + gearratio_ = 0; +} +double UserConstraintCommand::gearratio() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.UserConstraintCommand.gearRatio) + return gearratio_; +} +void UserConstraintCommand::set_gearratio(double value) { + + gearratio_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.UserConstraintCommand.gearRatio) +} + +// int32 gearAuxLink = 12; +void UserConstraintCommand::clear_gearauxlink() { + gearauxlink_ = 0; +} +::google::protobuf::int32 UserConstraintCommand::gearauxlink() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.UserConstraintCommand.gearAuxLink) + return gearauxlink_; +} +void UserConstraintCommand::set_gearauxlink(::google::protobuf::int32 value) { + + gearauxlink_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.UserConstraintCommand.gearAuxLink) +} + +// double relativePositionTarget = 13; +void UserConstraintCommand::clear_relativepositiontarget() { + relativepositiontarget_ = 0; +} +double UserConstraintCommand::relativepositiontarget() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.UserConstraintCommand.relativePositionTarget) + return relativepositiontarget_; +} +void UserConstraintCommand::set_relativepositiontarget(double value) { + + relativepositiontarget_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.UserConstraintCommand.relativePositionTarget) +} + +// double erp = 14; +void UserConstraintCommand::clear_erp() { + erp_ = 0; +} +double UserConstraintCommand::erp() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.UserConstraintCommand.erp) + return erp_; +} +void UserConstraintCommand::set_erp(double value) { + + erp_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.UserConstraintCommand.erp) +} + +// int32 updateFlags = 15; +void UserConstraintCommand::clear_updateflags() { + updateflags_ = 0; +} +::google::protobuf::int32 UserConstraintCommand::updateflags() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.UserConstraintCommand.updateFlags) + return updateflags_; +} +void UserConstraintCommand::set_updateflags(::google::protobuf::int32 value) { + + updateflags_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.UserConstraintCommand.updateFlags) +} + +#endif // PROTOBUF_INLINE_NOT_IN_HEADERS + +// =================================================================== + +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const int UserConstraintStatus::kMaxAppliedForceFieldNumber; +const int UserConstraintStatus::kUserConstraintUniqueIdFieldNumber; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 + +UserConstraintStatus::UserConstraintStatus() + : ::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.UserConstraintStatus) +} +UserConstraintStatus::UserConstraintStatus(const UserConstraintStatus& from) + : ::google::protobuf::Message(), + _internal_metadata_(NULL), + _cached_size_(0) { + _internal_metadata_.MergeFrom(from._internal_metadata_); + ::memcpy(&maxappliedforce_, &from.maxappliedforce_, + reinterpret_cast(&userconstraintuniqueid_) - + reinterpret_cast(&maxappliedforce_) + sizeof(userconstraintuniqueid_)); + // @@protoc_insertion_point(copy_constructor:pybullet_grpc.UserConstraintStatus) +} + +void UserConstraintStatus::SharedCtor() { + ::memset(&maxappliedforce_, 0, reinterpret_cast(&userconstraintuniqueid_) - + reinterpret_cast(&maxappliedforce_) + sizeof(userconstraintuniqueid_)); + _cached_size_ = 0; +} + +UserConstraintStatus::~UserConstraintStatus() { + // @@protoc_insertion_point(destructor:pybullet_grpc.UserConstraintStatus) + SharedDtor(); +} + +void UserConstraintStatus::SharedDtor() { +} + +void UserConstraintStatus::SetCachedSize(int size) const { + GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN(); + _cached_size_ = size; + GOOGLE_SAFE_CONCURRENT_WRITES_END(); +} +const ::google::protobuf::Descriptor* UserConstraintStatus::descriptor() { + protobuf_pybullet_2eproto::protobuf_AssignDescriptorsOnce(); + return protobuf_pybullet_2eproto::file_level_metadata[30].descriptor; +} + +const UserConstraintStatus& UserConstraintStatus::default_instance() { + protobuf_pybullet_2eproto::InitDefaults(); + return *internal_default_instance(); +} + +UserConstraintStatus* UserConstraintStatus::New(::google::protobuf::Arena* arena) const { + UserConstraintStatus* n = new UserConstraintStatus; + if (arena != NULL) { + arena->Own(n); + } + return n; +} + +void UserConstraintStatus::Clear() { +// @@protoc_insertion_point(message_clear_start:pybullet_grpc.UserConstraintStatus) + ::memset(&maxappliedforce_, 0, reinterpret_cast(&userconstraintuniqueid_) - + reinterpret_cast(&maxappliedforce_) + sizeof(userconstraintuniqueid_)); +} + +bool UserConstraintStatus::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.UserConstraintStatus) + 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 maxAppliedForce = 9; + case 9: { + if (tag == 73u) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &maxappliedforce_))); + } else { + goto handle_unusual; + } + break; + } + + // int32 userConstraintUniqueId = 10; + case 10: { + if (tag == 80u) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>( + input, &userconstraintuniqueid_))); + } 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.UserConstraintStatus) + return true; +failure: + // @@protoc_insertion_point(parse_failure:pybullet_grpc.UserConstraintStatus) + return false; +#undef DO_ +} + +void UserConstraintStatus::SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const { + // @@protoc_insertion_point(serialize_start:pybullet_grpc.UserConstraintStatus) + // double maxAppliedForce = 9; + if (this->maxappliedforce() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(9, this->maxappliedforce(), output); + } + + // int32 userConstraintUniqueId = 10; + if (this->userconstraintuniqueid() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteInt32(10, this->userconstraintuniqueid(), output); + } + + // @@protoc_insertion_point(serialize_end:pybullet_grpc.UserConstraintStatus) +} + +::google::protobuf::uint8* UserConstraintStatus::InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const { + (void)deterministic; // Unused + // @@protoc_insertion_point(serialize_to_array_start:pybullet_grpc.UserConstraintStatus) + // double maxAppliedForce = 9; + if (this->maxappliedforce() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(9, this->maxappliedforce(), target); + } + + // int32 userConstraintUniqueId = 10; + if (this->userconstraintuniqueid() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteInt32ToArray(10, this->userconstraintuniqueid(), target); + } + + // @@protoc_insertion_point(serialize_to_array_end:pybullet_grpc.UserConstraintStatus) + return target; +} + +size_t UserConstraintStatus::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:pybullet_grpc.UserConstraintStatus) + size_t total_size = 0; + + // double maxAppliedForce = 9; + if (this->maxappliedforce() != 0) { + total_size += 1 + 8; + } + + // int32 userConstraintUniqueId = 10; + if (this->userconstraintuniqueid() != 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::Int32Size( + this->userconstraintuniqueid()); + } + + 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 UserConstraintStatus::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:pybullet_grpc.UserConstraintStatus) + GOOGLE_DCHECK_NE(&from, this); + const UserConstraintStatus* source = + ::google::protobuf::internal::DynamicCastToGenerated( + &from); + if (source == NULL) { + // @@protoc_insertion_point(generalized_merge_from_cast_fail:pybullet_grpc.UserConstraintStatus) + ::google::protobuf::internal::ReflectionOps::Merge(from, this); + } else { + // @@protoc_insertion_point(generalized_merge_from_cast_success:pybullet_grpc.UserConstraintStatus) + MergeFrom(*source); + } +} + +void UserConstraintStatus::MergeFrom(const UserConstraintStatus& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:pybullet_grpc.UserConstraintStatus) + GOOGLE_DCHECK_NE(&from, this); + _internal_metadata_.MergeFrom(from._internal_metadata_); + if (from.maxappliedforce() != 0) { + set_maxappliedforce(from.maxappliedforce()); + } + if (from.userconstraintuniqueid() != 0) { + set_userconstraintuniqueid(from.userconstraintuniqueid()); + } +} + +void UserConstraintStatus::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:pybullet_grpc.UserConstraintStatus) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +void UserConstraintStatus::CopyFrom(const UserConstraintStatus& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:pybullet_grpc.UserConstraintStatus) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool UserConstraintStatus::IsInitialized() const { + return true; +} + +void UserConstraintStatus::Swap(UserConstraintStatus* other) { + if (other == this) return; + InternalSwap(other); +} +void UserConstraintStatus::InternalSwap(UserConstraintStatus* other) { + std::swap(maxappliedforce_, other->maxappliedforce_); + std::swap(userconstraintuniqueid_, other->userconstraintuniqueid_); + std::swap(_cached_size_, other->_cached_size_); +} + +::google::protobuf::Metadata UserConstraintStatus::GetMetadata() const { + protobuf_pybullet_2eproto::protobuf_AssignDescriptorsOnce(); + return protobuf_pybullet_2eproto::file_level_metadata[30]; +} + +#if PROTOBUF_INLINE_NOT_IN_HEADERS +// UserConstraintStatus + +// double maxAppliedForce = 9; +void UserConstraintStatus::clear_maxappliedforce() { + maxappliedforce_ = 0; +} +double UserConstraintStatus::maxappliedforce() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.UserConstraintStatus.maxAppliedForce) + return maxappliedforce_; +} +void UserConstraintStatus::set_maxappliedforce(double value) { + + maxappliedforce_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.UserConstraintStatus.maxAppliedForce) +} + +// int32 userConstraintUniqueId = 10; +void UserConstraintStatus::clear_userconstraintuniqueid() { + userconstraintuniqueid_ = 0; +} +::google::protobuf::int32 UserConstraintStatus::userconstraintuniqueid() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.UserConstraintStatus.userConstraintUniqueId) + return userconstraintuniqueid_; +} +void UserConstraintStatus::set_userconstraintuniqueid(::google::protobuf::int32 value) { + + userconstraintuniqueid_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.UserConstraintStatus.userConstraintUniqueId) +} + +#endif // PROTOBUF_INLINE_NOT_IN_HEADERS + +// =================================================================== + +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const int UserConstraintStateStatus::kAppliedConstraintForcesLinearFieldNumber; +const int UserConstraintStateStatus::kAppliedConstraintForcesAngularFieldNumber; +const int UserConstraintStateStatus::kNumDofsFieldNumber; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 + +UserConstraintStateStatus::UserConstraintStateStatus() + : ::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.UserConstraintStateStatus) +} +UserConstraintStateStatus::UserConstraintStateStatus(const UserConstraintStateStatus& from) + : ::google::protobuf::Message(), + _internal_metadata_(NULL), + _cached_size_(0) { + _internal_metadata_.MergeFrom(from._internal_metadata_); + if (from.has_appliedconstraintforceslinear()) { + appliedconstraintforceslinear_ = new ::pybullet_grpc::vec3(*from.appliedconstraintforceslinear_); + } else { + appliedconstraintforceslinear_ = NULL; + } + if (from.has_appliedconstraintforcesangular()) { + appliedconstraintforcesangular_ = new ::pybullet_grpc::vec3(*from.appliedconstraintforcesangular_); + } else { + appliedconstraintforcesangular_ = NULL; + } + numdofs_ = from.numdofs_; + // @@protoc_insertion_point(copy_constructor:pybullet_grpc.UserConstraintStateStatus) +} + +void UserConstraintStateStatus::SharedCtor() { + ::memset(&appliedconstraintforceslinear_, 0, reinterpret_cast(&numdofs_) - + reinterpret_cast(&appliedconstraintforceslinear_) + sizeof(numdofs_)); + _cached_size_ = 0; +} + +UserConstraintStateStatus::~UserConstraintStateStatus() { + // @@protoc_insertion_point(destructor:pybullet_grpc.UserConstraintStateStatus) + SharedDtor(); +} + +void UserConstraintStateStatus::SharedDtor() { + if (this != internal_default_instance()) { + delete appliedconstraintforceslinear_; + } + if (this != internal_default_instance()) { + delete appliedconstraintforcesangular_; + } +} + +void UserConstraintStateStatus::SetCachedSize(int size) const { + GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN(); + _cached_size_ = size; + GOOGLE_SAFE_CONCURRENT_WRITES_END(); +} +const ::google::protobuf::Descriptor* UserConstraintStateStatus::descriptor() { + protobuf_pybullet_2eproto::protobuf_AssignDescriptorsOnce(); + return protobuf_pybullet_2eproto::file_level_metadata[31].descriptor; +} + +const UserConstraintStateStatus& UserConstraintStateStatus::default_instance() { + protobuf_pybullet_2eproto::InitDefaults(); + return *internal_default_instance(); +} + +UserConstraintStateStatus* UserConstraintStateStatus::New(::google::protobuf::Arena* arena) const { + UserConstraintStateStatus* n = new UserConstraintStateStatus; + if (arena != NULL) { + arena->Own(n); + } + return n; +} + +void UserConstraintStateStatus::Clear() { +// @@protoc_insertion_point(message_clear_start:pybullet_grpc.UserConstraintStateStatus) + if (GetArenaNoVirtual() == NULL && appliedconstraintforceslinear_ != NULL) { + delete appliedconstraintforceslinear_; + } + appliedconstraintforceslinear_ = NULL; + if (GetArenaNoVirtual() == NULL && appliedconstraintforcesangular_ != NULL) { + delete appliedconstraintforcesangular_; + } + appliedconstraintforcesangular_ = NULL; + numdofs_ = 0; +} + +bool UserConstraintStateStatus::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.UserConstraintStateStatus) + 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)) { + // .pybullet_grpc.vec3 appliedConstraintForcesLinear = 1; + case 1: { + if (tag == 10u) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessageNoVirtual( + input, mutable_appliedconstraintforceslinear())); + } else { + goto handle_unusual; + } + break; + } + + // .pybullet_grpc.vec3 appliedConstraintForcesAngular = 2; + case 2: { + if (tag == 18u) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessageNoVirtual( + input, mutable_appliedconstraintforcesangular())); + } else { + goto handle_unusual; + } + break; + } + + // int32 numDofs = 3; + case 3: { + if (tag == 24u) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>( + input, &numdofs_))); + } 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.UserConstraintStateStatus) + return true; +failure: + // @@protoc_insertion_point(parse_failure:pybullet_grpc.UserConstraintStateStatus) + return false; +#undef DO_ +} + +void UserConstraintStateStatus::SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const { + // @@protoc_insertion_point(serialize_start:pybullet_grpc.UserConstraintStateStatus) + // .pybullet_grpc.vec3 appliedConstraintForcesLinear = 1; + if (this->has_appliedconstraintforceslinear()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 1, *this->appliedconstraintforceslinear_, output); + } + + // .pybullet_grpc.vec3 appliedConstraintForcesAngular = 2; + if (this->has_appliedconstraintforcesangular()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 2, *this->appliedconstraintforcesangular_, output); + } + + // int32 numDofs = 3; + if (this->numdofs() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteInt32(3, this->numdofs(), output); + } + + // @@protoc_insertion_point(serialize_end:pybullet_grpc.UserConstraintStateStatus) +} + +::google::protobuf::uint8* UserConstraintStateStatus::InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const { + (void)deterministic; // Unused + // @@protoc_insertion_point(serialize_to_array_start:pybullet_grpc.UserConstraintStateStatus) + // .pybullet_grpc.vec3 appliedConstraintForcesLinear = 1; + if (this->has_appliedconstraintforceslinear()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageNoVirtualToArray( + 1, *this->appliedconstraintforceslinear_, false, target); + } + + // .pybullet_grpc.vec3 appliedConstraintForcesAngular = 2; + if (this->has_appliedconstraintforcesangular()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageNoVirtualToArray( + 2, *this->appliedconstraintforcesangular_, false, target); + } + + // int32 numDofs = 3; + if (this->numdofs() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteInt32ToArray(3, this->numdofs(), target); + } + + // @@protoc_insertion_point(serialize_to_array_end:pybullet_grpc.UserConstraintStateStatus) + return target; +} + +size_t UserConstraintStateStatus::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:pybullet_grpc.UserConstraintStateStatus) + size_t total_size = 0; + + // .pybullet_grpc.vec3 appliedConstraintForcesLinear = 1; + if (this->has_appliedconstraintforceslinear()) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSizeNoVirtual( + *this->appliedconstraintforceslinear_); + } + + // .pybullet_grpc.vec3 appliedConstraintForcesAngular = 2; + if (this->has_appliedconstraintforcesangular()) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSizeNoVirtual( + *this->appliedconstraintforcesangular_); + } + + // int32 numDofs = 3; + if (this->numdofs() != 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::Int32Size( + this->numdofs()); + } + + 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 UserConstraintStateStatus::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:pybullet_grpc.UserConstraintStateStatus) + GOOGLE_DCHECK_NE(&from, this); + const UserConstraintStateStatus* source = + ::google::protobuf::internal::DynamicCastToGenerated( + &from); + if (source == NULL) { + // @@protoc_insertion_point(generalized_merge_from_cast_fail:pybullet_grpc.UserConstraintStateStatus) + ::google::protobuf::internal::ReflectionOps::Merge(from, this); + } else { + // @@protoc_insertion_point(generalized_merge_from_cast_success:pybullet_grpc.UserConstraintStateStatus) + MergeFrom(*source); + } +} + +void UserConstraintStateStatus::MergeFrom(const UserConstraintStateStatus& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:pybullet_grpc.UserConstraintStateStatus) + GOOGLE_DCHECK_NE(&from, this); + _internal_metadata_.MergeFrom(from._internal_metadata_); + if (from.has_appliedconstraintforceslinear()) { + mutable_appliedconstraintforceslinear()->::pybullet_grpc::vec3::MergeFrom(from.appliedconstraintforceslinear()); + } + if (from.has_appliedconstraintforcesangular()) { + mutable_appliedconstraintforcesangular()->::pybullet_grpc::vec3::MergeFrom(from.appliedconstraintforcesangular()); + } + if (from.numdofs() != 0) { + set_numdofs(from.numdofs()); + } +} + +void UserConstraintStateStatus::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:pybullet_grpc.UserConstraintStateStatus) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +void UserConstraintStateStatus::CopyFrom(const UserConstraintStateStatus& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:pybullet_grpc.UserConstraintStateStatus) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool UserConstraintStateStatus::IsInitialized() const { + return true; +} + +void UserConstraintStateStatus::Swap(UserConstraintStateStatus* other) { + if (other == this) return; + InternalSwap(other); +} +void UserConstraintStateStatus::InternalSwap(UserConstraintStateStatus* other) { + std::swap(appliedconstraintforceslinear_, other->appliedconstraintforceslinear_); + std::swap(appliedconstraintforcesangular_, other->appliedconstraintforcesangular_); + std::swap(numdofs_, other->numdofs_); + std::swap(_cached_size_, other->_cached_size_); +} + +::google::protobuf::Metadata UserConstraintStateStatus::GetMetadata() const { + protobuf_pybullet_2eproto::protobuf_AssignDescriptorsOnce(); + return protobuf_pybullet_2eproto::file_level_metadata[31]; +} + +#if PROTOBUF_INLINE_NOT_IN_HEADERS +// UserConstraintStateStatus + +// .pybullet_grpc.vec3 appliedConstraintForcesLinear = 1; +bool UserConstraintStateStatus::has_appliedconstraintforceslinear() const { + return this != internal_default_instance() && appliedconstraintforceslinear_ != NULL; +} +void UserConstraintStateStatus::clear_appliedconstraintforceslinear() { + if (GetArenaNoVirtual() == NULL && appliedconstraintforceslinear_ != NULL) delete appliedconstraintforceslinear_; + appliedconstraintforceslinear_ = NULL; +} +const ::pybullet_grpc::vec3& UserConstraintStateStatus::appliedconstraintforceslinear() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.UserConstraintStateStatus.appliedConstraintForcesLinear) + return appliedconstraintforceslinear_ != NULL ? *appliedconstraintforceslinear_ + : *::pybullet_grpc::vec3::internal_default_instance(); +} +::pybullet_grpc::vec3* UserConstraintStateStatus::mutable_appliedconstraintforceslinear() { + + if (appliedconstraintforceslinear_ == NULL) { + appliedconstraintforceslinear_ = new ::pybullet_grpc::vec3; + } + // @@protoc_insertion_point(field_mutable:pybullet_grpc.UserConstraintStateStatus.appliedConstraintForcesLinear) + return appliedconstraintforceslinear_; +} +::pybullet_grpc::vec3* UserConstraintStateStatus::release_appliedconstraintforceslinear() { + // @@protoc_insertion_point(field_release:pybullet_grpc.UserConstraintStateStatus.appliedConstraintForcesLinear) + + ::pybullet_grpc::vec3* temp = appliedconstraintforceslinear_; + appliedconstraintforceslinear_ = NULL; + return temp; +} +void UserConstraintStateStatus::set_allocated_appliedconstraintforceslinear(::pybullet_grpc::vec3* appliedconstraintforceslinear) { + delete appliedconstraintforceslinear_; + appliedconstraintforceslinear_ = appliedconstraintforceslinear; + if (appliedconstraintforceslinear) { + + } else { + + } + // @@protoc_insertion_point(field_set_allocated:pybullet_grpc.UserConstraintStateStatus.appliedConstraintForcesLinear) +} + +// .pybullet_grpc.vec3 appliedConstraintForcesAngular = 2; +bool UserConstraintStateStatus::has_appliedconstraintforcesangular() const { + return this != internal_default_instance() && appliedconstraintforcesangular_ != NULL; +} +void UserConstraintStateStatus::clear_appliedconstraintforcesangular() { + if (GetArenaNoVirtual() == NULL && appliedconstraintforcesangular_ != NULL) delete appliedconstraintforcesangular_; + appliedconstraintforcesangular_ = NULL; +} +const ::pybullet_grpc::vec3& UserConstraintStateStatus::appliedconstraintforcesangular() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.UserConstraintStateStatus.appliedConstraintForcesAngular) + return appliedconstraintforcesangular_ != NULL ? *appliedconstraintforcesangular_ + : *::pybullet_grpc::vec3::internal_default_instance(); +} +::pybullet_grpc::vec3* UserConstraintStateStatus::mutable_appliedconstraintforcesangular() { + + if (appliedconstraintforcesangular_ == NULL) { + appliedconstraintforcesangular_ = new ::pybullet_grpc::vec3; + } + // @@protoc_insertion_point(field_mutable:pybullet_grpc.UserConstraintStateStatus.appliedConstraintForcesAngular) + return appliedconstraintforcesangular_; +} +::pybullet_grpc::vec3* UserConstraintStateStatus::release_appliedconstraintforcesangular() { + // @@protoc_insertion_point(field_release:pybullet_grpc.UserConstraintStateStatus.appliedConstraintForcesAngular) + + ::pybullet_grpc::vec3* temp = appliedconstraintforcesangular_; + appliedconstraintforcesangular_ = NULL; + return temp; +} +void UserConstraintStateStatus::set_allocated_appliedconstraintforcesangular(::pybullet_grpc::vec3* appliedconstraintforcesangular) { + delete appliedconstraintforcesangular_; + appliedconstraintforcesangular_ = appliedconstraintforcesangular; + if (appliedconstraintforcesangular) { + + } else { + + } + // @@protoc_insertion_point(field_set_allocated:pybullet_grpc.UserConstraintStateStatus.appliedConstraintForcesAngular) +} + +// int32 numDofs = 3; +void UserConstraintStateStatus::clear_numdofs() { + numdofs_ = 0; +} +::google::protobuf::int32 UserConstraintStateStatus::numdofs() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.UserConstraintStateStatus.numDofs) + return numdofs_; +} +void UserConstraintStateStatus::set_numdofs(::google::protobuf::int32 value) { + + numdofs_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.UserConstraintStateStatus.numDofs) +} + +#endif // PROTOBUF_INLINE_NOT_IN_HEADERS + +// =================================================================== + +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 + +RequestKeyboardEventsCommand::RequestKeyboardEventsCommand() + : ::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.RequestKeyboardEventsCommand) +} +RequestKeyboardEventsCommand::RequestKeyboardEventsCommand(const RequestKeyboardEventsCommand& from) + : ::google::protobuf::Message(), + _internal_metadata_(NULL), + _cached_size_(0) { + _internal_metadata_.MergeFrom(from._internal_metadata_); + // @@protoc_insertion_point(copy_constructor:pybullet_grpc.RequestKeyboardEventsCommand) +} + +void RequestKeyboardEventsCommand::SharedCtor() { + _cached_size_ = 0; +} + +RequestKeyboardEventsCommand::~RequestKeyboardEventsCommand() { + // @@protoc_insertion_point(destructor:pybullet_grpc.RequestKeyboardEventsCommand) + SharedDtor(); +} + +void RequestKeyboardEventsCommand::SharedDtor() { +} + +void RequestKeyboardEventsCommand::SetCachedSize(int size) const { + GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN(); + _cached_size_ = size; + GOOGLE_SAFE_CONCURRENT_WRITES_END(); +} +const ::google::protobuf::Descriptor* RequestKeyboardEventsCommand::descriptor() { + protobuf_pybullet_2eproto::protobuf_AssignDescriptorsOnce(); + return protobuf_pybullet_2eproto::file_level_metadata[32].descriptor; +} + +const RequestKeyboardEventsCommand& RequestKeyboardEventsCommand::default_instance() { + protobuf_pybullet_2eproto::InitDefaults(); + return *internal_default_instance(); +} + +RequestKeyboardEventsCommand* RequestKeyboardEventsCommand::New(::google::protobuf::Arena* arena) const { + RequestKeyboardEventsCommand* n = new RequestKeyboardEventsCommand; + if (arena != NULL) { + arena->Own(n); + } + return n; +} + +void RequestKeyboardEventsCommand::Clear() { +// @@protoc_insertion_point(message_clear_start:pybullet_grpc.RequestKeyboardEventsCommand) +} + +bool RequestKeyboardEventsCommand::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.RequestKeyboardEventsCommand) + 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.RequestKeyboardEventsCommand) + return true; +failure: + // @@protoc_insertion_point(parse_failure:pybullet_grpc.RequestKeyboardEventsCommand) + return false; +#undef DO_ +} + +void RequestKeyboardEventsCommand::SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const { + // @@protoc_insertion_point(serialize_start:pybullet_grpc.RequestKeyboardEventsCommand) + // @@protoc_insertion_point(serialize_end:pybullet_grpc.RequestKeyboardEventsCommand) +} + +::google::protobuf::uint8* RequestKeyboardEventsCommand::InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const { + (void)deterministic; // Unused + // @@protoc_insertion_point(serialize_to_array_start:pybullet_grpc.RequestKeyboardEventsCommand) + // @@protoc_insertion_point(serialize_to_array_end:pybullet_grpc.RequestKeyboardEventsCommand) + return target; +} + +size_t RequestKeyboardEventsCommand::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:pybullet_grpc.RequestKeyboardEventsCommand) + 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 RequestKeyboardEventsCommand::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:pybullet_grpc.RequestKeyboardEventsCommand) + GOOGLE_DCHECK_NE(&from, this); + const RequestKeyboardEventsCommand* source = + ::google::protobuf::internal::DynamicCastToGenerated( + &from); + if (source == NULL) { + // @@protoc_insertion_point(generalized_merge_from_cast_fail:pybullet_grpc.RequestKeyboardEventsCommand) + ::google::protobuf::internal::ReflectionOps::Merge(from, this); + } else { + // @@protoc_insertion_point(generalized_merge_from_cast_success:pybullet_grpc.RequestKeyboardEventsCommand) + MergeFrom(*source); + } +} + +void RequestKeyboardEventsCommand::MergeFrom(const RequestKeyboardEventsCommand& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:pybullet_grpc.RequestKeyboardEventsCommand) + GOOGLE_DCHECK_NE(&from, this); + _internal_metadata_.MergeFrom(from._internal_metadata_); +} + +void RequestKeyboardEventsCommand::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:pybullet_grpc.RequestKeyboardEventsCommand) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +void RequestKeyboardEventsCommand::CopyFrom(const RequestKeyboardEventsCommand& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:pybullet_grpc.RequestKeyboardEventsCommand) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool RequestKeyboardEventsCommand::IsInitialized() const { + return true; +} + +void RequestKeyboardEventsCommand::Swap(RequestKeyboardEventsCommand* other) { + if (other == this) return; + InternalSwap(other); +} +void RequestKeyboardEventsCommand::InternalSwap(RequestKeyboardEventsCommand* other) { + std::swap(_cached_size_, other->_cached_size_); +} + +::google::protobuf::Metadata RequestKeyboardEventsCommand::GetMetadata() const { + protobuf_pybullet_2eproto::protobuf_AssignDescriptorsOnce(); + return protobuf_pybullet_2eproto::file_level_metadata[32]; +} + +#if PROTOBUF_INLINE_NOT_IN_HEADERS +// RequestKeyboardEventsCommand + +#endif // PROTOBUF_INLINE_NOT_IN_HEADERS + +// =================================================================== + +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const int KeyboardEvent::kKeyCodeFieldNumber; +const int KeyboardEvent::kKeyStateFieldNumber; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 + +KeyboardEvent::KeyboardEvent() + : ::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.KeyboardEvent) +} +KeyboardEvent::KeyboardEvent(const KeyboardEvent& from) + : ::google::protobuf::Message(), + _internal_metadata_(NULL), + _cached_size_(0) { + _internal_metadata_.MergeFrom(from._internal_metadata_); + ::memcpy(&keycode_, &from.keycode_, + reinterpret_cast(&keystate_) - + reinterpret_cast(&keycode_) + sizeof(keystate_)); + // @@protoc_insertion_point(copy_constructor:pybullet_grpc.KeyboardEvent) +} + +void KeyboardEvent::SharedCtor() { + ::memset(&keycode_, 0, reinterpret_cast(&keystate_) - + reinterpret_cast(&keycode_) + sizeof(keystate_)); + _cached_size_ = 0; +} + +KeyboardEvent::~KeyboardEvent() { + // @@protoc_insertion_point(destructor:pybullet_grpc.KeyboardEvent) + SharedDtor(); +} + +void KeyboardEvent::SharedDtor() { +} + +void KeyboardEvent::SetCachedSize(int size) const { + GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN(); + _cached_size_ = size; + GOOGLE_SAFE_CONCURRENT_WRITES_END(); +} +const ::google::protobuf::Descriptor* KeyboardEvent::descriptor() { + protobuf_pybullet_2eproto::protobuf_AssignDescriptorsOnce(); + return protobuf_pybullet_2eproto::file_level_metadata[33].descriptor; +} + +const KeyboardEvent& KeyboardEvent::default_instance() { + protobuf_pybullet_2eproto::InitDefaults(); + return *internal_default_instance(); +} + +KeyboardEvent* KeyboardEvent::New(::google::protobuf::Arena* arena) const { + KeyboardEvent* n = new KeyboardEvent; + if (arena != NULL) { + arena->Own(n); + } + return n; +} + +void KeyboardEvent::Clear() { +// @@protoc_insertion_point(message_clear_start:pybullet_grpc.KeyboardEvent) + ::memset(&keycode_, 0, reinterpret_cast(&keystate_) - + reinterpret_cast(&keycode_) + sizeof(keystate_)); +} + +bool KeyboardEvent::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.KeyboardEvent) + 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 keyCode = 1; + case 1: { + if (tag == 8u) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>( + input, &keycode_))); + } else { + goto handle_unusual; + } + break; + } + + // int32 keyState = 2; + case 2: { + if (tag == 16u) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>( + input, &keystate_))); + } 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.KeyboardEvent) + return true; +failure: + // @@protoc_insertion_point(parse_failure:pybullet_grpc.KeyboardEvent) + return false; +#undef DO_ +} + +void KeyboardEvent::SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const { + // @@protoc_insertion_point(serialize_start:pybullet_grpc.KeyboardEvent) + // int32 keyCode = 1; + if (this->keycode() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteInt32(1, this->keycode(), output); + } + + // int32 keyState = 2; + if (this->keystate() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteInt32(2, this->keystate(), output); + } + + // @@protoc_insertion_point(serialize_end:pybullet_grpc.KeyboardEvent) +} + +::google::protobuf::uint8* KeyboardEvent::InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const { + (void)deterministic; // Unused + // @@protoc_insertion_point(serialize_to_array_start:pybullet_grpc.KeyboardEvent) + // int32 keyCode = 1; + if (this->keycode() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteInt32ToArray(1, this->keycode(), target); + } + + // int32 keyState = 2; + if (this->keystate() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteInt32ToArray(2, this->keystate(), target); + } + + // @@protoc_insertion_point(serialize_to_array_end:pybullet_grpc.KeyboardEvent) + return target; +} + +size_t KeyboardEvent::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:pybullet_grpc.KeyboardEvent) + size_t total_size = 0; + + // int32 keyCode = 1; + if (this->keycode() != 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::Int32Size( + this->keycode()); + } + + // int32 keyState = 2; + if (this->keystate() != 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::Int32Size( + this->keystate()); + } + + 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 KeyboardEvent::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:pybullet_grpc.KeyboardEvent) + GOOGLE_DCHECK_NE(&from, this); + const KeyboardEvent* source = + ::google::protobuf::internal::DynamicCastToGenerated( + &from); + if (source == NULL) { + // @@protoc_insertion_point(generalized_merge_from_cast_fail:pybullet_grpc.KeyboardEvent) + ::google::protobuf::internal::ReflectionOps::Merge(from, this); + } else { + // @@protoc_insertion_point(generalized_merge_from_cast_success:pybullet_grpc.KeyboardEvent) + MergeFrom(*source); + } +} + +void KeyboardEvent::MergeFrom(const KeyboardEvent& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:pybullet_grpc.KeyboardEvent) + GOOGLE_DCHECK_NE(&from, this); + _internal_metadata_.MergeFrom(from._internal_metadata_); + if (from.keycode() != 0) { + set_keycode(from.keycode()); + } + if (from.keystate() != 0) { + set_keystate(from.keystate()); + } +} + +void KeyboardEvent::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:pybullet_grpc.KeyboardEvent) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +void KeyboardEvent::CopyFrom(const KeyboardEvent& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:pybullet_grpc.KeyboardEvent) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool KeyboardEvent::IsInitialized() const { + return true; +} + +void KeyboardEvent::Swap(KeyboardEvent* other) { + if (other == this) return; + InternalSwap(other); +} +void KeyboardEvent::InternalSwap(KeyboardEvent* other) { + std::swap(keycode_, other->keycode_); + std::swap(keystate_, other->keystate_); + std::swap(_cached_size_, other->_cached_size_); +} + +::google::protobuf::Metadata KeyboardEvent::GetMetadata() const { + protobuf_pybullet_2eproto::protobuf_AssignDescriptorsOnce(); + return protobuf_pybullet_2eproto::file_level_metadata[33]; +} + +#if PROTOBUF_INLINE_NOT_IN_HEADERS +// KeyboardEvent + +// int32 keyCode = 1; +void KeyboardEvent::clear_keycode() { + keycode_ = 0; +} +::google::protobuf::int32 KeyboardEvent::keycode() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.KeyboardEvent.keyCode) + return keycode_; +} +void KeyboardEvent::set_keycode(::google::protobuf::int32 value) { + + keycode_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.KeyboardEvent.keyCode) +} + +// int32 keyState = 2; +void KeyboardEvent::clear_keystate() { + keystate_ = 0; +} +::google::protobuf::int32 KeyboardEvent::keystate() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.KeyboardEvent.keyState) + return keystate_; +} +void KeyboardEvent::set_keystate(::google::protobuf::int32 value) { + + keystate_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.KeyboardEvent.keyState) +} + +#endif // PROTOBUF_INLINE_NOT_IN_HEADERS + +// =================================================================== + +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const int KeyboardEventsStatus::kKeyboardEventsFieldNumber; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 + +KeyboardEventsStatus::KeyboardEventsStatus() + : ::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.KeyboardEventsStatus) +} +KeyboardEventsStatus::KeyboardEventsStatus(const KeyboardEventsStatus& from) + : ::google::protobuf::Message(), + _internal_metadata_(NULL), + keyboardevents_(from.keyboardevents_), + _cached_size_(0) { + _internal_metadata_.MergeFrom(from._internal_metadata_); + // @@protoc_insertion_point(copy_constructor:pybullet_grpc.KeyboardEventsStatus) +} + +void KeyboardEventsStatus::SharedCtor() { + _cached_size_ = 0; +} + +KeyboardEventsStatus::~KeyboardEventsStatus() { + // @@protoc_insertion_point(destructor:pybullet_grpc.KeyboardEventsStatus) + SharedDtor(); +} + +void KeyboardEventsStatus::SharedDtor() { +} + +void KeyboardEventsStatus::SetCachedSize(int size) const { + GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN(); + _cached_size_ = size; + GOOGLE_SAFE_CONCURRENT_WRITES_END(); +} +const ::google::protobuf::Descriptor* KeyboardEventsStatus::descriptor() { + protobuf_pybullet_2eproto::protobuf_AssignDescriptorsOnce(); + return protobuf_pybullet_2eproto::file_level_metadata[34].descriptor; +} + +const KeyboardEventsStatus& KeyboardEventsStatus::default_instance() { + protobuf_pybullet_2eproto::InitDefaults(); + return *internal_default_instance(); +} + +KeyboardEventsStatus* KeyboardEventsStatus::New(::google::protobuf::Arena* arena) const { + KeyboardEventsStatus* n = new KeyboardEventsStatus; + if (arena != NULL) { + arena->Own(n); + } + return n; +} + +void KeyboardEventsStatus::Clear() { +// @@protoc_insertion_point(message_clear_start:pybullet_grpc.KeyboardEventsStatus) + keyboardevents_.Clear(); +} + +bool KeyboardEventsStatus::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.KeyboardEventsStatus) + 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)) { + // repeated .pybullet_grpc.KeyboardEvent keyboardEvents = 1; + case 1: { + if (tag == 10u) { + DO_(input->IncrementRecursionDepth()); + DO_(::google::protobuf::internal::WireFormatLite::ReadMessageNoVirtualNoRecursionDepth( + input, add_keyboardevents())); + } else { + goto handle_unusual; + } + input->UnsafeDecrementRecursionDepth(); + 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.KeyboardEventsStatus) + return true; +failure: + // @@protoc_insertion_point(parse_failure:pybullet_grpc.KeyboardEventsStatus) + return false; +#undef DO_ +} + +void KeyboardEventsStatus::SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const { + // @@protoc_insertion_point(serialize_start:pybullet_grpc.KeyboardEventsStatus) + // repeated .pybullet_grpc.KeyboardEvent keyboardEvents = 1; + for (unsigned int i = 0, n = this->keyboardevents_size(); i < n; i++) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 1, this->keyboardevents(i), output); + } + + // @@protoc_insertion_point(serialize_end:pybullet_grpc.KeyboardEventsStatus) +} + +::google::protobuf::uint8* KeyboardEventsStatus::InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const { + (void)deterministic; // Unused + // @@protoc_insertion_point(serialize_to_array_start:pybullet_grpc.KeyboardEventsStatus) + // repeated .pybullet_grpc.KeyboardEvent keyboardEvents = 1; + for (unsigned int i = 0, n = this->keyboardevents_size(); i < n; i++) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageNoVirtualToArray( + 1, this->keyboardevents(i), false, target); + } + + // @@protoc_insertion_point(serialize_to_array_end:pybullet_grpc.KeyboardEventsStatus) + return target; +} + +size_t KeyboardEventsStatus::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:pybullet_grpc.KeyboardEventsStatus) + size_t total_size = 0; + + // repeated .pybullet_grpc.KeyboardEvent keyboardEvents = 1; + { + unsigned int count = this->keyboardevents_size(); + total_size += 1UL * count; + for (unsigned int i = 0; i < count; i++) { + total_size += + ::google::protobuf::internal::WireFormatLite::MessageSizeNoVirtual( + this->keyboardevents(i)); + } + } + + 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 KeyboardEventsStatus::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:pybullet_grpc.KeyboardEventsStatus) + GOOGLE_DCHECK_NE(&from, this); + const KeyboardEventsStatus* source = + ::google::protobuf::internal::DynamicCastToGenerated( + &from); + if (source == NULL) { + // @@protoc_insertion_point(generalized_merge_from_cast_fail:pybullet_grpc.KeyboardEventsStatus) + ::google::protobuf::internal::ReflectionOps::Merge(from, this); + } else { + // @@protoc_insertion_point(generalized_merge_from_cast_success:pybullet_grpc.KeyboardEventsStatus) + MergeFrom(*source); + } +} + +void KeyboardEventsStatus::MergeFrom(const KeyboardEventsStatus& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:pybullet_grpc.KeyboardEventsStatus) + GOOGLE_DCHECK_NE(&from, this); + _internal_metadata_.MergeFrom(from._internal_metadata_); + keyboardevents_.MergeFrom(from.keyboardevents_); +} + +void KeyboardEventsStatus::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:pybullet_grpc.KeyboardEventsStatus) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +void KeyboardEventsStatus::CopyFrom(const KeyboardEventsStatus& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:pybullet_grpc.KeyboardEventsStatus) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool KeyboardEventsStatus::IsInitialized() const { + return true; +} + +void KeyboardEventsStatus::Swap(KeyboardEventsStatus* other) { + if (other == this) return; + InternalSwap(other); +} +void KeyboardEventsStatus::InternalSwap(KeyboardEventsStatus* other) { + keyboardevents_.UnsafeArenaSwap(&other->keyboardevents_); + std::swap(_cached_size_, other->_cached_size_); +} + +::google::protobuf::Metadata KeyboardEventsStatus::GetMetadata() const { + protobuf_pybullet_2eproto::protobuf_AssignDescriptorsOnce(); + return protobuf_pybullet_2eproto::file_level_metadata[34]; +} + +#if PROTOBUF_INLINE_NOT_IN_HEADERS +// KeyboardEventsStatus + +// repeated .pybullet_grpc.KeyboardEvent keyboardEvents = 1; +int KeyboardEventsStatus::keyboardevents_size() const { + return keyboardevents_.size(); +} +void KeyboardEventsStatus::clear_keyboardevents() { + keyboardevents_.Clear(); +} +const ::pybullet_grpc::KeyboardEvent& KeyboardEventsStatus::keyboardevents(int index) const { + // @@protoc_insertion_point(field_get:pybullet_grpc.KeyboardEventsStatus.keyboardEvents) + return keyboardevents_.Get(index); +} +::pybullet_grpc::KeyboardEvent* KeyboardEventsStatus::mutable_keyboardevents(int index) { + // @@protoc_insertion_point(field_mutable:pybullet_grpc.KeyboardEventsStatus.keyboardEvents) + return keyboardevents_.Mutable(index); +} +::pybullet_grpc::KeyboardEvent* KeyboardEventsStatus::add_keyboardevents() { + // @@protoc_insertion_point(field_add:pybullet_grpc.KeyboardEventsStatus.keyboardEvents) + return keyboardevents_.Add(); +} +::google::protobuf::RepeatedPtrField< ::pybullet_grpc::KeyboardEvent >* +KeyboardEventsStatus::mutable_keyboardevents() { + // @@protoc_insertion_point(field_mutable_list:pybullet_grpc.KeyboardEventsStatus.keyboardEvents) + return &keyboardevents_; +} +const ::google::protobuf::RepeatedPtrField< ::pybullet_grpc::KeyboardEvent >& +KeyboardEventsStatus::keyboardevents() const { + // @@protoc_insertion_point(field_list:pybullet_grpc.KeyboardEventsStatus.keyboardEvents) + return keyboardevents_; +} + +#endif // PROTOBUF_INLINE_NOT_IN_HEADERS + +// =================================================================== + +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const int RequestCameraImageCommand::kUpdateFlagsFieldNumber; +const int RequestCameraImageCommand::kCameraFlagsFieldNumber; +const int RequestCameraImageCommand::kViewMatrixFieldNumber; +const int RequestCameraImageCommand::kProjectionMatrixFieldNumber; +const int RequestCameraImageCommand::kStartPixelIndexFieldNumber; +const int RequestCameraImageCommand::kPixelWidthFieldNumber; +const int RequestCameraImageCommand::kPixelHeightFieldNumber; +const int RequestCameraImageCommand::kLightDirectionFieldNumber; +const int RequestCameraImageCommand::kLightColorFieldNumber; +const int RequestCameraImageCommand::kLightDistanceFieldNumber; +const int RequestCameraImageCommand::kLightAmbientCoeffFieldNumber; +const int RequestCameraImageCommand::kLightDiffuseCoeffFieldNumber; +const int RequestCameraImageCommand::kLightSpecularCoeffFieldNumber; +const int RequestCameraImageCommand::kHasShadowFieldNumber; +const int RequestCameraImageCommand::kProjectiveTextureViewMatrixFieldNumber; +const int RequestCameraImageCommand::kProjectiveTextureProjectionMatrixFieldNumber; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 + +RequestCameraImageCommand::RequestCameraImageCommand() + : ::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.RequestCameraImageCommand) +} +RequestCameraImageCommand::RequestCameraImageCommand(const RequestCameraImageCommand& from) + : ::google::protobuf::Message(), + _internal_metadata_(NULL), + _cached_size_(0) { + _internal_metadata_.MergeFrom(from._internal_metadata_); + if (from.has_viewmatrix()) { + viewmatrix_ = new ::pybullet_grpc::matrix4x4(*from.viewmatrix_); + } else { + viewmatrix_ = NULL; + } + if (from.has_projectionmatrix()) { + projectionmatrix_ = new ::pybullet_grpc::matrix4x4(*from.projectionmatrix_); + } else { + projectionmatrix_ = NULL; + } + if (from.has_lightdirection()) { + lightdirection_ = new ::pybullet_grpc::vec3(*from.lightdirection_); + } else { + lightdirection_ = NULL; + } + if (from.has_lightcolor()) { + lightcolor_ = new ::pybullet_grpc::vec3(*from.lightcolor_); + } else { + lightcolor_ = NULL; + } + if (from.has_projectivetextureviewmatrix()) { + projectivetextureviewmatrix_ = new ::pybullet_grpc::matrix4x4(*from.projectivetextureviewmatrix_); + } else { + projectivetextureviewmatrix_ = NULL; + } + if (from.has_projectivetextureprojectionmatrix()) { + projectivetextureprojectionmatrix_ = new ::pybullet_grpc::matrix4x4(*from.projectivetextureprojectionmatrix_); + } else { + projectivetextureprojectionmatrix_ = NULL; + } + ::memcpy(&updateflags_, &from.updateflags_, + reinterpret_cast(&lightspecularcoeff_) - + reinterpret_cast(&updateflags_) + sizeof(lightspecularcoeff_)); + // @@protoc_insertion_point(copy_constructor:pybullet_grpc.RequestCameraImageCommand) +} + +void RequestCameraImageCommand::SharedCtor() { + ::memset(&viewmatrix_, 0, reinterpret_cast(&lightspecularcoeff_) - + reinterpret_cast(&viewmatrix_) + sizeof(lightspecularcoeff_)); + _cached_size_ = 0; +} + +RequestCameraImageCommand::~RequestCameraImageCommand() { + // @@protoc_insertion_point(destructor:pybullet_grpc.RequestCameraImageCommand) + SharedDtor(); +} + +void RequestCameraImageCommand::SharedDtor() { + if (this != internal_default_instance()) { + delete viewmatrix_; + } + if (this != internal_default_instance()) { + delete projectionmatrix_; + } + if (this != internal_default_instance()) { + delete lightdirection_; + } + if (this != internal_default_instance()) { + delete lightcolor_; + } + if (this != internal_default_instance()) { + delete projectivetextureviewmatrix_; + } + if (this != internal_default_instance()) { + delete projectivetextureprojectionmatrix_; + } +} + +void RequestCameraImageCommand::SetCachedSize(int size) const { + GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN(); + _cached_size_ = size; + GOOGLE_SAFE_CONCURRENT_WRITES_END(); +} +const ::google::protobuf::Descriptor* RequestCameraImageCommand::descriptor() { + protobuf_pybullet_2eproto::protobuf_AssignDescriptorsOnce(); + return protobuf_pybullet_2eproto::file_level_metadata[35].descriptor; +} + +const RequestCameraImageCommand& RequestCameraImageCommand::default_instance() { + protobuf_pybullet_2eproto::InitDefaults(); + return *internal_default_instance(); +} + +RequestCameraImageCommand* RequestCameraImageCommand::New(::google::protobuf::Arena* arena) const { + RequestCameraImageCommand* n = new RequestCameraImageCommand; + if (arena != NULL) { + arena->Own(n); + } + return n; +} + +void RequestCameraImageCommand::Clear() { +// @@protoc_insertion_point(message_clear_start:pybullet_grpc.RequestCameraImageCommand) + if (GetArenaNoVirtual() == NULL && viewmatrix_ != NULL) { + delete viewmatrix_; + } + viewmatrix_ = NULL; + if (GetArenaNoVirtual() == NULL && projectionmatrix_ != NULL) { + delete projectionmatrix_; + } + projectionmatrix_ = NULL; + if (GetArenaNoVirtual() == NULL && lightdirection_ != NULL) { + delete lightdirection_; + } + lightdirection_ = NULL; + if (GetArenaNoVirtual() == NULL && lightcolor_ != NULL) { + delete lightcolor_; + } + lightcolor_ = NULL; + if (GetArenaNoVirtual() == NULL && projectivetextureviewmatrix_ != NULL) { + delete projectivetextureviewmatrix_; + } + projectivetextureviewmatrix_ = NULL; + if (GetArenaNoVirtual() == NULL && projectivetextureprojectionmatrix_ != NULL) { + delete projectivetextureprojectionmatrix_; + } + projectivetextureprojectionmatrix_ = NULL; + ::memset(&updateflags_, 0, reinterpret_cast(&lightspecularcoeff_) - + reinterpret_cast(&updateflags_) + sizeof(lightspecularcoeff_)); +} + +bool RequestCameraImageCommand::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.RequestCameraImageCommand) + for (;;) { + ::std::pair< ::google::protobuf::uint32, bool> p = input->ReadTagWithCutoffNoLastTag(16383u); + tag = p.first; + if (!p.second) goto handle_unusual; + switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { + // int32 updateFlags = 1; + case 1: { + if (tag == 8u) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>( + input, &updateflags_))); + } else { + goto handle_unusual; + } + break; + } + + // int32 cameraFlags = 2; + case 2: { + if (tag == 16u) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>( + input, &cameraflags_))); + } else { + goto handle_unusual; + } + break; + } + + // .pybullet_grpc.matrix4x4 viewMatrix = 3; + case 3: { + if (tag == 26u) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessageNoVirtual( + input, mutable_viewmatrix())); + } else { + goto handle_unusual; + } + break; + } + + // .pybullet_grpc.matrix4x4 projectionMatrix = 4; + case 4: { + if (tag == 34u) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessageNoVirtual( + input, mutable_projectionmatrix())); + } else { + goto handle_unusual; + } + break; + } + + // int32 startPixelIndex = 5; + case 5: { + if (tag == 40u) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>( + input, &startpixelindex_))); + } else { + goto handle_unusual; + } + break; + } + + // int32 pixelWidth = 6; + case 6: { + if (tag == 48u) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>( + input, &pixelwidth_))); + } else { + goto handle_unusual; + } + break; + } + + // int32 pixelHeight = 7; + case 7: { + if (tag == 56u) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>( + input, &pixelheight_))); + } else { + goto handle_unusual; + } + break; + } + + // .pybullet_grpc.vec3 lightDirection = 8; + case 8: { + if (tag == 66u) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessageNoVirtual( + input, mutable_lightdirection())); + } else { + goto handle_unusual; + } + break; + } + + // .pybullet_grpc.vec3 lightColor = 9; + case 9: { + if (tag == 74u) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessageNoVirtual( + input, mutable_lightcolor())); + } else { + goto handle_unusual; + } + break; + } + + // double lightDistance = 10; + case 10: { + if (tag == 81u) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &lightdistance_))); + } else { + goto handle_unusual; + } + break; + } + + // double lightAmbientCoeff = 11; + case 11: { + if (tag == 89u) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &lightambientcoeff_))); + } else { + goto handle_unusual; + } + break; + } + + // double lightDiffuseCoeff = 12; + case 12: { + if (tag == 97u) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &lightdiffusecoeff_))); + } else { + goto handle_unusual; + } + break; + } + + // double lightSpecularCoeff = 13; + case 13: { + if (tag == 105u) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &lightspecularcoeff_))); + } else { + goto handle_unusual; + } + break; + } + + // int32 hasShadow = 14; + case 14: { + if (tag == 112u) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>( + input, &hasshadow_))); + } else { + goto handle_unusual; + } + break; + } + + // .pybullet_grpc.matrix4x4 projectiveTextureViewMatrix = 15; + case 15: { + if (tag == 122u) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessageNoVirtual( + input, mutable_projectivetextureviewmatrix())); + } else { + goto handle_unusual; + } + break; + } + + // .pybullet_grpc.matrix4x4 projectiveTextureProjectionMatrix = 16; + case 16: { + if (tag == 130u) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessageNoVirtual( + input, mutable_projectivetextureprojectionmatrix())); + } 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.RequestCameraImageCommand) + return true; +failure: + // @@protoc_insertion_point(parse_failure:pybullet_grpc.RequestCameraImageCommand) + return false; +#undef DO_ +} + +void RequestCameraImageCommand::SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const { + // @@protoc_insertion_point(serialize_start:pybullet_grpc.RequestCameraImageCommand) + // int32 updateFlags = 1; + if (this->updateflags() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteInt32(1, this->updateflags(), output); + } + + // int32 cameraFlags = 2; + if (this->cameraflags() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteInt32(2, this->cameraflags(), output); + } + + // .pybullet_grpc.matrix4x4 viewMatrix = 3; + if (this->has_viewmatrix()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 3, *this->viewmatrix_, output); + } + + // .pybullet_grpc.matrix4x4 projectionMatrix = 4; + if (this->has_projectionmatrix()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 4, *this->projectionmatrix_, output); + } + + // int32 startPixelIndex = 5; + if (this->startpixelindex() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteInt32(5, this->startpixelindex(), output); + } + + // int32 pixelWidth = 6; + if (this->pixelwidth() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteInt32(6, this->pixelwidth(), output); + } + + // int32 pixelHeight = 7; + if (this->pixelheight() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteInt32(7, this->pixelheight(), output); + } + + // .pybullet_grpc.vec3 lightDirection = 8; + if (this->has_lightdirection()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 8, *this->lightdirection_, output); + } + + // .pybullet_grpc.vec3 lightColor = 9; + if (this->has_lightcolor()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 9, *this->lightcolor_, output); + } + + // double lightDistance = 10; + if (this->lightdistance() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(10, this->lightdistance(), output); + } + + // double lightAmbientCoeff = 11; + if (this->lightambientcoeff() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(11, this->lightambientcoeff(), output); + } + + // double lightDiffuseCoeff = 12; + if (this->lightdiffusecoeff() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(12, this->lightdiffusecoeff(), output); + } + + // double lightSpecularCoeff = 13; + if (this->lightspecularcoeff() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(13, this->lightspecularcoeff(), output); + } + + // int32 hasShadow = 14; + if (this->hasshadow() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteInt32(14, this->hasshadow(), output); + } + + // .pybullet_grpc.matrix4x4 projectiveTextureViewMatrix = 15; + if (this->has_projectivetextureviewmatrix()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 15, *this->projectivetextureviewmatrix_, output); + } + + // .pybullet_grpc.matrix4x4 projectiveTextureProjectionMatrix = 16; + if (this->has_projectivetextureprojectionmatrix()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 16, *this->projectivetextureprojectionmatrix_, output); + } + + // @@protoc_insertion_point(serialize_end:pybullet_grpc.RequestCameraImageCommand) +} + +::google::protobuf::uint8* RequestCameraImageCommand::InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const { + (void)deterministic; // Unused + // @@protoc_insertion_point(serialize_to_array_start:pybullet_grpc.RequestCameraImageCommand) + // int32 updateFlags = 1; + if (this->updateflags() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteInt32ToArray(1, this->updateflags(), target); + } + + // int32 cameraFlags = 2; + if (this->cameraflags() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteInt32ToArray(2, this->cameraflags(), target); + } + + // .pybullet_grpc.matrix4x4 viewMatrix = 3; + if (this->has_viewmatrix()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageNoVirtualToArray( + 3, *this->viewmatrix_, false, target); + } + + // .pybullet_grpc.matrix4x4 projectionMatrix = 4; + if (this->has_projectionmatrix()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageNoVirtualToArray( + 4, *this->projectionmatrix_, false, target); + } + + // int32 startPixelIndex = 5; + if (this->startpixelindex() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteInt32ToArray(5, this->startpixelindex(), target); + } + + // int32 pixelWidth = 6; + if (this->pixelwidth() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteInt32ToArray(6, this->pixelwidth(), target); + } + + // int32 pixelHeight = 7; + if (this->pixelheight() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteInt32ToArray(7, this->pixelheight(), target); + } + + // .pybullet_grpc.vec3 lightDirection = 8; + if (this->has_lightdirection()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageNoVirtualToArray( + 8, *this->lightdirection_, false, target); + } + + // .pybullet_grpc.vec3 lightColor = 9; + if (this->has_lightcolor()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageNoVirtualToArray( + 9, *this->lightcolor_, false, target); + } + + // double lightDistance = 10; + if (this->lightdistance() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(10, this->lightdistance(), target); + } + + // double lightAmbientCoeff = 11; + if (this->lightambientcoeff() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(11, this->lightambientcoeff(), target); + } + + // double lightDiffuseCoeff = 12; + if (this->lightdiffusecoeff() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(12, this->lightdiffusecoeff(), target); + } + + // double lightSpecularCoeff = 13; + if (this->lightspecularcoeff() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(13, this->lightspecularcoeff(), target); + } + + // int32 hasShadow = 14; + if (this->hasshadow() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteInt32ToArray(14, this->hasshadow(), target); + } + + // .pybullet_grpc.matrix4x4 projectiveTextureViewMatrix = 15; + if (this->has_projectivetextureviewmatrix()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageNoVirtualToArray( + 15, *this->projectivetextureviewmatrix_, false, target); + } + + // .pybullet_grpc.matrix4x4 projectiveTextureProjectionMatrix = 16; + if (this->has_projectivetextureprojectionmatrix()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageNoVirtualToArray( + 16, *this->projectivetextureprojectionmatrix_, false, target); + } + + // @@protoc_insertion_point(serialize_to_array_end:pybullet_grpc.RequestCameraImageCommand) + return target; +} + +size_t RequestCameraImageCommand::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:pybullet_grpc.RequestCameraImageCommand) + size_t total_size = 0; + + // .pybullet_grpc.matrix4x4 viewMatrix = 3; + if (this->has_viewmatrix()) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSizeNoVirtual( + *this->viewmatrix_); + } + + // .pybullet_grpc.matrix4x4 projectionMatrix = 4; + if (this->has_projectionmatrix()) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSizeNoVirtual( + *this->projectionmatrix_); + } + + // .pybullet_grpc.vec3 lightDirection = 8; + if (this->has_lightdirection()) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSizeNoVirtual( + *this->lightdirection_); + } + + // .pybullet_grpc.vec3 lightColor = 9; + if (this->has_lightcolor()) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSizeNoVirtual( + *this->lightcolor_); + } + + // .pybullet_grpc.matrix4x4 projectiveTextureViewMatrix = 15; + if (this->has_projectivetextureviewmatrix()) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSizeNoVirtual( + *this->projectivetextureviewmatrix_); + } + + // .pybullet_grpc.matrix4x4 projectiveTextureProjectionMatrix = 16; + if (this->has_projectivetextureprojectionmatrix()) { + total_size += 2 + + ::google::protobuf::internal::WireFormatLite::MessageSizeNoVirtual( + *this->projectivetextureprojectionmatrix_); + } + + // int32 updateFlags = 1; + if (this->updateflags() != 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::Int32Size( + this->updateflags()); + } + + // int32 cameraFlags = 2; + if (this->cameraflags() != 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::Int32Size( + this->cameraflags()); + } + + // int32 startPixelIndex = 5; + if (this->startpixelindex() != 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::Int32Size( + this->startpixelindex()); + } + + // int32 pixelWidth = 6; + if (this->pixelwidth() != 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::Int32Size( + this->pixelwidth()); + } + + // double lightDistance = 10; + if (this->lightdistance() != 0) { + total_size += 1 + 8; + } + + // int32 pixelHeight = 7; + if (this->pixelheight() != 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::Int32Size( + this->pixelheight()); + } + + // int32 hasShadow = 14; + if (this->hasshadow() != 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::Int32Size( + this->hasshadow()); + } + + // double lightAmbientCoeff = 11; + if (this->lightambientcoeff() != 0) { + total_size += 1 + 8; + } + + // double lightDiffuseCoeff = 12; + if (this->lightdiffusecoeff() != 0) { + total_size += 1 + 8; + } + + // double lightSpecularCoeff = 13; + if (this->lightspecularcoeff() != 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 RequestCameraImageCommand::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:pybullet_grpc.RequestCameraImageCommand) + GOOGLE_DCHECK_NE(&from, this); + const RequestCameraImageCommand* source = + ::google::protobuf::internal::DynamicCastToGenerated( + &from); + if (source == NULL) { + // @@protoc_insertion_point(generalized_merge_from_cast_fail:pybullet_grpc.RequestCameraImageCommand) + ::google::protobuf::internal::ReflectionOps::Merge(from, this); + } else { + // @@protoc_insertion_point(generalized_merge_from_cast_success:pybullet_grpc.RequestCameraImageCommand) + MergeFrom(*source); + } +} + +void RequestCameraImageCommand::MergeFrom(const RequestCameraImageCommand& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:pybullet_grpc.RequestCameraImageCommand) + GOOGLE_DCHECK_NE(&from, this); + _internal_metadata_.MergeFrom(from._internal_metadata_); + if (from.has_viewmatrix()) { + mutable_viewmatrix()->::pybullet_grpc::matrix4x4::MergeFrom(from.viewmatrix()); + } + if (from.has_projectionmatrix()) { + mutable_projectionmatrix()->::pybullet_grpc::matrix4x4::MergeFrom(from.projectionmatrix()); + } + if (from.has_lightdirection()) { + mutable_lightdirection()->::pybullet_grpc::vec3::MergeFrom(from.lightdirection()); + } + if (from.has_lightcolor()) { + mutable_lightcolor()->::pybullet_grpc::vec3::MergeFrom(from.lightcolor()); + } + if (from.has_projectivetextureviewmatrix()) { + mutable_projectivetextureviewmatrix()->::pybullet_grpc::matrix4x4::MergeFrom(from.projectivetextureviewmatrix()); + } + if (from.has_projectivetextureprojectionmatrix()) { + mutable_projectivetextureprojectionmatrix()->::pybullet_grpc::matrix4x4::MergeFrom(from.projectivetextureprojectionmatrix()); + } + if (from.updateflags() != 0) { + set_updateflags(from.updateflags()); + } + if (from.cameraflags() != 0) { + set_cameraflags(from.cameraflags()); + } + if (from.startpixelindex() != 0) { + set_startpixelindex(from.startpixelindex()); + } + if (from.pixelwidth() != 0) { + set_pixelwidth(from.pixelwidth()); + } + if (from.lightdistance() != 0) { + set_lightdistance(from.lightdistance()); + } + if (from.pixelheight() != 0) { + set_pixelheight(from.pixelheight()); + } + if (from.hasshadow() != 0) { + set_hasshadow(from.hasshadow()); + } + if (from.lightambientcoeff() != 0) { + set_lightambientcoeff(from.lightambientcoeff()); + } + if (from.lightdiffusecoeff() != 0) { + set_lightdiffusecoeff(from.lightdiffusecoeff()); + } + if (from.lightspecularcoeff() != 0) { + set_lightspecularcoeff(from.lightspecularcoeff()); + } +} + +void RequestCameraImageCommand::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:pybullet_grpc.RequestCameraImageCommand) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +void RequestCameraImageCommand::CopyFrom(const RequestCameraImageCommand& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:pybullet_grpc.RequestCameraImageCommand) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool RequestCameraImageCommand::IsInitialized() const { + return true; +} + +void RequestCameraImageCommand::Swap(RequestCameraImageCommand* other) { + if (other == this) return; + InternalSwap(other); +} +void RequestCameraImageCommand::InternalSwap(RequestCameraImageCommand* other) { + std::swap(viewmatrix_, other->viewmatrix_); + std::swap(projectionmatrix_, other->projectionmatrix_); + std::swap(lightdirection_, other->lightdirection_); + std::swap(lightcolor_, other->lightcolor_); + std::swap(projectivetextureviewmatrix_, other->projectivetextureviewmatrix_); + std::swap(projectivetextureprojectionmatrix_, other->projectivetextureprojectionmatrix_); + std::swap(updateflags_, other->updateflags_); + std::swap(cameraflags_, other->cameraflags_); + std::swap(startpixelindex_, other->startpixelindex_); + std::swap(pixelwidth_, other->pixelwidth_); + std::swap(lightdistance_, other->lightdistance_); + std::swap(pixelheight_, other->pixelheight_); + std::swap(hasshadow_, other->hasshadow_); + std::swap(lightambientcoeff_, other->lightambientcoeff_); + std::swap(lightdiffusecoeff_, other->lightdiffusecoeff_); + std::swap(lightspecularcoeff_, other->lightspecularcoeff_); + std::swap(_cached_size_, other->_cached_size_); +} + +::google::protobuf::Metadata RequestCameraImageCommand::GetMetadata() const { + protobuf_pybullet_2eproto::protobuf_AssignDescriptorsOnce(); + return protobuf_pybullet_2eproto::file_level_metadata[35]; +} + +#if PROTOBUF_INLINE_NOT_IN_HEADERS +// RequestCameraImageCommand + +// int32 updateFlags = 1; +void RequestCameraImageCommand::clear_updateflags() { + updateflags_ = 0; +} +::google::protobuf::int32 RequestCameraImageCommand::updateflags() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.RequestCameraImageCommand.updateFlags) + return updateflags_; +} +void RequestCameraImageCommand::set_updateflags(::google::protobuf::int32 value) { + + updateflags_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.RequestCameraImageCommand.updateFlags) +} + +// int32 cameraFlags = 2; +void RequestCameraImageCommand::clear_cameraflags() { + cameraflags_ = 0; +} +::google::protobuf::int32 RequestCameraImageCommand::cameraflags() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.RequestCameraImageCommand.cameraFlags) + return cameraflags_; +} +void RequestCameraImageCommand::set_cameraflags(::google::protobuf::int32 value) { + + cameraflags_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.RequestCameraImageCommand.cameraFlags) +} + +// .pybullet_grpc.matrix4x4 viewMatrix = 3; +bool RequestCameraImageCommand::has_viewmatrix() const { + return this != internal_default_instance() && viewmatrix_ != NULL; +} +void RequestCameraImageCommand::clear_viewmatrix() { + if (GetArenaNoVirtual() == NULL && viewmatrix_ != NULL) delete viewmatrix_; + viewmatrix_ = NULL; +} +const ::pybullet_grpc::matrix4x4& RequestCameraImageCommand::viewmatrix() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.RequestCameraImageCommand.viewMatrix) + return viewmatrix_ != NULL ? *viewmatrix_ + : *::pybullet_grpc::matrix4x4::internal_default_instance(); +} +::pybullet_grpc::matrix4x4* RequestCameraImageCommand::mutable_viewmatrix() { + + if (viewmatrix_ == NULL) { + viewmatrix_ = new ::pybullet_grpc::matrix4x4; + } + // @@protoc_insertion_point(field_mutable:pybullet_grpc.RequestCameraImageCommand.viewMatrix) + return viewmatrix_; +} +::pybullet_grpc::matrix4x4* RequestCameraImageCommand::release_viewmatrix() { + // @@protoc_insertion_point(field_release:pybullet_grpc.RequestCameraImageCommand.viewMatrix) + + ::pybullet_grpc::matrix4x4* temp = viewmatrix_; + viewmatrix_ = NULL; + return temp; +} +void RequestCameraImageCommand::set_allocated_viewmatrix(::pybullet_grpc::matrix4x4* viewmatrix) { + delete viewmatrix_; + viewmatrix_ = viewmatrix; + if (viewmatrix) { + + } else { + + } + // @@protoc_insertion_point(field_set_allocated:pybullet_grpc.RequestCameraImageCommand.viewMatrix) +} + +// .pybullet_grpc.matrix4x4 projectionMatrix = 4; +bool RequestCameraImageCommand::has_projectionmatrix() const { + return this != internal_default_instance() && projectionmatrix_ != NULL; +} +void RequestCameraImageCommand::clear_projectionmatrix() { + if (GetArenaNoVirtual() == NULL && projectionmatrix_ != NULL) delete projectionmatrix_; + projectionmatrix_ = NULL; +} +const ::pybullet_grpc::matrix4x4& RequestCameraImageCommand::projectionmatrix() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.RequestCameraImageCommand.projectionMatrix) + return projectionmatrix_ != NULL ? *projectionmatrix_ + : *::pybullet_grpc::matrix4x4::internal_default_instance(); +} +::pybullet_grpc::matrix4x4* RequestCameraImageCommand::mutable_projectionmatrix() { + + if (projectionmatrix_ == NULL) { + projectionmatrix_ = new ::pybullet_grpc::matrix4x4; + } + // @@protoc_insertion_point(field_mutable:pybullet_grpc.RequestCameraImageCommand.projectionMatrix) + return projectionmatrix_; +} +::pybullet_grpc::matrix4x4* RequestCameraImageCommand::release_projectionmatrix() { + // @@protoc_insertion_point(field_release:pybullet_grpc.RequestCameraImageCommand.projectionMatrix) + + ::pybullet_grpc::matrix4x4* temp = projectionmatrix_; + projectionmatrix_ = NULL; + return temp; +} +void RequestCameraImageCommand::set_allocated_projectionmatrix(::pybullet_grpc::matrix4x4* projectionmatrix) { + delete projectionmatrix_; + projectionmatrix_ = projectionmatrix; + if (projectionmatrix) { + + } else { + + } + // @@protoc_insertion_point(field_set_allocated:pybullet_grpc.RequestCameraImageCommand.projectionMatrix) +} + +// int32 startPixelIndex = 5; +void RequestCameraImageCommand::clear_startpixelindex() { + startpixelindex_ = 0; +} +::google::protobuf::int32 RequestCameraImageCommand::startpixelindex() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.RequestCameraImageCommand.startPixelIndex) + return startpixelindex_; +} +void RequestCameraImageCommand::set_startpixelindex(::google::protobuf::int32 value) { + + startpixelindex_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.RequestCameraImageCommand.startPixelIndex) +} + +// int32 pixelWidth = 6; +void RequestCameraImageCommand::clear_pixelwidth() { + pixelwidth_ = 0; +} +::google::protobuf::int32 RequestCameraImageCommand::pixelwidth() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.RequestCameraImageCommand.pixelWidth) + return pixelwidth_; +} +void RequestCameraImageCommand::set_pixelwidth(::google::protobuf::int32 value) { + + pixelwidth_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.RequestCameraImageCommand.pixelWidth) +} + +// int32 pixelHeight = 7; +void RequestCameraImageCommand::clear_pixelheight() { + pixelheight_ = 0; +} +::google::protobuf::int32 RequestCameraImageCommand::pixelheight() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.RequestCameraImageCommand.pixelHeight) + return pixelheight_; +} +void RequestCameraImageCommand::set_pixelheight(::google::protobuf::int32 value) { + + pixelheight_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.RequestCameraImageCommand.pixelHeight) +} + +// .pybullet_grpc.vec3 lightDirection = 8; +bool RequestCameraImageCommand::has_lightdirection() const { + return this != internal_default_instance() && lightdirection_ != NULL; +} +void RequestCameraImageCommand::clear_lightdirection() { + if (GetArenaNoVirtual() == NULL && lightdirection_ != NULL) delete lightdirection_; + lightdirection_ = NULL; +} +const ::pybullet_grpc::vec3& RequestCameraImageCommand::lightdirection() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.RequestCameraImageCommand.lightDirection) + return lightdirection_ != NULL ? *lightdirection_ + : *::pybullet_grpc::vec3::internal_default_instance(); +} +::pybullet_grpc::vec3* RequestCameraImageCommand::mutable_lightdirection() { + + if (lightdirection_ == NULL) { + lightdirection_ = new ::pybullet_grpc::vec3; + } + // @@protoc_insertion_point(field_mutable:pybullet_grpc.RequestCameraImageCommand.lightDirection) + return lightdirection_; +} +::pybullet_grpc::vec3* RequestCameraImageCommand::release_lightdirection() { + // @@protoc_insertion_point(field_release:pybullet_grpc.RequestCameraImageCommand.lightDirection) + + ::pybullet_grpc::vec3* temp = lightdirection_; + lightdirection_ = NULL; + return temp; +} +void RequestCameraImageCommand::set_allocated_lightdirection(::pybullet_grpc::vec3* lightdirection) { + delete lightdirection_; + lightdirection_ = lightdirection; + if (lightdirection) { + + } else { + + } + // @@protoc_insertion_point(field_set_allocated:pybullet_grpc.RequestCameraImageCommand.lightDirection) +} + +// .pybullet_grpc.vec3 lightColor = 9; +bool RequestCameraImageCommand::has_lightcolor() const { + return this != internal_default_instance() && lightcolor_ != NULL; +} +void RequestCameraImageCommand::clear_lightcolor() { + if (GetArenaNoVirtual() == NULL && lightcolor_ != NULL) delete lightcolor_; + lightcolor_ = NULL; +} +const ::pybullet_grpc::vec3& RequestCameraImageCommand::lightcolor() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.RequestCameraImageCommand.lightColor) + return lightcolor_ != NULL ? *lightcolor_ + : *::pybullet_grpc::vec3::internal_default_instance(); +} +::pybullet_grpc::vec3* RequestCameraImageCommand::mutable_lightcolor() { + + if (lightcolor_ == NULL) { + lightcolor_ = new ::pybullet_grpc::vec3; + } + // @@protoc_insertion_point(field_mutable:pybullet_grpc.RequestCameraImageCommand.lightColor) + return lightcolor_; +} +::pybullet_grpc::vec3* RequestCameraImageCommand::release_lightcolor() { + // @@protoc_insertion_point(field_release:pybullet_grpc.RequestCameraImageCommand.lightColor) + + ::pybullet_grpc::vec3* temp = lightcolor_; + lightcolor_ = NULL; + return temp; +} +void RequestCameraImageCommand::set_allocated_lightcolor(::pybullet_grpc::vec3* lightcolor) { + delete lightcolor_; + lightcolor_ = lightcolor; + if (lightcolor) { + + } else { + + } + // @@protoc_insertion_point(field_set_allocated:pybullet_grpc.RequestCameraImageCommand.lightColor) +} + +// double lightDistance = 10; +void RequestCameraImageCommand::clear_lightdistance() { + lightdistance_ = 0; +} +double RequestCameraImageCommand::lightdistance() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.RequestCameraImageCommand.lightDistance) + return lightdistance_; +} +void RequestCameraImageCommand::set_lightdistance(double value) { + + lightdistance_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.RequestCameraImageCommand.lightDistance) +} + +// double lightAmbientCoeff = 11; +void RequestCameraImageCommand::clear_lightambientcoeff() { + lightambientcoeff_ = 0; +} +double RequestCameraImageCommand::lightambientcoeff() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.RequestCameraImageCommand.lightAmbientCoeff) + return lightambientcoeff_; +} +void RequestCameraImageCommand::set_lightambientcoeff(double value) { + + lightambientcoeff_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.RequestCameraImageCommand.lightAmbientCoeff) +} + +// double lightDiffuseCoeff = 12; +void RequestCameraImageCommand::clear_lightdiffusecoeff() { + lightdiffusecoeff_ = 0; +} +double RequestCameraImageCommand::lightdiffusecoeff() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.RequestCameraImageCommand.lightDiffuseCoeff) + return lightdiffusecoeff_; +} +void RequestCameraImageCommand::set_lightdiffusecoeff(double value) { + + lightdiffusecoeff_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.RequestCameraImageCommand.lightDiffuseCoeff) +} + +// double lightSpecularCoeff = 13; +void RequestCameraImageCommand::clear_lightspecularcoeff() { + lightspecularcoeff_ = 0; +} +double RequestCameraImageCommand::lightspecularcoeff() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.RequestCameraImageCommand.lightSpecularCoeff) + return lightspecularcoeff_; +} +void RequestCameraImageCommand::set_lightspecularcoeff(double value) { + + lightspecularcoeff_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.RequestCameraImageCommand.lightSpecularCoeff) +} + +// int32 hasShadow = 14; +void RequestCameraImageCommand::clear_hasshadow() { + hasshadow_ = 0; +} +::google::protobuf::int32 RequestCameraImageCommand::hasshadow() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.RequestCameraImageCommand.hasShadow) + return hasshadow_; +} +void RequestCameraImageCommand::set_hasshadow(::google::protobuf::int32 value) { + + hasshadow_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.RequestCameraImageCommand.hasShadow) +} + +// .pybullet_grpc.matrix4x4 projectiveTextureViewMatrix = 15; +bool RequestCameraImageCommand::has_projectivetextureviewmatrix() const { + return this != internal_default_instance() && projectivetextureviewmatrix_ != NULL; +} +void RequestCameraImageCommand::clear_projectivetextureviewmatrix() { + if (GetArenaNoVirtual() == NULL && projectivetextureviewmatrix_ != NULL) delete projectivetextureviewmatrix_; + projectivetextureviewmatrix_ = NULL; +} +const ::pybullet_grpc::matrix4x4& RequestCameraImageCommand::projectivetextureviewmatrix() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.RequestCameraImageCommand.projectiveTextureViewMatrix) + return projectivetextureviewmatrix_ != NULL ? *projectivetextureviewmatrix_ + : *::pybullet_grpc::matrix4x4::internal_default_instance(); +} +::pybullet_grpc::matrix4x4* RequestCameraImageCommand::mutable_projectivetextureviewmatrix() { + + if (projectivetextureviewmatrix_ == NULL) { + projectivetextureviewmatrix_ = new ::pybullet_grpc::matrix4x4; + } + // @@protoc_insertion_point(field_mutable:pybullet_grpc.RequestCameraImageCommand.projectiveTextureViewMatrix) + return projectivetextureviewmatrix_; +} +::pybullet_grpc::matrix4x4* RequestCameraImageCommand::release_projectivetextureviewmatrix() { + // @@protoc_insertion_point(field_release:pybullet_grpc.RequestCameraImageCommand.projectiveTextureViewMatrix) + + ::pybullet_grpc::matrix4x4* temp = projectivetextureviewmatrix_; + projectivetextureviewmatrix_ = NULL; + return temp; +} +void RequestCameraImageCommand::set_allocated_projectivetextureviewmatrix(::pybullet_grpc::matrix4x4* projectivetextureviewmatrix) { + delete projectivetextureviewmatrix_; + projectivetextureviewmatrix_ = projectivetextureviewmatrix; + if (projectivetextureviewmatrix) { + + } else { + + } + // @@protoc_insertion_point(field_set_allocated:pybullet_grpc.RequestCameraImageCommand.projectiveTextureViewMatrix) +} + +// .pybullet_grpc.matrix4x4 projectiveTextureProjectionMatrix = 16; +bool RequestCameraImageCommand::has_projectivetextureprojectionmatrix() const { + return this != internal_default_instance() && projectivetextureprojectionmatrix_ != NULL; +} +void RequestCameraImageCommand::clear_projectivetextureprojectionmatrix() { + if (GetArenaNoVirtual() == NULL && projectivetextureprojectionmatrix_ != NULL) delete projectivetextureprojectionmatrix_; + projectivetextureprojectionmatrix_ = NULL; +} +const ::pybullet_grpc::matrix4x4& RequestCameraImageCommand::projectivetextureprojectionmatrix() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.RequestCameraImageCommand.projectiveTextureProjectionMatrix) + return projectivetextureprojectionmatrix_ != NULL ? *projectivetextureprojectionmatrix_ + : *::pybullet_grpc::matrix4x4::internal_default_instance(); +} +::pybullet_grpc::matrix4x4* RequestCameraImageCommand::mutable_projectivetextureprojectionmatrix() { + + if (projectivetextureprojectionmatrix_ == NULL) { + projectivetextureprojectionmatrix_ = new ::pybullet_grpc::matrix4x4; + } + // @@protoc_insertion_point(field_mutable:pybullet_grpc.RequestCameraImageCommand.projectiveTextureProjectionMatrix) + return projectivetextureprojectionmatrix_; +} +::pybullet_grpc::matrix4x4* RequestCameraImageCommand::release_projectivetextureprojectionmatrix() { + // @@protoc_insertion_point(field_release:pybullet_grpc.RequestCameraImageCommand.projectiveTextureProjectionMatrix) + + ::pybullet_grpc::matrix4x4* temp = projectivetextureprojectionmatrix_; + projectivetextureprojectionmatrix_ = NULL; + return temp; +} +void RequestCameraImageCommand::set_allocated_projectivetextureprojectionmatrix(::pybullet_grpc::matrix4x4* projectivetextureprojectionmatrix) { + delete projectivetextureprojectionmatrix_; + projectivetextureprojectionmatrix_ = projectivetextureprojectionmatrix; + if (projectivetextureprojectionmatrix) { + + } else { + + } + // @@protoc_insertion_point(field_set_allocated:pybullet_grpc.RequestCameraImageCommand.projectiveTextureProjectionMatrix) +} + +#endif // PROTOBUF_INLINE_NOT_IN_HEADERS + +// =================================================================== + +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const int RequestCameraImageStatus::kImageWidthFieldNumber; +const int RequestCameraImageStatus::kImageHeightFieldNumber; +const int RequestCameraImageStatus::kStartingPixelIndexFieldNumber; +const int RequestCameraImageStatus::kNumPixelsCopiedFieldNumber; +const int RequestCameraImageStatus::kNumRemainingPixelsFieldNumber; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 + +RequestCameraImageStatus::RequestCameraImageStatus() + : ::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.RequestCameraImageStatus) +} +RequestCameraImageStatus::RequestCameraImageStatus(const RequestCameraImageStatus& from) + : ::google::protobuf::Message(), + _internal_metadata_(NULL), + _cached_size_(0) { + _internal_metadata_.MergeFrom(from._internal_metadata_); + ::memcpy(&imagewidth_, &from.imagewidth_, + reinterpret_cast(&numremainingpixels_) - + reinterpret_cast(&imagewidth_) + sizeof(numremainingpixels_)); + // @@protoc_insertion_point(copy_constructor:pybullet_grpc.RequestCameraImageStatus) +} + +void RequestCameraImageStatus::SharedCtor() { + ::memset(&imagewidth_, 0, reinterpret_cast(&numremainingpixels_) - + reinterpret_cast(&imagewidth_) + sizeof(numremainingpixels_)); + _cached_size_ = 0; +} + +RequestCameraImageStatus::~RequestCameraImageStatus() { + // @@protoc_insertion_point(destructor:pybullet_grpc.RequestCameraImageStatus) + SharedDtor(); +} + +void RequestCameraImageStatus::SharedDtor() { +} + +void RequestCameraImageStatus::SetCachedSize(int size) const { + GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN(); + _cached_size_ = size; + GOOGLE_SAFE_CONCURRENT_WRITES_END(); +} +const ::google::protobuf::Descriptor* RequestCameraImageStatus::descriptor() { + protobuf_pybullet_2eproto::protobuf_AssignDescriptorsOnce(); + return protobuf_pybullet_2eproto::file_level_metadata[36].descriptor; +} + +const RequestCameraImageStatus& RequestCameraImageStatus::default_instance() { + protobuf_pybullet_2eproto::InitDefaults(); + return *internal_default_instance(); +} + +RequestCameraImageStatus* RequestCameraImageStatus::New(::google::protobuf::Arena* arena) const { + RequestCameraImageStatus* n = new RequestCameraImageStatus; + if (arena != NULL) { + arena->Own(n); + } + return n; +} + +void RequestCameraImageStatus::Clear() { +// @@protoc_insertion_point(message_clear_start:pybullet_grpc.RequestCameraImageStatus) + ::memset(&imagewidth_, 0, reinterpret_cast(&numremainingpixels_) - + reinterpret_cast(&imagewidth_) + sizeof(numremainingpixels_)); +} + +bool RequestCameraImageStatus::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.RequestCameraImageStatus) + 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 imageWidth = 1; + case 1: { + if (tag == 8u) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>( + input, &imagewidth_))); + } else { + goto handle_unusual; + } + break; + } + + // int32 imageHeight = 2; + case 2: { + if (tag == 16u) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>( + input, &imageheight_))); + } else { + goto handle_unusual; + } + break; + } + + // int32 startingPixelIndex = 3; + case 3: { + if (tag == 24u) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>( + input, &startingpixelindex_))); + } else { + goto handle_unusual; + } + break; + } + + // int32 numPixelsCopied = 4; + case 4: { + if (tag == 32u) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>( + input, &numpixelscopied_))); + } else { + goto handle_unusual; + } + break; + } + + // int32 numRemainingPixels = 5; + case 5: { + if (tag == 40u) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>( + input, &numremainingpixels_))); + } 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.RequestCameraImageStatus) + return true; +failure: + // @@protoc_insertion_point(parse_failure:pybullet_grpc.RequestCameraImageStatus) + return false; +#undef DO_ +} + +void RequestCameraImageStatus::SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const { + // @@protoc_insertion_point(serialize_start:pybullet_grpc.RequestCameraImageStatus) + // int32 imageWidth = 1; + if (this->imagewidth() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteInt32(1, this->imagewidth(), output); + } + + // int32 imageHeight = 2; + if (this->imageheight() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteInt32(2, this->imageheight(), output); + } + + // int32 startingPixelIndex = 3; + if (this->startingpixelindex() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteInt32(3, this->startingpixelindex(), output); + } + + // int32 numPixelsCopied = 4; + if (this->numpixelscopied() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteInt32(4, this->numpixelscopied(), output); + } + + // int32 numRemainingPixels = 5; + if (this->numremainingpixels() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteInt32(5, this->numremainingpixels(), output); + } + + // @@protoc_insertion_point(serialize_end:pybullet_grpc.RequestCameraImageStatus) +} + +::google::protobuf::uint8* RequestCameraImageStatus::InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const { + (void)deterministic; // Unused + // @@protoc_insertion_point(serialize_to_array_start:pybullet_grpc.RequestCameraImageStatus) + // int32 imageWidth = 1; + if (this->imagewidth() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteInt32ToArray(1, this->imagewidth(), target); + } + + // int32 imageHeight = 2; + if (this->imageheight() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteInt32ToArray(2, this->imageheight(), target); + } + + // int32 startingPixelIndex = 3; + if (this->startingpixelindex() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteInt32ToArray(3, this->startingpixelindex(), target); + } + + // int32 numPixelsCopied = 4; + if (this->numpixelscopied() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteInt32ToArray(4, this->numpixelscopied(), target); + } + + // int32 numRemainingPixels = 5; + if (this->numremainingpixels() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteInt32ToArray(5, this->numremainingpixels(), target); + } + + // @@protoc_insertion_point(serialize_to_array_end:pybullet_grpc.RequestCameraImageStatus) + return target; +} + +size_t RequestCameraImageStatus::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:pybullet_grpc.RequestCameraImageStatus) + size_t total_size = 0; + + // int32 imageWidth = 1; + if (this->imagewidth() != 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::Int32Size( + this->imagewidth()); + } + + // int32 imageHeight = 2; + if (this->imageheight() != 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::Int32Size( + this->imageheight()); + } + + // int32 startingPixelIndex = 3; + if (this->startingpixelindex() != 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::Int32Size( + this->startingpixelindex()); + } + + // int32 numPixelsCopied = 4; + if (this->numpixelscopied() != 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::Int32Size( + this->numpixelscopied()); + } + + // int32 numRemainingPixels = 5; + if (this->numremainingpixels() != 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::Int32Size( + this->numremainingpixels()); + } + + 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 RequestCameraImageStatus::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:pybullet_grpc.RequestCameraImageStatus) + GOOGLE_DCHECK_NE(&from, this); + const RequestCameraImageStatus* source = + ::google::protobuf::internal::DynamicCastToGenerated( + &from); + if (source == NULL) { + // @@protoc_insertion_point(generalized_merge_from_cast_fail:pybullet_grpc.RequestCameraImageStatus) + ::google::protobuf::internal::ReflectionOps::Merge(from, this); + } else { + // @@protoc_insertion_point(generalized_merge_from_cast_success:pybullet_grpc.RequestCameraImageStatus) + MergeFrom(*source); + } +} + +void RequestCameraImageStatus::MergeFrom(const RequestCameraImageStatus& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:pybullet_grpc.RequestCameraImageStatus) + GOOGLE_DCHECK_NE(&from, this); + _internal_metadata_.MergeFrom(from._internal_metadata_); + if (from.imagewidth() != 0) { + set_imagewidth(from.imagewidth()); + } + if (from.imageheight() != 0) { + set_imageheight(from.imageheight()); + } + if (from.startingpixelindex() != 0) { + set_startingpixelindex(from.startingpixelindex()); + } + if (from.numpixelscopied() != 0) { + set_numpixelscopied(from.numpixelscopied()); + } + if (from.numremainingpixels() != 0) { + set_numremainingpixels(from.numremainingpixels()); + } +} + +void RequestCameraImageStatus::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:pybullet_grpc.RequestCameraImageStatus) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +void RequestCameraImageStatus::CopyFrom(const RequestCameraImageStatus& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:pybullet_grpc.RequestCameraImageStatus) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool RequestCameraImageStatus::IsInitialized() const { + return true; +} + +void RequestCameraImageStatus::Swap(RequestCameraImageStatus* other) { + if (other == this) return; + InternalSwap(other); +} +void RequestCameraImageStatus::InternalSwap(RequestCameraImageStatus* other) { + std::swap(imagewidth_, other->imagewidth_); + std::swap(imageheight_, other->imageheight_); + std::swap(startingpixelindex_, other->startingpixelindex_); + std::swap(numpixelscopied_, other->numpixelscopied_); + std::swap(numremainingpixels_, other->numremainingpixels_); + std::swap(_cached_size_, other->_cached_size_); +} + +::google::protobuf::Metadata RequestCameraImageStatus::GetMetadata() const { + protobuf_pybullet_2eproto::protobuf_AssignDescriptorsOnce(); + return protobuf_pybullet_2eproto::file_level_metadata[36]; +} + +#if PROTOBUF_INLINE_NOT_IN_HEADERS +// RequestCameraImageStatus + +// int32 imageWidth = 1; +void RequestCameraImageStatus::clear_imagewidth() { + imagewidth_ = 0; +} +::google::protobuf::int32 RequestCameraImageStatus::imagewidth() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.RequestCameraImageStatus.imageWidth) + return imagewidth_; +} +void RequestCameraImageStatus::set_imagewidth(::google::protobuf::int32 value) { + + imagewidth_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.RequestCameraImageStatus.imageWidth) +} + +// int32 imageHeight = 2; +void RequestCameraImageStatus::clear_imageheight() { + imageheight_ = 0; +} +::google::protobuf::int32 RequestCameraImageStatus::imageheight() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.RequestCameraImageStatus.imageHeight) + return imageheight_; +} +void RequestCameraImageStatus::set_imageheight(::google::protobuf::int32 value) { + + imageheight_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.RequestCameraImageStatus.imageHeight) +} + +// int32 startingPixelIndex = 3; +void RequestCameraImageStatus::clear_startingpixelindex() { + startingpixelindex_ = 0; +} +::google::protobuf::int32 RequestCameraImageStatus::startingpixelindex() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.RequestCameraImageStatus.startingPixelIndex) + return startingpixelindex_; +} +void RequestCameraImageStatus::set_startingpixelindex(::google::protobuf::int32 value) { + + startingpixelindex_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.RequestCameraImageStatus.startingPixelIndex) +} + +// int32 numPixelsCopied = 4; +void RequestCameraImageStatus::clear_numpixelscopied() { + numpixelscopied_ = 0; +} +::google::protobuf::int32 RequestCameraImageStatus::numpixelscopied() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.RequestCameraImageStatus.numPixelsCopied) + return numpixelscopied_; +} +void RequestCameraImageStatus::set_numpixelscopied(::google::protobuf::int32 value) { + + numpixelscopied_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.RequestCameraImageStatus.numPixelsCopied) +} + +// int32 numRemainingPixels = 5; +void RequestCameraImageStatus::clear_numremainingpixels() { + numremainingpixels_ = 0; +} +::google::protobuf::int32 RequestCameraImageStatus::numremainingpixels() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.RequestCameraImageStatus.numRemainingPixels) + return numremainingpixels_; +} +void RequestCameraImageStatus::set_numremainingpixels(::google::protobuf::int32 value) { + + numremainingpixels_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.RequestCameraImageStatus.numRemainingPixels) +} + +#endif // PROTOBUF_INLINE_NOT_IN_HEADERS + +// =================================================================== + #if !defined(_MSC_VER) || _MSC_VER >= 1900 const int PyBulletCommand::kCommandTypeFieldNumber; +const int PyBulletCommand::kBinaryBlobFieldNumber; +const int PyBulletCommand::kUnknownCommandBinaryBlobFieldNumber; const int PyBulletCommand::kLoadUrdfCommandFieldNumber; const int PyBulletCommand::kTerminateServerCommandFieldNumber; const int PyBulletCommand::kStepSimulationCommandFieldNumber; @@ -9219,6 +19839,15 @@ const int PyBulletCommand::kChangeDynamicsCommandFieldNumber; const int PyBulletCommand::kGetDynamicsCommandFieldNumber; const int PyBulletCommand::kInitPoseCommandFieldNumber; const int PyBulletCommand::kRequestActualStateCommandFieldNumber; +const int PyBulletCommand::kConfigureOpenGLVisualizerCommandFieldNumber; +const int PyBulletCommand::kSyncBodiesCommandFieldNumber; +const int PyBulletCommand::kRequestBodyInfoCommandFieldNumber; +const int PyBulletCommand::kSetPhysicsSimulationParametersCommandFieldNumber; +const int PyBulletCommand::kJointMotorControlCommandFieldNumber; +const int PyBulletCommand::kUserConstraintCommandFieldNumber; +const int PyBulletCommand::kCheckVersionCommandFieldNumber; +const int PyBulletCommand::kRequestKeyboardEventsCommandFieldNumber; +const int PyBulletCommand::kRequestCameraImageCommandFieldNumber; #endif // !defined(_MSC_VER) || _MSC_VER >= 1900 PyBulletCommand::PyBulletCommand() @@ -9232,6 +19861,8 @@ PyBulletCommand::PyBulletCommand() PyBulletCommand::PyBulletCommand(const PyBulletCommand& from) : ::google::protobuf::Message(), _internal_metadata_(NULL), + binaryblob_(from.binaryblob_), + unknowncommandbinaryblob_(from.unknowncommandbinaryblob_), _cached_size_(0) { _internal_metadata_.MergeFrom(from._internal_metadata_); commandtype_ = from.commandtype_; @@ -9273,6 +19904,42 @@ PyBulletCommand::PyBulletCommand(const PyBulletCommand& from) mutable_requestactualstatecommand()->::pybullet_grpc::RequestActualStateCommand::MergeFrom(from.requestactualstatecommand()); break; } + case kConfigureOpenGLVisualizerCommand: { + mutable_configureopenglvisualizercommand()->::pybullet_grpc::ConfigureOpenGLVisualizerCommand::MergeFrom(from.configureopenglvisualizercommand()); + break; + } + case kSyncBodiesCommand: { + mutable_syncbodiescommand()->::pybullet_grpc::SyncBodiesCommand::MergeFrom(from.syncbodiescommand()); + break; + } + case kRequestBodyInfoCommand: { + mutable_requestbodyinfocommand()->::pybullet_grpc::RequestBodyInfoCommand::MergeFrom(from.requestbodyinfocommand()); + break; + } + case kSetPhysicsSimulationParametersCommand: { + mutable_setphysicssimulationparameterscommand()->::pybullet_grpc::PhysicsSimulationParametersCommand::MergeFrom(from.setphysicssimulationparameterscommand()); + break; + } + case kJointMotorControlCommand: { + mutable_jointmotorcontrolcommand()->::pybullet_grpc::JointMotorControlCommand::MergeFrom(from.jointmotorcontrolcommand()); + break; + } + case kUserConstraintCommand: { + mutable_userconstraintcommand()->::pybullet_grpc::UserConstraintCommand::MergeFrom(from.userconstraintcommand()); + break; + } + case kCheckVersionCommand: { + mutable_checkversioncommand()->::pybullet_grpc::CheckVersionCommand::MergeFrom(from.checkversioncommand()); + break; + } + case kRequestKeyboardEventsCommand: { + mutable_requestkeyboardeventscommand()->::pybullet_grpc::RequestKeyboardEventsCommand::MergeFrom(from.requestkeyboardeventscommand()); + break; + } + case kRequestCameraImageCommand: { + mutable_requestcameraimagecommand()->::pybullet_grpc::RequestCameraImageCommand::MergeFrom(from.requestcameraimagecommand()); + break; + } case COMMANDS_NOT_SET: { break; } @@ -9304,7 +19971,7 @@ void PyBulletCommand::SetCachedSize(int size) const { } const ::google::protobuf::Descriptor* PyBulletCommand::descriptor() { protobuf_pybullet_2eproto::protobuf_AssignDescriptorsOnce(); - return protobuf_pybullet_2eproto::file_level_metadata[16].descriptor; + return protobuf_pybullet_2eproto::file_level_metadata[37].descriptor; } const PyBulletCommand& PyBulletCommand::default_instance() { @@ -9359,6 +20026,42 @@ void PyBulletCommand::clear_commands() { delete commands_.requestactualstatecommand_; break; } + case kConfigureOpenGLVisualizerCommand: { + delete commands_.configureopenglvisualizercommand_; + break; + } + case kSyncBodiesCommand: { + delete commands_.syncbodiescommand_; + break; + } + case kRequestBodyInfoCommand: { + delete commands_.requestbodyinfocommand_; + break; + } + case kSetPhysicsSimulationParametersCommand: { + delete commands_.setphysicssimulationparameterscommand_; + break; + } + case kJointMotorControlCommand: { + delete commands_.jointmotorcontrolcommand_; + break; + } + case kUserConstraintCommand: { + delete commands_.userconstraintcommand_; + break; + } + case kCheckVersionCommand: { + delete commands_.checkversioncommand_; + break; + } + case kRequestKeyboardEventsCommand: { + delete commands_.requestkeyboardeventscommand_; + break; + } + case kRequestCameraImageCommand: { + delete commands_.requestcameraimagecommand_; + break; + } case COMMANDS_NOT_SET: { break; } @@ -9369,6 +20072,8 @@ void PyBulletCommand::clear_commands() { void PyBulletCommand::Clear() { // @@protoc_insertion_point(message_clear_start:pybullet_grpc.PyBulletCommand) + binaryblob_.Clear(); + unknowncommandbinaryblob_.Clear(); commandtype_ = 0; clear_commands(); } @@ -9379,7 +20084,7 @@ bool PyBulletCommand::MergePartialFromCodedStream( ::google::protobuf::uint32 tag; // @@protoc_insertion_point(parse_start:pybullet_grpc.PyBulletCommand) for (;;) { - ::std::pair< ::google::protobuf::uint32, bool> p = input->ReadTagWithCutoffNoLastTag(127u); + ::std::pair< ::google::protobuf::uint32, bool> p = input->ReadTagWithCutoffNoLastTag(16383u); tag = p.first; if (!p.second) goto handle_unusual; switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { @@ -9396,9 +20101,31 @@ bool PyBulletCommand::MergePartialFromCodedStream( break; } - // .pybullet_grpc.LoadUrdfCommand loadUrdfCommand = 3; + // repeated bytes binaryBlob = 2; + case 2: { + if (tag == 18u) { + DO_(::google::protobuf::internal::WireFormatLite::ReadBytes( + input, this->add_binaryblob())); + } else { + goto handle_unusual; + } + break; + } + + // repeated bytes unknownCommandBinaryBlob = 3; case 3: { if (tag == 26u) { + DO_(::google::protobuf::internal::WireFormatLite::ReadBytes( + input, this->add_unknowncommandbinaryblob())); + } else { + goto handle_unusual; + } + break; + } + + // .pybullet_grpc.LoadUrdfCommand loadUrdfCommand = 4; + case 4: { + if (tag == 34u) { DO_(::google::protobuf::internal::WireFormatLite::ReadMessageNoVirtual( input, mutable_loadurdfcommand())); } else { @@ -9407,9 +20134,9 @@ bool PyBulletCommand::MergePartialFromCodedStream( break; } - // .pybullet_grpc.TerminateServerCommand terminateServerCommand = 4; - case 4: { - if (tag == 34u) { + // .pybullet_grpc.TerminateServerCommand terminateServerCommand = 5; + case 5: { + if (tag == 42u) { DO_(::google::protobuf::internal::WireFormatLite::ReadMessageNoVirtual( input, mutable_terminateservercommand())); } else { @@ -9418,9 +20145,9 @@ bool PyBulletCommand::MergePartialFromCodedStream( break; } - // .pybullet_grpc.StepSimulationCommand stepSimulationCommand = 5; - case 5: { - if (tag == 42u) { + // .pybullet_grpc.StepSimulationCommand stepSimulationCommand = 6; + case 6: { + if (tag == 50u) { DO_(::google::protobuf::internal::WireFormatLite::ReadMessageNoVirtual( input, mutable_stepsimulationcommand())); } else { @@ -9429,9 +20156,9 @@ bool PyBulletCommand::MergePartialFromCodedStream( break; } - // .pybullet_grpc.LoadSdfCommand loadSdfCommand = 6; - case 6: { - if (tag == 50u) { + // .pybullet_grpc.LoadSdfCommand loadSdfCommand = 7; + case 7: { + if (tag == 58u) { DO_(::google::protobuf::internal::WireFormatLite::ReadMessageNoVirtual( input, mutable_loadsdfcommand())); } else { @@ -9440,9 +20167,9 @@ bool PyBulletCommand::MergePartialFromCodedStream( break; } - // .pybullet_grpc.LoadMjcfCommand loadMjcfCommand = 7; - case 7: { - if (tag == 58u) { + // .pybullet_grpc.LoadMjcfCommand loadMjcfCommand = 8; + case 8: { + if (tag == 66u) { DO_(::google::protobuf::internal::WireFormatLite::ReadMessageNoVirtual( input, mutable_loadmjcfcommand())); } else { @@ -9451,9 +20178,9 @@ bool PyBulletCommand::MergePartialFromCodedStream( break; } - // .pybullet_grpc.ChangeDynamicsCommand changeDynamicsCommand = 8; - case 8: { - if (tag == 66u) { + // .pybullet_grpc.ChangeDynamicsCommand changeDynamicsCommand = 9; + case 9: { + if (tag == 74u) { DO_(::google::protobuf::internal::WireFormatLite::ReadMessageNoVirtual( input, mutable_changedynamicscommand())); } else { @@ -9462,9 +20189,9 @@ bool PyBulletCommand::MergePartialFromCodedStream( break; } - // .pybullet_grpc.GetDynamicsCommand getDynamicsCommand = 9; - case 9: { - if (tag == 74u) { + // .pybullet_grpc.GetDynamicsCommand getDynamicsCommand = 10; + case 10: { + if (tag == 82u) { DO_(::google::protobuf::internal::WireFormatLite::ReadMessageNoVirtual( input, mutable_getdynamicscommand())); } else { @@ -9473,9 +20200,9 @@ bool PyBulletCommand::MergePartialFromCodedStream( break; } - // .pybullet_grpc.InitPoseCommand initPoseCommand = 10; - case 10: { - if (tag == 82u) { + // .pybullet_grpc.InitPoseCommand initPoseCommand = 11; + case 11: { + if (tag == 90u) { DO_(::google::protobuf::internal::WireFormatLite::ReadMessageNoVirtual( input, mutable_initposecommand())); } else { @@ -9484,9 +20211,9 @@ bool PyBulletCommand::MergePartialFromCodedStream( break; } - // .pybullet_grpc.RequestActualStateCommand requestActualStateCommand = 11; - case 11: { - if (tag == 90u) { + // .pybullet_grpc.RequestActualStateCommand requestActualStateCommand = 12; + case 12: { + if (tag == 98u) { DO_(::google::protobuf::internal::WireFormatLite::ReadMessageNoVirtual( input, mutable_requestactualstatecommand())); } else { @@ -9495,6 +20222,105 @@ bool PyBulletCommand::MergePartialFromCodedStream( break; } + // .pybullet_grpc.ConfigureOpenGLVisualizerCommand configureOpenGLVisualizerCommand = 13; + case 13: { + if (tag == 106u) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessageNoVirtual( + input, mutable_configureopenglvisualizercommand())); + } else { + goto handle_unusual; + } + break; + } + + // .pybullet_grpc.SyncBodiesCommand syncBodiesCommand = 14; + case 14: { + if (tag == 114u) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessageNoVirtual( + input, mutable_syncbodiescommand())); + } else { + goto handle_unusual; + } + break; + } + + // .pybullet_grpc.RequestBodyInfoCommand requestBodyInfoCommand = 15; + case 15: { + if (tag == 122u) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessageNoVirtual( + input, mutable_requestbodyinfocommand())); + } else { + goto handle_unusual; + } + break; + } + + // .pybullet_grpc.PhysicsSimulationParametersCommand setPhysicsSimulationParametersCommand = 16; + case 16: { + if (tag == 130u) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessageNoVirtual( + input, mutable_setphysicssimulationparameterscommand())); + } else { + goto handle_unusual; + } + break; + } + + // .pybullet_grpc.JointMotorControlCommand jointMotorControlCommand = 17; + case 17: { + if (tag == 138u) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessageNoVirtual( + input, mutable_jointmotorcontrolcommand())); + } else { + goto handle_unusual; + } + break; + } + + // .pybullet_grpc.UserConstraintCommand userConstraintCommand = 18; + case 18: { + if (tag == 146u) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessageNoVirtual( + input, mutable_userconstraintcommand())); + } else { + goto handle_unusual; + } + break; + } + + // .pybullet_grpc.CheckVersionCommand checkVersionCommand = 19; + case 19: { + if (tag == 154u) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessageNoVirtual( + input, mutable_checkversioncommand())); + } else { + goto handle_unusual; + } + break; + } + + // .pybullet_grpc.RequestKeyboardEventsCommand requestKeyboardEventsCommand = 20; + case 20: { + if (tag == 162u) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessageNoVirtual( + input, mutable_requestkeyboardeventscommand())); + } else { + goto handle_unusual; + } + break; + } + + // .pybullet_grpc.RequestCameraImageCommand requestCameraImageCommand = 21; + case 21: { + if (tag == 170u) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessageNoVirtual( + input, mutable_requestcameraimagecommand())); + } else { + goto handle_unusual; + } + break; + } + default: { handle_unusual: if (tag == 0 || @@ -9524,58 +20350,124 @@ void PyBulletCommand::SerializeWithCachedSizes( ::google::protobuf::internal::WireFormatLite::WriteInt32(1, this->commandtype(), output); } - // .pybullet_grpc.LoadUrdfCommand loadUrdfCommand = 3; + // repeated bytes binaryBlob = 2; + for (int i = 0; i < this->binaryblob_size(); i++) { + ::google::protobuf::internal::WireFormatLite::WriteBytes( + 2, this->binaryblob(i), output); + } + + // repeated bytes unknownCommandBinaryBlob = 3; + for (int i = 0; i < this->unknowncommandbinaryblob_size(); i++) { + ::google::protobuf::internal::WireFormatLite::WriteBytes( + 3, this->unknowncommandbinaryblob(i), output); + } + + // .pybullet_grpc.LoadUrdfCommand loadUrdfCommand = 4; if (has_loadurdfcommand()) { ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( - 3, *commands_.loadurdfcommand_, output); + 4, *commands_.loadurdfcommand_, output); } - // .pybullet_grpc.TerminateServerCommand terminateServerCommand = 4; + // .pybullet_grpc.TerminateServerCommand terminateServerCommand = 5; if (has_terminateservercommand()) { ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( - 4, *commands_.terminateservercommand_, output); + 5, *commands_.terminateservercommand_, output); } - // .pybullet_grpc.StepSimulationCommand stepSimulationCommand = 5; + // .pybullet_grpc.StepSimulationCommand stepSimulationCommand = 6; if (has_stepsimulationcommand()) { ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( - 5, *commands_.stepsimulationcommand_, output); + 6, *commands_.stepsimulationcommand_, output); } - // .pybullet_grpc.LoadSdfCommand loadSdfCommand = 6; + // .pybullet_grpc.LoadSdfCommand loadSdfCommand = 7; if (has_loadsdfcommand()) { ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( - 6, *commands_.loadsdfcommand_, output); + 7, *commands_.loadsdfcommand_, output); } - // .pybullet_grpc.LoadMjcfCommand loadMjcfCommand = 7; + // .pybullet_grpc.LoadMjcfCommand loadMjcfCommand = 8; if (has_loadmjcfcommand()) { ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( - 7, *commands_.loadmjcfcommand_, output); + 8, *commands_.loadmjcfcommand_, output); } - // .pybullet_grpc.ChangeDynamicsCommand changeDynamicsCommand = 8; + // .pybullet_grpc.ChangeDynamicsCommand changeDynamicsCommand = 9; if (has_changedynamicscommand()) { ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( - 8, *commands_.changedynamicscommand_, output); + 9, *commands_.changedynamicscommand_, output); } - // .pybullet_grpc.GetDynamicsCommand getDynamicsCommand = 9; + // .pybullet_grpc.GetDynamicsCommand getDynamicsCommand = 10; if (has_getdynamicscommand()) { ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( - 9, *commands_.getdynamicscommand_, output); + 10, *commands_.getdynamicscommand_, output); } - // .pybullet_grpc.InitPoseCommand initPoseCommand = 10; + // .pybullet_grpc.InitPoseCommand initPoseCommand = 11; if (has_initposecommand()) { ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( - 10, *commands_.initposecommand_, output); + 11, *commands_.initposecommand_, output); } - // .pybullet_grpc.RequestActualStateCommand requestActualStateCommand = 11; + // .pybullet_grpc.RequestActualStateCommand requestActualStateCommand = 12; if (has_requestactualstatecommand()) { ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( - 11, *commands_.requestactualstatecommand_, output); + 12, *commands_.requestactualstatecommand_, output); + } + + // .pybullet_grpc.ConfigureOpenGLVisualizerCommand configureOpenGLVisualizerCommand = 13; + if (has_configureopenglvisualizercommand()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 13, *commands_.configureopenglvisualizercommand_, output); + } + + // .pybullet_grpc.SyncBodiesCommand syncBodiesCommand = 14; + if (has_syncbodiescommand()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 14, *commands_.syncbodiescommand_, output); + } + + // .pybullet_grpc.RequestBodyInfoCommand requestBodyInfoCommand = 15; + if (has_requestbodyinfocommand()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 15, *commands_.requestbodyinfocommand_, output); + } + + // .pybullet_grpc.PhysicsSimulationParametersCommand setPhysicsSimulationParametersCommand = 16; + if (has_setphysicssimulationparameterscommand()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 16, *commands_.setphysicssimulationparameterscommand_, output); + } + + // .pybullet_grpc.JointMotorControlCommand jointMotorControlCommand = 17; + if (has_jointmotorcontrolcommand()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 17, *commands_.jointmotorcontrolcommand_, output); + } + + // .pybullet_grpc.UserConstraintCommand userConstraintCommand = 18; + if (has_userconstraintcommand()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 18, *commands_.userconstraintcommand_, output); + } + + // .pybullet_grpc.CheckVersionCommand checkVersionCommand = 19; + if (has_checkversioncommand()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 19, *commands_.checkversioncommand_, output); + } + + // .pybullet_grpc.RequestKeyboardEventsCommand requestKeyboardEventsCommand = 20; + if (has_requestkeyboardeventscommand()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 20, *commands_.requestkeyboardeventscommand_, output); + } + + // .pybullet_grpc.RequestCameraImageCommand requestCameraImageCommand = 21; + if (has_requestcameraimagecommand()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 21, *commands_.requestcameraimagecommand_, output); } // @@protoc_insertion_point(serialize_end:pybullet_grpc.PyBulletCommand) @@ -9590,67 +20482,142 @@ void PyBulletCommand::SerializeWithCachedSizes( target = ::google::protobuf::internal::WireFormatLite::WriteInt32ToArray(1, this->commandtype(), target); } - // .pybullet_grpc.LoadUrdfCommand loadUrdfCommand = 3; + // repeated bytes binaryBlob = 2; + for (int i = 0; i < this->binaryblob_size(); i++) { + target = ::google::protobuf::internal::WireFormatLite:: + WriteBytesToArray(2, this->binaryblob(i), target); + } + + // repeated bytes unknownCommandBinaryBlob = 3; + for (int i = 0; i < this->unknowncommandbinaryblob_size(); i++) { + target = ::google::protobuf::internal::WireFormatLite:: + WriteBytesToArray(3, this->unknowncommandbinaryblob(i), target); + } + + // .pybullet_grpc.LoadUrdfCommand loadUrdfCommand = 4; if (has_loadurdfcommand()) { target = ::google::protobuf::internal::WireFormatLite:: InternalWriteMessageNoVirtualToArray( - 3, *commands_.loadurdfcommand_, false, target); + 4, *commands_.loadurdfcommand_, false, target); } - // .pybullet_grpc.TerminateServerCommand terminateServerCommand = 4; + // .pybullet_grpc.TerminateServerCommand terminateServerCommand = 5; if (has_terminateservercommand()) { target = ::google::protobuf::internal::WireFormatLite:: InternalWriteMessageNoVirtualToArray( - 4, *commands_.terminateservercommand_, false, target); + 5, *commands_.terminateservercommand_, false, target); } - // .pybullet_grpc.StepSimulationCommand stepSimulationCommand = 5; + // .pybullet_grpc.StepSimulationCommand stepSimulationCommand = 6; if (has_stepsimulationcommand()) { target = ::google::protobuf::internal::WireFormatLite:: InternalWriteMessageNoVirtualToArray( - 5, *commands_.stepsimulationcommand_, false, target); + 6, *commands_.stepsimulationcommand_, false, target); } - // .pybullet_grpc.LoadSdfCommand loadSdfCommand = 6; + // .pybullet_grpc.LoadSdfCommand loadSdfCommand = 7; if (has_loadsdfcommand()) { target = ::google::protobuf::internal::WireFormatLite:: InternalWriteMessageNoVirtualToArray( - 6, *commands_.loadsdfcommand_, false, target); + 7, *commands_.loadsdfcommand_, false, target); } - // .pybullet_grpc.LoadMjcfCommand loadMjcfCommand = 7; + // .pybullet_grpc.LoadMjcfCommand loadMjcfCommand = 8; if (has_loadmjcfcommand()) { target = ::google::protobuf::internal::WireFormatLite:: InternalWriteMessageNoVirtualToArray( - 7, *commands_.loadmjcfcommand_, false, target); + 8, *commands_.loadmjcfcommand_, false, target); } - // .pybullet_grpc.ChangeDynamicsCommand changeDynamicsCommand = 8; + // .pybullet_grpc.ChangeDynamicsCommand changeDynamicsCommand = 9; if (has_changedynamicscommand()) { target = ::google::protobuf::internal::WireFormatLite:: InternalWriteMessageNoVirtualToArray( - 8, *commands_.changedynamicscommand_, false, target); + 9, *commands_.changedynamicscommand_, false, target); } - // .pybullet_grpc.GetDynamicsCommand getDynamicsCommand = 9; + // .pybullet_grpc.GetDynamicsCommand getDynamicsCommand = 10; if (has_getdynamicscommand()) { target = ::google::protobuf::internal::WireFormatLite:: InternalWriteMessageNoVirtualToArray( - 9, *commands_.getdynamicscommand_, false, target); + 10, *commands_.getdynamicscommand_, false, target); } - // .pybullet_grpc.InitPoseCommand initPoseCommand = 10; + // .pybullet_grpc.InitPoseCommand initPoseCommand = 11; if (has_initposecommand()) { target = ::google::protobuf::internal::WireFormatLite:: InternalWriteMessageNoVirtualToArray( - 10, *commands_.initposecommand_, false, target); + 11, *commands_.initposecommand_, false, target); } - // .pybullet_grpc.RequestActualStateCommand requestActualStateCommand = 11; + // .pybullet_grpc.RequestActualStateCommand requestActualStateCommand = 12; if (has_requestactualstatecommand()) { target = ::google::protobuf::internal::WireFormatLite:: InternalWriteMessageNoVirtualToArray( - 11, *commands_.requestactualstatecommand_, false, target); + 12, *commands_.requestactualstatecommand_, false, target); + } + + // .pybullet_grpc.ConfigureOpenGLVisualizerCommand configureOpenGLVisualizerCommand = 13; + if (has_configureopenglvisualizercommand()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageNoVirtualToArray( + 13, *commands_.configureopenglvisualizercommand_, false, target); + } + + // .pybullet_grpc.SyncBodiesCommand syncBodiesCommand = 14; + if (has_syncbodiescommand()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageNoVirtualToArray( + 14, *commands_.syncbodiescommand_, false, target); + } + + // .pybullet_grpc.RequestBodyInfoCommand requestBodyInfoCommand = 15; + if (has_requestbodyinfocommand()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageNoVirtualToArray( + 15, *commands_.requestbodyinfocommand_, false, target); + } + + // .pybullet_grpc.PhysicsSimulationParametersCommand setPhysicsSimulationParametersCommand = 16; + if (has_setphysicssimulationparameterscommand()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageNoVirtualToArray( + 16, *commands_.setphysicssimulationparameterscommand_, false, target); + } + + // .pybullet_grpc.JointMotorControlCommand jointMotorControlCommand = 17; + if (has_jointmotorcontrolcommand()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageNoVirtualToArray( + 17, *commands_.jointmotorcontrolcommand_, false, target); + } + + // .pybullet_grpc.UserConstraintCommand userConstraintCommand = 18; + if (has_userconstraintcommand()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageNoVirtualToArray( + 18, *commands_.userconstraintcommand_, false, target); + } + + // .pybullet_grpc.CheckVersionCommand checkVersionCommand = 19; + if (has_checkversioncommand()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageNoVirtualToArray( + 19, *commands_.checkversioncommand_, false, target); + } + + // .pybullet_grpc.RequestKeyboardEventsCommand requestKeyboardEventsCommand = 20; + if (has_requestkeyboardeventscommand()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageNoVirtualToArray( + 20, *commands_.requestkeyboardeventscommand_, false, target); + } + + // .pybullet_grpc.RequestCameraImageCommand requestCameraImageCommand = 21; + if (has_requestcameraimagecommand()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageNoVirtualToArray( + 21, *commands_.requestcameraimagecommand_, false, target); } // @@protoc_insertion_point(serialize_to_array_end:pybullet_grpc.PyBulletCommand) @@ -9661,6 +20628,22 @@ size_t PyBulletCommand::ByteSizeLong() const { // @@protoc_insertion_point(message_byte_size_start:pybullet_grpc.PyBulletCommand) size_t total_size = 0; + // repeated bytes binaryBlob = 2; + total_size += 1 * + ::google::protobuf::internal::FromIntSize(this->binaryblob_size()); + for (int i = 0; i < this->binaryblob_size(); i++) { + total_size += ::google::protobuf::internal::WireFormatLite::BytesSize( + this->binaryblob(i)); + } + + // repeated bytes unknownCommandBinaryBlob = 3; + total_size += 1 * + ::google::protobuf::internal::FromIntSize(this->unknowncommandbinaryblob_size()); + for (int i = 0; i < this->unknowncommandbinaryblob_size(); i++) { + total_size += ::google::protobuf::internal::WireFormatLite::BytesSize( + this->unknowncommandbinaryblob(i)); + } + // int32 commandType = 1; if (this->commandtype() != 0) { total_size += 1 + @@ -9669,69 +20652,132 @@ size_t PyBulletCommand::ByteSizeLong() const { } switch (commands_case()) { - // .pybullet_grpc.LoadUrdfCommand loadUrdfCommand = 3; + // .pybullet_grpc.LoadUrdfCommand loadUrdfCommand = 4; case kLoadUrdfCommand: { total_size += 1 + ::google::protobuf::internal::WireFormatLite::MessageSizeNoVirtual( *commands_.loadurdfcommand_); break; } - // .pybullet_grpc.TerminateServerCommand terminateServerCommand = 4; + // .pybullet_grpc.TerminateServerCommand terminateServerCommand = 5; case kTerminateServerCommand: { total_size += 1 + ::google::protobuf::internal::WireFormatLite::MessageSizeNoVirtual( *commands_.terminateservercommand_); break; } - // .pybullet_grpc.StepSimulationCommand stepSimulationCommand = 5; + // .pybullet_grpc.StepSimulationCommand stepSimulationCommand = 6; case kStepSimulationCommand: { total_size += 1 + ::google::protobuf::internal::WireFormatLite::MessageSizeNoVirtual( *commands_.stepsimulationcommand_); break; } - // .pybullet_grpc.LoadSdfCommand loadSdfCommand = 6; + // .pybullet_grpc.LoadSdfCommand loadSdfCommand = 7; case kLoadSdfCommand: { total_size += 1 + ::google::protobuf::internal::WireFormatLite::MessageSizeNoVirtual( *commands_.loadsdfcommand_); break; } - // .pybullet_grpc.LoadMjcfCommand loadMjcfCommand = 7; + // .pybullet_grpc.LoadMjcfCommand loadMjcfCommand = 8; case kLoadMjcfCommand: { total_size += 1 + ::google::protobuf::internal::WireFormatLite::MessageSizeNoVirtual( *commands_.loadmjcfcommand_); break; } - // .pybullet_grpc.ChangeDynamicsCommand changeDynamicsCommand = 8; + // .pybullet_grpc.ChangeDynamicsCommand changeDynamicsCommand = 9; case kChangeDynamicsCommand: { total_size += 1 + ::google::protobuf::internal::WireFormatLite::MessageSizeNoVirtual( *commands_.changedynamicscommand_); break; } - // .pybullet_grpc.GetDynamicsCommand getDynamicsCommand = 9; + // .pybullet_grpc.GetDynamicsCommand getDynamicsCommand = 10; case kGetDynamicsCommand: { total_size += 1 + ::google::protobuf::internal::WireFormatLite::MessageSizeNoVirtual( *commands_.getdynamicscommand_); break; } - // .pybullet_grpc.InitPoseCommand initPoseCommand = 10; + // .pybullet_grpc.InitPoseCommand initPoseCommand = 11; case kInitPoseCommand: { total_size += 1 + ::google::protobuf::internal::WireFormatLite::MessageSizeNoVirtual( *commands_.initposecommand_); break; } - // .pybullet_grpc.RequestActualStateCommand requestActualStateCommand = 11; + // .pybullet_grpc.RequestActualStateCommand requestActualStateCommand = 12; case kRequestActualStateCommand: { total_size += 1 + ::google::protobuf::internal::WireFormatLite::MessageSizeNoVirtual( *commands_.requestactualstatecommand_); break; } + // .pybullet_grpc.ConfigureOpenGLVisualizerCommand configureOpenGLVisualizerCommand = 13; + case kConfigureOpenGLVisualizerCommand: { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSizeNoVirtual( + *commands_.configureopenglvisualizercommand_); + break; + } + // .pybullet_grpc.SyncBodiesCommand syncBodiesCommand = 14; + case kSyncBodiesCommand: { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSizeNoVirtual( + *commands_.syncbodiescommand_); + break; + } + // .pybullet_grpc.RequestBodyInfoCommand requestBodyInfoCommand = 15; + case kRequestBodyInfoCommand: { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSizeNoVirtual( + *commands_.requestbodyinfocommand_); + break; + } + // .pybullet_grpc.PhysicsSimulationParametersCommand setPhysicsSimulationParametersCommand = 16; + case kSetPhysicsSimulationParametersCommand: { + total_size += 2 + + ::google::protobuf::internal::WireFormatLite::MessageSizeNoVirtual( + *commands_.setphysicssimulationparameterscommand_); + break; + } + // .pybullet_grpc.JointMotorControlCommand jointMotorControlCommand = 17; + case kJointMotorControlCommand: { + total_size += 2 + + ::google::protobuf::internal::WireFormatLite::MessageSizeNoVirtual( + *commands_.jointmotorcontrolcommand_); + break; + } + // .pybullet_grpc.UserConstraintCommand userConstraintCommand = 18; + case kUserConstraintCommand: { + total_size += 2 + + ::google::protobuf::internal::WireFormatLite::MessageSizeNoVirtual( + *commands_.userconstraintcommand_); + break; + } + // .pybullet_grpc.CheckVersionCommand checkVersionCommand = 19; + case kCheckVersionCommand: { + total_size += 2 + + ::google::protobuf::internal::WireFormatLite::MessageSizeNoVirtual( + *commands_.checkversioncommand_); + break; + } + // .pybullet_grpc.RequestKeyboardEventsCommand requestKeyboardEventsCommand = 20; + case kRequestKeyboardEventsCommand: { + total_size += 2 + + ::google::protobuf::internal::WireFormatLite::MessageSizeNoVirtual( + *commands_.requestkeyboardeventscommand_); + break; + } + // .pybullet_grpc.RequestCameraImageCommand requestCameraImageCommand = 21; + case kRequestCameraImageCommand: { + total_size += 2 + + ::google::protobuf::internal::WireFormatLite::MessageSizeNoVirtual( + *commands_.requestcameraimagecommand_); + break; + } case COMMANDS_NOT_SET: { break; } @@ -9762,6 +20808,8 @@ 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_); + binaryblob_.MergeFrom(from.binaryblob_); + unknowncommandbinaryblob_.MergeFrom(from.unknowncommandbinaryblob_); if (from.commandtype() != 0) { set_commandtype(from.commandtype()); } @@ -9802,6 +20850,42 @@ void PyBulletCommand::MergeFrom(const PyBulletCommand& from) { mutable_requestactualstatecommand()->::pybullet_grpc::RequestActualStateCommand::MergeFrom(from.requestactualstatecommand()); break; } + case kConfigureOpenGLVisualizerCommand: { + mutable_configureopenglvisualizercommand()->::pybullet_grpc::ConfigureOpenGLVisualizerCommand::MergeFrom(from.configureopenglvisualizercommand()); + break; + } + case kSyncBodiesCommand: { + mutable_syncbodiescommand()->::pybullet_grpc::SyncBodiesCommand::MergeFrom(from.syncbodiescommand()); + break; + } + case kRequestBodyInfoCommand: { + mutable_requestbodyinfocommand()->::pybullet_grpc::RequestBodyInfoCommand::MergeFrom(from.requestbodyinfocommand()); + break; + } + case kSetPhysicsSimulationParametersCommand: { + mutable_setphysicssimulationparameterscommand()->::pybullet_grpc::PhysicsSimulationParametersCommand::MergeFrom(from.setphysicssimulationparameterscommand()); + break; + } + case kJointMotorControlCommand: { + mutable_jointmotorcontrolcommand()->::pybullet_grpc::JointMotorControlCommand::MergeFrom(from.jointmotorcontrolcommand()); + break; + } + case kUserConstraintCommand: { + mutable_userconstraintcommand()->::pybullet_grpc::UserConstraintCommand::MergeFrom(from.userconstraintcommand()); + break; + } + case kCheckVersionCommand: { + mutable_checkversioncommand()->::pybullet_grpc::CheckVersionCommand::MergeFrom(from.checkversioncommand()); + break; + } + case kRequestKeyboardEventsCommand: { + mutable_requestkeyboardeventscommand()->::pybullet_grpc::RequestKeyboardEventsCommand::MergeFrom(from.requestkeyboardeventscommand()); + break; + } + case kRequestCameraImageCommand: { + mutable_requestcameraimagecommand()->::pybullet_grpc::RequestCameraImageCommand::MergeFrom(from.requestcameraimagecommand()); + break; + } case COMMANDS_NOT_SET: { break; } @@ -9831,6 +20915,8 @@ void PyBulletCommand::Swap(PyBulletCommand* other) { InternalSwap(other); } void PyBulletCommand::InternalSwap(PyBulletCommand* other) { + binaryblob_.UnsafeArenaSwap(&other->binaryblob_); + unknowncommandbinaryblob_.UnsafeArenaSwap(&other->unknowncommandbinaryblob_); std::swap(commandtype_, other->commandtype_); std::swap(commands_, other->commands_); std::swap(_oneof_case_[0], other->_oneof_case_[0]); @@ -9839,7 +20925,7 @@ void PyBulletCommand::InternalSwap(PyBulletCommand* other) { ::google::protobuf::Metadata PyBulletCommand::GetMetadata() const { protobuf_pybullet_2eproto::protobuf_AssignDescriptorsOnce(); - return protobuf_pybullet_2eproto::file_level_metadata[16]; + return protobuf_pybullet_2eproto::file_level_metadata[37]; } #if PROTOBUF_INLINE_NOT_IN_HEADERS @@ -9859,7 +20945,117 @@ void PyBulletCommand::set_commandtype(::google::protobuf::int32 value) { // @@protoc_insertion_point(field_set:pybullet_grpc.PyBulletCommand.commandType) } -// .pybullet_grpc.LoadUrdfCommand loadUrdfCommand = 3; +// repeated bytes binaryBlob = 2; +int PyBulletCommand::binaryblob_size() const { + return binaryblob_.size(); +} +void PyBulletCommand::clear_binaryblob() { + binaryblob_.Clear(); +} +const ::std::string& PyBulletCommand::binaryblob(int index) const { + // @@protoc_insertion_point(field_get:pybullet_grpc.PyBulletCommand.binaryBlob) + return binaryblob_.Get(index); +} +::std::string* PyBulletCommand::mutable_binaryblob(int index) { + // @@protoc_insertion_point(field_mutable:pybullet_grpc.PyBulletCommand.binaryBlob) + return binaryblob_.Mutable(index); +} +void PyBulletCommand::set_binaryblob(int index, const ::std::string& value) { + // @@protoc_insertion_point(field_set:pybullet_grpc.PyBulletCommand.binaryBlob) + binaryblob_.Mutable(index)->assign(value); +} +void PyBulletCommand::set_binaryblob(int index, const char* value) { + binaryblob_.Mutable(index)->assign(value); + // @@protoc_insertion_point(field_set_char:pybullet_grpc.PyBulletCommand.binaryBlob) +} +void PyBulletCommand::set_binaryblob(int index, const void* value, size_t size) { + binaryblob_.Mutable(index)->assign( + reinterpret_cast(value), size); + // @@protoc_insertion_point(field_set_pointer:pybullet_grpc.PyBulletCommand.binaryBlob) +} +::std::string* PyBulletCommand::add_binaryblob() { + // @@protoc_insertion_point(field_add_mutable:pybullet_grpc.PyBulletCommand.binaryBlob) + return binaryblob_.Add(); +} +void PyBulletCommand::add_binaryblob(const ::std::string& value) { + binaryblob_.Add()->assign(value); + // @@protoc_insertion_point(field_add:pybullet_grpc.PyBulletCommand.binaryBlob) +} +void PyBulletCommand::add_binaryblob(const char* value) { + binaryblob_.Add()->assign(value); + // @@protoc_insertion_point(field_add_char:pybullet_grpc.PyBulletCommand.binaryBlob) +} +void PyBulletCommand::add_binaryblob(const void* value, size_t size) { + binaryblob_.Add()->assign(reinterpret_cast(value), size); + // @@protoc_insertion_point(field_add_pointer:pybullet_grpc.PyBulletCommand.binaryBlob) +} +const ::google::protobuf::RepeatedPtrField< ::std::string>& +PyBulletCommand::binaryblob() const { + // @@protoc_insertion_point(field_list:pybullet_grpc.PyBulletCommand.binaryBlob) + return binaryblob_; +} +::google::protobuf::RepeatedPtrField< ::std::string>* +PyBulletCommand::mutable_binaryblob() { + // @@protoc_insertion_point(field_mutable_list:pybullet_grpc.PyBulletCommand.binaryBlob) + return &binaryblob_; +} + +// repeated bytes unknownCommandBinaryBlob = 3; +int PyBulletCommand::unknowncommandbinaryblob_size() const { + return unknowncommandbinaryblob_.size(); +} +void PyBulletCommand::clear_unknowncommandbinaryblob() { + unknowncommandbinaryblob_.Clear(); +} +const ::std::string& PyBulletCommand::unknowncommandbinaryblob(int index) const { + // @@protoc_insertion_point(field_get:pybullet_grpc.PyBulletCommand.unknownCommandBinaryBlob) + return unknowncommandbinaryblob_.Get(index); +} +::std::string* PyBulletCommand::mutable_unknowncommandbinaryblob(int index) { + // @@protoc_insertion_point(field_mutable:pybullet_grpc.PyBulletCommand.unknownCommandBinaryBlob) + return unknowncommandbinaryblob_.Mutable(index); +} +void PyBulletCommand::set_unknowncommandbinaryblob(int index, const ::std::string& value) { + // @@protoc_insertion_point(field_set:pybullet_grpc.PyBulletCommand.unknownCommandBinaryBlob) + unknowncommandbinaryblob_.Mutable(index)->assign(value); +} +void PyBulletCommand::set_unknowncommandbinaryblob(int index, const char* value) { + unknowncommandbinaryblob_.Mutable(index)->assign(value); + // @@protoc_insertion_point(field_set_char:pybullet_grpc.PyBulletCommand.unknownCommandBinaryBlob) +} +void PyBulletCommand::set_unknowncommandbinaryblob(int index, const void* value, size_t size) { + unknowncommandbinaryblob_.Mutable(index)->assign( + reinterpret_cast(value), size); + // @@protoc_insertion_point(field_set_pointer:pybullet_grpc.PyBulletCommand.unknownCommandBinaryBlob) +} +::std::string* PyBulletCommand::add_unknowncommandbinaryblob() { + // @@protoc_insertion_point(field_add_mutable:pybullet_grpc.PyBulletCommand.unknownCommandBinaryBlob) + return unknowncommandbinaryblob_.Add(); +} +void PyBulletCommand::add_unknowncommandbinaryblob(const ::std::string& value) { + unknowncommandbinaryblob_.Add()->assign(value); + // @@protoc_insertion_point(field_add:pybullet_grpc.PyBulletCommand.unknownCommandBinaryBlob) +} +void PyBulletCommand::add_unknowncommandbinaryblob(const char* value) { + unknowncommandbinaryblob_.Add()->assign(value); + // @@protoc_insertion_point(field_add_char:pybullet_grpc.PyBulletCommand.unknownCommandBinaryBlob) +} +void PyBulletCommand::add_unknowncommandbinaryblob(const void* value, size_t size) { + unknowncommandbinaryblob_.Add()->assign(reinterpret_cast(value), size); + // @@protoc_insertion_point(field_add_pointer:pybullet_grpc.PyBulletCommand.unknownCommandBinaryBlob) +} +const ::google::protobuf::RepeatedPtrField< ::std::string>& +PyBulletCommand::unknowncommandbinaryblob() const { + // @@protoc_insertion_point(field_list:pybullet_grpc.PyBulletCommand.unknownCommandBinaryBlob) + return unknowncommandbinaryblob_; +} +::google::protobuf::RepeatedPtrField< ::std::string>* +PyBulletCommand::mutable_unknowncommandbinaryblob() { + // @@protoc_insertion_point(field_mutable_list:pybullet_grpc.PyBulletCommand.unknownCommandBinaryBlob) + return &unknowncommandbinaryblob_; +} + +// .pybullet_grpc.LoadUrdfCommand loadUrdfCommand = 4; bool PyBulletCommand::has_loadurdfcommand() const { return commands_case() == kLoadUrdfCommand; } @@ -9907,7 +21103,7 @@ void PyBulletCommand::set_allocated_loadurdfcommand(::pybullet_grpc::LoadUrdfCom // @@protoc_insertion_point(field_set_allocated:pybullet_grpc.PyBulletCommand.loadUrdfCommand) } -// .pybullet_grpc.TerminateServerCommand terminateServerCommand = 4; +// .pybullet_grpc.TerminateServerCommand terminateServerCommand = 5; bool PyBulletCommand::has_terminateservercommand() const { return commands_case() == kTerminateServerCommand; } @@ -9955,7 +21151,7 @@ void PyBulletCommand::set_allocated_terminateservercommand(::pybullet_grpc::Term // @@protoc_insertion_point(field_set_allocated:pybullet_grpc.PyBulletCommand.terminateServerCommand) } -// .pybullet_grpc.StepSimulationCommand stepSimulationCommand = 5; +// .pybullet_grpc.StepSimulationCommand stepSimulationCommand = 6; bool PyBulletCommand::has_stepsimulationcommand() const { return commands_case() == kStepSimulationCommand; } @@ -10003,7 +21199,7 @@ void PyBulletCommand::set_allocated_stepsimulationcommand(::pybullet_grpc::StepS // @@protoc_insertion_point(field_set_allocated:pybullet_grpc.PyBulletCommand.stepSimulationCommand) } -// .pybullet_grpc.LoadSdfCommand loadSdfCommand = 6; +// .pybullet_grpc.LoadSdfCommand loadSdfCommand = 7; bool PyBulletCommand::has_loadsdfcommand() const { return commands_case() == kLoadSdfCommand; } @@ -10051,7 +21247,7 @@ void PyBulletCommand::set_allocated_loadsdfcommand(::pybullet_grpc::LoadSdfComma // @@protoc_insertion_point(field_set_allocated:pybullet_grpc.PyBulletCommand.loadSdfCommand) } -// .pybullet_grpc.LoadMjcfCommand loadMjcfCommand = 7; +// .pybullet_grpc.LoadMjcfCommand loadMjcfCommand = 8; bool PyBulletCommand::has_loadmjcfcommand() const { return commands_case() == kLoadMjcfCommand; } @@ -10099,7 +21295,7 @@ void PyBulletCommand::set_allocated_loadmjcfcommand(::pybullet_grpc::LoadMjcfCom // @@protoc_insertion_point(field_set_allocated:pybullet_grpc.PyBulletCommand.loadMjcfCommand) } -// .pybullet_grpc.ChangeDynamicsCommand changeDynamicsCommand = 8; +// .pybullet_grpc.ChangeDynamicsCommand changeDynamicsCommand = 9; bool PyBulletCommand::has_changedynamicscommand() const { return commands_case() == kChangeDynamicsCommand; } @@ -10147,7 +21343,7 @@ void PyBulletCommand::set_allocated_changedynamicscommand(::pybullet_grpc::Chang // @@protoc_insertion_point(field_set_allocated:pybullet_grpc.PyBulletCommand.changeDynamicsCommand) } -// .pybullet_grpc.GetDynamicsCommand getDynamicsCommand = 9; +// .pybullet_grpc.GetDynamicsCommand getDynamicsCommand = 10; bool PyBulletCommand::has_getdynamicscommand() const { return commands_case() == kGetDynamicsCommand; } @@ -10195,7 +21391,7 @@ void PyBulletCommand::set_allocated_getdynamicscommand(::pybullet_grpc::GetDynam // @@protoc_insertion_point(field_set_allocated:pybullet_grpc.PyBulletCommand.getDynamicsCommand) } -// .pybullet_grpc.InitPoseCommand initPoseCommand = 10; +// .pybullet_grpc.InitPoseCommand initPoseCommand = 11; bool PyBulletCommand::has_initposecommand() const { return commands_case() == kInitPoseCommand; } @@ -10243,7 +21439,7 @@ void PyBulletCommand::set_allocated_initposecommand(::pybullet_grpc::InitPoseCom // @@protoc_insertion_point(field_set_allocated:pybullet_grpc.PyBulletCommand.initPoseCommand) } -// .pybullet_grpc.RequestActualStateCommand requestActualStateCommand = 11; +// .pybullet_grpc.RequestActualStateCommand requestActualStateCommand = 12; bool PyBulletCommand::has_requestactualstatecommand() const { return commands_case() == kRequestActualStateCommand; } @@ -10291,6 +21487,438 @@ void PyBulletCommand::set_allocated_requestactualstatecommand(::pybullet_grpc::R // @@protoc_insertion_point(field_set_allocated:pybullet_grpc.PyBulletCommand.requestActualStateCommand) } +// .pybullet_grpc.ConfigureOpenGLVisualizerCommand configureOpenGLVisualizerCommand = 13; +bool PyBulletCommand::has_configureopenglvisualizercommand() const { + return commands_case() == kConfigureOpenGLVisualizerCommand; +} +void PyBulletCommand::set_has_configureopenglvisualizercommand() { + _oneof_case_[0] = kConfigureOpenGLVisualizerCommand; +} +void PyBulletCommand::clear_configureopenglvisualizercommand() { + if (has_configureopenglvisualizercommand()) { + delete commands_.configureopenglvisualizercommand_; + clear_has_commands(); + } +} + const ::pybullet_grpc::ConfigureOpenGLVisualizerCommand& PyBulletCommand::configureopenglvisualizercommand() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.PyBulletCommand.configureOpenGLVisualizerCommand) + return has_configureopenglvisualizercommand() + ? *commands_.configureopenglvisualizercommand_ + : ::pybullet_grpc::ConfigureOpenGLVisualizerCommand::default_instance(); +} +::pybullet_grpc::ConfigureOpenGLVisualizerCommand* PyBulletCommand::mutable_configureopenglvisualizercommand() { + if (!has_configureopenglvisualizercommand()) { + clear_commands(); + set_has_configureopenglvisualizercommand(); + commands_.configureopenglvisualizercommand_ = new ::pybullet_grpc::ConfigureOpenGLVisualizerCommand; + } + // @@protoc_insertion_point(field_mutable:pybullet_grpc.PyBulletCommand.configureOpenGLVisualizerCommand) + return commands_.configureopenglvisualizercommand_; +} +::pybullet_grpc::ConfigureOpenGLVisualizerCommand* PyBulletCommand::release_configureopenglvisualizercommand() { + // @@protoc_insertion_point(field_release:pybullet_grpc.PyBulletCommand.configureOpenGLVisualizerCommand) + if (has_configureopenglvisualizercommand()) { + clear_has_commands(); + ::pybullet_grpc::ConfigureOpenGLVisualizerCommand* temp = commands_.configureopenglvisualizercommand_; + commands_.configureopenglvisualizercommand_ = NULL; + return temp; + } else { + return NULL; + } +} +void PyBulletCommand::set_allocated_configureopenglvisualizercommand(::pybullet_grpc::ConfigureOpenGLVisualizerCommand* configureopenglvisualizercommand) { + clear_commands(); + if (configureopenglvisualizercommand) { + set_has_configureopenglvisualizercommand(); + commands_.configureopenglvisualizercommand_ = configureopenglvisualizercommand; + } + // @@protoc_insertion_point(field_set_allocated:pybullet_grpc.PyBulletCommand.configureOpenGLVisualizerCommand) +} + +// .pybullet_grpc.SyncBodiesCommand syncBodiesCommand = 14; +bool PyBulletCommand::has_syncbodiescommand() const { + return commands_case() == kSyncBodiesCommand; +} +void PyBulletCommand::set_has_syncbodiescommand() { + _oneof_case_[0] = kSyncBodiesCommand; +} +void PyBulletCommand::clear_syncbodiescommand() { + if (has_syncbodiescommand()) { + delete commands_.syncbodiescommand_; + clear_has_commands(); + } +} + const ::pybullet_grpc::SyncBodiesCommand& PyBulletCommand::syncbodiescommand() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.PyBulletCommand.syncBodiesCommand) + return has_syncbodiescommand() + ? *commands_.syncbodiescommand_ + : ::pybullet_grpc::SyncBodiesCommand::default_instance(); +} +::pybullet_grpc::SyncBodiesCommand* PyBulletCommand::mutable_syncbodiescommand() { + if (!has_syncbodiescommand()) { + clear_commands(); + set_has_syncbodiescommand(); + commands_.syncbodiescommand_ = new ::pybullet_grpc::SyncBodiesCommand; + } + // @@protoc_insertion_point(field_mutable:pybullet_grpc.PyBulletCommand.syncBodiesCommand) + return commands_.syncbodiescommand_; +} +::pybullet_grpc::SyncBodiesCommand* PyBulletCommand::release_syncbodiescommand() { + // @@protoc_insertion_point(field_release:pybullet_grpc.PyBulletCommand.syncBodiesCommand) + if (has_syncbodiescommand()) { + clear_has_commands(); + ::pybullet_grpc::SyncBodiesCommand* temp = commands_.syncbodiescommand_; + commands_.syncbodiescommand_ = NULL; + return temp; + } else { + return NULL; + } +} +void PyBulletCommand::set_allocated_syncbodiescommand(::pybullet_grpc::SyncBodiesCommand* syncbodiescommand) { + clear_commands(); + if (syncbodiescommand) { + set_has_syncbodiescommand(); + commands_.syncbodiescommand_ = syncbodiescommand; + } + // @@protoc_insertion_point(field_set_allocated:pybullet_grpc.PyBulletCommand.syncBodiesCommand) +} + +// .pybullet_grpc.RequestBodyInfoCommand requestBodyInfoCommand = 15; +bool PyBulletCommand::has_requestbodyinfocommand() const { + return commands_case() == kRequestBodyInfoCommand; +} +void PyBulletCommand::set_has_requestbodyinfocommand() { + _oneof_case_[0] = kRequestBodyInfoCommand; +} +void PyBulletCommand::clear_requestbodyinfocommand() { + if (has_requestbodyinfocommand()) { + delete commands_.requestbodyinfocommand_; + clear_has_commands(); + } +} + const ::pybullet_grpc::RequestBodyInfoCommand& PyBulletCommand::requestbodyinfocommand() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.PyBulletCommand.requestBodyInfoCommand) + return has_requestbodyinfocommand() + ? *commands_.requestbodyinfocommand_ + : ::pybullet_grpc::RequestBodyInfoCommand::default_instance(); +} +::pybullet_grpc::RequestBodyInfoCommand* PyBulletCommand::mutable_requestbodyinfocommand() { + if (!has_requestbodyinfocommand()) { + clear_commands(); + set_has_requestbodyinfocommand(); + commands_.requestbodyinfocommand_ = new ::pybullet_grpc::RequestBodyInfoCommand; + } + // @@protoc_insertion_point(field_mutable:pybullet_grpc.PyBulletCommand.requestBodyInfoCommand) + return commands_.requestbodyinfocommand_; +} +::pybullet_grpc::RequestBodyInfoCommand* PyBulletCommand::release_requestbodyinfocommand() { + // @@protoc_insertion_point(field_release:pybullet_grpc.PyBulletCommand.requestBodyInfoCommand) + if (has_requestbodyinfocommand()) { + clear_has_commands(); + ::pybullet_grpc::RequestBodyInfoCommand* temp = commands_.requestbodyinfocommand_; + commands_.requestbodyinfocommand_ = NULL; + return temp; + } else { + return NULL; + } +} +void PyBulletCommand::set_allocated_requestbodyinfocommand(::pybullet_grpc::RequestBodyInfoCommand* requestbodyinfocommand) { + clear_commands(); + if (requestbodyinfocommand) { + set_has_requestbodyinfocommand(); + commands_.requestbodyinfocommand_ = requestbodyinfocommand; + } + // @@protoc_insertion_point(field_set_allocated:pybullet_grpc.PyBulletCommand.requestBodyInfoCommand) +} + +// .pybullet_grpc.PhysicsSimulationParametersCommand setPhysicsSimulationParametersCommand = 16; +bool PyBulletCommand::has_setphysicssimulationparameterscommand() const { + return commands_case() == kSetPhysicsSimulationParametersCommand; +} +void PyBulletCommand::set_has_setphysicssimulationparameterscommand() { + _oneof_case_[0] = kSetPhysicsSimulationParametersCommand; +} +void PyBulletCommand::clear_setphysicssimulationparameterscommand() { + if (has_setphysicssimulationparameterscommand()) { + delete commands_.setphysicssimulationparameterscommand_; + clear_has_commands(); + } +} + const ::pybullet_grpc::PhysicsSimulationParametersCommand& PyBulletCommand::setphysicssimulationparameterscommand() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.PyBulletCommand.setPhysicsSimulationParametersCommand) + return has_setphysicssimulationparameterscommand() + ? *commands_.setphysicssimulationparameterscommand_ + : ::pybullet_grpc::PhysicsSimulationParametersCommand::default_instance(); +} +::pybullet_grpc::PhysicsSimulationParametersCommand* PyBulletCommand::mutable_setphysicssimulationparameterscommand() { + if (!has_setphysicssimulationparameterscommand()) { + clear_commands(); + set_has_setphysicssimulationparameterscommand(); + commands_.setphysicssimulationparameterscommand_ = new ::pybullet_grpc::PhysicsSimulationParametersCommand; + } + // @@protoc_insertion_point(field_mutable:pybullet_grpc.PyBulletCommand.setPhysicsSimulationParametersCommand) + return commands_.setphysicssimulationparameterscommand_; +} +::pybullet_grpc::PhysicsSimulationParametersCommand* PyBulletCommand::release_setphysicssimulationparameterscommand() { + // @@protoc_insertion_point(field_release:pybullet_grpc.PyBulletCommand.setPhysicsSimulationParametersCommand) + if (has_setphysicssimulationparameterscommand()) { + clear_has_commands(); + ::pybullet_grpc::PhysicsSimulationParametersCommand* temp = commands_.setphysicssimulationparameterscommand_; + commands_.setphysicssimulationparameterscommand_ = NULL; + return temp; + } else { + return NULL; + } +} +void PyBulletCommand::set_allocated_setphysicssimulationparameterscommand(::pybullet_grpc::PhysicsSimulationParametersCommand* setphysicssimulationparameterscommand) { + clear_commands(); + if (setphysicssimulationparameterscommand) { + set_has_setphysicssimulationparameterscommand(); + commands_.setphysicssimulationparameterscommand_ = setphysicssimulationparameterscommand; + } + // @@protoc_insertion_point(field_set_allocated:pybullet_grpc.PyBulletCommand.setPhysicsSimulationParametersCommand) +} + +// .pybullet_grpc.JointMotorControlCommand jointMotorControlCommand = 17; +bool PyBulletCommand::has_jointmotorcontrolcommand() const { + return commands_case() == kJointMotorControlCommand; +} +void PyBulletCommand::set_has_jointmotorcontrolcommand() { + _oneof_case_[0] = kJointMotorControlCommand; +} +void PyBulletCommand::clear_jointmotorcontrolcommand() { + if (has_jointmotorcontrolcommand()) { + delete commands_.jointmotorcontrolcommand_; + clear_has_commands(); + } +} + const ::pybullet_grpc::JointMotorControlCommand& PyBulletCommand::jointmotorcontrolcommand() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.PyBulletCommand.jointMotorControlCommand) + return has_jointmotorcontrolcommand() + ? *commands_.jointmotorcontrolcommand_ + : ::pybullet_grpc::JointMotorControlCommand::default_instance(); +} +::pybullet_grpc::JointMotorControlCommand* PyBulletCommand::mutable_jointmotorcontrolcommand() { + if (!has_jointmotorcontrolcommand()) { + clear_commands(); + set_has_jointmotorcontrolcommand(); + commands_.jointmotorcontrolcommand_ = new ::pybullet_grpc::JointMotorControlCommand; + } + // @@protoc_insertion_point(field_mutable:pybullet_grpc.PyBulletCommand.jointMotorControlCommand) + return commands_.jointmotorcontrolcommand_; +} +::pybullet_grpc::JointMotorControlCommand* PyBulletCommand::release_jointmotorcontrolcommand() { + // @@protoc_insertion_point(field_release:pybullet_grpc.PyBulletCommand.jointMotorControlCommand) + if (has_jointmotorcontrolcommand()) { + clear_has_commands(); + ::pybullet_grpc::JointMotorControlCommand* temp = commands_.jointmotorcontrolcommand_; + commands_.jointmotorcontrolcommand_ = NULL; + return temp; + } else { + return NULL; + } +} +void PyBulletCommand::set_allocated_jointmotorcontrolcommand(::pybullet_grpc::JointMotorControlCommand* jointmotorcontrolcommand) { + clear_commands(); + if (jointmotorcontrolcommand) { + set_has_jointmotorcontrolcommand(); + commands_.jointmotorcontrolcommand_ = jointmotorcontrolcommand; + } + // @@protoc_insertion_point(field_set_allocated:pybullet_grpc.PyBulletCommand.jointMotorControlCommand) +} + +// .pybullet_grpc.UserConstraintCommand userConstraintCommand = 18; +bool PyBulletCommand::has_userconstraintcommand() const { + return commands_case() == kUserConstraintCommand; +} +void PyBulletCommand::set_has_userconstraintcommand() { + _oneof_case_[0] = kUserConstraintCommand; +} +void PyBulletCommand::clear_userconstraintcommand() { + if (has_userconstraintcommand()) { + delete commands_.userconstraintcommand_; + clear_has_commands(); + } +} + const ::pybullet_grpc::UserConstraintCommand& PyBulletCommand::userconstraintcommand() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.PyBulletCommand.userConstraintCommand) + return has_userconstraintcommand() + ? *commands_.userconstraintcommand_ + : ::pybullet_grpc::UserConstraintCommand::default_instance(); +} +::pybullet_grpc::UserConstraintCommand* PyBulletCommand::mutable_userconstraintcommand() { + if (!has_userconstraintcommand()) { + clear_commands(); + set_has_userconstraintcommand(); + commands_.userconstraintcommand_ = new ::pybullet_grpc::UserConstraintCommand; + } + // @@protoc_insertion_point(field_mutable:pybullet_grpc.PyBulletCommand.userConstraintCommand) + return commands_.userconstraintcommand_; +} +::pybullet_grpc::UserConstraintCommand* PyBulletCommand::release_userconstraintcommand() { + // @@protoc_insertion_point(field_release:pybullet_grpc.PyBulletCommand.userConstraintCommand) + if (has_userconstraintcommand()) { + clear_has_commands(); + ::pybullet_grpc::UserConstraintCommand* temp = commands_.userconstraintcommand_; + commands_.userconstraintcommand_ = NULL; + return temp; + } else { + return NULL; + } +} +void PyBulletCommand::set_allocated_userconstraintcommand(::pybullet_grpc::UserConstraintCommand* userconstraintcommand) { + clear_commands(); + if (userconstraintcommand) { + set_has_userconstraintcommand(); + commands_.userconstraintcommand_ = userconstraintcommand; + } + // @@protoc_insertion_point(field_set_allocated:pybullet_grpc.PyBulletCommand.userConstraintCommand) +} + +// .pybullet_grpc.CheckVersionCommand checkVersionCommand = 19; +bool PyBulletCommand::has_checkversioncommand() const { + return commands_case() == kCheckVersionCommand; +} +void PyBulletCommand::set_has_checkversioncommand() { + _oneof_case_[0] = kCheckVersionCommand; +} +void PyBulletCommand::clear_checkversioncommand() { + if (has_checkversioncommand()) { + delete commands_.checkversioncommand_; + clear_has_commands(); + } +} + const ::pybullet_grpc::CheckVersionCommand& PyBulletCommand::checkversioncommand() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.PyBulletCommand.checkVersionCommand) + return has_checkversioncommand() + ? *commands_.checkversioncommand_ + : ::pybullet_grpc::CheckVersionCommand::default_instance(); +} +::pybullet_grpc::CheckVersionCommand* PyBulletCommand::mutable_checkversioncommand() { + if (!has_checkversioncommand()) { + clear_commands(); + set_has_checkversioncommand(); + commands_.checkversioncommand_ = new ::pybullet_grpc::CheckVersionCommand; + } + // @@protoc_insertion_point(field_mutable:pybullet_grpc.PyBulletCommand.checkVersionCommand) + return commands_.checkversioncommand_; +} +::pybullet_grpc::CheckVersionCommand* PyBulletCommand::release_checkversioncommand() { + // @@protoc_insertion_point(field_release:pybullet_grpc.PyBulletCommand.checkVersionCommand) + if (has_checkversioncommand()) { + clear_has_commands(); + ::pybullet_grpc::CheckVersionCommand* temp = commands_.checkversioncommand_; + commands_.checkversioncommand_ = NULL; + return temp; + } else { + return NULL; + } +} +void PyBulletCommand::set_allocated_checkversioncommand(::pybullet_grpc::CheckVersionCommand* checkversioncommand) { + clear_commands(); + if (checkversioncommand) { + set_has_checkversioncommand(); + commands_.checkversioncommand_ = checkversioncommand; + } + // @@protoc_insertion_point(field_set_allocated:pybullet_grpc.PyBulletCommand.checkVersionCommand) +} + +// .pybullet_grpc.RequestKeyboardEventsCommand requestKeyboardEventsCommand = 20; +bool PyBulletCommand::has_requestkeyboardeventscommand() const { + return commands_case() == kRequestKeyboardEventsCommand; +} +void PyBulletCommand::set_has_requestkeyboardeventscommand() { + _oneof_case_[0] = kRequestKeyboardEventsCommand; +} +void PyBulletCommand::clear_requestkeyboardeventscommand() { + if (has_requestkeyboardeventscommand()) { + delete commands_.requestkeyboardeventscommand_; + clear_has_commands(); + } +} + const ::pybullet_grpc::RequestKeyboardEventsCommand& PyBulletCommand::requestkeyboardeventscommand() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.PyBulletCommand.requestKeyboardEventsCommand) + return has_requestkeyboardeventscommand() + ? *commands_.requestkeyboardeventscommand_ + : ::pybullet_grpc::RequestKeyboardEventsCommand::default_instance(); +} +::pybullet_grpc::RequestKeyboardEventsCommand* PyBulletCommand::mutable_requestkeyboardeventscommand() { + if (!has_requestkeyboardeventscommand()) { + clear_commands(); + set_has_requestkeyboardeventscommand(); + commands_.requestkeyboardeventscommand_ = new ::pybullet_grpc::RequestKeyboardEventsCommand; + } + // @@protoc_insertion_point(field_mutable:pybullet_grpc.PyBulletCommand.requestKeyboardEventsCommand) + return commands_.requestkeyboardeventscommand_; +} +::pybullet_grpc::RequestKeyboardEventsCommand* PyBulletCommand::release_requestkeyboardeventscommand() { + // @@protoc_insertion_point(field_release:pybullet_grpc.PyBulletCommand.requestKeyboardEventsCommand) + if (has_requestkeyboardeventscommand()) { + clear_has_commands(); + ::pybullet_grpc::RequestKeyboardEventsCommand* temp = commands_.requestkeyboardeventscommand_; + commands_.requestkeyboardeventscommand_ = NULL; + return temp; + } else { + return NULL; + } +} +void PyBulletCommand::set_allocated_requestkeyboardeventscommand(::pybullet_grpc::RequestKeyboardEventsCommand* requestkeyboardeventscommand) { + clear_commands(); + if (requestkeyboardeventscommand) { + set_has_requestkeyboardeventscommand(); + commands_.requestkeyboardeventscommand_ = requestkeyboardeventscommand; + } + // @@protoc_insertion_point(field_set_allocated:pybullet_grpc.PyBulletCommand.requestKeyboardEventsCommand) +} + +// .pybullet_grpc.RequestCameraImageCommand requestCameraImageCommand = 21; +bool PyBulletCommand::has_requestcameraimagecommand() const { + return commands_case() == kRequestCameraImageCommand; +} +void PyBulletCommand::set_has_requestcameraimagecommand() { + _oneof_case_[0] = kRequestCameraImageCommand; +} +void PyBulletCommand::clear_requestcameraimagecommand() { + if (has_requestcameraimagecommand()) { + delete commands_.requestcameraimagecommand_; + clear_has_commands(); + } +} + const ::pybullet_grpc::RequestCameraImageCommand& PyBulletCommand::requestcameraimagecommand() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.PyBulletCommand.requestCameraImageCommand) + return has_requestcameraimagecommand() + ? *commands_.requestcameraimagecommand_ + : ::pybullet_grpc::RequestCameraImageCommand::default_instance(); +} +::pybullet_grpc::RequestCameraImageCommand* PyBulletCommand::mutable_requestcameraimagecommand() { + if (!has_requestcameraimagecommand()) { + clear_commands(); + set_has_requestcameraimagecommand(); + commands_.requestcameraimagecommand_ = new ::pybullet_grpc::RequestCameraImageCommand; + } + // @@protoc_insertion_point(field_mutable:pybullet_grpc.PyBulletCommand.requestCameraImageCommand) + return commands_.requestcameraimagecommand_; +} +::pybullet_grpc::RequestCameraImageCommand* PyBulletCommand::release_requestcameraimagecommand() { + // @@protoc_insertion_point(field_release:pybullet_grpc.PyBulletCommand.requestCameraImageCommand) + if (has_requestcameraimagecommand()) { + clear_has_commands(); + ::pybullet_grpc::RequestCameraImageCommand* temp = commands_.requestcameraimagecommand_; + commands_.requestcameraimagecommand_ = NULL; + return temp; + } else { + return NULL; + } +} +void PyBulletCommand::set_allocated_requestcameraimagecommand(::pybullet_grpc::RequestCameraImageCommand* requestcameraimagecommand) { + clear_commands(); + if (requestcameraimagecommand) { + set_has_requestcameraimagecommand(); + commands_.requestcameraimagecommand_ = requestcameraimagecommand; + } + // @@protoc_insertion_point(field_set_allocated:pybullet_grpc.PyBulletCommand.requestCameraImageCommand) +} + bool PyBulletCommand::has_commands() const { return commands_case() != COMMANDS_NOT_SET; } @@ -10306,11 +21934,21 @@ PyBulletCommand::CommandsCase PyBulletCommand::commands_case() const { #if !defined(_MSC_VER) || _MSC_VER >= 1900 const int PyBulletStatus::kStatusTypeFieldNumber; +const int PyBulletStatus::kBinaryBlobFieldNumber; +const int PyBulletStatus::kUnknownStatusBinaryBlobFieldNumber; const int PyBulletStatus::kUrdfStatusFieldNumber; const int PyBulletStatus::kSdfStatusFieldNumber; const int PyBulletStatus::kMjcfStatusFieldNumber; const int PyBulletStatus::kGetDynamicsStatusFieldNumber; const int PyBulletStatus::kActualStateStatusFieldNumber; +const int PyBulletStatus::kSyncBodiesStatusFieldNumber; +const int PyBulletStatus::kRequestBodyInfoStatusFieldNumber; +const int PyBulletStatus::kRequestPhysicsSimulationParametersStatusFieldNumber; +const int PyBulletStatus::kCheckVersionStatusFieldNumber; +const int PyBulletStatus::kUserConstraintStatusFieldNumber; +const int PyBulletStatus::kUserConstraintStateStatusFieldNumber; +const int PyBulletStatus::kKeyboardEventsStatusFieldNumber; +const int PyBulletStatus::kRequestCameraImageStatusFieldNumber; #endif // !defined(_MSC_VER) || _MSC_VER >= 1900 PyBulletStatus::PyBulletStatus() @@ -10324,6 +21962,8 @@ PyBulletStatus::PyBulletStatus() PyBulletStatus::PyBulletStatus(const PyBulletStatus& from) : ::google::protobuf::Message(), _internal_metadata_(NULL), + binaryblob_(from.binaryblob_), + unknownstatusbinaryblob_(from.unknownstatusbinaryblob_), _cached_size_(0) { _internal_metadata_.MergeFrom(from._internal_metadata_); statustype_ = from.statustype_; @@ -10349,6 +21989,38 @@ PyBulletStatus::PyBulletStatus(const PyBulletStatus& from) mutable_actualstatestatus()->::pybullet_grpc::SendActualStateStatus::MergeFrom(from.actualstatestatus()); break; } + case kSyncBodiesStatus: { + mutable_syncbodiesstatus()->::pybullet_grpc::SyncBodiesStatus::MergeFrom(from.syncbodiesstatus()); + break; + } + case kRequestBodyInfoStatus: { + mutable_requestbodyinfostatus()->::pybullet_grpc::RequestBodyInfoStatus::MergeFrom(from.requestbodyinfostatus()); + break; + } + case kRequestPhysicsSimulationParametersStatus: { + mutable_requestphysicssimulationparametersstatus()->::pybullet_grpc::PhysicsSimulationParameters::MergeFrom(from.requestphysicssimulationparametersstatus()); + break; + } + case kCheckVersionStatus: { + mutable_checkversionstatus()->::pybullet_grpc::CheckVersionStatus::MergeFrom(from.checkversionstatus()); + break; + } + case kUserConstraintStatus: { + mutable_userconstraintstatus()->::pybullet_grpc::UserConstraintStatus::MergeFrom(from.userconstraintstatus()); + break; + } + case kUserConstraintStateStatus: { + mutable_userconstraintstatestatus()->::pybullet_grpc::UserConstraintStateStatus::MergeFrom(from.userconstraintstatestatus()); + break; + } + case kKeyboardEventsStatus: { + mutable_keyboardeventsstatus()->::pybullet_grpc::KeyboardEventsStatus::MergeFrom(from.keyboardeventsstatus()); + break; + } + case kRequestCameraImageStatus: { + mutable_requestcameraimagestatus()->::pybullet_grpc::RequestCameraImageStatus::MergeFrom(from.requestcameraimagestatus()); + break; + } case STATUS_NOT_SET: { break; } @@ -10380,7 +22052,7 @@ void PyBulletStatus::SetCachedSize(int size) const { } const ::google::protobuf::Descriptor* PyBulletStatus::descriptor() { protobuf_pybullet_2eproto::protobuf_AssignDescriptorsOnce(); - return protobuf_pybullet_2eproto::file_level_metadata[17].descriptor; + return protobuf_pybullet_2eproto::file_level_metadata[38].descriptor; } const PyBulletStatus& PyBulletStatus::default_instance() { @@ -10419,6 +22091,38 @@ void PyBulletStatus::clear_status() { delete status_.actualstatestatus_; break; } + case kSyncBodiesStatus: { + delete status_.syncbodiesstatus_; + break; + } + case kRequestBodyInfoStatus: { + delete status_.requestbodyinfostatus_; + break; + } + case kRequestPhysicsSimulationParametersStatus: { + delete status_.requestphysicssimulationparametersstatus_; + break; + } + case kCheckVersionStatus: { + delete status_.checkversionstatus_; + break; + } + case kUserConstraintStatus: { + delete status_.userconstraintstatus_; + break; + } + case kUserConstraintStateStatus: { + delete status_.userconstraintstatestatus_; + break; + } + case kKeyboardEventsStatus: { + delete status_.keyboardeventsstatus_; + break; + } + case kRequestCameraImageStatus: { + delete status_.requestcameraimagestatus_; + break; + } case STATUS_NOT_SET: { break; } @@ -10429,6 +22133,8 @@ void PyBulletStatus::clear_status() { void PyBulletStatus::Clear() { // @@protoc_insertion_point(message_clear_start:pybullet_grpc.PyBulletStatus) + binaryblob_.Clear(); + unknownstatusbinaryblob_.Clear(); statustype_ = 0; clear_status(); } @@ -10439,7 +22145,7 @@ bool PyBulletStatus::MergePartialFromCodedStream( ::google::protobuf::uint32 tag; // @@protoc_insertion_point(parse_start:pybullet_grpc.PyBulletStatus) for (;;) { - ::std::pair< ::google::protobuf::uint32, bool> p = input->ReadTagWithCutoffNoLastTag(127u); + ::std::pair< ::google::protobuf::uint32, bool> p = input->ReadTagWithCutoffNoLastTag(16383u); tag = p.first; if (!p.second) goto handle_unusual; switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { @@ -10456,9 +22162,31 @@ bool PyBulletStatus::MergePartialFromCodedStream( break; } - // .pybullet_grpc.LoadUrdfStatus urdfStatus = 2; + // repeated bytes binaryBlob = 2; case 2: { if (tag == 18u) { + DO_(::google::protobuf::internal::WireFormatLite::ReadBytes( + input, this->add_binaryblob())); + } else { + goto handle_unusual; + } + break; + } + + // repeated bytes unknownStatusBinaryBlob = 3; + case 3: { + if (tag == 26u) { + DO_(::google::protobuf::internal::WireFormatLite::ReadBytes( + input, this->add_unknownstatusbinaryblob())); + } else { + goto handle_unusual; + } + break; + } + + // .pybullet_grpc.LoadUrdfStatus urdfStatus = 4; + case 4: { + if (tag == 34u) { DO_(::google::protobuf::internal::WireFormatLite::ReadMessageNoVirtual( input, mutable_urdfstatus())); } else { @@ -10467,9 +22195,9 @@ bool PyBulletStatus::MergePartialFromCodedStream( break; } - // .pybullet_grpc.SdfLoadedStatus sdfStatus = 3; - case 3: { - if (tag == 26u) { + // .pybullet_grpc.SdfLoadedStatus sdfStatus = 5; + case 5: { + if (tag == 42u) { DO_(::google::protobuf::internal::WireFormatLite::ReadMessageNoVirtual( input, mutable_sdfstatus())); } else { @@ -10478,9 +22206,9 @@ bool PyBulletStatus::MergePartialFromCodedStream( break; } - // .pybullet_grpc.MjcfLoadedStatus mjcfStatus = 4; - case 4: { - if (tag == 34u) { + // .pybullet_grpc.MjcfLoadedStatus mjcfStatus = 6; + case 6: { + if (tag == 50u) { DO_(::google::protobuf::internal::WireFormatLite::ReadMessageNoVirtual( input, mutable_mjcfstatus())); } else { @@ -10489,9 +22217,9 @@ bool PyBulletStatus::MergePartialFromCodedStream( break; } - // .pybullet_grpc.GetDynamicsStatus getDynamicsStatus = 5; - case 5: { - if (tag == 42u) { + // .pybullet_grpc.GetDynamicsStatus getDynamicsStatus = 7; + case 7: { + if (tag == 58u) { DO_(::google::protobuf::internal::WireFormatLite::ReadMessageNoVirtual( input, mutable_getdynamicsstatus())); } else { @@ -10500,9 +22228,9 @@ bool PyBulletStatus::MergePartialFromCodedStream( break; } - // .pybullet_grpc.SendActualStateStatus actualStateStatus = 6; - case 6: { - if (tag == 50u) { + // .pybullet_grpc.SendActualStateStatus actualStateStatus = 8; + case 8: { + if (tag == 66u) { DO_(::google::protobuf::internal::WireFormatLite::ReadMessageNoVirtual( input, mutable_actualstatestatus())); } else { @@ -10511,6 +22239,94 @@ bool PyBulletStatus::MergePartialFromCodedStream( break; } + // .pybullet_grpc.SyncBodiesStatus syncBodiesStatus = 9; + case 9: { + if (tag == 74u) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessageNoVirtual( + input, mutable_syncbodiesstatus())); + } else { + goto handle_unusual; + } + break; + } + + // .pybullet_grpc.RequestBodyInfoStatus requestBodyInfoStatus = 10; + case 10: { + if (tag == 82u) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessageNoVirtual( + input, mutable_requestbodyinfostatus())); + } else { + goto handle_unusual; + } + break; + } + + // .pybullet_grpc.PhysicsSimulationParameters requestPhysicsSimulationParametersStatus = 11; + case 11: { + if (tag == 90u) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessageNoVirtual( + input, mutable_requestphysicssimulationparametersstatus())); + } else { + goto handle_unusual; + } + break; + } + + // .pybullet_grpc.CheckVersionStatus checkVersionStatus = 12; + case 12: { + if (tag == 98u) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessageNoVirtual( + input, mutable_checkversionstatus())); + } else { + goto handle_unusual; + } + break; + } + + // .pybullet_grpc.UserConstraintStatus userConstraintStatus = 13; + case 13: { + if (tag == 106u) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessageNoVirtual( + input, mutable_userconstraintstatus())); + } else { + goto handle_unusual; + } + break; + } + + // .pybullet_grpc.UserConstraintStateStatus userConstraintStateStatus = 14; + case 14: { + if (tag == 114u) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessageNoVirtual( + input, mutable_userconstraintstatestatus())); + } else { + goto handle_unusual; + } + break; + } + + // .pybullet_grpc.KeyboardEventsStatus keyboardEventsStatus = 15; + case 15: { + if (tag == 122u) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessageNoVirtual( + input, mutable_keyboardeventsstatus())); + } else { + goto handle_unusual; + } + break; + } + + // .pybullet_grpc.RequestCameraImageStatus requestCameraImageStatus = 16; + case 16: { + if (tag == 130u) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessageNoVirtual( + input, mutable_requestcameraimagestatus())); + } else { + goto handle_unusual; + } + break; + } + default: { handle_unusual: if (tag == 0 || @@ -10540,34 +22356,94 @@ void PyBulletStatus::SerializeWithCachedSizes( ::google::protobuf::internal::WireFormatLite::WriteInt32(1, this->statustype(), output); } - // .pybullet_grpc.LoadUrdfStatus urdfStatus = 2; + // repeated bytes binaryBlob = 2; + for (int i = 0; i < this->binaryblob_size(); i++) { + ::google::protobuf::internal::WireFormatLite::WriteBytes( + 2, this->binaryblob(i), output); + } + + // repeated bytes unknownStatusBinaryBlob = 3; + for (int i = 0; i < this->unknownstatusbinaryblob_size(); i++) { + ::google::protobuf::internal::WireFormatLite::WriteBytes( + 3, this->unknownstatusbinaryblob(i), output); + } + + // .pybullet_grpc.LoadUrdfStatus urdfStatus = 4; if (has_urdfstatus()) { ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( - 2, *status_.urdfstatus_, output); + 4, *status_.urdfstatus_, output); } - // .pybullet_grpc.SdfLoadedStatus sdfStatus = 3; + // .pybullet_grpc.SdfLoadedStatus sdfStatus = 5; if (has_sdfstatus()) { ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( - 3, *status_.sdfstatus_, output); + 5, *status_.sdfstatus_, output); } - // .pybullet_grpc.MjcfLoadedStatus mjcfStatus = 4; + // .pybullet_grpc.MjcfLoadedStatus mjcfStatus = 6; if (has_mjcfstatus()) { ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( - 4, *status_.mjcfstatus_, output); + 6, *status_.mjcfstatus_, output); } - // .pybullet_grpc.GetDynamicsStatus getDynamicsStatus = 5; + // .pybullet_grpc.GetDynamicsStatus getDynamicsStatus = 7; if (has_getdynamicsstatus()) { ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( - 5, *status_.getdynamicsstatus_, output); + 7, *status_.getdynamicsstatus_, output); } - // .pybullet_grpc.SendActualStateStatus actualStateStatus = 6; + // .pybullet_grpc.SendActualStateStatus actualStateStatus = 8; if (has_actualstatestatus()) { ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( - 6, *status_.actualstatestatus_, output); + 8, *status_.actualstatestatus_, output); + } + + // .pybullet_grpc.SyncBodiesStatus syncBodiesStatus = 9; + if (has_syncbodiesstatus()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 9, *status_.syncbodiesstatus_, output); + } + + // .pybullet_grpc.RequestBodyInfoStatus requestBodyInfoStatus = 10; + if (has_requestbodyinfostatus()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 10, *status_.requestbodyinfostatus_, output); + } + + // .pybullet_grpc.PhysicsSimulationParameters requestPhysicsSimulationParametersStatus = 11; + if (has_requestphysicssimulationparametersstatus()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 11, *status_.requestphysicssimulationparametersstatus_, output); + } + + // .pybullet_grpc.CheckVersionStatus checkVersionStatus = 12; + if (has_checkversionstatus()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 12, *status_.checkversionstatus_, output); + } + + // .pybullet_grpc.UserConstraintStatus userConstraintStatus = 13; + if (has_userconstraintstatus()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 13, *status_.userconstraintstatus_, output); + } + + // .pybullet_grpc.UserConstraintStateStatus userConstraintStateStatus = 14; + if (has_userconstraintstatestatus()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 14, *status_.userconstraintstatestatus_, output); + } + + // .pybullet_grpc.KeyboardEventsStatus keyboardEventsStatus = 15; + if (has_keyboardeventsstatus()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 15, *status_.keyboardeventsstatus_, output); + } + + // .pybullet_grpc.RequestCameraImageStatus requestCameraImageStatus = 16; + if (has_requestcameraimagestatus()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 16, *status_.requestcameraimagestatus_, output); } // @@protoc_insertion_point(serialize_end:pybullet_grpc.PyBulletStatus) @@ -10582,39 +22458,107 @@ void PyBulletStatus::SerializeWithCachedSizes( target = ::google::protobuf::internal::WireFormatLite::WriteInt32ToArray(1, this->statustype(), target); } - // .pybullet_grpc.LoadUrdfStatus urdfStatus = 2; + // repeated bytes binaryBlob = 2; + for (int i = 0; i < this->binaryblob_size(); i++) { + target = ::google::protobuf::internal::WireFormatLite:: + WriteBytesToArray(2, this->binaryblob(i), target); + } + + // repeated bytes unknownStatusBinaryBlob = 3; + for (int i = 0; i < this->unknownstatusbinaryblob_size(); i++) { + target = ::google::protobuf::internal::WireFormatLite:: + WriteBytesToArray(3, this->unknownstatusbinaryblob(i), target); + } + + // .pybullet_grpc.LoadUrdfStatus urdfStatus = 4; if (has_urdfstatus()) { target = ::google::protobuf::internal::WireFormatLite:: InternalWriteMessageNoVirtualToArray( - 2, *status_.urdfstatus_, false, target); + 4, *status_.urdfstatus_, false, target); } - // .pybullet_grpc.SdfLoadedStatus sdfStatus = 3; + // .pybullet_grpc.SdfLoadedStatus sdfStatus = 5; if (has_sdfstatus()) { target = ::google::protobuf::internal::WireFormatLite:: InternalWriteMessageNoVirtualToArray( - 3, *status_.sdfstatus_, false, target); + 5, *status_.sdfstatus_, false, target); } - // .pybullet_grpc.MjcfLoadedStatus mjcfStatus = 4; + // .pybullet_grpc.MjcfLoadedStatus mjcfStatus = 6; if (has_mjcfstatus()) { target = ::google::protobuf::internal::WireFormatLite:: InternalWriteMessageNoVirtualToArray( - 4, *status_.mjcfstatus_, false, target); + 6, *status_.mjcfstatus_, false, target); } - // .pybullet_grpc.GetDynamicsStatus getDynamicsStatus = 5; + // .pybullet_grpc.GetDynamicsStatus getDynamicsStatus = 7; if (has_getdynamicsstatus()) { target = ::google::protobuf::internal::WireFormatLite:: InternalWriteMessageNoVirtualToArray( - 5, *status_.getdynamicsstatus_, false, target); + 7, *status_.getdynamicsstatus_, false, target); } - // .pybullet_grpc.SendActualStateStatus actualStateStatus = 6; + // .pybullet_grpc.SendActualStateStatus actualStateStatus = 8; if (has_actualstatestatus()) { target = ::google::protobuf::internal::WireFormatLite:: InternalWriteMessageNoVirtualToArray( - 6, *status_.actualstatestatus_, false, target); + 8, *status_.actualstatestatus_, false, target); + } + + // .pybullet_grpc.SyncBodiesStatus syncBodiesStatus = 9; + if (has_syncbodiesstatus()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageNoVirtualToArray( + 9, *status_.syncbodiesstatus_, false, target); + } + + // .pybullet_grpc.RequestBodyInfoStatus requestBodyInfoStatus = 10; + if (has_requestbodyinfostatus()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageNoVirtualToArray( + 10, *status_.requestbodyinfostatus_, false, target); + } + + // .pybullet_grpc.PhysicsSimulationParameters requestPhysicsSimulationParametersStatus = 11; + if (has_requestphysicssimulationparametersstatus()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageNoVirtualToArray( + 11, *status_.requestphysicssimulationparametersstatus_, false, target); + } + + // .pybullet_grpc.CheckVersionStatus checkVersionStatus = 12; + if (has_checkversionstatus()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageNoVirtualToArray( + 12, *status_.checkversionstatus_, false, target); + } + + // .pybullet_grpc.UserConstraintStatus userConstraintStatus = 13; + if (has_userconstraintstatus()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageNoVirtualToArray( + 13, *status_.userconstraintstatus_, false, target); + } + + // .pybullet_grpc.UserConstraintStateStatus userConstraintStateStatus = 14; + if (has_userconstraintstatestatus()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageNoVirtualToArray( + 14, *status_.userconstraintstatestatus_, false, target); + } + + // .pybullet_grpc.KeyboardEventsStatus keyboardEventsStatus = 15; + if (has_keyboardeventsstatus()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageNoVirtualToArray( + 15, *status_.keyboardeventsstatus_, false, target); + } + + // .pybullet_grpc.RequestCameraImageStatus requestCameraImageStatus = 16; + if (has_requestcameraimagestatus()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageNoVirtualToArray( + 16, *status_.requestcameraimagestatus_, false, target); } // @@protoc_insertion_point(serialize_to_array_end:pybullet_grpc.PyBulletStatus) @@ -10625,6 +22569,22 @@ size_t PyBulletStatus::ByteSizeLong() const { // @@protoc_insertion_point(message_byte_size_start:pybullet_grpc.PyBulletStatus) size_t total_size = 0; + // repeated bytes binaryBlob = 2; + total_size += 1 * + ::google::protobuf::internal::FromIntSize(this->binaryblob_size()); + for (int i = 0; i < this->binaryblob_size(); i++) { + total_size += ::google::protobuf::internal::WireFormatLite::BytesSize( + this->binaryblob(i)); + } + + // repeated bytes unknownStatusBinaryBlob = 3; + total_size += 1 * + ::google::protobuf::internal::FromIntSize(this->unknownstatusbinaryblob_size()); + for (int i = 0; i < this->unknownstatusbinaryblob_size(); i++) { + total_size += ::google::protobuf::internal::WireFormatLite::BytesSize( + this->unknownstatusbinaryblob(i)); + } + // int32 statusType = 1; if (this->statustype() != 0) { total_size += 1 + @@ -10633,41 +22593,97 @@ size_t PyBulletStatus::ByteSizeLong() const { } switch (status_case()) { - // .pybullet_grpc.LoadUrdfStatus urdfStatus = 2; + // .pybullet_grpc.LoadUrdfStatus urdfStatus = 4; case kUrdfStatus: { total_size += 1 + ::google::protobuf::internal::WireFormatLite::MessageSizeNoVirtual( *status_.urdfstatus_); break; } - // .pybullet_grpc.SdfLoadedStatus sdfStatus = 3; + // .pybullet_grpc.SdfLoadedStatus sdfStatus = 5; case kSdfStatus: { total_size += 1 + ::google::protobuf::internal::WireFormatLite::MessageSizeNoVirtual( *status_.sdfstatus_); break; } - // .pybullet_grpc.MjcfLoadedStatus mjcfStatus = 4; + // .pybullet_grpc.MjcfLoadedStatus mjcfStatus = 6; case kMjcfStatus: { total_size += 1 + ::google::protobuf::internal::WireFormatLite::MessageSizeNoVirtual( *status_.mjcfstatus_); break; } - // .pybullet_grpc.GetDynamicsStatus getDynamicsStatus = 5; + // .pybullet_grpc.GetDynamicsStatus getDynamicsStatus = 7; case kGetDynamicsStatus: { total_size += 1 + ::google::protobuf::internal::WireFormatLite::MessageSizeNoVirtual( *status_.getdynamicsstatus_); break; } - // .pybullet_grpc.SendActualStateStatus actualStateStatus = 6; + // .pybullet_grpc.SendActualStateStatus actualStateStatus = 8; case kActualStateStatus: { total_size += 1 + ::google::protobuf::internal::WireFormatLite::MessageSizeNoVirtual( *status_.actualstatestatus_); break; } + // .pybullet_grpc.SyncBodiesStatus syncBodiesStatus = 9; + case kSyncBodiesStatus: { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSizeNoVirtual( + *status_.syncbodiesstatus_); + break; + } + // .pybullet_grpc.RequestBodyInfoStatus requestBodyInfoStatus = 10; + case kRequestBodyInfoStatus: { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSizeNoVirtual( + *status_.requestbodyinfostatus_); + break; + } + // .pybullet_grpc.PhysicsSimulationParameters requestPhysicsSimulationParametersStatus = 11; + case kRequestPhysicsSimulationParametersStatus: { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSizeNoVirtual( + *status_.requestphysicssimulationparametersstatus_); + break; + } + // .pybullet_grpc.CheckVersionStatus checkVersionStatus = 12; + case kCheckVersionStatus: { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSizeNoVirtual( + *status_.checkversionstatus_); + break; + } + // .pybullet_grpc.UserConstraintStatus userConstraintStatus = 13; + case kUserConstraintStatus: { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSizeNoVirtual( + *status_.userconstraintstatus_); + break; + } + // .pybullet_grpc.UserConstraintStateStatus userConstraintStateStatus = 14; + case kUserConstraintStateStatus: { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSizeNoVirtual( + *status_.userconstraintstatestatus_); + break; + } + // .pybullet_grpc.KeyboardEventsStatus keyboardEventsStatus = 15; + case kKeyboardEventsStatus: { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSizeNoVirtual( + *status_.keyboardeventsstatus_); + break; + } + // .pybullet_grpc.RequestCameraImageStatus requestCameraImageStatus = 16; + case kRequestCameraImageStatus: { + total_size += 2 + + ::google::protobuf::internal::WireFormatLite::MessageSizeNoVirtual( + *status_.requestcameraimagestatus_); + break; + } case STATUS_NOT_SET: { break; } @@ -10698,6 +22714,8 @@ 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_); + binaryblob_.MergeFrom(from.binaryblob_); + unknownstatusbinaryblob_.MergeFrom(from.unknownstatusbinaryblob_); if (from.statustype() != 0) { set_statustype(from.statustype()); } @@ -10722,6 +22740,38 @@ void PyBulletStatus::MergeFrom(const PyBulletStatus& from) { mutable_actualstatestatus()->::pybullet_grpc::SendActualStateStatus::MergeFrom(from.actualstatestatus()); break; } + case kSyncBodiesStatus: { + mutable_syncbodiesstatus()->::pybullet_grpc::SyncBodiesStatus::MergeFrom(from.syncbodiesstatus()); + break; + } + case kRequestBodyInfoStatus: { + mutable_requestbodyinfostatus()->::pybullet_grpc::RequestBodyInfoStatus::MergeFrom(from.requestbodyinfostatus()); + break; + } + case kRequestPhysicsSimulationParametersStatus: { + mutable_requestphysicssimulationparametersstatus()->::pybullet_grpc::PhysicsSimulationParameters::MergeFrom(from.requestphysicssimulationparametersstatus()); + break; + } + case kCheckVersionStatus: { + mutable_checkversionstatus()->::pybullet_grpc::CheckVersionStatus::MergeFrom(from.checkversionstatus()); + break; + } + case kUserConstraintStatus: { + mutable_userconstraintstatus()->::pybullet_grpc::UserConstraintStatus::MergeFrom(from.userconstraintstatus()); + break; + } + case kUserConstraintStateStatus: { + mutable_userconstraintstatestatus()->::pybullet_grpc::UserConstraintStateStatus::MergeFrom(from.userconstraintstatestatus()); + break; + } + case kKeyboardEventsStatus: { + mutable_keyboardeventsstatus()->::pybullet_grpc::KeyboardEventsStatus::MergeFrom(from.keyboardeventsstatus()); + break; + } + case kRequestCameraImageStatus: { + mutable_requestcameraimagestatus()->::pybullet_grpc::RequestCameraImageStatus::MergeFrom(from.requestcameraimagestatus()); + break; + } case STATUS_NOT_SET: { break; } @@ -10751,6 +22801,8 @@ void PyBulletStatus::Swap(PyBulletStatus* other) { InternalSwap(other); } void PyBulletStatus::InternalSwap(PyBulletStatus* other) { + binaryblob_.UnsafeArenaSwap(&other->binaryblob_); + unknownstatusbinaryblob_.UnsafeArenaSwap(&other->unknownstatusbinaryblob_); std::swap(statustype_, other->statustype_); std::swap(status_, other->status_); std::swap(_oneof_case_[0], other->_oneof_case_[0]); @@ -10759,7 +22811,7 @@ void PyBulletStatus::InternalSwap(PyBulletStatus* other) { ::google::protobuf::Metadata PyBulletStatus::GetMetadata() const { protobuf_pybullet_2eproto::protobuf_AssignDescriptorsOnce(); - return protobuf_pybullet_2eproto::file_level_metadata[17]; + return protobuf_pybullet_2eproto::file_level_metadata[38]; } #if PROTOBUF_INLINE_NOT_IN_HEADERS @@ -10779,7 +22831,117 @@ void PyBulletStatus::set_statustype(::google::protobuf::int32 value) { // @@protoc_insertion_point(field_set:pybullet_grpc.PyBulletStatus.statusType) } -// .pybullet_grpc.LoadUrdfStatus urdfStatus = 2; +// repeated bytes binaryBlob = 2; +int PyBulletStatus::binaryblob_size() const { + return binaryblob_.size(); +} +void PyBulletStatus::clear_binaryblob() { + binaryblob_.Clear(); +} +const ::std::string& PyBulletStatus::binaryblob(int index) const { + // @@protoc_insertion_point(field_get:pybullet_grpc.PyBulletStatus.binaryBlob) + return binaryblob_.Get(index); +} +::std::string* PyBulletStatus::mutable_binaryblob(int index) { + // @@protoc_insertion_point(field_mutable:pybullet_grpc.PyBulletStatus.binaryBlob) + return binaryblob_.Mutable(index); +} +void PyBulletStatus::set_binaryblob(int index, const ::std::string& value) { + // @@protoc_insertion_point(field_set:pybullet_grpc.PyBulletStatus.binaryBlob) + binaryblob_.Mutable(index)->assign(value); +} +void PyBulletStatus::set_binaryblob(int index, const char* value) { + binaryblob_.Mutable(index)->assign(value); + // @@protoc_insertion_point(field_set_char:pybullet_grpc.PyBulletStatus.binaryBlob) +} +void PyBulletStatus::set_binaryblob(int index, const void* value, size_t size) { + binaryblob_.Mutable(index)->assign( + reinterpret_cast(value), size); + // @@protoc_insertion_point(field_set_pointer:pybullet_grpc.PyBulletStatus.binaryBlob) +} +::std::string* PyBulletStatus::add_binaryblob() { + // @@protoc_insertion_point(field_add_mutable:pybullet_grpc.PyBulletStatus.binaryBlob) + return binaryblob_.Add(); +} +void PyBulletStatus::add_binaryblob(const ::std::string& value) { + binaryblob_.Add()->assign(value); + // @@protoc_insertion_point(field_add:pybullet_grpc.PyBulletStatus.binaryBlob) +} +void PyBulletStatus::add_binaryblob(const char* value) { + binaryblob_.Add()->assign(value); + // @@protoc_insertion_point(field_add_char:pybullet_grpc.PyBulletStatus.binaryBlob) +} +void PyBulletStatus::add_binaryblob(const void* value, size_t size) { + binaryblob_.Add()->assign(reinterpret_cast(value), size); + // @@protoc_insertion_point(field_add_pointer:pybullet_grpc.PyBulletStatus.binaryBlob) +} +const ::google::protobuf::RepeatedPtrField< ::std::string>& +PyBulletStatus::binaryblob() const { + // @@protoc_insertion_point(field_list:pybullet_grpc.PyBulletStatus.binaryBlob) + return binaryblob_; +} +::google::protobuf::RepeatedPtrField< ::std::string>* +PyBulletStatus::mutable_binaryblob() { + // @@protoc_insertion_point(field_mutable_list:pybullet_grpc.PyBulletStatus.binaryBlob) + return &binaryblob_; +} + +// repeated bytes unknownStatusBinaryBlob = 3; +int PyBulletStatus::unknownstatusbinaryblob_size() const { + return unknownstatusbinaryblob_.size(); +} +void PyBulletStatus::clear_unknownstatusbinaryblob() { + unknownstatusbinaryblob_.Clear(); +} +const ::std::string& PyBulletStatus::unknownstatusbinaryblob(int index) const { + // @@protoc_insertion_point(field_get:pybullet_grpc.PyBulletStatus.unknownStatusBinaryBlob) + return unknownstatusbinaryblob_.Get(index); +} +::std::string* PyBulletStatus::mutable_unknownstatusbinaryblob(int index) { + // @@protoc_insertion_point(field_mutable:pybullet_grpc.PyBulletStatus.unknownStatusBinaryBlob) + return unknownstatusbinaryblob_.Mutable(index); +} +void PyBulletStatus::set_unknownstatusbinaryblob(int index, const ::std::string& value) { + // @@protoc_insertion_point(field_set:pybullet_grpc.PyBulletStatus.unknownStatusBinaryBlob) + unknownstatusbinaryblob_.Mutable(index)->assign(value); +} +void PyBulletStatus::set_unknownstatusbinaryblob(int index, const char* value) { + unknownstatusbinaryblob_.Mutable(index)->assign(value); + // @@protoc_insertion_point(field_set_char:pybullet_grpc.PyBulletStatus.unknownStatusBinaryBlob) +} +void PyBulletStatus::set_unknownstatusbinaryblob(int index, const void* value, size_t size) { + unknownstatusbinaryblob_.Mutable(index)->assign( + reinterpret_cast(value), size); + // @@protoc_insertion_point(field_set_pointer:pybullet_grpc.PyBulletStatus.unknownStatusBinaryBlob) +} +::std::string* PyBulletStatus::add_unknownstatusbinaryblob() { + // @@protoc_insertion_point(field_add_mutable:pybullet_grpc.PyBulletStatus.unknownStatusBinaryBlob) + return unknownstatusbinaryblob_.Add(); +} +void PyBulletStatus::add_unknownstatusbinaryblob(const ::std::string& value) { + unknownstatusbinaryblob_.Add()->assign(value); + // @@protoc_insertion_point(field_add:pybullet_grpc.PyBulletStatus.unknownStatusBinaryBlob) +} +void PyBulletStatus::add_unknownstatusbinaryblob(const char* value) { + unknownstatusbinaryblob_.Add()->assign(value); + // @@protoc_insertion_point(field_add_char:pybullet_grpc.PyBulletStatus.unknownStatusBinaryBlob) +} +void PyBulletStatus::add_unknownstatusbinaryblob(const void* value, size_t size) { + unknownstatusbinaryblob_.Add()->assign(reinterpret_cast(value), size); + // @@protoc_insertion_point(field_add_pointer:pybullet_grpc.PyBulletStatus.unknownStatusBinaryBlob) +} +const ::google::protobuf::RepeatedPtrField< ::std::string>& +PyBulletStatus::unknownstatusbinaryblob() const { + // @@protoc_insertion_point(field_list:pybullet_grpc.PyBulletStatus.unknownStatusBinaryBlob) + return unknownstatusbinaryblob_; +} +::google::protobuf::RepeatedPtrField< ::std::string>* +PyBulletStatus::mutable_unknownstatusbinaryblob() { + // @@protoc_insertion_point(field_mutable_list:pybullet_grpc.PyBulletStatus.unknownStatusBinaryBlob) + return &unknownstatusbinaryblob_; +} + +// .pybullet_grpc.LoadUrdfStatus urdfStatus = 4; bool PyBulletStatus::has_urdfstatus() const { return status_case() == kUrdfStatus; } @@ -10827,7 +22989,7 @@ void PyBulletStatus::set_allocated_urdfstatus(::pybullet_grpc::LoadUrdfStatus* u // @@protoc_insertion_point(field_set_allocated:pybullet_grpc.PyBulletStatus.urdfStatus) } -// .pybullet_grpc.SdfLoadedStatus sdfStatus = 3; +// .pybullet_grpc.SdfLoadedStatus sdfStatus = 5; bool PyBulletStatus::has_sdfstatus() const { return status_case() == kSdfStatus; } @@ -10875,7 +23037,7 @@ void PyBulletStatus::set_allocated_sdfstatus(::pybullet_grpc::SdfLoadedStatus* s // @@protoc_insertion_point(field_set_allocated:pybullet_grpc.PyBulletStatus.sdfStatus) } -// .pybullet_grpc.MjcfLoadedStatus mjcfStatus = 4; +// .pybullet_grpc.MjcfLoadedStatus mjcfStatus = 6; bool PyBulletStatus::has_mjcfstatus() const { return status_case() == kMjcfStatus; } @@ -10923,7 +23085,7 @@ void PyBulletStatus::set_allocated_mjcfstatus(::pybullet_grpc::MjcfLoadedStatus* // @@protoc_insertion_point(field_set_allocated:pybullet_grpc.PyBulletStatus.mjcfStatus) } -// .pybullet_grpc.GetDynamicsStatus getDynamicsStatus = 5; +// .pybullet_grpc.GetDynamicsStatus getDynamicsStatus = 7; bool PyBulletStatus::has_getdynamicsstatus() const { return status_case() == kGetDynamicsStatus; } @@ -10971,7 +23133,7 @@ void PyBulletStatus::set_allocated_getdynamicsstatus(::pybullet_grpc::GetDynamic // @@protoc_insertion_point(field_set_allocated:pybullet_grpc.PyBulletStatus.getDynamicsStatus) } -// .pybullet_grpc.SendActualStateStatus actualStateStatus = 6; +// .pybullet_grpc.SendActualStateStatus actualStateStatus = 8; bool PyBulletStatus::has_actualstatestatus() const { return status_case() == kActualStateStatus; } @@ -11019,6 +23181,390 @@ void PyBulletStatus::set_allocated_actualstatestatus(::pybullet_grpc::SendActual // @@protoc_insertion_point(field_set_allocated:pybullet_grpc.PyBulletStatus.actualStateStatus) } +// .pybullet_grpc.SyncBodiesStatus syncBodiesStatus = 9; +bool PyBulletStatus::has_syncbodiesstatus() const { + return status_case() == kSyncBodiesStatus; +} +void PyBulletStatus::set_has_syncbodiesstatus() { + _oneof_case_[0] = kSyncBodiesStatus; +} +void PyBulletStatus::clear_syncbodiesstatus() { + if (has_syncbodiesstatus()) { + delete status_.syncbodiesstatus_; + clear_has_status(); + } +} + const ::pybullet_grpc::SyncBodiesStatus& PyBulletStatus::syncbodiesstatus() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.PyBulletStatus.syncBodiesStatus) + return has_syncbodiesstatus() + ? *status_.syncbodiesstatus_ + : ::pybullet_grpc::SyncBodiesStatus::default_instance(); +} +::pybullet_grpc::SyncBodiesStatus* PyBulletStatus::mutable_syncbodiesstatus() { + if (!has_syncbodiesstatus()) { + clear_status(); + set_has_syncbodiesstatus(); + status_.syncbodiesstatus_ = new ::pybullet_grpc::SyncBodiesStatus; + } + // @@protoc_insertion_point(field_mutable:pybullet_grpc.PyBulletStatus.syncBodiesStatus) + return status_.syncbodiesstatus_; +} +::pybullet_grpc::SyncBodiesStatus* PyBulletStatus::release_syncbodiesstatus() { + // @@protoc_insertion_point(field_release:pybullet_grpc.PyBulletStatus.syncBodiesStatus) + if (has_syncbodiesstatus()) { + clear_has_status(); + ::pybullet_grpc::SyncBodiesStatus* temp = status_.syncbodiesstatus_; + status_.syncbodiesstatus_ = NULL; + return temp; + } else { + return NULL; + } +} +void PyBulletStatus::set_allocated_syncbodiesstatus(::pybullet_grpc::SyncBodiesStatus* syncbodiesstatus) { + clear_status(); + if (syncbodiesstatus) { + set_has_syncbodiesstatus(); + status_.syncbodiesstatus_ = syncbodiesstatus; + } + // @@protoc_insertion_point(field_set_allocated:pybullet_grpc.PyBulletStatus.syncBodiesStatus) +} + +// .pybullet_grpc.RequestBodyInfoStatus requestBodyInfoStatus = 10; +bool PyBulletStatus::has_requestbodyinfostatus() const { + return status_case() == kRequestBodyInfoStatus; +} +void PyBulletStatus::set_has_requestbodyinfostatus() { + _oneof_case_[0] = kRequestBodyInfoStatus; +} +void PyBulletStatus::clear_requestbodyinfostatus() { + if (has_requestbodyinfostatus()) { + delete status_.requestbodyinfostatus_; + clear_has_status(); + } +} + const ::pybullet_grpc::RequestBodyInfoStatus& PyBulletStatus::requestbodyinfostatus() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.PyBulletStatus.requestBodyInfoStatus) + return has_requestbodyinfostatus() + ? *status_.requestbodyinfostatus_ + : ::pybullet_grpc::RequestBodyInfoStatus::default_instance(); +} +::pybullet_grpc::RequestBodyInfoStatus* PyBulletStatus::mutable_requestbodyinfostatus() { + if (!has_requestbodyinfostatus()) { + clear_status(); + set_has_requestbodyinfostatus(); + status_.requestbodyinfostatus_ = new ::pybullet_grpc::RequestBodyInfoStatus; + } + // @@protoc_insertion_point(field_mutable:pybullet_grpc.PyBulletStatus.requestBodyInfoStatus) + return status_.requestbodyinfostatus_; +} +::pybullet_grpc::RequestBodyInfoStatus* PyBulletStatus::release_requestbodyinfostatus() { + // @@protoc_insertion_point(field_release:pybullet_grpc.PyBulletStatus.requestBodyInfoStatus) + if (has_requestbodyinfostatus()) { + clear_has_status(); + ::pybullet_grpc::RequestBodyInfoStatus* temp = status_.requestbodyinfostatus_; + status_.requestbodyinfostatus_ = NULL; + return temp; + } else { + return NULL; + } +} +void PyBulletStatus::set_allocated_requestbodyinfostatus(::pybullet_grpc::RequestBodyInfoStatus* requestbodyinfostatus) { + clear_status(); + if (requestbodyinfostatus) { + set_has_requestbodyinfostatus(); + status_.requestbodyinfostatus_ = requestbodyinfostatus; + } + // @@protoc_insertion_point(field_set_allocated:pybullet_grpc.PyBulletStatus.requestBodyInfoStatus) +} + +// .pybullet_grpc.PhysicsSimulationParameters requestPhysicsSimulationParametersStatus = 11; +bool PyBulletStatus::has_requestphysicssimulationparametersstatus() const { + return status_case() == kRequestPhysicsSimulationParametersStatus; +} +void PyBulletStatus::set_has_requestphysicssimulationparametersstatus() { + _oneof_case_[0] = kRequestPhysicsSimulationParametersStatus; +} +void PyBulletStatus::clear_requestphysicssimulationparametersstatus() { + if (has_requestphysicssimulationparametersstatus()) { + delete status_.requestphysicssimulationparametersstatus_; + clear_has_status(); + } +} + const ::pybullet_grpc::PhysicsSimulationParameters& PyBulletStatus::requestphysicssimulationparametersstatus() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.PyBulletStatus.requestPhysicsSimulationParametersStatus) + return has_requestphysicssimulationparametersstatus() + ? *status_.requestphysicssimulationparametersstatus_ + : ::pybullet_grpc::PhysicsSimulationParameters::default_instance(); +} +::pybullet_grpc::PhysicsSimulationParameters* PyBulletStatus::mutable_requestphysicssimulationparametersstatus() { + if (!has_requestphysicssimulationparametersstatus()) { + clear_status(); + set_has_requestphysicssimulationparametersstatus(); + status_.requestphysicssimulationparametersstatus_ = new ::pybullet_grpc::PhysicsSimulationParameters; + } + // @@protoc_insertion_point(field_mutable:pybullet_grpc.PyBulletStatus.requestPhysicsSimulationParametersStatus) + return status_.requestphysicssimulationparametersstatus_; +} +::pybullet_grpc::PhysicsSimulationParameters* PyBulletStatus::release_requestphysicssimulationparametersstatus() { + // @@protoc_insertion_point(field_release:pybullet_grpc.PyBulletStatus.requestPhysicsSimulationParametersStatus) + if (has_requestphysicssimulationparametersstatus()) { + clear_has_status(); + ::pybullet_grpc::PhysicsSimulationParameters* temp = status_.requestphysicssimulationparametersstatus_; + status_.requestphysicssimulationparametersstatus_ = NULL; + return temp; + } else { + return NULL; + } +} +void PyBulletStatus::set_allocated_requestphysicssimulationparametersstatus(::pybullet_grpc::PhysicsSimulationParameters* requestphysicssimulationparametersstatus) { + clear_status(); + if (requestphysicssimulationparametersstatus) { + set_has_requestphysicssimulationparametersstatus(); + status_.requestphysicssimulationparametersstatus_ = requestphysicssimulationparametersstatus; + } + // @@protoc_insertion_point(field_set_allocated:pybullet_grpc.PyBulletStatus.requestPhysicsSimulationParametersStatus) +} + +// .pybullet_grpc.CheckVersionStatus checkVersionStatus = 12; +bool PyBulletStatus::has_checkversionstatus() const { + return status_case() == kCheckVersionStatus; +} +void PyBulletStatus::set_has_checkversionstatus() { + _oneof_case_[0] = kCheckVersionStatus; +} +void PyBulletStatus::clear_checkversionstatus() { + if (has_checkversionstatus()) { + delete status_.checkversionstatus_; + clear_has_status(); + } +} + const ::pybullet_grpc::CheckVersionStatus& PyBulletStatus::checkversionstatus() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.PyBulletStatus.checkVersionStatus) + return has_checkversionstatus() + ? *status_.checkversionstatus_ + : ::pybullet_grpc::CheckVersionStatus::default_instance(); +} +::pybullet_grpc::CheckVersionStatus* PyBulletStatus::mutable_checkversionstatus() { + if (!has_checkversionstatus()) { + clear_status(); + set_has_checkversionstatus(); + status_.checkversionstatus_ = new ::pybullet_grpc::CheckVersionStatus; + } + // @@protoc_insertion_point(field_mutable:pybullet_grpc.PyBulletStatus.checkVersionStatus) + return status_.checkversionstatus_; +} +::pybullet_grpc::CheckVersionStatus* PyBulletStatus::release_checkversionstatus() { + // @@protoc_insertion_point(field_release:pybullet_grpc.PyBulletStatus.checkVersionStatus) + if (has_checkversionstatus()) { + clear_has_status(); + ::pybullet_grpc::CheckVersionStatus* temp = status_.checkversionstatus_; + status_.checkversionstatus_ = NULL; + return temp; + } else { + return NULL; + } +} +void PyBulletStatus::set_allocated_checkversionstatus(::pybullet_grpc::CheckVersionStatus* checkversionstatus) { + clear_status(); + if (checkversionstatus) { + set_has_checkversionstatus(); + status_.checkversionstatus_ = checkversionstatus; + } + // @@protoc_insertion_point(field_set_allocated:pybullet_grpc.PyBulletStatus.checkVersionStatus) +} + +// .pybullet_grpc.UserConstraintStatus userConstraintStatus = 13; +bool PyBulletStatus::has_userconstraintstatus() const { + return status_case() == kUserConstraintStatus; +} +void PyBulletStatus::set_has_userconstraintstatus() { + _oneof_case_[0] = kUserConstraintStatus; +} +void PyBulletStatus::clear_userconstraintstatus() { + if (has_userconstraintstatus()) { + delete status_.userconstraintstatus_; + clear_has_status(); + } +} + const ::pybullet_grpc::UserConstraintStatus& PyBulletStatus::userconstraintstatus() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.PyBulletStatus.userConstraintStatus) + return has_userconstraintstatus() + ? *status_.userconstraintstatus_ + : ::pybullet_grpc::UserConstraintStatus::default_instance(); +} +::pybullet_grpc::UserConstraintStatus* PyBulletStatus::mutable_userconstraintstatus() { + if (!has_userconstraintstatus()) { + clear_status(); + set_has_userconstraintstatus(); + status_.userconstraintstatus_ = new ::pybullet_grpc::UserConstraintStatus; + } + // @@protoc_insertion_point(field_mutable:pybullet_grpc.PyBulletStatus.userConstraintStatus) + return status_.userconstraintstatus_; +} +::pybullet_grpc::UserConstraintStatus* PyBulletStatus::release_userconstraintstatus() { + // @@protoc_insertion_point(field_release:pybullet_grpc.PyBulletStatus.userConstraintStatus) + if (has_userconstraintstatus()) { + clear_has_status(); + ::pybullet_grpc::UserConstraintStatus* temp = status_.userconstraintstatus_; + status_.userconstraintstatus_ = NULL; + return temp; + } else { + return NULL; + } +} +void PyBulletStatus::set_allocated_userconstraintstatus(::pybullet_grpc::UserConstraintStatus* userconstraintstatus) { + clear_status(); + if (userconstraintstatus) { + set_has_userconstraintstatus(); + status_.userconstraintstatus_ = userconstraintstatus; + } + // @@protoc_insertion_point(field_set_allocated:pybullet_grpc.PyBulletStatus.userConstraintStatus) +} + +// .pybullet_grpc.UserConstraintStateStatus userConstraintStateStatus = 14; +bool PyBulletStatus::has_userconstraintstatestatus() const { + return status_case() == kUserConstraintStateStatus; +} +void PyBulletStatus::set_has_userconstraintstatestatus() { + _oneof_case_[0] = kUserConstraintStateStatus; +} +void PyBulletStatus::clear_userconstraintstatestatus() { + if (has_userconstraintstatestatus()) { + delete status_.userconstraintstatestatus_; + clear_has_status(); + } +} + const ::pybullet_grpc::UserConstraintStateStatus& PyBulletStatus::userconstraintstatestatus() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.PyBulletStatus.userConstraintStateStatus) + return has_userconstraintstatestatus() + ? *status_.userconstraintstatestatus_ + : ::pybullet_grpc::UserConstraintStateStatus::default_instance(); +} +::pybullet_grpc::UserConstraintStateStatus* PyBulletStatus::mutable_userconstraintstatestatus() { + if (!has_userconstraintstatestatus()) { + clear_status(); + set_has_userconstraintstatestatus(); + status_.userconstraintstatestatus_ = new ::pybullet_grpc::UserConstraintStateStatus; + } + // @@protoc_insertion_point(field_mutable:pybullet_grpc.PyBulletStatus.userConstraintStateStatus) + return status_.userconstraintstatestatus_; +} +::pybullet_grpc::UserConstraintStateStatus* PyBulletStatus::release_userconstraintstatestatus() { + // @@protoc_insertion_point(field_release:pybullet_grpc.PyBulletStatus.userConstraintStateStatus) + if (has_userconstraintstatestatus()) { + clear_has_status(); + ::pybullet_grpc::UserConstraintStateStatus* temp = status_.userconstraintstatestatus_; + status_.userconstraintstatestatus_ = NULL; + return temp; + } else { + return NULL; + } +} +void PyBulletStatus::set_allocated_userconstraintstatestatus(::pybullet_grpc::UserConstraintStateStatus* userconstraintstatestatus) { + clear_status(); + if (userconstraintstatestatus) { + set_has_userconstraintstatestatus(); + status_.userconstraintstatestatus_ = userconstraintstatestatus; + } + // @@protoc_insertion_point(field_set_allocated:pybullet_grpc.PyBulletStatus.userConstraintStateStatus) +} + +// .pybullet_grpc.KeyboardEventsStatus keyboardEventsStatus = 15; +bool PyBulletStatus::has_keyboardeventsstatus() const { + return status_case() == kKeyboardEventsStatus; +} +void PyBulletStatus::set_has_keyboardeventsstatus() { + _oneof_case_[0] = kKeyboardEventsStatus; +} +void PyBulletStatus::clear_keyboardeventsstatus() { + if (has_keyboardeventsstatus()) { + delete status_.keyboardeventsstatus_; + clear_has_status(); + } +} + const ::pybullet_grpc::KeyboardEventsStatus& PyBulletStatus::keyboardeventsstatus() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.PyBulletStatus.keyboardEventsStatus) + return has_keyboardeventsstatus() + ? *status_.keyboardeventsstatus_ + : ::pybullet_grpc::KeyboardEventsStatus::default_instance(); +} +::pybullet_grpc::KeyboardEventsStatus* PyBulletStatus::mutable_keyboardeventsstatus() { + if (!has_keyboardeventsstatus()) { + clear_status(); + set_has_keyboardeventsstatus(); + status_.keyboardeventsstatus_ = new ::pybullet_grpc::KeyboardEventsStatus; + } + // @@protoc_insertion_point(field_mutable:pybullet_grpc.PyBulletStatus.keyboardEventsStatus) + return status_.keyboardeventsstatus_; +} +::pybullet_grpc::KeyboardEventsStatus* PyBulletStatus::release_keyboardeventsstatus() { + // @@protoc_insertion_point(field_release:pybullet_grpc.PyBulletStatus.keyboardEventsStatus) + if (has_keyboardeventsstatus()) { + clear_has_status(); + ::pybullet_grpc::KeyboardEventsStatus* temp = status_.keyboardeventsstatus_; + status_.keyboardeventsstatus_ = NULL; + return temp; + } else { + return NULL; + } +} +void PyBulletStatus::set_allocated_keyboardeventsstatus(::pybullet_grpc::KeyboardEventsStatus* keyboardeventsstatus) { + clear_status(); + if (keyboardeventsstatus) { + set_has_keyboardeventsstatus(); + status_.keyboardeventsstatus_ = keyboardeventsstatus; + } + // @@protoc_insertion_point(field_set_allocated:pybullet_grpc.PyBulletStatus.keyboardEventsStatus) +} + +// .pybullet_grpc.RequestCameraImageStatus requestCameraImageStatus = 16; +bool PyBulletStatus::has_requestcameraimagestatus() const { + return status_case() == kRequestCameraImageStatus; +} +void PyBulletStatus::set_has_requestcameraimagestatus() { + _oneof_case_[0] = kRequestCameraImageStatus; +} +void PyBulletStatus::clear_requestcameraimagestatus() { + if (has_requestcameraimagestatus()) { + delete status_.requestcameraimagestatus_; + clear_has_status(); + } +} + const ::pybullet_grpc::RequestCameraImageStatus& PyBulletStatus::requestcameraimagestatus() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.PyBulletStatus.requestCameraImageStatus) + return has_requestcameraimagestatus() + ? *status_.requestcameraimagestatus_ + : ::pybullet_grpc::RequestCameraImageStatus::default_instance(); +} +::pybullet_grpc::RequestCameraImageStatus* PyBulletStatus::mutable_requestcameraimagestatus() { + if (!has_requestcameraimagestatus()) { + clear_status(); + set_has_requestcameraimagestatus(); + status_.requestcameraimagestatus_ = new ::pybullet_grpc::RequestCameraImageStatus; + } + // @@protoc_insertion_point(field_mutable:pybullet_grpc.PyBulletStatus.requestCameraImageStatus) + return status_.requestcameraimagestatus_; +} +::pybullet_grpc::RequestCameraImageStatus* PyBulletStatus::release_requestcameraimagestatus() { + // @@protoc_insertion_point(field_release:pybullet_grpc.PyBulletStatus.requestCameraImageStatus) + if (has_requestcameraimagestatus()) { + clear_has_status(); + ::pybullet_grpc::RequestCameraImageStatus* temp = status_.requestcameraimagestatus_; + status_.requestcameraimagestatus_ = NULL; + return temp; + } else { + return NULL; + } +} +void PyBulletStatus::set_allocated_requestcameraimagestatus(::pybullet_grpc::RequestCameraImageStatus* requestcameraimagestatus) { + clear_status(); + if (requestcameraimagestatus) { + set_has_requestcameraimagestatus(); + status_.requestcameraimagestatus_ = requestcameraimagestatus; + } + // @@protoc_insertion_point(field_set_allocated:pybullet_grpc.PyBulletStatus.requestCameraImageStatus) +} + bool PyBulletStatus::has_status() const { return status_case() != STATUS_NOT_SET; } diff --git a/examples/SharedMemory/grpc/pybullet.pb.h b/examples/SharedMemory/grpc/pybullet.pb.h index 526b694f3..9e3209131 100644 --- a/examples/SharedMemory/grpc/pybullet.pb.h +++ b/examples/SharedMemory/grpc/pybullet.pb.h @@ -33,6 +33,15 @@ namespace pybullet_grpc { class ChangeDynamicsCommand; class ChangeDynamicsCommandDefaultTypeInternal; extern ChangeDynamicsCommandDefaultTypeInternal _ChangeDynamicsCommand_default_instance_; +class CheckVersionCommand; +class CheckVersionCommandDefaultTypeInternal; +extern CheckVersionCommandDefaultTypeInternal _CheckVersionCommand_default_instance_; +class CheckVersionStatus; +class CheckVersionStatusDefaultTypeInternal; +extern CheckVersionStatusDefaultTypeInternal _CheckVersionStatus_default_instance_; +class ConfigureOpenGLVisualizerCommand; +class ConfigureOpenGLVisualizerCommandDefaultTypeInternal; +extern ConfigureOpenGLVisualizerCommandDefaultTypeInternal _ConfigureOpenGLVisualizerCommand_default_instance_; class GetDynamicsCommand; class GetDynamicsCommandDefaultTypeInternal; extern GetDynamicsCommandDefaultTypeInternal _GetDynamicsCommand_default_instance_; @@ -42,6 +51,15 @@ extern GetDynamicsStatusDefaultTypeInternal _GetDynamicsStatus_default_instance_ class InitPoseCommand; class InitPoseCommandDefaultTypeInternal; extern InitPoseCommandDefaultTypeInternal _InitPoseCommand_default_instance_; +class JointMotorControlCommand; +class JointMotorControlCommandDefaultTypeInternal; +extern JointMotorControlCommandDefaultTypeInternal _JointMotorControlCommand_default_instance_; +class KeyboardEvent; +class KeyboardEventDefaultTypeInternal; +extern KeyboardEventDefaultTypeInternal _KeyboardEvent_default_instance_; +class KeyboardEventsStatus; +class KeyboardEventsStatusDefaultTypeInternal; +extern KeyboardEventsStatusDefaultTypeInternal _KeyboardEventsStatus_default_instance_; class LoadMjcfCommand; class LoadMjcfCommandDefaultTypeInternal; extern LoadMjcfCommandDefaultTypeInternal _LoadMjcfCommand_default_instance_; @@ -57,6 +75,12 @@ extern LoadUrdfStatusDefaultTypeInternal _LoadUrdfStatus_default_instance_; class MjcfLoadedStatus; class MjcfLoadedStatusDefaultTypeInternal; extern MjcfLoadedStatusDefaultTypeInternal _MjcfLoadedStatus_default_instance_; +class PhysicsSimulationParameters; +class PhysicsSimulationParametersDefaultTypeInternal; +extern PhysicsSimulationParametersDefaultTypeInternal _PhysicsSimulationParameters_default_instance_; +class PhysicsSimulationParametersCommand; +class PhysicsSimulationParametersCommandDefaultTypeInternal; +extern PhysicsSimulationParametersCommandDefaultTypeInternal _PhysicsSimulationParametersCommand_default_instance_; class PyBulletCommand; class PyBulletCommandDefaultTypeInternal; extern PyBulletCommandDefaultTypeInternal _PyBulletCommand_default_instance_; @@ -66,6 +90,21 @@ extern PyBulletStatusDefaultTypeInternal _PyBulletStatus_default_instance_; class RequestActualStateCommand; class RequestActualStateCommandDefaultTypeInternal; extern RequestActualStateCommandDefaultTypeInternal _RequestActualStateCommand_default_instance_; +class RequestBodyInfoCommand; +class RequestBodyInfoCommandDefaultTypeInternal; +extern RequestBodyInfoCommandDefaultTypeInternal _RequestBodyInfoCommand_default_instance_; +class RequestBodyInfoStatus; +class RequestBodyInfoStatusDefaultTypeInternal; +extern RequestBodyInfoStatusDefaultTypeInternal _RequestBodyInfoStatus_default_instance_; +class RequestCameraImageCommand; +class RequestCameraImageCommandDefaultTypeInternal; +extern RequestCameraImageCommandDefaultTypeInternal _RequestCameraImageCommand_default_instance_; +class RequestCameraImageStatus; +class RequestCameraImageStatusDefaultTypeInternal; +extern RequestCameraImageStatusDefaultTypeInternal _RequestCameraImageStatus_default_instance_; +class RequestKeyboardEventsCommand; +class RequestKeyboardEventsCommandDefaultTypeInternal; +extern RequestKeyboardEventsCommandDefaultTypeInternal _RequestKeyboardEventsCommand_default_instance_; class SdfLoadedStatus; class SdfLoadedStatusDefaultTypeInternal; extern SdfLoadedStatusDefaultTypeInternal _SdfLoadedStatus_default_instance_; @@ -75,15 +114,39 @@ extern SendActualStateStatusDefaultTypeInternal _SendActualStateStatus_default_i class StepSimulationCommand; class StepSimulationCommandDefaultTypeInternal; extern StepSimulationCommandDefaultTypeInternal _StepSimulationCommand_default_instance_; +class SyncBodiesCommand; +class SyncBodiesCommandDefaultTypeInternal; +extern SyncBodiesCommandDefaultTypeInternal _SyncBodiesCommand_default_instance_; +class SyncBodiesStatus; +class SyncBodiesStatusDefaultTypeInternal; +extern SyncBodiesStatusDefaultTypeInternal _SyncBodiesStatus_default_instance_; class TerminateServerCommand; class TerminateServerCommandDefaultTypeInternal; extern TerminateServerCommandDefaultTypeInternal _TerminateServerCommand_default_instance_; +class UserConstraintCommand; +class UserConstraintCommandDefaultTypeInternal; +extern UserConstraintCommandDefaultTypeInternal _UserConstraintCommand_default_instance_; +class UserConstraintStateStatus; +class UserConstraintStateStatusDefaultTypeInternal; +extern UserConstraintStateStatusDefaultTypeInternal _UserConstraintStateStatus_default_instance_; +class UserConstraintStatus; +class UserConstraintStatusDefaultTypeInternal; +extern UserConstraintStatusDefaultTypeInternal _UserConstraintStatus_default_instance_; +class matrix4x4; +class matrix4x4DefaultTypeInternal; +extern matrix4x4DefaultTypeInternal _matrix4x4_default_instance_; class quat4; class quat4DefaultTypeInternal; extern quat4DefaultTypeInternal _quat4_default_instance_; +class transform; +class transformDefaultTypeInternal; +extern transformDefaultTypeInternal _transform_default_instance_; class vec3; class vec3DefaultTypeInternal; extern vec3DefaultTypeInternal _vec3_default_instance_; +class vec4; +class vec4DefaultTypeInternal; +extern vec4DefaultTypeInternal _vec4_default_instance_; } // namespace pybullet_grpc namespace pybullet_grpc { @@ -302,6 +365,462 @@ class quat4 : public ::google::protobuf::Message /* @@protoc_insertion_point(cla }; // ------------------------------------------------------------------- +class vec4 : public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:pybullet_grpc.vec4) */ { + public: + vec4(); + virtual ~vec4(); + + vec4(const vec4& from); + + inline vec4& operator=(const vec4& from) { + CopyFrom(from); + return *this; + } + + static const ::google::protobuf::Descriptor* descriptor(); + static const vec4& default_instance(); + + static inline const vec4* internal_default_instance() { + return reinterpret_cast( + &_vec4_default_instance_); + } + + void Swap(vec4* other); + + // implements Message ---------------------------------------------- + + inline vec4* New() const PROTOBUF_FINAL { return New(NULL); } + + vec4* 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 vec4& from); + void MergeFrom(const vec4& 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(vec4* 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.vec4) + 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 transform : public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:pybullet_grpc.transform) */ { + public: + transform(); + virtual ~transform(); + + transform(const transform& from); + + inline transform& operator=(const transform& from) { + CopyFrom(from); + return *this; + } + + static const ::google::protobuf::Descriptor* descriptor(); + static const transform& default_instance(); + + static inline const transform* internal_default_instance() { + return reinterpret_cast( + &_transform_default_instance_); + } + + void Swap(transform* other); + + // implements Message ---------------------------------------------- + + inline transform* New() const PROTOBUF_FINAL { return New(NULL); } + + transform* 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 transform& from); + void MergeFrom(const transform& 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(transform* 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 ------------------------------------------------------- + + // .pybullet_grpc.vec3 origin = 1; + bool has_origin() const; + void clear_origin(); + static const int kOriginFieldNumber = 1; + const ::pybullet_grpc::vec3& origin() const; + ::pybullet_grpc::vec3* mutable_origin(); + ::pybullet_grpc::vec3* release_origin(); + void set_allocated_origin(::pybullet_grpc::vec3* origin); + + // .pybullet_grpc.quat4 orientation = 2; + bool has_orientation() const; + void clear_orientation(); + static const int kOrientationFieldNumber = 2; + const ::pybullet_grpc::quat4& orientation() const; + ::pybullet_grpc::quat4* mutable_orientation(); + ::pybullet_grpc::quat4* release_orientation(); + void set_allocated_orientation(::pybullet_grpc::quat4* orientation); + + // @@protoc_insertion_point(class_scope:pybullet_grpc.transform) + private: + + ::google::protobuf::internal::InternalMetadataWithArena _internal_metadata_; + ::pybullet_grpc::vec3* origin_; + ::pybullet_grpc::quat4* orientation_; + mutable int _cached_size_; + friend struct protobuf_pybullet_2eproto::TableStruct; +}; +// ------------------------------------------------------------------- + +class matrix4x4 : public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:pybullet_grpc.matrix4x4) */ { + public: + matrix4x4(); + virtual ~matrix4x4(); + + matrix4x4(const matrix4x4& from); + + inline matrix4x4& operator=(const matrix4x4& from) { + CopyFrom(from); + return *this; + } + + static const ::google::protobuf::Descriptor* descriptor(); + static const matrix4x4& default_instance(); + + static inline const matrix4x4* internal_default_instance() { + return reinterpret_cast( + &_matrix4x4_default_instance_); + } + + void Swap(matrix4x4* other); + + // implements Message ---------------------------------------------- + + inline matrix4x4* New() const PROTOBUF_FINAL { return New(NULL); } + + matrix4x4* 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 matrix4x4& from); + void MergeFrom(const matrix4x4& 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(matrix4x4* 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 ------------------------------------------------------- + + // repeated double elems = 1; + int elems_size() const; + void clear_elems(); + static const int kElemsFieldNumber = 1; + double elems(int index) const; + void set_elems(int index, double value); + void add_elems(double value); + const ::google::protobuf::RepeatedField< double >& + elems() const; + ::google::protobuf::RepeatedField< double >* + mutable_elems(); + + // @@protoc_insertion_point(class_scope:pybullet_grpc.matrix4x4) + private: + + ::google::protobuf::internal::InternalMetadataWithArena _internal_metadata_; + ::google::protobuf::RepeatedField< double > elems_; + mutable int _elems_cached_byte_size_; + mutable int _cached_size_; + friend struct protobuf_pybullet_2eproto::TableStruct; +}; +// ------------------------------------------------------------------- + +class CheckVersionCommand : public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:pybullet_grpc.CheckVersionCommand) */ { + public: + CheckVersionCommand(); + virtual ~CheckVersionCommand(); + + CheckVersionCommand(const CheckVersionCommand& from); + + inline CheckVersionCommand& operator=(const CheckVersionCommand& from) { + CopyFrom(from); + return *this; + } + + static const ::google::protobuf::Descriptor* descriptor(); + static const CheckVersionCommand& default_instance(); + + static inline const CheckVersionCommand* internal_default_instance() { + return reinterpret_cast( + &_CheckVersionCommand_default_instance_); + } + + void Swap(CheckVersionCommand* other); + + // implements Message ---------------------------------------------- + + inline CheckVersionCommand* New() const PROTOBUF_FINAL { return New(NULL); } + + CheckVersionCommand* 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 CheckVersionCommand& from); + void MergeFrom(const CheckVersionCommand& 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(CheckVersionCommand* 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 clientVersion = 1; + void clear_clientversion(); + static const int kClientVersionFieldNumber = 1; + ::google::protobuf::int32 clientversion() const; + void set_clientversion(::google::protobuf::int32 value); + + // @@protoc_insertion_point(class_scope:pybullet_grpc.CheckVersionCommand) + private: + + ::google::protobuf::internal::InternalMetadataWithArena _internal_metadata_; + ::google::protobuf::int32 clientversion_; + mutable int _cached_size_; + friend struct protobuf_pybullet_2eproto::TableStruct; +}; +// ------------------------------------------------------------------- + +class CheckVersionStatus : public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:pybullet_grpc.CheckVersionStatus) */ { + public: + CheckVersionStatus(); + virtual ~CheckVersionStatus(); + + CheckVersionStatus(const CheckVersionStatus& from); + + inline CheckVersionStatus& operator=(const CheckVersionStatus& from) { + CopyFrom(from); + return *this; + } + + static const ::google::protobuf::Descriptor* descriptor(); + static const CheckVersionStatus& default_instance(); + + static inline const CheckVersionStatus* internal_default_instance() { + return reinterpret_cast( + &_CheckVersionStatus_default_instance_); + } + + void Swap(CheckVersionStatus* other); + + // implements Message ---------------------------------------------- + + inline CheckVersionStatus* New() const PROTOBUF_FINAL { return New(NULL); } + + CheckVersionStatus* 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 CheckVersionStatus& from); + void MergeFrom(const CheckVersionStatus& 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(CheckVersionStatus* 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 serverVersion = 1; + void clear_serverversion(); + static const int kServerVersionFieldNumber = 1; + ::google::protobuf::int32 serverversion() const; + void set_serverversion(::google::protobuf::int32 value); + + // @@protoc_insertion_point(class_scope:pybullet_grpc.CheckVersionStatus) + private: + + ::google::protobuf::internal::InternalMetadataWithArena _internal_metadata_; + ::google::protobuf::int32 serverversion_; + 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(); @@ -469,6 +988,367 @@ class StepSimulationCommand : public ::google::protobuf::Message /* @@protoc_ins }; // ------------------------------------------------------------------- +class SyncBodiesCommand : public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:pybullet_grpc.SyncBodiesCommand) */ { + public: + SyncBodiesCommand(); + virtual ~SyncBodiesCommand(); + + SyncBodiesCommand(const SyncBodiesCommand& from); + + inline SyncBodiesCommand& operator=(const SyncBodiesCommand& from) { + CopyFrom(from); + return *this; + } + + static const ::google::protobuf::Descriptor* descriptor(); + static const SyncBodiesCommand& default_instance(); + + static inline const SyncBodiesCommand* internal_default_instance() { + return reinterpret_cast( + &_SyncBodiesCommand_default_instance_); + } + + void Swap(SyncBodiesCommand* other); + + // implements Message ---------------------------------------------- + + inline SyncBodiesCommand* New() const PROTOBUF_FINAL { return New(NULL); } + + SyncBodiesCommand* 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 SyncBodiesCommand& from); + void MergeFrom(const SyncBodiesCommand& 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(SyncBodiesCommand* 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.SyncBodiesCommand) + private: + + ::google::protobuf::internal::InternalMetadataWithArena _internal_metadata_; + mutable int _cached_size_; + friend struct protobuf_pybullet_2eproto::TableStruct; +}; +// ------------------------------------------------------------------- + +class SyncBodiesStatus : public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:pybullet_grpc.SyncBodiesStatus) */ { + public: + SyncBodiesStatus(); + virtual ~SyncBodiesStatus(); + + SyncBodiesStatus(const SyncBodiesStatus& from); + + inline SyncBodiesStatus& operator=(const SyncBodiesStatus& from) { + CopyFrom(from); + return *this; + } + + static const ::google::protobuf::Descriptor* descriptor(); + static const SyncBodiesStatus& default_instance(); + + static inline const SyncBodiesStatus* internal_default_instance() { + return reinterpret_cast( + &_SyncBodiesStatus_default_instance_); + } + + void Swap(SyncBodiesStatus* other); + + // implements Message ---------------------------------------------- + + inline SyncBodiesStatus* New() const PROTOBUF_FINAL { return New(NULL); } + + SyncBodiesStatus* 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 SyncBodiesStatus& from); + void MergeFrom(const SyncBodiesStatus& 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(SyncBodiesStatus* 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 ------------------------------------------------------- + + // repeated int32 bodyUniqueIds = 1; + int bodyuniqueids_size() const; + void clear_bodyuniqueids(); + static const int kBodyUniqueIdsFieldNumber = 1; + ::google::protobuf::int32 bodyuniqueids(int index) const; + void set_bodyuniqueids(int index, ::google::protobuf::int32 value); + void add_bodyuniqueids(::google::protobuf::int32 value); + const ::google::protobuf::RepeatedField< ::google::protobuf::int32 >& + bodyuniqueids() const; + ::google::protobuf::RepeatedField< ::google::protobuf::int32 >* + mutable_bodyuniqueids(); + + // repeated int32 userConstraintUniqueIds = 2; + int userconstraintuniqueids_size() const; + void clear_userconstraintuniqueids(); + static const int kUserConstraintUniqueIdsFieldNumber = 2; + ::google::protobuf::int32 userconstraintuniqueids(int index) const; + void set_userconstraintuniqueids(int index, ::google::protobuf::int32 value); + void add_userconstraintuniqueids(::google::protobuf::int32 value); + const ::google::protobuf::RepeatedField< ::google::protobuf::int32 >& + userconstraintuniqueids() const; + ::google::protobuf::RepeatedField< ::google::protobuf::int32 >* + mutable_userconstraintuniqueids(); + + // @@protoc_insertion_point(class_scope:pybullet_grpc.SyncBodiesStatus) + private: + + ::google::protobuf::internal::InternalMetadataWithArena _internal_metadata_; + ::google::protobuf::RepeatedField< ::google::protobuf::int32 > bodyuniqueids_; + mutable int _bodyuniqueids_cached_byte_size_; + ::google::protobuf::RepeatedField< ::google::protobuf::int32 > userconstraintuniqueids_; + mutable int _userconstraintuniqueids_cached_byte_size_; + mutable int _cached_size_; + friend struct protobuf_pybullet_2eproto::TableStruct; +}; +// ------------------------------------------------------------------- + +class RequestBodyInfoCommand : public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:pybullet_grpc.RequestBodyInfoCommand) */ { + public: + RequestBodyInfoCommand(); + virtual ~RequestBodyInfoCommand(); + + RequestBodyInfoCommand(const RequestBodyInfoCommand& from); + + inline RequestBodyInfoCommand& operator=(const RequestBodyInfoCommand& from) { + CopyFrom(from); + return *this; + } + + static const ::google::protobuf::Descriptor* descriptor(); + static const RequestBodyInfoCommand& default_instance(); + + static inline const RequestBodyInfoCommand* internal_default_instance() { + return reinterpret_cast( + &_RequestBodyInfoCommand_default_instance_); + } + + void Swap(RequestBodyInfoCommand* other); + + // implements Message ---------------------------------------------- + + inline RequestBodyInfoCommand* New() const PROTOBUF_FINAL { return New(NULL); } + + RequestBodyInfoCommand* 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 RequestBodyInfoCommand& from); + void MergeFrom(const RequestBodyInfoCommand& 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(RequestBodyInfoCommand* 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 bodyUniqueId = 1; + void clear_bodyuniqueid(); + static const int kBodyUniqueIdFieldNumber = 1; + ::google::protobuf::int32 bodyuniqueid() const; + void set_bodyuniqueid(::google::protobuf::int32 value); + + // @@protoc_insertion_point(class_scope:pybullet_grpc.RequestBodyInfoCommand) + private: + + ::google::protobuf::internal::InternalMetadataWithArena _internal_metadata_; + ::google::protobuf::int32 bodyuniqueid_; + mutable int _cached_size_; + friend struct protobuf_pybullet_2eproto::TableStruct; +}; +// ------------------------------------------------------------------- + +class RequestBodyInfoStatus : public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:pybullet_grpc.RequestBodyInfoStatus) */ { + public: + RequestBodyInfoStatus(); + virtual ~RequestBodyInfoStatus(); + + RequestBodyInfoStatus(const RequestBodyInfoStatus& from); + + inline RequestBodyInfoStatus& operator=(const RequestBodyInfoStatus& from) { + CopyFrom(from); + return *this; + } + + static const ::google::protobuf::Descriptor* descriptor(); + static const RequestBodyInfoStatus& default_instance(); + + static inline const RequestBodyInfoStatus* internal_default_instance() { + return reinterpret_cast( + &_RequestBodyInfoStatus_default_instance_); + } + + void Swap(RequestBodyInfoStatus* other); + + // implements Message ---------------------------------------------- + + inline RequestBodyInfoStatus* New() const PROTOBUF_FINAL { return New(NULL); } + + RequestBodyInfoStatus* 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 RequestBodyInfoStatus& from); + void MergeFrom(const RequestBodyInfoStatus& 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(RequestBodyInfoStatus* 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 bodyName = 2; + void clear_bodyname(); + static const int kBodyNameFieldNumber = 2; + const ::std::string& bodyname() const; + void set_bodyname(const ::std::string& value); + #if LANG_CXX11 + void set_bodyname(::std::string&& value); + #endif + void set_bodyname(const char* value); + void set_bodyname(const char* value, size_t size); + ::std::string* mutable_bodyname(); + ::std::string* release_bodyname(); + void set_allocated_bodyname(::std::string* bodyname); + + // int32 bodyUniqueId = 1; + void clear_bodyuniqueid(); + static const int kBodyUniqueIdFieldNumber = 1; + ::google::protobuf::int32 bodyuniqueid() const; + void set_bodyuniqueid(::google::protobuf::int32 value); + + // @@protoc_insertion_point(class_scope:pybullet_grpc.RequestBodyInfoStatus) + private: + + ::google::protobuf::internal::InternalMetadataWithArena _internal_metadata_; + ::google::protobuf::internal::ArenaStringPtr bodyname_; + ::google::protobuf::int32 bodyuniqueid_; + 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(); @@ -728,6 +1608,34 @@ class LoadUrdfStatus : public ::google::protobuf::Message /* @@protoc_insertion_ // accessors ------------------------------------------------------- + // string bodyName = 2; + void clear_bodyname(); + static const int kBodyNameFieldNumber = 2; + const ::std::string& bodyname() const; + void set_bodyname(const ::std::string& value); + #if LANG_CXX11 + void set_bodyname(::std::string&& value); + #endif + void set_bodyname(const char* value); + void set_bodyname(const char* value, size_t size); + ::std::string* mutable_bodyname(); + ::std::string* release_bodyname(); + void set_allocated_bodyname(::std::string* bodyname); + + // string fileName = 3; + void clear_filename(); + static const int kFileNameFieldNumber = 3; + const ::std::string& filename() const; + void set_filename(const ::std::string& value); + #if LANG_CXX11 + void set_filename(::std::string&& value); + #endif + void set_filename(const char* value); + void set_filename(const char* value, size_t size); + ::std::string* mutable_filename(); + ::std::string* release_filename(); + void set_allocated_filename(::std::string* filename); + // int32 bodyUniqueId = 1; void clear_bodyuniqueid(); static const int kBodyUniqueIdFieldNumber = 1; @@ -738,6 +1646,8 @@ class LoadUrdfStatus : public ::google::protobuf::Message /* @@protoc_insertion_ private: ::google::protobuf::internal::InternalMetadataWithArena _internal_metadata_; + ::google::protobuf::internal::ArenaStringPtr bodyname_; + ::google::protobuf::internal::ArenaStringPtr filename_; ::google::protobuf::int32 bodyuniqueid_; mutable int _cached_size_; friend struct protobuf_pybullet_2eproto::TableStruct; @@ -1925,10 +2835,10 @@ class InitPoseCommand : public ::google::protobuf::Message /* @@protoc_insertion // accessors ------------------------------------------------------- - // repeated int32 hasInitialStateQ = 2; + // repeated int32 hasInitialStateQ = 3; int hasinitialstateq_size() const; void clear_hasinitialstateq(); - static const int kHasInitialStateQFieldNumber = 2; + static const int kHasInitialStateQFieldNumber = 3; ::google::protobuf::int32 hasinitialstateq(int index) const; void set_hasinitialstateq(int index, ::google::protobuf::int32 value); void add_hasinitialstateq(::google::protobuf::int32 value); @@ -1937,10 +2847,10 @@ class InitPoseCommand : public ::google::protobuf::Message /* @@protoc_insertion ::google::protobuf::RepeatedField< ::google::protobuf::int32 >* mutable_hasinitialstateq(); - // repeated double initialStateQ = 3; + // repeated double initialStateQ = 4; int initialstateq_size() const; void clear_initialstateq(); - static const int kInitialStateQFieldNumber = 3; + static const int kInitialStateQFieldNumber = 4; double initialstateq(int index) const; void set_initialstateq(int index, double value); void add_initialstateq(double value); @@ -1949,10 +2859,10 @@ class InitPoseCommand : public ::google::protobuf::Message /* @@protoc_insertion ::google::protobuf::RepeatedField< double >* mutable_initialstateq(); - // repeated int32 hasInitialStateQdot = 4; + // repeated int32 hasInitialStateQdot = 5; int hasinitialstateqdot_size() const; void clear_hasinitialstateqdot(); - static const int kHasInitialStateQdotFieldNumber = 4; + static const int kHasInitialStateQdotFieldNumber = 5; ::google::protobuf::int32 hasinitialstateqdot(int index) const; void set_hasinitialstateqdot(int index, ::google::protobuf::int32 value); void add_hasinitialstateqdot(::google::protobuf::int32 value); @@ -1961,10 +2871,10 @@ class InitPoseCommand : public ::google::protobuf::Message /* @@protoc_insertion ::google::protobuf::RepeatedField< ::google::protobuf::int32 >* mutable_hasinitialstateqdot(); - // repeated double initialStateQdot = 5; + // repeated double initialStateQdot = 6; int initialstateqdot_size() const; void clear_initialstateqdot(); - static const int kInitialStateQdotFieldNumber = 5; + static const int kInitialStateQdotFieldNumber = 6; double initialstateqdot(int index) const; void set_initialstateqdot(int index, double value); void add_initialstateqdot(double value); @@ -1979,6 +2889,12 @@ class InitPoseCommand : public ::google::protobuf::Message /* @@protoc_insertion ::google::protobuf::int32 bodyuniqueid() const; void set_bodyuniqueid(::google::protobuf::int32 value); + // int32 updateflags = 2; + void clear_updateflags(); + static const int kUpdateflagsFieldNumber = 2; + ::google::protobuf::int32 updateflags() const; + void set_updateflags(::google::protobuf::int32 value); + // @@protoc_insertion_point(class_scope:pybullet_grpc.InitPoseCommand) private: @@ -1992,6 +2908,7 @@ class InitPoseCommand : public ::google::protobuf::Message /* @@protoc_insertion ::google::protobuf::RepeatedField< double > initialstateqdot_; mutable int _initialstateqdot_cached_byte_size_; ::google::protobuf::int32 bodyuniqueid_; + ::google::protobuf::int32 updateflags_; mutable int _cached_size_; friend struct protobuf_pybullet_2eproto::TableStruct; }; @@ -2310,6 +3227,1638 @@ class SendActualStateStatus : public ::google::protobuf::Message /* @@protoc_ins }; // ------------------------------------------------------------------- +class ConfigureOpenGLVisualizerCommand : public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:pybullet_grpc.ConfigureOpenGLVisualizerCommand) */ { + public: + ConfigureOpenGLVisualizerCommand(); + virtual ~ConfigureOpenGLVisualizerCommand(); + + ConfigureOpenGLVisualizerCommand(const ConfigureOpenGLVisualizerCommand& from); + + inline ConfigureOpenGLVisualizerCommand& operator=(const ConfigureOpenGLVisualizerCommand& from) { + CopyFrom(from); + return *this; + } + + static const ::google::protobuf::Descriptor* descriptor(); + static const ConfigureOpenGLVisualizerCommand& default_instance(); + + static inline const ConfigureOpenGLVisualizerCommand* internal_default_instance() { + return reinterpret_cast( + &_ConfigureOpenGLVisualizerCommand_default_instance_); + } + + void Swap(ConfigureOpenGLVisualizerCommand* other); + + // implements Message ---------------------------------------------- + + inline ConfigureOpenGLVisualizerCommand* New() const PROTOBUF_FINAL { return New(NULL); } + + ConfigureOpenGLVisualizerCommand* 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 ConfigureOpenGLVisualizerCommand& from); + void MergeFrom(const ConfigureOpenGLVisualizerCommand& 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(ConfigureOpenGLVisualizerCommand* 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 ------------------------------------------------------- + + // .pybullet_grpc.vec3 cameraTargetPosition = 5; + bool has_cameratargetposition() const; + void clear_cameratargetposition(); + static const int kCameraTargetPositionFieldNumber = 5; + const ::pybullet_grpc::vec3& cameratargetposition() const; + ::pybullet_grpc::vec3* mutable_cameratargetposition(); + ::pybullet_grpc::vec3* release_cameratargetposition(); + void set_allocated_cameratargetposition(::pybullet_grpc::vec3* cameratargetposition); + + // double cameraDistance = 2; + void clear_cameradistance(); + static const int kCameraDistanceFieldNumber = 2; + double cameradistance() const; + void set_cameradistance(double value); + + // double cameraPitch = 3; + void clear_camerapitch(); + static const int kCameraPitchFieldNumber = 3; + double camerapitch() const; + void set_camerapitch(double value); + + // int32 updateFlags = 1; + void clear_updateflags(); + static const int kUpdateFlagsFieldNumber = 1; + ::google::protobuf::int32 updateflags() const; + void set_updateflags(::google::protobuf::int32 value); + + // int32 setFlag = 6; + void clear_setflag(); + static const int kSetFlagFieldNumber = 6; + ::google::protobuf::int32 setflag() const; + void set_setflag(::google::protobuf::int32 value); + + // double cameraYaw = 4; + void clear_camerayaw(); + static const int kCameraYawFieldNumber = 4; + double camerayaw() const; + void set_camerayaw(double value); + + // int32 setEnabled = 7; + void clear_setenabled(); + static const int kSetEnabledFieldNumber = 7; + ::google::protobuf::int32 setenabled() const; + void set_setenabled(::google::protobuf::int32 value); + + // @@protoc_insertion_point(class_scope:pybullet_grpc.ConfigureOpenGLVisualizerCommand) + private: + + ::google::protobuf::internal::InternalMetadataWithArena _internal_metadata_; + ::pybullet_grpc::vec3* cameratargetposition_; + double cameradistance_; + double camerapitch_; + ::google::protobuf::int32 updateflags_; + ::google::protobuf::int32 setflag_; + double camerayaw_; + ::google::protobuf::int32 setenabled_; + mutable int _cached_size_; + friend struct protobuf_pybullet_2eproto::TableStruct; +}; +// ------------------------------------------------------------------- + +class PhysicsSimulationParameters : public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:pybullet_grpc.PhysicsSimulationParameters) */ { + public: + PhysicsSimulationParameters(); + virtual ~PhysicsSimulationParameters(); + + PhysicsSimulationParameters(const PhysicsSimulationParameters& from); + + inline PhysicsSimulationParameters& operator=(const PhysicsSimulationParameters& from) { + CopyFrom(from); + return *this; + } + + static const ::google::protobuf::Descriptor* descriptor(); + static const PhysicsSimulationParameters& default_instance(); + + static inline const PhysicsSimulationParameters* internal_default_instance() { + return reinterpret_cast( + &_PhysicsSimulationParameters_default_instance_); + } + + void Swap(PhysicsSimulationParameters* other); + + // implements Message ---------------------------------------------- + + inline PhysicsSimulationParameters* New() const PROTOBUF_FINAL { return New(NULL); } + + PhysicsSimulationParameters* 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 PhysicsSimulationParameters& from); + void MergeFrom(const PhysicsSimulationParameters& 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(PhysicsSimulationParameters* 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 ------------------------------------------------------- + + // .pybullet_grpc.vec3 gravityAcceleration = 2; + bool has_gravityacceleration() const; + void clear_gravityacceleration(); + static const int kGravityAccelerationFieldNumber = 2; + const ::pybullet_grpc::vec3& gravityacceleration() const; + ::pybullet_grpc::vec3* mutable_gravityacceleration(); + ::pybullet_grpc::vec3* release_gravityacceleration(); + void set_allocated_gravityacceleration(::pybullet_grpc::vec3* gravityacceleration); + + // double deltaTime = 1; + void clear_deltatime(); + static const int kDeltaTimeFieldNumber = 1; + double deltatime() const; + void set_deltatime(double value); + + // int32 numSimulationSubSteps = 3; + void clear_numsimulationsubsteps(); + static const int kNumSimulationSubStepsFieldNumber = 3; + ::google::protobuf::int32 numsimulationsubsteps() const; + void set_numsimulationsubsteps(::google::protobuf::int32 value); + + // int32 numSolverIterations = 4; + void clear_numsolveriterations(); + static const int kNumSolverIterationsFieldNumber = 4; + ::google::protobuf::int32 numsolveriterations() const; + void set_numsolveriterations(::google::protobuf::int32 value); + + // int32 useRealTimeSimulation = 5; + void clear_userealtimesimulation(); + static const int kUseRealTimeSimulationFieldNumber = 5; + ::google::protobuf::int32 userealtimesimulation() const; + void set_userealtimesimulation(::google::protobuf::int32 value); + + // int32 useSplitImpulse = 6; + void clear_usesplitimpulse(); + static const int kUseSplitImpulseFieldNumber = 6; + ::google::protobuf::int32 usesplitimpulse() const; + void set_usesplitimpulse(::google::protobuf::int32 value); + + // double splitImpulsePenetrationThreshold = 7; + void clear_splitimpulsepenetrationthreshold(); + static const int kSplitImpulsePenetrationThresholdFieldNumber = 7; + double splitimpulsepenetrationthreshold() const; + void set_splitimpulsepenetrationthreshold(double value); + + // double contactBreakingThreshold = 8; + void clear_contactbreakingthreshold(); + static const int kContactBreakingThresholdFieldNumber = 8; + double contactbreakingthreshold() const; + void set_contactbreakingthreshold(double value); + + // double defaultContactERP = 10; + void clear_defaultcontacterp(); + static const int kDefaultContactERPFieldNumber = 10; + double defaultcontacterp() const; + void set_defaultcontacterp(double value); + + // int32 internalSimFlags = 9; + void clear_internalsimflags(); + static const int kInternalSimFlagsFieldNumber = 9; + ::google::protobuf::int32 internalsimflags() const; + void set_internalsimflags(::google::protobuf::int32 value); + + // int32 collisionFilterMode = 11; + void clear_collisionfiltermode(); + static const int kCollisionFilterModeFieldNumber = 11; + ::google::protobuf::int32 collisionfiltermode() const; + void set_collisionfiltermode(::google::protobuf::int32 value); + + // double restitutionVelocityThreshold = 13; + void clear_restitutionvelocitythreshold(); + static const int kRestitutionVelocityThresholdFieldNumber = 13; + double restitutionvelocitythreshold() const; + void set_restitutionvelocitythreshold(double value); + + // double defaultNonContactERP = 14; + void clear_defaultnoncontacterp(); + static const int kDefaultNonContactERPFieldNumber = 14; + double defaultnoncontacterp() const; + void set_defaultnoncontacterp(double value); + + // double frictionERP = 15; + void clear_frictionerp(); + static const int kFrictionERPFieldNumber = 15; + double frictionerp() const; + void set_frictionerp(double value); + + // int32 enableFileCaching = 12; + void clear_enablefilecaching(); + static const int kEnableFileCachingFieldNumber = 12; + ::google::protobuf::int32 enablefilecaching() const; + void set_enablefilecaching(::google::protobuf::int32 value); + + // int32 enableConeFriction = 18; + void clear_enableconefriction(); + static const int kEnableConeFrictionFieldNumber = 18; + ::google::protobuf::int32 enableconefriction() const; + void set_enableconefriction(::google::protobuf::int32 value); + + // double defaultGlobalCFM = 16; + void clear_defaultglobalcfm(); + static const int kDefaultGlobalCFMFieldNumber = 16; + double defaultglobalcfm() const; + void set_defaultglobalcfm(double value); + + // double frictionCFM = 17; + void clear_frictioncfm(); + static const int kFrictionCFMFieldNumber = 17; + double frictioncfm() const; + void set_frictioncfm(double value); + + // double allowedCcdPenetration = 20; + void clear_allowedccdpenetration(); + static const int kAllowedCcdPenetrationFieldNumber = 20; + double allowedccdpenetration() const; + void set_allowedccdpenetration(double value); + + // int32 deterministicOverlappingPairs = 19; + void clear_deterministicoverlappingpairs(); + static const int kDeterministicOverlappingPairsFieldNumber = 19; + ::google::protobuf::int32 deterministicoverlappingpairs() const; + void set_deterministicoverlappingpairs(::google::protobuf::int32 value); + + // int32 jointFeedbackMode = 21; + void clear_jointfeedbackmode(); + static const int kJointFeedbackModeFieldNumber = 21; + ::google::protobuf::int32 jointfeedbackmode() const; + void set_jointfeedbackmode(::google::protobuf::int32 value); + + // double solverResidualThreshold = 22; + void clear_solverresidualthreshold(); + static const int kSolverResidualThresholdFieldNumber = 22; + double solverresidualthreshold() const; + void set_solverresidualthreshold(double value); + + // double contactSlop = 23; + void clear_contactslop(); + static const int kContactSlopFieldNumber = 23; + double contactslop() const; + void set_contactslop(double value); + + // int32 enableSAT = 24; + void clear_enablesat(); + static const int kEnableSATFieldNumber = 24; + ::google::protobuf::int32 enablesat() const; + void set_enablesat(::google::protobuf::int32 value); + + // int32 constraintSolverType = 25; + void clear_constraintsolvertype(); + static const int kConstraintSolverTypeFieldNumber = 25; + ::google::protobuf::int32 constraintsolvertype() const; + void set_constraintsolvertype(::google::protobuf::int32 value); + + // int32 minimumSolverIslandSize = 26; + void clear_minimumsolverislandsize(); + static const int kMinimumSolverIslandSizeFieldNumber = 26; + ::google::protobuf::int32 minimumsolverislandsize() const; + void set_minimumsolverislandsize(::google::protobuf::int32 value); + + // @@protoc_insertion_point(class_scope:pybullet_grpc.PhysicsSimulationParameters) + private: + + ::google::protobuf::internal::InternalMetadataWithArena _internal_metadata_; + ::pybullet_grpc::vec3* gravityacceleration_; + double deltatime_; + ::google::protobuf::int32 numsimulationsubsteps_; + ::google::protobuf::int32 numsolveriterations_; + ::google::protobuf::int32 userealtimesimulation_; + ::google::protobuf::int32 usesplitimpulse_; + double splitimpulsepenetrationthreshold_; + double contactbreakingthreshold_; + double defaultcontacterp_; + ::google::protobuf::int32 internalsimflags_; + ::google::protobuf::int32 collisionfiltermode_; + double restitutionvelocitythreshold_; + double defaultnoncontacterp_; + double frictionerp_; + ::google::protobuf::int32 enablefilecaching_; + ::google::protobuf::int32 enableconefriction_; + double defaultglobalcfm_; + double frictioncfm_; + double allowedccdpenetration_; + ::google::protobuf::int32 deterministicoverlappingpairs_; + ::google::protobuf::int32 jointfeedbackmode_; + double solverresidualthreshold_; + double contactslop_; + ::google::protobuf::int32 enablesat_; + ::google::protobuf::int32 constraintsolvertype_; + ::google::protobuf::int32 minimumsolverislandsize_; + mutable int _cached_size_; + friend struct protobuf_pybullet_2eproto::TableStruct; +}; +// ------------------------------------------------------------------- + +class PhysicsSimulationParametersCommand : public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:pybullet_grpc.PhysicsSimulationParametersCommand) */ { + public: + PhysicsSimulationParametersCommand(); + virtual ~PhysicsSimulationParametersCommand(); + + PhysicsSimulationParametersCommand(const PhysicsSimulationParametersCommand& from); + + inline PhysicsSimulationParametersCommand& operator=(const PhysicsSimulationParametersCommand& from) { + CopyFrom(from); + return *this; + } + + static const ::google::protobuf::Descriptor* descriptor(); + static const PhysicsSimulationParametersCommand& default_instance(); + + static inline const PhysicsSimulationParametersCommand* internal_default_instance() { + return reinterpret_cast( + &_PhysicsSimulationParametersCommand_default_instance_); + } + + void Swap(PhysicsSimulationParametersCommand* other); + + // implements Message ---------------------------------------------- + + inline PhysicsSimulationParametersCommand* New() const PROTOBUF_FINAL { return New(NULL); } + + PhysicsSimulationParametersCommand* 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 PhysicsSimulationParametersCommand& from); + void MergeFrom(const PhysicsSimulationParametersCommand& 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(PhysicsSimulationParametersCommand* 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 ------------------------------------------------------- + + // .pybullet_grpc.PhysicsSimulationParameters params = 2; + bool has_params() const; + void clear_params(); + static const int kParamsFieldNumber = 2; + const ::pybullet_grpc::PhysicsSimulationParameters& params() const; + ::pybullet_grpc::PhysicsSimulationParameters* mutable_params(); + ::pybullet_grpc::PhysicsSimulationParameters* release_params(); + void set_allocated_params(::pybullet_grpc::PhysicsSimulationParameters* params); + + // int32 updateFlags = 1; + void clear_updateflags(); + static const int kUpdateFlagsFieldNumber = 1; + ::google::protobuf::int32 updateflags() const; + void set_updateflags(::google::protobuf::int32 value); + + // @@protoc_insertion_point(class_scope:pybullet_grpc.PhysicsSimulationParametersCommand) + private: + + ::google::protobuf::internal::InternalMetadataWithArena _internal_metadata_; + ::pybullet_grpc::PhysicsSimulationParameters* params_; + ::google::protobuf::int32 updateflags_; + mutable int _cached_size_; + friend struct protobuf_pybullet_2eproto::TableStruct; +}; +// ------------------------------------------------------------------- + +class JointMotorControlCommand : public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:pybullet_grpc.JointMotorControlCommand) */ { + public: + JointMotorControlCommand(); + virtual ~JointMotorControlCommand(); + + JointMotorControlCommand(const JointMotorControlCommand& from); + + inline JointMotorControlCommand& operator=(const JointMotorControlCommand& from) { + CopyFrom(from); + return *this; + } + + static const ::google::protobuf::Descriptor* descriptor(); + static const JointMotorControlCommand& default_instance(); + + static inline const JointMotorControlCommand* internal_default_instance() { + return reinterpret_cast( + &_JointMotorControlCommand_default_instance_); + } + + void Swap(JointMotorControlCommand* other); + + // implements Message ---------------------------------------------- + + inline JointMotorControlCommand* New() const PROTOBUF_FINAL { return New(NULL); } + + JointMotorControlCommand* 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 JointMotorControlCommand& from); + void MergeFrom(const JointMotorControlCommand& 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(JointMotorControlCommand* 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 ------------------------------------------------------- + + // repeated double Kp = 4; + int kp_size() const; + void clear_kp(); + static const int kKpFieldNumber = 4; + double kp(int index) const; + void set_kp(int index, double value); + void add_kp(double value); + const ::google::protobuf::RepeatedField< double >& + kp() const; + ::google::protobuf::RepeatedField< double >* + mutable_kp(); + + // repeated double Kd = 5; + int kd_size() const; + void clear_kd(); + static const int kKdFieldNumber = 5; + double kd(int index) const; + void set_kd(int index, double value); + void add_kd(double value); + const ::google::protobuf::RepeatedField< double >& + kd() const; + ::google::protobuf::RepeatedField< double >* + mutable_kd(); + + // repeated double maxVelocity = 6; + int maxvelocity_size() const; + void clear_maxvelocity(); + static const int kMaxVelocityFieldNumber = 6; + double maxvelocity(int index) const; + void set_maxvelocity(int index, double value); + void add_maxvelocity(double value); + const ::google::protobuf::RepeatedField< double >& + maxvelocity() const; + ::google::protobuf::RepeatedField< double >* + mutable_maxvelocity(); + + // repeated int32 hasDesiredStateFlags = 7; + int hasdesiredstateflags_size() const; + void clear_hasdesiredstateflags(); + static const int kHasDesiredStateFlagsFieldNumber = 7; + ::google::protobuf::int32 hasdesiredstateflags(int index) const; + void set_hasdesiredstateflags(int index, ::google::protobuf::int32 value); + void add_hasdesiredstateflags(::google::protobuf::int32 value); + const ::google::protobuf::RepeatedField< ::google::protobuf::int32 >& + hasdesiredstateflags() const; + ::google::protobuf::RepeatedField< ::google::protobuf::int32 >* + mutable_hasdesiredstateflags(); + + // repeated double desiredStateQ = 8; + int desiredstateq_size() const; + void clear_desiredstateq(); + static const int kDesiredStateQFieldNumber = 8; + double desiredstateq(int index) const; + void set_desiredstateq(int index, double value); + void add_desiredstateq(double value); + const ::google::protobuf::RepeatedField< double >& + desiredstateq() const; + ::google::protobuf::RepeatedField< double >* + mutable_desiredstateq(); + + // repeated double desiredStateQdot = 9; + int desiredstateqdot_size() const; + void clear_desiredstateqdot(); + static const int kDesiredStateQdotFieldNumber = 9; + double desiredstateqdot(int index) const; + void set_desiredstateqdot(int index, double value); + void add_desiredstateqdot(double value); + const ::google::protobuf::RepeatedField< double >& + desiredstateqdot() const; + ::google::protobuf::RepeatedField< double >* + mutable_desiredstateqdot(); + + // repeated double desiredStateForceTorque = 10; + int desiredstateforcetorque_size() const; + void clear_desiredstateforcetorque(); + static const int kDesiredStateForceTorqueFieldNumber = 10; + double desiredstateforcetorque(int index) const; + void set_desiredstateforcetorque(int index, double value); + void add_desiredstateforcetorque(double value); + const ::google::protobuf::RepeatedField< double >& + desiredstateforcetorque() const; + ::google::protobuf::RepeatedField< double >* + mutable_desiredstateforcetorque(); + + // int32 bodyUniqueId = 1; + void clear_bodyuniqueid(); + static const int kBodyUniqueIdFieldNumber = 1; + ::google::protobuf::int32 bodyuniqueid() const; + void set_bodyuniqueid(::google::protobuf::int32 value); + + // int32 controlMode = 2; + void clear_controlmode(); + static const int kControlModeFieldNumber = 2; + ::google::protobuf::int32 controlmode() const; + void set_controlmode(::google::protobuf::int32 value); + + // int32 updateFlags = 3; + void clear_updateflags(); + static const int kUpdateFlagsFieldNumber = 3; + ::google::protobuf::int32 updateflags() const; + void set_updateflags(::google::protobuf::int32 value); + + // @@protoc_insertion_point(class_scope:pybullet_grpc.JointMotorControlCommand) + private: + + ::google::protobuf::internal::InternalMetadataWithArena _internal_metadata_; + ::google::protobuf::RepeatedField< double > kp_; + mutable int _kp_cached_byte_size_; + ::google::protobuf::RepeatedField< double > kd_; + mutable int _kd_cached_byte_size_; + ::google::protobuf::RepeatedField< double > maxvelocity_; + mutable int _maxvelocity_cached_byte_size_; + ::google::protobuf::RepeatedField< ::google::protobuf::int32 > hasdesiredstateflags_; + mutable int _hasdesiredstateflags_cached_byte_size_; + ::google::protobuf::RepeatedField< double > desiredstateq_; + mutable int _desiredstateq_cached_byte_size_; + ::google::protobuf::RepeatedField< double > desiredstateqdot_; + mutable int _desiredstateqdot_cached_byte_size_; + ::google::protobuf::RepeatedField< double > desiredstateforcetorque_; + mutable int _desiredstateforcetorque_cached_byte_size_; + ::google::protobuf::int32 bodyuniqueid_; + ::google::protobuf::int32 controlmode_; + ::google::protobuf::int32 updateflags_; + mutable int _cached_size_; + friend struct protobuf_pybullet_2eproto::TableStruct; +}; +// ------------------------------------------------------------------- + +class UserConstraintCommand : public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:pybullet_grpc.UserConstraintCommand) */ { + public: + UserConstraintCommand(); + virtual ~UserConstraintCommand(); + + UserConstraintCommand(const UserConstraintCommand& from); + + inline UserConstraintCommand& operator=(const UserConstraintCommand& from) { + CopyFrom(from); + return *this; + } + + static const ::google::protobuf::Descriptor* descriptor(); + static const UserConstraintCommand& default_instance(); + + static inline const UserConstraintCommand* internal_default_instance() { + return reinterpret_cast( + &_UserConstraintCommand_default_instance_); + } + + void Swap(UserConstraintCommand* other); + + // implements Message ---------------------------------------------- + + inline UserConstraintCommand* New() const PROTOBUF_FINAL { return New(NULL); } + + UserConstraintCommand* 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 UserConstraintCommand& from); + void MergeFrom(const UserConstraintCommand& 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(UserConstraintCommand* 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 ------------------------------------------------------- + + // .pybullet_grpc.transform parentFrame = 5; + bool has_parentframe() const; + void clear_parentframe(); + static const int kParentFrameFieldNumber = 5; + const ::pybullet_grpc::transform& parentframe() const; + ::pybullet_grpc::transform* mutable_parentframe(); + ::pybullet_grpc::transform* release_parentframe(); + void set_allocated_parentframe(::pybullet_grpc::transform* parentframe); + + // .pybullet_grpc.transform childFrame = 6; + bool has_childframe() const; + void clear_childframe(); + static const int kChildFrameFieldNumber = 6; + const ::pybullet_grpc::transform& childframe() const; + ::pybullet_grpc::transform* mutable_childframe(); + ::pybullet_grpc::transform* release_childframe(); + void set_allocated_childframe(::pybullet_grpc::transform* childframe); + + // .pybullet_grpc.vec3 jointAxis = 7; + bool has_jointaxis() const; + void clear_jointaxis(); + static const int kJointAxisFieldNumber = 7; + const ::pybullet_grpc::vec3& jointaxis() const; + ::pybullet_grpc::vec3* mutable_jointaxis(); + ::pybullet_grpc::vec3* release_jointaxis(); + void set_allocated_jointaxis(::pybullet_grpc::vec3* jointaxis); + + // int32 parentBodyIndex = 1; + void clear_parentbodyindex(); + static const int kParentBodyIndexFieldNumber = 1; + ::google::protobuf::int32 parentbodyindex() const; + void set_parentbodyindex(::google::protobuf::int32 value); + + // int32 parentJointIndex = 2; + void clear_parentjointindex(); + static const int kParentJointIndexFieldNumber = 2; + ::google::protobuf::int32 parentjointindex() const; + void set_parentjointindex(::google::protobuf::int32 value); + + // int32 childBodyIndex = 3; + void clear_childbodyindex(); + static const int kChildBodyIndexFieldNumber = 3; + ::google::protobuf::int32 childbodyindex() const; + void set_childbodyindex(::google::protobuf::int32 value); + + // int32 childJointIndex = 4; + void clear_childjointindex(); + static const int kChildJointIndexFieldNumber = 4; + ::google::protobuf::int32 childjointindex() const; + void set_childjointindex(::google::protobuf::int32 value); + + // double maxAppliedForce = 9; + void clear_maxappliedforce(); + static const int kMaxAppliedForceFieldNumber = 9; + double maxappliedforce() const; + void set_maxappliedforce(double value); + + // int32 jointType = 8; + void clear_jointtype(); + static const int kJointTypeFieldNumber = 8; + ::google::protobuf::int32 jointtype() const; + void set_jointtype(::google::protobuf::int32 value); + + // int32 userConstraintUniqueId = 10; + void clear_userconstraintuniqueid(); + static const int kUserConstraintUniqueIdFieldNumber = 10; + ::google::protobuf::int32 userconstraintuniqueid() const; + void set_userconstraintuniqueid(::google::protobuf::int32 value); + + // double gearRatio = 11; + void clear_gearratio(); + static const int kGearRatioFieldNumber = 11; + double gearratio() const; + void set_gearratio(double value); + + // double relativePositionTarget = 13; + void clear_relativepositiontarget(); + static const int kRelativePositionTargetFieldNumber = 13; + double relativepositiontarget() const; + void set_relativepositiontarget(double value); + + // int32 gearAuxLink = 12; + void clear_gearauxlink(); + static const int kGearAuxLinkFieldNumber = 12; + ::google::protobuf::int32 gearauxlink() const; + void set_gearauxlink(::google::protobuf::int32 value); + + // int32 updateFlags = 15; + void clear_updateflags(); + static const int kUpdateFlagsFieldNumber = 15; + ::google::protobuf::int32 updateflags() const; + void set_updateflags(::google::protobuf::int32 value); + + // double erp = 14; + void clear_erp(); + static const int kErpFieldNumber = 14; + double erp() const; + void set_erp(double value); + + // @@protoc_insertion_point(class_scope:pybullet_grpc.UserConstraintCommand) + private: + + ::google::protobuf::internal::InternalMetadataWithArena _internal_metadata_; + ::pybullet_grpc::transform* parentframe_; + ::pybullet_grpc::transform* childframe_; + ::pybullet_grpc::vec3* jointaxis_; + ::google::protobuf::int32 parentbodyindex_; + ::google::protobuf::int32 parentjointindex_; + ::google::protobuf::int32 childbodyindex_; + ::google::protobuf::int32 childjointindex_; + double maxappliedforce_; + ::google::protobuf::int32 jointtype_; + ::google::protobuf::int32 userconstraintuniqueid_; + double gearratio_; + double relativepositiontarget_; + ::google::protobuf::int32 gearauxlink_; + ::google::protobuf::int32 updateflags_; + double erp_; + mutable int _cached_size_; + friend struct protobuf_pybullet_2eproto::TableStruct; +}; +// ------------------------------------------------------------------- + +class UserConstraintStatus : public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:pybullet_grpc.UserConstraintStatus) */ { + public: + UserConstraintStatus(); + virtual ~UserConstraintStatus(); + + UserConstraintStatus(const UserConstraintStatus& from); + + inline UserConstraintStatus& operator=(const UserConstraintStatus& from) { + CopyFrom(from); + return *this; + } + + static const ::google::protobuf::Descriptor* descriptor(); + static const UserConstraintStatus& default_instance(); + + static inline const UserConstraintStatus* internal_default_instance() { + return reinterpret_cast( + &_UserConstraintStatus_default_instance_); + } + + void Swap(UserConstraintStatus* other); + + // implements Message ---------------------------------------------- + + inline UserConstraintStatus* New() const PROTOBUF_FINAL { return New(NULL); } + + UserConstraintStatus* 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 UserConstraintStatus& from); + void MergeFrom(const UserConstraintStatus& 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(UserConstraintStatus* 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 maxAppliedForce = 9; + void clear_maxappliedforce(); + static const int kMaxAppliedForceFieldNumber = 9; + double maxappliedforce() const; + void set_maxappliedforce(double value); + + // int32 userConstraintUniqueId = 10; + void clear_userconstraintuniqueid(); + static const int kUserConstraintUniqueIdFieldNumber = 10; + ::google::protobuf::int32 userconstraintuniqueid() const; + void set_userconstraintuniqueid(::google::protobuf::int32 value); + + // @@protoc_insertion_point(class_scope:pybullet_grpc.UserConstraintStatus) + private: + + ::google::protobuf::internal::InternalMetadataWithArena _internal_metadata_; + double maxappliedforce_; + ::google::protobuf::int32 userconstraintuniqueid_; + mutable int _cached_size_; + friend struct protobuf_pybullet_2eproto::TableStruct; +}; +// ------------------------------------------------------------------- + +class UserConstraintStateStatus : public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:pybullet_grpc.UserConstraintStateStatus) */ { + public: + UserConstraintStateStatus(); + virtual ~UserConstraintStateStatus(); + + UserConstraintStateStatus(const UserConstraintStateStatus& from); + + inline UserConstraintStateStatus& operator=(const UserConstraintStateStatus& from) { + CopyFrom(from); + return *this; + } + + static const ::google::protobuf::Descriptor* descriptor(); + static const UserConstraintStateStatus& default_instance(); + + static inline const UserConstraintStateStatus* internal_default_instance() { + return reinterpret_cast( + &_UserConstraintStateStatus_default_instance_); + } + + void Swap(UserConstraintStateStatus* other); + + // implements Message ---------------------------------------------- + + inline UserConstraintStateStatus* New() const PROTOBUF_FINAL { return New(NULL); } + + UserConstraintStateStatus* 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 UserConstraintStateStatus& from); + void MergeFrom(const UserConstraintStateStatus& 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(UserConstraintStateStatus* 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 ------------------------------------------------------- + + // .pybullet_grpc.vec3 appliedConstraintForcesLinear = 1; + bool has_appliedconstraintforceslinear() const; + void clear_appliedconstraintforceslinear(); + static const int kAppliedConstraintForcesLinearFieldNumber = 1; + const ::pybullet_grpc::vec3& appliedconstraintforceslinear() const; + ::pybullet_grpc::vec3* mutable_appliedconstraintforceslinear(); + ::pybullet_grpc::vec3* release_appliedconstraintforceslinear(); + void set_allocated_appliedconstraintforceslinear(::pybullet_grpc::vec3* appliedconstraintforceslinear); + + // .pybullet_grpc.vec3 appliedConstraintForcesAngular = 2; + bool has_appliedconstraintforcesangular() const; + void clear_appliedconstraintforcesangular(); + static const int kAppliedConstraintForcesAngularFieldNumber = 2; + const ::pybullet_grpc::vec3& appliedconstraintforcesangular() const; + ::pybullet_grpc::vec3* mutable_appliedconstraintforcesangular(); + ::pybullet_grpc::vec3* release_appliedconstraintforcesangular(); + void set_allocated_appliedconstraintforcesangular(::pybullet_grpc::vec3* appliedconstraintforcesangular); + + // int32 numDofs = 3; + void clear_numdofs(); + static const int kNumDofsFieldNumber = 3; + ::google::protobuf::int32 numdofs() const; + void set_numdofs(::google::protobuf::int32 value); + + // @@protoc_insertion_point(class_scope:pybullet_grpc.UserConstraintStateStatus) + private: + + ::google::protobuf::internal::InternalMetadataWithArena _internal_metadata_; + ::pybullet_grpc::vec3* appliedconstraintforceslinear_; + ::pybullet_grpc::vec3* appliedconstraintforcesangular_; + ::google::protobuf::int32 numdofs_; + mutable int _cached_size_; + friend struct protobuf_pybullet_2eproto::TableStruct; +}; +// ------------------------------------------------------------------- + +class RequestKeyboardEventsCommand : public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:pybullet_grpc.RequestKeyboardEventsCommand) */ { + public: + RequestKeyboardEventsCommand(); + virtual ~RequestKeyboardEventsCommand(); + + RequestKeyboardEventsCommand(const RequestKeyboardEventsCommand& from); + + inline RequestKeyboardEventsCommand& operator=(const RequestKeyboardEventsCommand& from) { + CopyFrom(from); + return *this; + } + + static const ::google::protobuf::Descriptor* descriptor(); + static const RequestKeyboardEventsCommand& default_instance(); + + static inline const RequestKeyboardEventsCommand* internal_default_instance() { + return reinterpret_cast( + &_RequestKeyboardEventsCommand_default_instance_); + } + + void Swap(RequestKeyboardEventsCommand* other); + + // implements Message ---------------------------------------------- + + inline RequestKeyboardEventsCommand* New() const PROTOBUF_FINAL { return New(NULL); } + + RequestKeyboardEventsCommand* 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 RequestKeyboardEventsCommand& from); + void MergeFrom(const RequestKeyboardEventsCommand& 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(RequestKeyboardEventsCommand* 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.RequestKeyboardEventsCommand) + private: + + ::google::protobuf::internal::InternalMetadataWithArena _internal_metadata_; + mutable int _cached_size_; + friend struct protobuf_pybullet_2eproto::TableStruct; +}; +// ------------------------------------------------------------------- + +class KeyboardEvent : public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:pybullet_grpc.KeyboardEvent) */ { + public: + KeyboardEvent(); + virtual ~KeyboardEvent(); + + KeyboardEvent(const KeyboardEvent& from); + + inline KeyboardEvent& operator=(const KeyboardEvent& from) { + CopyFrom(from); + return *this; + } + + static const ::google::protobuf::Descriptor* descriptor(); + static const KeyboardEvent& default_instance(); + + static inline const KeyboardEvent* internal_default_instance() { + return reinterpret_cast( + &_KeyboardEvent_default_instance_); + } + + void Swap(KeyboardEvent* other); + + // implements Message ---------------------------------------------- + + inline KeyboardEvent* New() const PROTOBUF_FINAL { return New(NULL); } + + KeyboardEvent* 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 KeyboardEvent& from); + void MergeFrom(const KeyboardEvent& 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(KeyboardEvent* 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 keyCode = 1; + void clear_keycode(); + static const int kKeyCodeFieldNumber = 1; + ::google::protobuf::int32 keycode() const; + void set_keycode(::google::protobuf::int32 value); + + // int32 keyState = 2; + void clear_keystate(); + static const int kKeyStateFieldNumber = 2; + ::google::protobuf::int32 keystate() const; + void set_keystate(::google::protobuf::int32 value); + + // @@protoc_insertion_point(class_scope:pybullet_grpc.KeyboardEvent) + private: + + ::google::protobuf::internal::InternalMetadataWithArena _internal_metadata_; + ::google::protobuf::int32 keycode_; + ::google::protobuf::int32 keystate_; + mutable int _cached_size_; + friend struct protobuf_pybullet_2eproto::TableStruct; +}; +// ------------------------------------------------------------------- + +class KeyboardEventsStatus : public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:pybullet_grpc.KeyboardEventsStatus) */ { + public: + KeyboardEventsStatus(); + virtual ~KeyboardEventsStatus(); + + KeyboardEventsStatus(const KeyboardEventsStatus& from); + + inline KeyboardEventsStatus& operator=(const KeyboardEventsStatus& from) { + CopyFrom(from); + return *this; + } + + static const ::google::protobuf::Descriptor* descriptor(); + static const KeyboardEventsStatus& default_instance(); + + static inline const KeyboardEventsStatus* internal_default_instance() { + return reinterpret_cast( + &_KeyboardEventsStatus_default_instance_); + } + + void Swap(KeyboardEventsStatus* other); + + // implements Message ---------------------------------------------- + + inline KeyboardEventsStatus* New() const PROTOBUF_FINAL { return New(NULL); } + + KeyboardEventsStatus* 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 KeyboardEventsStatus& from); + void MergeFrom(const KeyboardEventsStatus& 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(KeyboardEventsStatus* 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 ------------------------------------------------------- + + // repeated .pybullet_grpc.KeyboardEvent keyboardEvents = 1; + int keyboardevents_size() const; + void clear_keyboardevents(); + static const int kKeyboardEventsFieldNumber = 1; + const ::pybullet_grpc::KeyboardEvent& keyboardevents(int index) const; + ::pybullet_grpc::KeyboardEvent* mutable_keyboardevents(int index); + ::pybullet_grpc::KeyboardEvent* add_keyboardevents(); + ::google::protobuf::RepeatedPtrField< ::pybullet_grpc::KeyboardEvent >* + mutable_keyboardevents(); + const ::google::protobuf::RepeatedPtrField< ::pybullet_grpc::KeyboardEvent >& + keyboardevents() const; + + // @@protoc_insertion_point(class_scope:pybullet_grpc.KeyboardEventsStatus) + private: + + ::google::protobuf::internal::InternalMetadataWithArena _internal_metadata_; + ::google::protobuf::RepeatedPtrField< ::pybullet_grpc::KeyboardEvent > keyboardevents_; + mutable int _cached_size_; + friend struct protobuf_pybullet_2eproto::TableStruct; +}; +// ------------------------------------------------------------------- + +class RequestCameraImageCommand : public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:pybullet_grpc.RequestCameraImageCommand) */ { + public: + RequestCameraImageCommand(); + virtual ~RequestCameraImageCommand(); + + RequestCameraImageCommand(const RequestCameraImageCommand& from); + + inline RequestCameraImageCommand& operator=(const RequestCameraImageCommand& from) { + CopyFrom(from); + return *this; + } + + static const ::google::protobuf::Descriptor* descriptor(); + static const RequestCameraImageCommand& default_instance(); + + static inline const RequestCameraImageCommand* internal_default_instance() { + return reinterpret_cast( + &_RequestCameraImageCommand_default_instance_); + } + + void Swap(RequestCameraImageCommand* other); + + // implements Message ---------------------------------------------- + + inline RequestCameraImageCommand* New() const PROTOBUF_FINAL { return New(NULL); } + + RequestCameraImageCommand* 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 RequestCameraImageCommand& from); + void MergeFrom(const RequestCameraImageCommand& 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(RequestCameraImageCommand* 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 ------------------------------------------------------- + + // .pybullet_grpc.matrix4x4 viewMatrix = 3; + bool has_viewmatrix() const; + void clear_viewmatrix(); + static const int kViewMatrixFieldNumber = 3; + const ::pybullet_grpc::matrix4x4& viewmatrix() const; + ::pybullet_grpc::matrix4x4* mutable_viewmatrix(); + ::pybullet_grpc::matrix4x4* release_viewmatrix(); + void set_allocated_viewmatrix(::pybullet_grpc::matrix4x4* viewmatrix); + + // .pybullet_grpc.matrix4x4 projectionMatrix = 4; + bool has_projectionmatrix() const; + void clear_projectionmatrix(); + static const int kProjectionMatrixFieldNumber = 4; + const ::pybullet_grpc::matrix4x4& projectionmatrix() const; + ::pybullet_grpc::matrix4x4* mutable_projectionmatrix(); + ::pybullet_grpc::matrix4x4* release_projectionmatrix(); + void set_allocated_projectionmatrix(::pybullet_grpc::matrix4x4* projectionmatrix); + + // .pybullet_grpc.vec3 lightDirection = 8; + bool has_lightdirection() const; + void clear_lightdirection(); + static const int kLightDirectionFieldNumber = 8; + const ::pybullet_grpc::vec3& lightdirection() const; + ::pybullet_grpc::vec3* mutable_lightdirection(); + ::pybullet_grpc::vec3* release_lightdirection(); + void set_allocated_lightdirection(::pybullet_grpc::vec3* lightdirection); + + // .pybullet_grpc.vec3 lightColor = 9; + bool has_lightcolor() const; + void clear_lightcolor(); + static const int kLightColorFieldNumber = 9; + const ::pybullet_grpc::vec3& lightcolor() const; + ::pybullet_grpc::vec3* mutable_lightcolor(); + ::pybullet_grpc::vec3* release_lightcolor(); + void set_allocated_lightcolor(::pybullet_grpc::vec3* lightcolor); + + // .pybullet_grpc.matrix4x4 projectiveTextureViewMatrix = 15; + bool has_projectivetextureviewmatrix() const; + void clear_projectivetextureviewmatrix(); + static const int kProjectiveTextureViewMatrixFieldNumber = 15; + const ::pybullet_grpc::matrix4x4& projectivetextureviewmatrix() const; + ::pybullet_grpc::matrix4x4* mutable_projectivetextureviewmatrix(); + ::pybullet_grpc::matrix4x4* release_projectivetextureviewmatrix(); + void set_allocated_projectivetextureviewmatrix(::pybullet_grpc::matrix4x4* projectivetextureviewmatrix); + + // .pybullet_grpc.matrix4x4 projectiveTextureProjectionMatrix = 16; + bool has_projectivetextureprojectionmatrix() const; + void clear_projectivetextureprojectionmatrix(); + static const int kProjectiveTextureProjectionMatrixFieldNumber = 16; + const ::pybullet_grpc::matrix4x4& projectivetextureprojectionmatrix() const; + ::pybullet_grpc::matrix4x4* mutable_projectivetextureprojectionmatrix(); + ::pybullet_grpc::matrix4x4* release_projectivetextureprojectionmatrix(); + void set_allocated_projectivetextureprojectionmatrix(::pybullet_grpc::matrix4x4* projectivetextureprojectionmatrix); + + // int32 updateFlags = 1; + void clear_updateflags(); + static const int kUpdateFlagsFieldNumber = 1; + ::google::protobuf::int32 updateflags() const; + void set_updateflags(::google::protobuf::int32 value); + + // int32 cameraFlags = 2; + void clear_cameraflags(); + static const int kCameraFlagsFieldNumber = 2; + ::google::protobuf::int32 cameraflags() const; + void set_cameraflags(::google::protobuf::int32 value); + + // int32 startPixelIndex = 5; + void clear_startpixelindex(); + static const int kStartPixelIndexFieldNumber = 5; + ::google::protobuf::int32 startpixelindex() const; + void set_startpixelindex(::google::protobuf::int32 value); + + // int32 pixelWidth = 6; + void clear_pixelwidth(); + static const int kPixelWidthFieldNumber = 6; + ::google::protobuf::int32 pixelwidth() const; + void set_pixelwidth(::google::protobuf::int32 value); + + // double lightDistance = 10; + void clear_lightdistance(); + static const int kLightDistanceFieldNumber = 10; + double lightdistance() const; + void set_lightdistance(double value); + + // int32 pixelHeight = 7; + void clear_pixelheight(); + static const int kPixelHeightFieldNumber = 7; + ::google::protobuf::int32 pixelheight() const; + void set_pixelheight(::google::protobuf::int32 value); + + // int32 hasShadow = 14; + void clear_hasshadow(); + static const int kHasShadowFieldNumber = 14; + ::google::protobuf::int32 hasshadow() const; + void set_hasshadow(::google::protobuf::int32 value); + + // double lightAmbientCoeff = 11; + void clear_lightambientcoeff(); + static const int kLightAmbientCoeffFieldNumber = 11; + double lightambientcoeff() const; + void set_lightambientcoeff(double value); + + // double lightDiffuseCoeff = 12; + void clear_lightdiffusecoeff(); + static const int kLightDiffuseCoeffFieldNumber = 12; + double lightdiffusecoeff() const; + void set_lightdiffusecoeff(double value); + + // double lightSpecularCoeff = 13; + void clear_lightspecularcoeff(); + static const int kLightSpecularCoeffFieldNumber = 13; + double lightspecularcoeff() const; + void set_lightspecularcoeff(double value); + + // @@protoc_insertion_point(class_scope:pybullet_grpc.RequestCameraImageCommand) + private: + + ::google::protobuf::internal::InternalMetadataWithArena _internal_metadata_; + ::pybullet_grpc::matrix4x4* viewmatrix_; + ::pybullet_grpc::matrix4x4* projectionmatrix_; + ::pybullet_grpc::vec3* lightdirection_; + ::pybullet_grpc::vec3* lightcolor_; + ::pybullet_grpc::matrix4x4* projectivetextureviewmatrix_; + ::pybullet_grpc::matrix4x4* projectivetextureprojectionmatrix_; + ::google::protobuf::int32 updateflags_; + ::google::protobuf::int32 cameraflags_; + ::google::protobuf::int32 startpixelindex_; + ::google::protobuf::int32 pixelwidth_; + double lightdistance_; + ::google::protobuf::int32 pixelheight_; + ::google::protobuf::int32 hasshadow_; + double lightambientcoeff_; + double lightdiffusecoeff_; + double lightspecularcoeff_; + mutable int _cached_size_; + friend struct protobuf_pybullet_2eproto::TableStruct; +}; +// ------------------------------------------------------------------- + +class RequestCameraImageStatus : public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:pybullet_grpc.RequestCameraImageStatus) */ { + public: + RequestCameraImageStatus(); + virtual ~RequestCameraImageStatus(); + + RequestCameraImageStatus(const RequestCameraImageStatus& from); + + inline RequestCameraImageStatus& operator=(const RequestCameraImageStatus& from) { + CopyFrom(from); + return *this; + } + + static const ::google::protobuf::Descriptor* descriptor(); + static const RequestCameraImageStatus& default_instance(); + + static inline const RequestCameraImageStatus* internal_default_instance() { + return reinterpret_cast( + &_RequestCameraImageStatus_default_instance_); + } + + void Swap(RequestCameraImageStatus* other); + + // implements Message ---------------------------------------------- + + inline RequestCameraImageStatus* New() const PROTOBUF_FINAL { return New(NULL); } + + RequestCameraImageStatus* 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 RequestCameraImageStatus& from); + void MergeFrom(const RequestCameraImageStatus& 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(RequestCameraImageStatus* 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 imageWidth = 1; + void clear_imagewidth(); + static const int kImageWidthFieldNumber = 1; + ::google::protobuf::int32 imagewidth() const; + void set_imagewidth(::google::protobuf::int32 value); + + // int32 imageHeight = 2; + void clear_imageheight(); + static const int kImageHeightFieldNumber = 2; + ::google::protobuf::int32 imageheight() const; + void set_imageheight(::google::protobuf::int32 value); + + // int32 startingPixelIndex = 3; + void clear_startingpixelindex(); + static const int kStartingPixelIndexFieldNumber = 3; + ::google::protobuf::int32 startingpixelindex() const; + void set_startingpixelindex(::google::protobuf::int32 value); + + // int32 numPixelsCopied = 4; + void clear_numpixelscopied(); + static const int kNumPixelsCopiedFieldNumber = 4; + ::google::protobuf::int32 numpixelscopied() const; + void set_numpixelscopied(::google::protobuf::int32 value); + + // int32 numRemainingPixels = 5; + void clear_numremainingpixels(); + static const int kNumRemainingPixelsFieldNumber = 5; + ::google::protobuf::int32 numremainingpixels() const; + void set_numremainingpixels(::google::protobuf::int32 value); + + // @@protoc_insertion_point(class_scope:pybullet_grpc.RequestCameraImageStatus) + private: + + ::google::protobuf::internal::InternalMetadataWithArena _internal_metadata_; + ::google::protobuf::int32 imagewidth_; + ::google::protobuf::int32 imageheight_; + ::google::protobuf::int32 startingpixelindex_; + ::google::protobuf::int32 numpixelscopied_; + ::google::protobuf::int32 numremainingpixels_; + 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(); @@ -2326,15 +4875,24 @@ class PyBulletCommand : public ::google::protobuf::Message /* @@protoc_insertion static const PyBulletCommand& default_instance(); enum CommandsCase { - kLoadUrdfCommand = 3, - kTerminateServerCommand = 4, - kStepSimulationCommand = 5, - kLoadSdfCommand = 6, - kLoadMjcfCommand = 7, - kChangeDynamicsCommand = 8, - kGetDynamicsCommand = 9, - kInitPoseCommand = 10, - kRequestActualStateCommand = 11, + kLoadUrdfCommand = 4, + kTerminateServerCommand = 5, + kStepSimulationCommand = 6, + kLoadSdfCommand = 7, + kLoadMjcfCommand = 8, + kChangeDynamicsCommand = 9, + kGetDynamicsCommand = 10, + kInitPoseCommand = 11, + kRequestActualStateCommand = 12, + kConfigureOpenGLVisualizerCommand = 13, + kSyncBodiesCommand = 14, + kRequestBodyInfoCommand = 15, + kSetPhysicsSimulationParametersCommand = 16, + kJointMotorControlCommand = 17, + kUserConstraintCommand = 18, + kCheckVersionCommand = 19, + kRequestKeyboardEventsCommand = 20, + kRequestCameraImageCommand = 21, COMMANDS_NOT_SET = 0, }; @@ -2390,93 +4948,206 @@ class PyBulletCommand : public ::google::protobuf::Message /* @@protoc_insertion // accessors ------------------------------------------------------- + // repeated bytes binaryBlob = 2; + int binaryblob_size() const; + void clear_binaryblob(); + static const int kBinaryBlobFieldNumber = 2; + const ::std::string& binaryblob(int index) const; + ::std::string* mutable_binaryblob(int index); + void set_binaryblob(int index, const ::std::string& value); + void set_binaryblob(int index, const char* value); + void set_binaryblob(int index, const void* value, size_t size); + ::std::string* add_binaryblob(); + void add_binaryblob(const ::std::string& value); + void add_binaryblob(const char* value); + void add_binaryblob(const void* value, size_t size); + const ::google::protobuf::RepeatedPtrField< ::std::string>& binaryblob() const; + ::google::protobuf::RepeatedPtrField< ::std::string>* mutable_binaryblob(); + + // repeated bytes unknownCommandBinaryBlob = 3; + int unknowncommandbinaryblob_size() const; + void clear_unknowncommandbinaryblob(); + static const int kUnknownCommandBinaryBlobFieldNumber = 3; + const ::std::string& unknowncommandbinaryblob(int index) const; + ::std::string* mutable_unknowncommandbinaryblob(int index); + void set_unknowncommandbinaryblob(int index, const ::std::string& value); + void set_unknowncommandbinaryblob(int index, const char* value); + void set_unknowncommandbinaryblob(int index, const void* value, size_t size); + ::std::string* add_unknowncommandbinaryblob(); + void add_unknowncommandbinaryblob(const ::std::string& value); + void add_unknowncommandbinaryblob(const char* value); + void add_unknowncommandbinaryblob(const void* value, size_t size); + const ::google::protobuf::RepeatedPtrField< ::std::string>& unknowncommandbinaryblob() const; + ::google::protobuf::RepeatedPtrField< ::std::string>* mutable_unknowncommandbinaryblob(); + // 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; + // .pybullet_grpc.LoadUrdfCommand loadUrdfCommand = 4; bool has_loadurdfcommand() const; void clear_loadurdfcommand(); - static const int kLoadUrdfCommandFieldNumber = 3; + static const int kLoadUrdfCommandFieldNumber = 4; 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; + // .pybullet_grpc.TerminateServerCommand terminateServerCommand = 5; bool has_terminateservercommand() const; void clear_terminateservercommand(); - static const int kTerminateServerCommandFieldNumber = 4; + static const int kTerminateServerCommandFieldNumber = 5; 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; + // .pybullet_grpc.StepSimulationCommand stepSimulationCommand = 6; bool has_stepsimulationcommand() const; void clear_stepsimulationcommand(); - static const int kStepSimulationCommandFieldNumber = 5; + static const int kStepSimulationCommandFieldNumber = 6; const ::pybullet_grpc::StepSimulationCommand& stepsimulationcommand() const; ::pybullet_grpc::StepSimulationCommand* mutable_stepsimulationcommand(); ::pybullet_grpc::StepSimulationCommand* release_stepsimulationcommand(); void set_allocated_stepsimulationcommand(::pybullet_grpc::StepSimulationCommand* stepsimulationcommand); - // .pybullet_grpc.LoadSdfCommand loadSdfCommand = 6; + // .pybullet_grpc.LoadSdfCommand loadSdfCommand = 7; bool has_loadsdfcommand() const; void clear_loadsdfcommand(); - static const int kLoadSdfCommandFieldNumber = 6; + static const int kLoadSdfCommandFieldNumber = 7; const ::pybullet_grpc::LoadSdfCommand& loadsdfcommand() const; ::pybullet_grpc::LoadSdfCommand* mutable_loadsdfcommand(); ::pybullet_grpc::LoadSdfCommand* release_loadsdfcommand(); void set_allocated_loadsdfcommand(::pybullet_grpc::LoadSdfCommand* loadsdfcommand); - // .pybullet_grpc.LoadMjcfCommand loadMjcfCommand = 7; + // .pybullet_grpc.LoadMjcfCommand loadMjcfCommand = 8; bool has_loadmjcfcommand() const; void clear_loadmjcfcommand(); - static const int kLoadMjcfCommandFieldNumber = 7; + static const int kLoadMjcfCommandFieldNumber = 8; const ::pybullet_grpc::LoadMjcfCommand& loadmjcfcommand() const; ::pybullet_grpc::LoadMjcfCommand* mutable_loadmjcfcommand(); ::pybullet_grpc::LoadMjcfCommand* release_loadmjcfcommand(); void set_allocated_loadmjcfcommand(::pybullet_grpc::LoadMjcfCommand* loadmjcfcommand); - // .pybullet_grpc.ChangeDynamicsCommand changeDynamicsCommand = 8; + // .pybullet_grpc.ChangeDynamicsCommand changeDynamicsCommand = 9; bool has_changedynamicscommand() const; void clear_changedynamicscommand(); - static const int kChangeDynamicsCommandFieldNumber = 8; + static const int kChangeDynamicsCommandFieldNumber = 9; const ::pybullet_grpc::ChangeDynamicsCommand& changedynamicscommand() const; ::pybullet_grpc::ChangeDynamicsCommand* mutable_changedynamicscommand(); ::pybullet_grpc::ChangeDynamicsCommand* release_changedynamicscommand(); void set_allocated_changedynamicscommand(::pybullet_grpc::ChangeDynamicsCommand* changedynamicscommand); - // .pybullet_grpc.GetDynamicsCommand getDynamicsCommand = 9; + // .pybullet_grpc.GetDynamicsCommand getDynamicsCommand = 10; bool has_getdynamicscommand() const; void clear_getdynamicscommand(); - static const int kGetDynamicsCommandFieldNumber = 9; + static const int kGetDynamicsCommandFieldNumber = 10; const ::pybullet_grpc::GetDynamicsCommand& getdynamicscommand() const; ::pybullet_grpc::GetDynamicsCommand* mutable_getdynamicscommand(); ::pybullet_grpc::GetDynamicsCommand* release_getdynamicscommand(); void set_allocated_getdynamicscommand(::pybullet_grpc::GetDynamicsCommand* getdynamicscommand); - // .pybullet_grpc.InitPoseCommand initPoseCommand = 10; + // .pybullet_grpc.InitPoseCommand initPoseCommand = 11; bool has_initposecommand() const; void clear_initposecommand(); - static const int kInitPoseCommandFieldNumber = 10; + static const int kInitPoseCommandFieldNumber = 11; const ::pybullet_grpc::InitPoseCommand& initposecommand() const; ::pybullet_grpc::InitPoseCommand* mutable_initposecommand(); ::pybullet_grpc::InitPoseCommand* release_initposecommand(); void set_allocated_initposecommand(::pybullet_grpc::InitPoseCommand* initposecommand); - // .pybullet_grpc.RequestActualStateCommand requestActualStateCommand = 11; + // .pybullet_grpc.RequestActualStateCommand requestActualStateCommand = 12; bool has_requestactualstatecommand() const; void clear_requestactualstatecommand(); - static const int kRequestActualStateCommandFieldNumber = 11; + static const int kRequestActualStateCommandFieldNumber = 12; const ::pybullet_grpc::RequestActualStateCommand& requestactualstatecommand() const; ::pybullet_grpc::RequestActualStateCommand* mutable_requestactualstatecommand(); ::pybullet_grpc::RequestActualStateCommand* release_requestactualstatecommand(); void set_allocated_requestactualstatecommand(::pybullet_grpc::RequestActualStateCommand* requestactualstatecommand); + // .pybullet_grpc.ConfigureOpenGLVisualizerCommand configureOpenGLVisualizerCommand = 13; + bool has_configureopenglvisualizercommand() const; + void clear_configureopenglvisualizercommand(); + static const int kConfigureOpenGLVisualizerCommandFieldNumber = 13; + const ::pybullet_grpc::ConfigureOpenGLVisualizerCommand& configureopenglvisualizercommand() const; + ::pybullet_grpc::ConfigureOpenGLVisualizerCommand* mutable_configureopenglvisualizercommand(); + ::pybullet_grpc::ConfigureOpenGLVisualizerCommand* release_configureopenglvisualizercommand(); + void set_allocated_configureopenglvisualizercommand(::pybullet_grpc::ConfigureOpenGLVisualizerCommand* configureopenglvisualizercommand); + + // .pybullet_grpc.SyncBodiesCommand syncBodiesCommand = 14; + bool has_syncbodiescommand() const; + void clear_syncbodiescommand(); + static const int kSyncBodiesCommandFieldNumber = 14; + const ::pybullet_grpc::SyncBodiesCommand& syncbodiescommand() const; + ::pybullet_grpc::SyncBodiesCommand* mutable_syncbodiescommand(); + ::pybullet_grpc::SyncBodiesCommand* release_syncbodiescommand(); + void set_allocated_syncbodiescommand(::pybullet_grpc::SyncBodiesCommand* syncbodiescommand); + + // .pybullet_grpc.RequestBodyInfoCommand requestBodyInfoCommand = 15; + bool has_requestbodyinfocommand() const; + void clear_requestbodyinfocommand(); + static const int kRequestBodyInfoCommandFieldNumber = 15; + const ::pybullet_grpc::RequestBodyInfoCommand& requestbodyinfocommand() const; + ::pybullet_grpc::RequestBodyInfoCommand* mutable_requestbodyinfocommand(); + ::pybullet_grpc::RequestBodyInfoCommand* release_requestbodyinfocommand(); + void set_allocated_requestbodyinfocommand(::pybullet_grpc::RequestBodyInfoCommand* requestbodyinfocommand); + + // .pybullet_grpc.PhysicsSimulationParametersCommand setPhysicsSimulationParametersCommand = 16; + bool has_setphysicssimulationparameterscommand() const; + void clear_setphysicssimulationparameterscommand(); + static const int kSetPhysicsSimulationParametersCommandFieldNumber = 16; + const ::pybullet_grpc::PhysicsSimulationParametersCommand& setphysicssimulationparameterscommand() const; + ::pybullet_grpc::PhysicsSimulationParametersCommand* mutable_setphysicssimulationparameterscommand(); + ::pybullet_grpc::PhysicsSimulationParametersCommand* release_setphysicssimulationparameterscommand(); + void set_allocated_setphysicssimulationparameterscommand(::pybullet_grpc::PhysicsSimulationParametersCommand* setphysicssimulationparameterscommand); + + // .pybullet_grpc.JointMotorControlCommand jointMotorControlCommand = 17; + bool has_jointmotorcontrolcommand() const; + void clear_jointmotorcontrolcommand(); + static const int kJointMotorControlCommandFieldNumber = 17; + const ::pybullet_grpc::JointMotorControlCommand& jointmotorcontrolcommand() const; + ::pybullet_grpc::JointMotorControlCommand* mutable_jointmotorcontrolcommand(); + ::pybullet_grpc::JointMotorControlCommand* release_jointmotorcontrolcommand(); + void set_allocated_jointmotorcontrolcommand(::pybullet_grpc::JointMotorControlCommand* jointmotorcontrolcommand); + + // .pybullet_grpc.UserConstraintCommand userConstraintCommand = 18; + bool has_userconstraintcommand() const; + void clear_userconstraintcommand(); + static const int kUserConstraintCommandFieldNumber = 18; + const ::pybullet_grpc::UserConstraintCommand& userconstraintcommand() const; + ::pybullet_grpc::UserConstraintCommand* mutable_userconstraintcommand(); + ::pybullet_grpc::UserConstraintCommand* release_userconstraintcommand(); + void set_allocated_userconstraintcommand(::pybullet_grpc::UserConstraintCommand* userconstraintcommand); + + // .pybullet_grpc.CheckVersionCommand checkVersionCommand = 19; + bool has_checkversioncommand() const; + void clear_checkversioncommand(); + static const int kCheckVersionCommandFieldNumber = 19; + const ::pybullet_grpc::CheckVersionCommand& checkversioncommand() const; + ::pybullet_grpc::CheckVersionCommand* mutable_checkversioncommand(); + ::pybullet_grpc::CheckVersionCommand* release_checkversioncommand(); + void set_allocated_checkversioncommand(::pybullet_grpc::CheckVersionCommand* checkversioncommand); + + // .pybullet_grpc.RequestKeyboardEventsCommand requestKeyboardEventsCommand = 20; + bool has_requestkeyboardeventscommand() const; + void clear_requestkeyboardeventscommand(); + static const int kRequestKeyboardEventsCommandFieldNumber = 20; + const ::pybullet_grpc::RequestKeyboardEventsCommand& requestkeyboardeventscommand() const; + ::pybullet_grpc::RequestKeyboardEventsCommand* mutable_requestkeyboardeventscommand(); + ::pybullet_grpc::RequestKeyboardEventsCommand* release_requestkeyboardeventscommand(); + void set_allocated_requestkeyboardeventscommand(::pybullet_grpc::RequestKeyboardEventsCommand* requestkeyboardeventscommand); + + // .pybullet_grpc.RequestCameraImageCommand requestCameraImageCommand = 21; + bool has_requestcameraimagecommand() const; + void clear_requestcameraimagecommand(); + static const int kRequestCameraImageCommandFieldNumber = 21; + const ::pybullet_grpc::RequestCameraImageCommand& requestcameraimagecommand() const; + ::pybullet_grpc::RequestCameraImageCommand* mutable_requestcameraimagecommand(); + ::pybullet_grpc::RequestCameraImageCommand* release_requestcameraimagecommand(); + void set_allocated_requestcameraimagecommand(::pybullet_grpc::RequestCameraImageCommand* requestcameraimagecommand); + CommandsCase commands_case() const; // @@protoc_insertion_point(class_scope:pybullet_grpc.PyBulletCommand) private: @@ -2489,12 +5160,23 @@ class PyBulletCommand : public ::google::protobuf::Message /* @@protoc_insertion void set_has_getdynamicscommand(); void set_has_initposecommand(); void set_has_requestactualstatecommand(); + void set_has_configureopenglvisualizercommand(); + void set_has_syncbodiescommand(); + void set_has_requestbodyinfocommand(); + void set_has_setphysicssimulationparameterscommand(); + void set_has_jointmotorcontrolcommand(); + void set_has_userconstraintcommand(); + void set_has_checkversioncommand(); + void set_has_requestkeyboardeventscommand(); + void set_has_requestcameraimagecommand(); inline bool has_commands() const; void clear_commands(); inline void clear_has_commands(); ::google::protobuf::internal::InternalMetadataWithArena _internal_metadata_; + ::google::protobuf::RepeatedPtrField< ::std::string> binaryblob_; + ::google::protobuf::RepeatedPtrField< ::std::string> unknowncommandbinaryblob_; ::google::protobuf::int32 commandtype_; union CommandsUnion { CommandsUnion() {} @@ -2507,6 +5189,15 @@ class PyBulletCommand : public ::google::protobuf::Message /* @@protoc_insertion ::pybullet_grpc::GetDynamicsCommand* getdynamicscommand_; ::pybullet_grpc::InitPoseCommand* initposecommand_; ::pybullet_grpc::RequestActualStateCommand* requestactualstatecommand_; + ::pybullet_grpc::ConfigureOpenGLVisualizerCommand* configureopenglvisualizercommand_; + ::pybullet_grpc::SyncBodiesCommand* syncbodiescommand_; + ::pybullet_grpc::RequestBodyInfoCommand* requestbodyinfocommand_; + ::pybullet_grpc::PhysicsSimulationParametersCommand* setphysicssimulationparameterscommand_; + ::pybullet_grpc::JointMotorControlCommand* jointmotorcontrolcommand_; + ::pybullet_grpc::UserConstraintCommand* userconstraintcommand_; + ::pybullet_grpc::CheckVersionCommand* checkversioncommand_; + ::pybullet_grpc::RequestKeyboardEventsCommand* requestkeyboardeventscommand_; + ::pybullet_grpc::RequestCameraImageCommand* requestcameraimagecommand_; } commands_; mutable int _cached_size_; ::google::protobuf::uint32 _oneof_case_[1]; @@ -2531,11 +5222,19 @@ class PyBulletStatus : public ::google::protobuf::Message /* @@protoc_insertion_ static const PyBulletStatus& default_instance(); enum StatusCase { - kUrdfStatus = 2, - kSdfStatus = 3, - kMjcfStatus = 4, - kGetDynamicsStatus = 5, - kActualStateStatus = 6, + kUrdfStatus = 4, + kSdfStatus = 5, + kMjcfStatus = 6, + kGetDynamicsStatus = 7, + kActualStateStatus = 8, + kSyncBodiesStatus = 9, + kRequestBodyInfoStatus = 10, + kRequestPhysicsSimulationParametersStatus = 11, + kCheckVersionStatus = 12, + kUserConstraintStatus = 13, + kUserConstraintStateStatus = 14, + kKeyboardEventsStatus = 15, + kRequestCameraImageStatus = 16, STATUS_NOT_SET = 0, }; @@ -2591,57 +5290,161 @@ class PyBulletStatus : public ::google::protobuf::Message /* @@protoc_insertion_ // accessors ------------------------------------------------------- + // repeated bytes binaryBlob = 2; + int binaryblob_size() const; + void clear_binaryblob(); + static const int kBinaryBlobFieldNumber = 2; + const ::std::string& binaryblob(int index) const; + ::std::string* mutable_binaryblob(int index); + void set_binaryblob(int index, const ::std::string& value); + void set_binaryblob(int index, const char* value); + void set_binaryblob(int index, const void* value, size_t size); + ::std::string* add_binaryblob(); + void add_binaryblob(const ::std::string& value); + void add_binaryblob(const char* value); + void add_binaryblob(const void* value, size_t size); + const ::google::protobuf::RepeatedPtrField< ::std::string>& binaryblob() const; + ::google::protobuf::RepeatedPtrField< ::std::string>* mutable_binaryblob(); + + // repeated bytes unknownStatusBinaryBlob = 3; + int unknownstatusbinaryblob_size() const; + void clear_unknownstatusbinaryblob(); + static const int kUnknownStatusBinaryBlobFieldNumber = 3; + const ::std::string& unknownstatusbinaryblob(int index) const; + ::std::string* mutable_unknownstatusbinaryblob(int index); + void set_unknownstatusbinaryblob(int index, const ::std::string& value); + void set_unknownstatusbinaryblob(int index, const char* value); + void set_unknownstatusbinaryblob(int index, const void* value, size_t size); + ::std::string* add_unknownstatusbinaryblob(); + void add_unknownstatusbinaryblob(const ::std::string& value); + void add_unknownstatusbinaryblob(const char* value); + void add_unknownstatusbinaryblob(const void* value, size_t size); + const ::google::protobuf::RepeatedPtrField< ::std::string>& unknownstatusbinaryblob() const; + ::google::protobuf::RepeatedPtrField< ::std::string>* mutable_unknownstatusbinaryblob(); + // 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; + // .pybullet_grpc.LoadUrdfStatus urdfStatus = 4; bool has_urdfstatus() const; void clear_urdfstatus(); - static const int kUrdfStatusFieldNumber = 2; + static const int kUrdfStatusFieldNumber = 4; const ::pybullet_grpc::LoadUrdfStatus& urdfstatus() const; ::pybullet_grpc::LoadUrdfStatus* mutable_urdfstatus(); ::pybullet_grpc::LoadUrdfStatus* release_urdfstatus(); void set_allocated_urdfstatus(::pybullet_grpc::LoadUrdfStatus* urdfstatus); - // .pybullet_grpc.SdfLoadedStatus sdfStatus = 3; + // .pybullet_grpc.SdfLoadedStatus sdfStatus = 5; bool has_sdfstatus() const; void clear_sdfstatus(); - static const int kSdfStatusFieldNumber = 3; + static const int kSdfStatusFieldNumber = 5; const ::pybullet_grpc::SdfLoadedStatus& sdfstatus() const; ::pybullet_grpc::SdfLoadedStatus* mutable_sdfstatus(); ::pybullet_grpc::SdfLoadedStatus* release_sdfstatus(); void set_allocated_sdfstatus(::pybullet_grpc::SdfLoadedStatus* sdfstatus); - // .pybullet_grpc.MjcfLoadedStatus mjcfStatus = 4; + // .pybullet_grpc.MjcfLoadedStatus mjcfStatus = 6; bool has_mjcfstatus() const; void clear_mjcfstatus(); - static const int kMjcfStatusFieldNumber = 4; + static const int kMjcfStatusFieldNumber = 6; const ::pybullet_grpc::MjcfLoadedStatus& mjcfstatus() const; ::pybullet_grpc::MjcfLoadedStatus* mutable_mjcfstatus(); ::pybullet_grpc::MjcfLoadedStatus* release_mjcfstatus(); void set_allocated_mjcfstatus(::pybullet_grpc::MjcfLoadedStatus* mjcfstatus); - // .pybullet_grpc.GetDynamicsStatus getDynamicsStatus = 5; + // .pybullet_grpc.GetDynamicsStatus getDynamicsStatus = 7; bool has_getdynamicsstatus() const; void clear_getdynamicsstatus(); - static const int kGetDynamicsStatusFieldNumber = 5; + static const int kGetDynamicsStatusFieldNumber = 7; const ::pybullet_grpc::GetDynamicsStatus& getdynamicsstatus() const; ::pybullet_grpc::GetDynamicsStatus* mutable_getdynamicsstatus(); ::pybullet_grpc::GetDynamicsStatus* release_getdynamicsstatus(); void set_allocated_getdynamicsstatus(::pybullet_grpc::GetDynamicsStatus* getdynamicsstatus); - // .pybullet_grpc.SendActualStateStatus actualStateStatus = 6; + // .pybullet_grpc.SendActualStateStatus actualStateStatus = 8; bool has_actualstatestatus() const; void clear_actualstatestatus(); - static const int kActualStateStatusFieldNumber = 6; + static const int kActualStateStatusFieldNumber = 8; const ::pybullet_grpc::SendActualStateStatus& actualstatestatus() const; ::pybullet_grpc::SendActualStateStatus* mutable_actualstatestatus(); ::pybullet_grpc::SendActualStateStatus* release_actualstatestatus(); void set_allocated_actualstatestatus(::pybullet_grpc::SendActualStateStatus* actualstatestatus); + // .pybullet_grpc.SyncBodiesStatus syncBodiesStatus = 9; + bool has_syncbodiesstatus() const; + void clear_syncbodiesstatus(); + static const int kSyncBodiesStatusFieldNumber = 9; + const ::pybullet_grpc::SyncBodiesStatus& syncbodiesstatus() const; + ::pybullet_grpc::SyncBodiesStatus* mutable_syncbodiesstatus(); + ::pybullet_grpc::SyncBodiesStatus* release_syncbodiesstatus(); + void set_allocated_syncbodiesstatus(::pybullet_grpc::SyncBodiesStatus* syncbodiesstatus); + + // .pybullet_grpc.RequestBodyInfoStatus requestBodyInfoStatus = 10; + bool has_requestbodyinfostatus() const; + void clear_requestbodyinfostatus(); + static const int kRequestBodyInfoStatusFieldNumber = 10; + const ::pybullet_grpc::RequestBodyInfoStatus& requestbodyinfostatus() const; + ::pybullet_grpc::RequestBodyInfoStatus* mutable_requestbodyinfostatus(); + ::pybullet_grpc::RequestBodyInfoStatus* release_requestbodyinfostatus(); + void set_allocated_requestbodyinfostatus(::pybullet_grpc::RequestBodyInfoStatus* requestbodyinfostatus); + + // .pybullet_grpc.PhysicsSimulationParameters requestPhysicsSimulationParametersStatus = 11; + bool has_requestphysicssimulationparametersstatus() const; + void clear_requestphysicssimulationparametersstatus(); + static const int kRequestPhysicsSimulationParametersStatusFieldNumber = 11; + const ::pybullet_grpc::PhysicsSimulationParameters& requestphysicssimulationparametersstatus() const; + ::pybullet_grpc::PhysicsSimulationParameters* mutable_requestphysicssimulationparametersstatus(); + ::pybullet_grpc::PhysicsSimulationParameters* release_requestphysicssimulationparametersstatus(); + void set_allocated_requestphysicssimulationparametersstatus(::pybullet_grpc::PhysicsSimulationParameters* requestphysicssimulationparametersstatus); + + // .pybullet_grpc.CheckVersionStatus checkVersionStatus = 12; + bool has_checkversionstatus() const; + void clear_checkversionstatus(); + static const int kCheckVersionStatusFieldNumber = 12; + const ::pybullet_grpc::CheckVersionStatus& checkversionstatus() const; + ::pybullet_grpc::CheckVersionStatus* mutable_checkversionstatus(); + ::pybullet_grpc::CheckVersionStatus* release_checkversionstatus(); + void set_allocated_checkversionstatus(::pybullet_grpc::CheckVersionStatus* checkversionstatus); + + // .pybullet_grpc.UserConstraintStatus userConstraintStatus = 13; + bool has_userconstraintstatus() const; + void clear_userconstraintstatus(); + static const int kUserConstraintStatusFieldNumber = 13; + const ::pybullet_grpc::UserConstraintStatus& userconstraintstatus() const; + ::pybullet_grpc::UserConstraintStatus* mutable_userconstraintstatus(); + ::pybullet_grpc::UserConstraintStatus* release_userconstraintstatus(); + void set_allocated_userconstraintstatus(::pybullet_grpc::UserConstraintStatus* userconstraintstatus); + + // .pybullet_grpc.UserConstraintStateStatus userConstraintStateStatus = 14; + bool has_userconstraintstatestatus() const; + void clear_userconstraintstatestatus(); + static const int kUserConstraintStateStatusFieldNumber = 14; + const ::pybullet_grpc::UserConstraintStateStatus& userconstraintstatestatus() const; + ::pybullet_grpc::UserConstraintStateStatus* mutable_userconstraintstatestatus(); + ::pybullet_grpc::UserConstraintStateStatus* release_userconstraintstatestatus(); + void set_allocated_userconstraintstatestatus(::pybullet_grpc::UserConstraintStateStatus* userconstraintstatestatus); + + // .pybullet_grpc.KeyboardEventsStatus keyboardEventsStatus = 15; + bool has_keyboardeventsstatus() const; + void clear_keyboardeventsstatus(); + static const int kKeyboardEventsStatusFieldNumber = 15; + const ::pybullet_grpc::KeyboardEventsStatus& keyboardeventsstatus() const; + ::pybullet_grpc::KeyboardEventsStatus* mutable_keyboardeventsstatus(); + ::pybullet_grpc::KeyboardEventsStatus* release_keyboardeventsstatus(); + void set_allocated_keyboardeventsstatus(::pybullet_grpc::KeyboardEventsStatus* keyboardeventsstatus); + + // .pybullet_grpc.RequestCameraImageStatus requestCameraImageStatus = 16; + bool has_requestcameraimagestatus() const; + void clear_requestcameraimagestatus(); + static const int kRequestCameraImageStatusFieldNumber = 16; + const ::pybullet_grpc::RequestCameraImageStatus& requestcameraimagestatus() const; + ::pybullet_grpc::RequestCameraImageStatus* mutable_requestcameraimagestatus(); + ::pybullet_grpc::RequestCameraImageStatus* release_requestcameraimagestatus(); + void set_allocated_requestcameraimagestatus(::pybullet_grpc::RequestCameraImageStatus* requestcameraimagestatus); + StatusCase status_case() const; // @@protoc_insertion_point(class_scope:pybullet_grpc.PyBulletStatus) private: @@ -2650,12 +5453,22 @@ class PyBulletStatus : public ::google::protobuf::Message /* @@protoc_insertion_ void set_has_mjcfstatus(); void set_has_getdynamicsstatus(); void set_has_actualstatestatus(); + void set_has_syncbodiesstatus(); + void set_has_requestbodyinfostatus(); + void set_has_requestphysicssimulationparametersstatus(); + void set_has_checkversionstatus(); + void set_has_userconstraintstatus(); + void set_has_userconstraintstatestatus(); + void set_has_keyboardeventsstatus(); + void set_has_requestcameraimagestatus(); inline bool has_status() const; void clear_status(); inline void clear_has_status(); ::google::protobuf::internal::InternalMetadataWithArena _internal_metadata_; + ::google::protobuf::RepeatedPtrField< ::std::string> binaryblob_; + ::google::protobuf::RepeatedPtrField< ::std::string> unknownstatusbinaryblob_; ::google::protobuf::int32 statustype_; union StatusUnion { StatusUnion() {} @@ -2664,6 +5477,14 @@ class PyBulletStatus : public ::google::protobuf::Message /* @@protoc_insertion_ ::pybullet_grpc::MjcfLoadedStatus* mjcfstatus_; ::pybullet_grpc::GetDynamicsStatus* getdynamicsstatus_; ::pybullet_grpc::SendActualStateStatus* actualstatestatus_; + ::pybullet_grpc::SyncBodiesStatus* syncbodiesstatus_; + ::pybullet_grpc::RequestBodyInfoStatus* requestbodyinfostatus_; + ::pybullet_grpc::PhysicsSimulationParameters* requestphysicssimulationparametersstatus_; + ::pybullet_grpc::CheckVersionStatus* checkversionstatus_; + ::pybullet_grpc::UserConstraintStatus* userconstraintstatus_; + ::pybullet_grpc::UserConstraintStateStatus* userconstraintstatestatus_; + ::pybullet_grpc::KeyboardEventsStatus* keyboardeventsstatus_; + ::pybullet_grpc::RequestCameraImageStatus* requestcameraimagestatus_; } status_; mutable int _cached_size_; ::google::protobuf::uint32 _oneof_case_[1]; @@ -2782,6 +5603,218 @@ inline void quat4::set_w(double value) { // ------------------------------------------------------------------- +// vec4 + +// double x = 1; +inline void vec4::clear_x() { + x_ = 0; +} +inline double vec4::x() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.vec4.x) + return x_; +} +inline void vec4::set_x(double value) { + + x_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.vec4.x) +} + +// double y = 2; +inline void vec4::clear_y() { + y_ = 0; +} +inline double vec4::y() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.vec4.y) + return y_; +} +inline void vec4::set_y(double value) { + + y_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.vec4.y) +} + +// double z = 3; +inline void vec4::clear_z() { + z_ = 0; +} +inline double vec4::z() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.vec4.z) + return z_; +} +inline void vec4::set_z(double value) { + + z_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.vec4.z) +} + +// double w = 4; +inline void vec4::clear_w() { + w_ = 0; +} +inline double vec4::w() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.vec4.w) + return w_; +} +inline void vec4::set_w(double value) { + + w_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.vec4.w) +} + +// ------------------------------------------------------------------- + +// transform + +// .pybullet_grpc.vec3 origin = 1; +inline bool transform::has_origin() const { + return this != internal_default_instance() && origin_ != NULL; +} +inline void transform::clear_origin() { + if (GetArenaNoVirtual() == NULL && origin_ != NULL) delete origin_; + origin_ = NULL; +} +inline const ::pybullet_grpc::vec3& transform::origin() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.transform.origin) + return origin_ != NULL ? *origin_ + : *::pybullet_grpc::vec3::internal_default_instance(); +} +inline ::pybullet_grpc::vec3* transform::mutable_origin() { + + if (origin_ == NULL) { + origin_ = new ::pybullet_grpc::vec3; + } + // @@protoc_insertion_point(field_mutable:pybullet_grpc.transform.origin) + return origin_; +} +inline ::pybullet_grpc::vec3* transform::release_origin() { + // @@protoc_insertion_point(field_release:pybullet_grpc.transform.origin) + + ::pybullet_grpc::vec3* temp = origin_; + origin_ = NULL; + return temp; +} +inline void transform::set_allocated_origin(::pybullet_grpc::vec3* origin) { + delete origin_; + origin_ = origin; + if (origin) { + + } else { + + } + // @@protoc_insertion_point(field_set_allocated:pybullet_grpc.transform.origin) +} + +// .pybullet_grpc.quat4 orientation = 2; +inline bool transform::has_orientation() const { + return this != internal_default_instance() && orientation_ != NULL; +} +inline void transform::clear_orientation() { + if (GetArenaNoVirtual() == NULL && orientation_ != NULL) delete orientation_; + orientation_ = NULL; +} +inline const ::pybullet_grpc::quat4& transform::orientation() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.transform.orientation) + return orientation_ != NULL ? *orientation_ + : *::pybullet_grpc::quat4::internal_default_instance(); +} +inline ::pybullet_grpc::quat4* transform::mutable_orientation() { + + if (orientation_ == NULL) { + orientation_ = new ::pybullet_grpc::quat4; + } + // @@protoc_insertion_point(field_mutable:pybullet_grpc.transform.orientation) + return orientation_; +} +inline ::pybullet_grpc::quat4* transform::release_orientation() { + // @@protoc_insertion_point(field_release:pybullet_grpc.transform.orientation) + + ::pybullet_grpc::quat4* temp = orientation_; + orientation_ = NULL; + return temp; +} +inline void transform::set_allocated_orientation(::pybullet_grpc::quat4* orientation) { + delete orientation_; + orientation_ = orientation; + if (orientation) { + + } else { + + } + // @@protoc_insertion_point(field_set_allocated:pybullet_grpc.transform.orientation) +} + +// ------------------------------------------------------------------- + +// matrix4x4 + +// repeated double elems = 1; +inline int matrix4x4::elems_size() const { + return elems_.size(); +} +inline void matrix4x4::clear_elems() { + elems_.Clear(); +} +inline double matrix4x4::elems(int index) const { + // @@protoc_insertion_point(field_get:pybullet_grpc.matrix4x4.elems) + return elems_.Get(index); +} +inline void matrix4x4::set_elems(int index, double value) { + elems_.Set(index, value); + // @@protoc_insertion_point(field_set:pybullet_grpc.matrix4x4.elems) +} +inline void matrix4x4::add_elems(double value) { + elems_.Add(value); + // @@protoc_insertion_point(field_add:pybullet_grpc.matrix4x4.elems) +} +inline const ::google::protobuf::RepeatedField< double >& +matrix4x4::elems() const { + // @@protoc_insertion_point(field_list:pybullet_grpc.matrix4x4.elems) + return elems_; +} +inline ::google::protobuf::RepeatedField< double >* +matrix4x4::mutable_elems() { + // @@protoc_insertion_point(field_mutable_list:pybullet_grpc.matrix4x4.elems) + return &elems_; +} + +// ------------------------------------------------------------------- + +// CheckVersionCommand + +// int32 clientVersion = 1; +inline void CheckVersionCommand::clear_clientversion() { + clientversion_ = 0; +} +inline ::google::protobuf::int32 CheckVersionCommand::clientversion() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.CheckVersionCommand.clientVersion) + return clientversion_; +} +inline void CheckVersionCommand::set_clientversion(::google::protobuf::int32 value) { + + clientversion_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.CheckVersionCommand.clientVersion) +} + +// ------------------------------------------------------------------- + +// CheckVersionStatus + +// int32 serverVersion = 1; +inline void CheckVersionStatus::clear_serverversion() { + serverversion_ = 0; +} +inline ::google::protobuf::int32 CheckVersionStatus::serverversion() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.CheckVersionStatus.serverVersion) + return serverversion_; +} +inline void CheckVersionStatus::set_serverversion(::google::protobuf::int32 value) { + + serverversion_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.CheckVersionStatus.serverVersion) +} + +// ------------------------------------------------------------------- + // TerminateServerCommand // string exitReason = 1; @@ -2842,6 +5875,162 @@ inline void TerminateServerCommand::set_allocated_exitreason(::std::string* exit // ------------------------------------------------------------------- +// SyncBodiesCommand + +// ------------------------------------------------------------------- + +// SyncBodiesStatus + +// repeated int32 bodyUniqueIds = 1; +inline int SyncBodiesStatus::bodyuniqueids_size() const { + return bodyuniqueids_.size(); +} +inline void SyncBodiesStatus::clear_bodyuniqueids() { + bodyuniqueids_.Clear(); +} +inline ::google::protobuf::int32 SyncBodiesStatus::bodyuniqueids(int index) const { + // @@protoc_insertion_point(field_get:pybullet_grpc.SyncBodiesStatus.bodyUniqueIds) + return bodyuniqueids_.Get(index); +} +inline void SyncBodiesStatus::set_bodyuniqueids(int index, ::google::protobuf::int32 value) { + bodyuniqueids_.Set(index, value); + // @@protoc_insertion_point(field_set:pybullet_grpc.SyncBodiesStatus.bodyUniqueIds) +} +inline void SyncBodiesStatus::add_bodyuniqueids(::google::protobuf::int32 value) { + bodyuniqueids_.Add(value); + // @@protoc_insertion_point(field_add:pybullet_grpc.SyncBodiesStatus.bodyUniqueIds) +} +inline const ::google::protobuf::RepeatedField< ::google::protobuf::int32 >& +SyncBodiesStatus::bodyuniqueids() const { + // @@protoc_insertion_point(field_list:pybullet_grpc.SyncBodiesStatus.bodyUniqueIds) + return bodyuniqueids_; +} +inline ::google::protobuf::RepeatedField< ::google::protobuf::int32 >* +SyncBodiesStatus::mutable_bodyuniqueids() { + // @@protoc_insertion_point(field_mutable_list:pybullet_grpc.SyncBodiesStatus.bodyUniqueIds) + return &bodyuniqueids_; +} + +// repeated int32 userConstraintUniqueIds = 2; +inline int SyncBodiesStatus::userconstraintuniqueids_size() const { + return userconstraintuniqueids_.size(); +} +inline void SyncBodiesStatus::clear_userconstraintuniqueids() { + userconstraintuniqueids_.Clear(); +} +inline ::google::protobuf::int32 SyncBodiesStatus::userconstraintuniqueids(int index) const { + // @@protoc_insertion_point(field_get:pybullet_grpc.SyncBodiesStatus.userConstraintUniqueIds) + return userconstraintuniqueids_.Get(index); +} +inline void SyncBodiesStatus::set_userconstraintuniqueids(int index, ::google::protobuf::int32 value) { + userconstraintuniqueids_.Set(index, value); + // @@protoc_insertion_point(field_set:pybullet_grpc.SyncBodiesStatus.userConstraintUniqueIds) +} +inline void SyncBodiesStatus::add_userconstraintuniqueids(::google::protobuf::int32 value) { + userconstraintuniqueids_.Add(value); + // @@protoc_insertion_point(field_add:pybullet_grpc.SyncBodiesStatus.userConstraintUniqueIds) +} +inline const ::google::protobuf::RepeatedField< ::google::protobuf::int32 >& +SyncBodiesStatus::userconstraintuniqueids() const { + // @@protoc_insertion_point(field_list:pybullet_grpc.SyncBodiesStatus.userConstraintUniqueIds) + return userconstraintuniqueids_; +} +inline ::google::protobuf::RepeatedField< ::google::protobuf::int32 >* +SyncBodiesStatus::mutable_userconstraintuniqueids() { + // @@protoc_insertion_point(field_mutable_list:pybullet_grpc.SyncBodiesStatus.userConstraintUniqueIds) + return &userconstraintuniqueids_; +} + +// ------------------------------------------------------------------- + +// RequestBodyInfoCommand + +// int32 bodyUniqueId = 1; +inline void RequestBodyInfoCommand::clear_bodyuniqueid() { + bodyuniqueid_ = 0; +} +inline ::google::protobuf::int32 RequestBodyInfoCommand::bodyuniqueid() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.RequestBodyInfoCommand.bodyUniqueId) + return bodyuniqueid_; +} +inline void RequestBodyInfoCommand::set_bodyuniqueid(::google::protobuf::int32 value) { + + bodyuniqueid_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.RequestBodyInfoCommand.bodyUniqueId) +} + +// ------------------------------------------------------------------- + +// RequestBodyInfoStatus + +// int32 bodyUniqueId = 1; +inline void RequestBodyInfoStatus::clear_bodyuniqueid() { + bodyuniqueid_ = 0; +} +inline ::google::protobuf::int32 RequestBodyInfoStatus::bodyuniqueid() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.RequestBodyInfoStatus.bodyUniqueId) + return bodyuniqueid_; +} +inline void RequestBodyInfoStatus::set_bodyuniqueid(::google::protobuf::int32 value) { + + bodyuniqueid_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.RequestBodyInfoStatus.bodyUniqueId) +} + +// string bodyName = 2; +inline void RequestBodyInfoStatus::clear_bodyname() { + bodyname_.ClearToEmptyNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); +} +inline const ::std::string& RequestBodyInfoStatus::bodyname() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.RequestBodyInfoStatus.bodyName) + return bodyname_.GetNoArena(); +} +inline void RequestBodyInfoStatus::set_bodyname(const ::std::string& value) { + + bodyname_.SetNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), value); + // @@protoc_insertion_point(field_set:pybullet_grpc.RequestBodyInfoStatus.bodyName) +} +#if LANG_CXX11 +inline void RequestBodyInfoStatus::set_bodyname(::std::string&& value) { + + bodyname_.SetNoArena( + &::google::protobuf::internal::GetEmptyStringAlreadyInited(), std::move(value)); + // @@protoc_insertion_point(field_set_rvalue:pybullet_grpc.RequestBodyInfoStatus.bodyName) +} +#endif +inline void RequestBodyInfoStatus::set_bodyname(const char* value) { + + bodyname_.SetNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), ::std::string(value)); + // @@protoc_insertion_point(field_set_char:pybullet_grpc.RequestBodyInfoStatus.bodyName) +} +inline void RequestBodyInfoStatus::set_bodyname(const char* value, size_t size) { + + bodyname_.SetNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), + ::std::string(reinterpret_cast(value), size)); + // @@protoc_insertion_point(field_set_pointer:pybullet_grpc.RequestBodyInfoStatus.bodyName) +} +inline ::std::string* RequestBodyInfoStatus::mutable_bodyname() { + + // @@protoc_insertion_point(field_mutable:pybullet_grpc.RequestBodyInfoStatus.bodyName) + return bodyname_.MutableNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); +} +inline ::std::string* RequestBodyInfoStatus::release_bodyname() { + // @@protoc_insertion_point(field_release:pybullet_grpc.RequestBodyInfoStatus.bodyName) + + return bodyname_.ReleaseNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); +} +inline void RequestBodyInfoStatus::set_allocated_bodyname(::std::string* bodyname) { + if (bodyname != NULL) { + + } else { + + } + bodyname_.SetAllocatedNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), bodyname); + // @@protoc_insertion_point(field_set_allocated:pybullet_grpc.RequestBodyInfoStatus.bodyName) +} + +// ------------------------------------------------------------------- + // LoadUrdfCommand // string fileName = 1; @@ -3120,6 +6309,110 @@ inline void LoadUrdfStatus::set_bodyuniqueid(::google::protobuf::int32 value) { // @@protoc_insertion_point(field_set:pybullet_grpc.LoadUrdfStatus.bodyUniqueId) } +// string bodyName = 2; +inline void LoadUrdfStatus::clear_bodyname() { + bodyname_.ClearToEmptyNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); +} +inline const ::std::string& LoadUrdfStatus::bodyname() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.LoadUrdfStatus.bodyName) + return bodyname_.GetNoArena(); +} +inline void LoadUrdfStatus::set_bodyname(const ::std::string& value) { + + bodyname_.SetNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), value); + // @@protoc_insertion_point(field_set:pybullet_grpc.LoadUrdfStatus.bodyName) +} +#if LANG_CXX11 +inline void LoadUrdfStatus::set_bodyname(::std::string&& value) { + + bodyname_.SetNoArena( + &::google::protobuf::internal::GetEmptyStringAlreadyInited(), std::move(value)); + // @@protoc_insertion_point(field_set_rvalue:pybullet_grpc.LoadUrdfStatus.bodyName) +} +#endif +inline void LoadUrdfStatus::set_bodyname(const char* value) { + + bodyname_.SetNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), ::std::string(value)); + // @@protoc_insertion_point(field_set_char:pybullet_grpc.LoadUrdfStatus.bodyName) +} +inline void LoadUrdfStatus::set_bodyname(const char* value, size_t size) { + + bodyname_.SetNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), + ::std::string(reinterpret_cast(value), size)); + // @@protoc_insertion_point(field_set_pointer:pybullet_grpc.LoadUrdfStatus.bodyName) +} +inline ::std::string* LoadUrdfStatus::mutable_bodyname() { + + // @@protoc_insertion_point(field_mutable:pybullet_grpc.LoadUrdfStatus.bodyName) + return bodyname_.MutableNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); +} +inline ::std::string* LoadUrdfStatus::release_bodyname() { + // @@protoc_insertion_point(field_release:pybullet_grpc.LoadUrdfStatus.bodyName) + + return bodyname_.ReleaseNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); +} +inline void LoadUrdfStatus::set_allocated_bodyname(::std::string* bodyname) { + if (bodyname != NULL) { + + } else { + + } + bodyname_.SetAllocatedNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), bodyname); + // @@protoc_insertion_point(field_set_allocated:pybullet_grpc.LoadUrdfStatus.bodyName) +} + +// string fileName = 3; +inline void LoadUrdfStatus::clear_filename() { + filename_.ClearToEmptyNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); +} +inline const ::std::string& LoadUrdfStatus::filename() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.LoadUrdfStatus.fileName) + return filename_.GetNoArena(); +} +inline void LoadUrdfStatus::set_filename(const ::std::string& value) { + + filename_.SetNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), value); + // @@protoc_insertion_point(field_set:pybullet_grpc.LoadUrdfStatus.fileName) +} +#if LANG_CXX11 +inline void LoadUrdfStatus::set_filename(::std::string&& value) { + + filename_.SetNoArena( + &::google::protobuf::internal::GetEmptyStringAlreadyInited(), std::move(value)); + // @@protoc_insertion_point(field_set_rvalue:pybullet_grpc.LoadUrdfStatus.fileName) +} +#endif +inline void LoadUrdfStatus::set_filename(const char* value) { + + filename_.SetNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), ::std::string(value)); + // @@protoc_insertion_point(field_set_char:pybullet_grpc.LoadUrdfStatus.fileName) +} +inline void LoadUrdfStatus::set_filename(const char* value, size_t size) { + + filename_.SetNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), + ::std::string(reinterpret_cast(value), size)); + // @@protoc_insertion_point(field_set_pointer:pybullet_grpc.LoadUrdfStatus.fileName) +} +inline ::std::string* LoadUrdfStatus::mutable_filename() { + + // @@protoc_insertion_point(field_mutable:pybullet_grpc.LoadUrdfStatus.fileName) + return filename_.MutableNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); +} +inline ::std::string* LoadUrdfStatus::release_filename() { + // @@protoc_insertion_point(field_release:pybullet_grpc.LoadUrdfStatus.fileName) + + return filename_.ReleaseNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); +} +inline void LoadUrdfStatus::set_allocated_filename(::std::string* filename) { + if (filename != NULL) { + + } else { + + } + filename_.SetAllocatedNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), filename); + // @@protoc_insertion_point(field_set_allocated:pybullet_grpc.LoadUrdfStatus.fileName) +} + // ------------------------------------------------------------------- // LoadSdfCommand @@ -4248,7 +7541,21 @@ inline void InitPoseCommand::set_bodyuniqueid(::google::protobuf::int32 value) { // @@protoc_insertion_point(field_set:pybullet_grpc.InitPoseCommand.bodyUniqueId) } -// repeated int32 hasInitialStateQ = 2; +// int32 updateflags = 2; +inline void InitPoseCommand::clear_updateflags() { + updateflags_ = 0; +} +inline ::google::protobuf::int32 InitPoseCommand::updateflags() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.InitPoseCommand.updateflags) + return updateflags_; +} +inline void InitPoseCommand::set_updateflags(::google::protobuf::int32 value) { + + updateflags_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.InitPoseCommand.updateflags) +} + +// repeated int32 hasInitialStateQ = 3; inline int InitPoseCommand::hasinitialstateq_size() const { return hasinitialstateq_.size(); } @@ -4278,7 +7585,7 @@ InitPoseCommand::mutable_hasinitialstateq() { return &hasinitialstateq_; } -// repeated double initialStateQ = 3; +// repeated double initialStateQ = 4; inline int InitPoseCommand::initialstateq_size() const { return initialstateq_.size(); } @@ -4308,7 +7615,7 @@ InitPoseCommand::mutable_initialstateq() { return &initialstateq_; } -// repeated int32 hasInitialStateQdot = 4; +// repeated int32 hasInitialStateQdot = 5; inline int InitPoseCommand::hasinitialstateqdot_size() const { return hasinitialstateqdot_.size(); } @@ -4338,7 +7645,7 @@ InitPoseCommand::mutable_hasinitialstateqdot() { return &hasinitialstateqdot_; } -// repeated double initialStateQdot = 5; +// repeated double initialStateQdot = 6; inline int InitPoseCommand::initialstateqdot_size() const { return initialstateqdot_.size(); } @@ -4716,6 +8023,1778 @@ SendActualStateStatus::mutable_linklocalinertialframes() { // ------------------------------------------------------------------- +// ConfigureOpenGLVisualizerCommand + +// int32 updateFlags = 1; +inline void ConfigureOpenGLVisualizerCommand::clear_updateflags() { + updateflags_ = 0; +} +inline ::google::protobuf::int32 ConfigureOpenGLVisualizerCommand::updateflags() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.ConfigureOpenGLVisualizerCommand.updateFlags) + return updateflags_; +} +inline void ConfigureOpenGLVisualizerCommand::set_updateflags(::google::protobuf::int32 value) { + + updateflags_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.ConfigureOpenGLVisualizerCommand.updateFlags) +} + +// double cameraDistance = 2; +inline void ConfigureOpenGLVisualizerCommand::clear_cameradistance() { + cameradistance_ = 0; +} +inline double ConfigureOpenGLVisualizerCommand::cameradistance() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.ConfigureOpenGLVisualizerCommand.cameraDistance) + return cameradistance_; +} +inline void ConfigureOpenGLVisualizerCommand::set_cameradistance(double value) { + + cameradistance_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.ConfigureOpenGLVisualizerCommand.cameraDistance) +} + +// double cameraPitch = 3; +inline void ConfigureOpenGLVisualizerCommand::clear_camerapitch() { + camerapitch_ = 0; +} +inline double ConfigureOpenGLVisualizerCommand::camerapitch() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.ConfigureOpenGLVisualizerCommand.cameraPitch) + return camerapitch_; +} +inline void ConfigureOpenGLVisualizerCommand::set_camerapitch(double value) { + + camerapitch_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.ConfigureOpenGLVisualizerCommand.cameraPitch) +} + +// double cameraYaw = 4; +inline void ConfigureOpenGLVisualizerCommand::clear_camerayaw() { + camerayaw_ = 0; +} +inline double ConfigureOpenGLVisualizerCommand::camerayaw() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.ConfigureOpenGLVisualizerCommand.cameraYaw) + return camerayaw_; +} +inline void ConfigureOpenGLVisualizerCommand::set_camerayaw(double value) { + + camerayaw_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.ConfigureOpenGLVisualizerCommand.cameraYaw) +} + +// .pybullet_grpc.vec3 cameraTargetPosition = 5; +inline bool ConfigureOpenGLVisualizerCommand::has_cameratargetposition() const { + return this != internal_default_instance() && cameratargetposition_ != NULL; +} +inline void ConfigureOpenGLVisualizerCommand::clear_cameratargetposition() { + if (GetArenaNoVirtual() == NULL && cameratargetposition_ != NULL) delete cameratargetposition_; + cameratargetposition_ = NULL; +} +inline const ::pybullet_grpc::vec3& ConfigureOpenGLVisualizerCommand::cameratargetposition() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.ConfigureOpenGLVisualizerCommand.cameraTargetPosition) + return cameratargetposition_ != NULL ? *cameratargetposition_ + : *::pybullet_grpc::vec3::internal_default_instance(); +} +inline ::pybullet_grpc::vec3* ConfigureOpenGLVisualizerCommand::mutable_cameratargetposition() { + + if (cameratargetposition_ == NULL) { + cameratargetposition_ = new ::pybullet_grpc::vec3; + } + // @@protoc_insertion_point(field_mutable:pybullet_grpc.ConfigureOpenGLVisualizerCommand.cameraTargetPosition) + return cameratargetposition_; +} +inline ::pybullet_grpc::vec3* ConfigureOpenGLVisualizerCommand::release_cameratargetposition() { + // @@protoc_insertion_point(field_release:pybullet_grpc.ConfigureOpenGLVisualizerCommand.cameraTargetPosition) + + ::pybullet_grpc::vec3* temp = cameratargetposition_; + cameratargetposition_ = NULL; + return temp; +} +inline void ConfigureOpenGLVisualizerCommand::set_allocated_cameratargetposition(::pybullet_grpc::vec3* cameratargetposition) { + delete cameratargetposition_; + cameratargetposition_ = cameratargetposition; + if (cameratargetposition) { + + } else { + + } + // @@protoc_insertion_point(field_set_allocated:pybullet_grpc.ConfigureOpenGLVisualizerCommand.cameraTargetPosition) +} + +// int32 setFlag = 6; +inline void ConfigureOpenGLVisualizerCommand::clear_setflag() { + setflag_ = 0; +} +inline ::google::protobuf::int32 ConfigureOpenGLVisualizerCommand::setflag() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.ConfigureOpenGLVisualizerCommand.setFlag) + return setflag_; +} +inline void ConfigureOpenGLVisualizerCommand::set_setflag(::google::protobuf::int32 value) { + + setflag_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.ConfigureOpenGLVisualizerCommand.setFlag) +} + +// int32 setEnabled = 7; +inline void ConfigureOpenGLVisualizerCommand::clear_setenabled() { + setenabled_ = 0; +} +inline ::google::protobuf::int32 ConfigureOpenGLVisualizerCommand::setenabled() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.ConfigureOpenGLVisualizerCommand.setEnabled) + return setenabled_; +} +inline void ConfigureOpenGLVisualizerCommand::set_setenabled(::google::protobuf::int32 value) { + + setenabled_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.ConfigureOpenGLVisualizerCommand.setEnabled) +} + +// ------------------------------------------------------------------- + +// PhysicsSimulationParameters + +// double deltaTime = 1; +inline void PhysicsSimulationParameters::clear_deltatime() { + deltatime_ = 0; +} +inline double PhysicsSimulationParameters::deltatime() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.PhysicsSimulationParameters.deltaTime) + return deltatime_; +} +inline void PhysicsSimulationParameters::set_deltatime(double value) { + + deltatime_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.PhysicsSimulationParameters.deltaTime) +} + +// .pybullet_grpc.vec3 gravityAcceleration = 2; +inline bool PhysicsSimulationParameters::has_gravityacceleration() const { + return this != internal_default_instance() && gravityacceleration_ != NULL; +} +inline void PhysicsSimulationParameters::clear_gravityacceleration() { + if (GetArenaNoVirtual() == NULL && gravityacceleration_ != NULL) delete gravityacceleration_; + gravityacceleration_ = NULL; +} +inline const ::pybullet_grpc::vec3& PhysicsSimulationParameters::gravityacceleration() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.PhysicsSimulationParameters.gravityAcceleration) + return gravityacceleration_ != NULL ? *gravityacceleration_ + : *::pybullet_grpc::vec3::internal_default_instance(); +} +inline ::pybullet_grpc::vec3* PhysicsSimulationParameters::mutable_gravityacceleration() { + + if (gravityacceleration_ == NULL) { + gravityacceleration_ = new ::pybullet_grpc::vec3; + } + // @@protoc_insertion_point(field_mutable:pybullet_grpc.PhysicsSimulationParameters.gravityAcceleration) + return gravityacceleration_; +} +inline ::pybullet_grpc::vec3* PhysicsSimulationParameters::release_gravityacceleration() { + // @@protoc_insertion_point(field_release:pybullet_grpc.PhysicsSimulationParameters.gravityAcceleration) + + ::pybullet_grpc::vec3* temp = gravityacceleration_; + gravityacceleration_ = NULL; + return temp; +} +inline void PhysicsSimulationParameters::set_allocated_gravityacceleration(::pybullet_grpc::vec3* gravityacceleration) { + delete gravityacceleration_; + gravityacceleration_ = gravityacceleration; + if (gravityacceleration) { + + } else { + + } + // @@protoc_insertion_point(field_set_allocated:pybullet_grpc.PhysicsSimulationParameters.gravityAcceleration) +} + +// int32 numSimulationSubSteps = 3; +inline void PhysicsSimulationParameters::clear_numsimulationsubsteps() { + numsimulationsubsteps_ = 0; +} +inline ::google::protobuf::int32 PhysicsSimulationParameters::numsimulationsubsteps() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.PhysicsSimulationParameters.numSimulationSubSteps) + return numsimulationsubsteps_; +} +inline void PhysicsSimulationParameters::set_numsimulationsubsteps(::google::protobuf::int32 value) { + + numsimulationsubsteps_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.PhysicsSimulationParameters.numSimulationSubSteps) +} + +// int32 numSolverIterations = 4; +inline void PhysicsSimulationParameters::clear_numsolveriterations() { + numsolveriterations_ = 0; +} +inline ::google::protobuf::int32 PhysicsSimulationParameters::numsolveriterations() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.PhysicsSimulationParameters.numSolverIterations) + return numsolveriterations_; +} +inline void PhysicsSimulationParameters::set_numsolveriterations(::google::protobuf::int32 value) { + + numsolveriterations_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.PhysicsSimulationParameters.numSolverIterations) +} + +// int32 useRealTimeSimulation = 5; +inline void PhysicsSimulationParameters::clear_userealtimesimulation() { + userealtimesimulation_ = 0; +} +inline ::google::protobuf::int32 PhysicsSimulationParameters::userealtimesimulation() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.PhysicsSimulationParameters.useRealTimeSimulation) + return userealtimesimulation_; +} +inline void PhysicsSimulationParameters::set_userealtimesimulation(::google::protobuf::int32 value) { + + userealtimesimulation_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.PhysicsSimulationParameters.useRealTimeSimulation) +} + +// int32 useSplitImpulse = 6; +inline void PhysicsSimulationParameters::clear_usesplitimpulse() { + usesplitimpulse_ = 0; +} +inline ::google::protobuf::int32 PhysicsSimulationParameters::usesplitimpulse() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.PhysicsSimulationParameters.useSplitImpulse) + return usesplitimpulse_; +} +inline void PhysicsSimulationParameters::set_usesplitimpulse(::google::protobuf::int32 value) { + + usesplitimpulse_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.PhysicsSimulationParameters.useSplitImpulse) +} + +// double splitImpulsePenetrationThreshold = 7; +inline void PhysicsSimulationParameters::clear_splitimpulsepenetrationthreshold() { + splitimpulsepenetrationthreshold_ = 0; +} +inline double PhysicsSimulationParameters::splitimpulsepenetrationthreshold() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.PhysicsSimulationParameters.splitImpulsePenetrationThreshold) + return splitimpulsepenetrationthreshold_; +} +inline void PhysicsSimulationParameters::set_splitimpulsepenetrationthreshold(double value) { + + splitimpulsepenetrationthreshold_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.PhysicsSimulationParameters.splitImpulsePenetrationThreshold) +} + +// double contactBreakingThreshold = 8; +inline void PhysicsSimulationParameters::clear_contactbreakingthreshold() { + contactbreakingthreshold_ = 0; +} +inline double PhysicsSimulationParameters::contactbreakingthreshold() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.PhysicsSimulationParameters.contactBreakingThreshold) + return contactbreakingthreshold_; +} +inline void PhysicsSimulationParameters::set_contactbreakingthreshold(double value) { + + contactbreakingthreshold_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.PhysicsSimulationParameters.contactBreakingThreshold) +} + +// int32 internalSimFlags = 9; +inline void PhysicsSimulationParameters::clear_internalsimflags() { + internalsimflags_ = 0; +} +inline ::google::protobuf::int32 PhysicsSimulationParameters::internalsimflags() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.PhysicsSimulationParameters.internalSimFlags) + return internalsimflags_; +} +inline void PhysicsSimulationParameters::set_internalsimflags(::google::protobuf::int32 value) { + + internalsimflags_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.PhysicsSimulationParameters.internalSimFlags) +} + +// double defaultContactERP = 10; +inline void PhysicsSimulationParameters::clear_defaultcontacterp() { + defaultcontacterp_ = 0; +} +inline double PhysicsSimulationParameters::defaultcontacterp() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.PhysicsSimulationParameters.defaultContactERP) + return defaultcontacterp_; +} +inline void PhysicsSimulationParameters::set_defaultcontacterp(double value) { + + defaultcontacterp_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.PhysicsSimulationParameters.defaultContactERP) +} + +// int32 collisionFilterMode = 11; +inline void PhysicsSimulationParameters::clear_collisionfiltermode() { + collisionfiltermode_ = 0; +} +inline ::google::protobuf::int32 PhysicsSimulationParameters::collisionfiltermode() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.PhysicsSimulationParameters.collisionFilterMode) + return collisionfiltermode_; +} +inline void PhysicsSimulationParameters::set_collisionfiltermode(::google::protobuf::int32 value) { + + collisionfiltermode_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.PhysicsSimulationParameters.collisionFilterMode) +} + +// int32 enableFileCaching = 12; +inline void PhysicsSimulationParameters::clear_enablefilecaching() { + enablefilecaching_ = 0; +} +inline ::google::protobuf::int32 PhysicsSimulationParameters::enablefilecaching() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.PhysicsSimulationParameters.enableFileCaching) + return enablefilecaching_; +} +inline void PhysicsSimulationParameters::set_enablefilecaching(::google::protobuf::int32 value) { + + enablefilecaching_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.PhysicsSimulationParameters.enableFileCaching) +} + +// double restitutionVelocityThreshold = 13; +inline void PhysicsSimulationParameters::clear_restitutionvelocitythreshold() { + restitutionvelocitythreshold_ = 0; +} +inline double PhysicsSimulationParameters::restitutionvelocitythreshold() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.PhysicsSimulationParameters.restitutionVelocityThreshold) + return restitutionvelocitythreshold_; +} +inline void PhysicsSimulationParameters::set_restitutionvelocitythreshold(double value) { + + restitutionvelocitythreshold_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.PhysicsSimulationParameters.restitutionVelocityThreshold) +} + +// double defaultNonContactERP = 14; +inline void PhysicsSimulationParameters::clear_defaultnoncontacterp() { + defaultnoncontacterp_ = 0; +} +inline double PhysicsSimulationParameters::defaultnoncontacterp() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.PhysicsSimulationParameters.defaultNonContactERP) + return defaultnoncontacterp_; +} +inline void PhysicsSimulationParameters::set_defaultnoncontacterp(double value) { + + defaultnoncontacterp_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.PhysicsSimulationParameters.defaultNonContactERP) +} + +// double frictionERP = 15; +inline void PhysicsSimulationParameters::clear_frictionerp() { + frictionerp_ = 0; +} +inline double PhysicsSimulationParameters::frictionerp() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.PhysicsSimulationParameters.frictionERP) + return frictionerp_; +} +inline void PhysicsSimulationParameters::set_frictionerp(double value) { + + frictionerp_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.PhysicsSimulationParameters.frictionERP) +} + +// double defaultGlobalCFM = 16; +inline void PhysicsSimulationParameters::clear_defaultglobalcfm() { + defaultglobalcfm_ = 0; +} +inline double PhysicsSimulationParameters::defaultglobalcfm() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.PhysicsSimulationParameters.defaultGlobalCFM) + return defaultglobalcfm_; +} +inline void PhysicsSimulationParameters::set_defaultglobalcfm(double value) { + + defaultglobalcfm_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.PhysicsSimulationParameters.defaultGlobalCFM) +} + +// double frictionCFM = 17; +inline void PhysicsSimulationParameters::clear_frictioncfm() { + frictioncfm_ = 0; +} +inline double PhysicsSimulationParameters::frictioncfm() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.PhysicsSimulationParameters.frictionCFM) + return frictioncfm_; +} +inline void PhysicsSimulationParameters::set_frictioncfm(double value) { + + frictioncfm_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.PhysicsSimulationParameters.frictionCFM) +} + +// int32 enableConeFriction = 18; +inline void PhysicsSimulationParameters::clear_enableconefriction() { + enableconefriction_ = 0; +} +inline ::google::protobuf::int32 PhysicsSimulationParameters::enableconefriction() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.PhysicsSimulationParameters.enableConeFriction) + return enableconefriction_; +} +inline void PhysicsSimulationParameters::set_enableconefriction(::google::protobuf::int32 value) { + + enableconefriction_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.PhysicsSimulationParameters.enableConeFriction) +} + +// int32 deterministicOverlappingPairs = 19; +inline void PhysicsSimulationParameters::clear_deterministicoverlappingpairs() { + deterministicoverlappingpairs_ = 0; +} +inline ::google::protobuf::int32 PhysicsSimulationParameters::deterministicoverlappingpairs() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.PhysicsSimulationParameters.deterministicOverlappingPairs) + return deterministicoverlappingpairs_; +} +inline void PhysicsSimulationParameters::set_deterministicoverlappingpairs(::google::protobuf::int32 value) { + + deterministicoverlappingpairs_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.PhysicsSimulationParameters.deterministicOverlappingPairs) +} + +// double allowedCcdPenetration = 20; +inline void PhysicsSimulationParameters::clear_allowedccdpenetration() { + allowedccdpenetration_ = 0; +} +inline double PhysicsSimulationParameters::allowedccdpenetration() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.PhysicsSimulationParameters.allowedCcdPenetration) + return allowedccdpenetration_; +} +inline void PhysicsSimulationParameters::set_allowedccdpenetration(double value) { + + allowedccdpenetration_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.PhysicsSimulationParameters.allowedCcdPenetration) +} + +// int32 jointFeedbackMode = 21; +inline void PhysicsSimulationParameters::clear_jointfeedbackmode() { + jointfeedbackmode_ = 0; +} +inline ::google::protobuf::int32 PhysicsSimulationParameters::jointfeedbackmode() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.PhysicsSimulationParameters.jointFeedbackMode) + return jointfeedbackmode_; +} +inline void PhysicsSimulationParameters::set_jointfeedbackmode(::google::protobuf::int32 value) { + + jointfeedbackmode_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.PhysicsSimulationParameters.jointFeedbackMode) +} + +// double solverResidualThreshold = 22; +inline void PhysicsSimulationParameters::clear_solverresidualthreshold() { + solverresidualthreshold_ = 0; +} +inline double PhysicsSimulationParameters::solverresidualthreshold() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.PhysicsSimulationParameters.solverResidualThreshold) + return solverresidualthreshold_; +} +inline void PhysicsSimulationParameters::set_solverresidualthreshold(double value) { + + solverresidualthreshold_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.PhysicsSimulationParameters.solverResidualThreshold) +} + +// double contactSlop = 23; +inline void PhysicsSimulationParameters::clear_contactslop() { + contactslop_ = 0; +} +inline double PhysicsSimulationParameters::contactslop() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.PhysicsSimulationParameters.contactSlop) + return contactslop_; +} +inline void PhysicsSimulationParameters::set_contactslop(double value) { + + contactslop_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.PhysicsSimulationParameters.contactSlop) +} + +// int32 enableSAT = 24; +inline void PhysicsSimulationParameters::clear_enablesat() { + enablesat_ = 0; +} +inline ::google::protobuf::int32 PhysicsSimulationParameters::enablesat() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.PhysicsSimulationParameters.enableSAT) + return enablesat_; +} +inline void PhysicsSimulationParameters::set_enablesat(::google::protobuf::int32 value) { + + enablesat_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.PhysicsSimulationParameters.enableSAT) +} + +// int32 constraintSolverType = 25; +inline void PhysicsSimulationParameters::clear_constraintsolvertype() { + constraintsolvertype_ = 0; +} +inline ::google::protobuf::int32 PhysicsSimulationParameters::constraintsolvertype() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.PhysicsSimulationParameters.constraintSolverType) + return constraintsolvertype_; +} +inline void PhysicsSimulationParameters::set_constraintsolvertype(::google::protobuf::int32 value) { + + constraintsolvertype_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.PhysicsSimulationParameters.constraintSolverType) +} + +// int32 minimumSolverIslandSize = 26; +inline void PhysicsSimulationParameters::clear_minimumsolverislandsize() { + minimumsolverislandsize_ = 0; +} +inline ::google::protobuf::int32 PhysicsSimulationParameters::minimumsolverislandsize() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.PhysicsSimulationParameters.minimumSolverIslandSize) + return minimumsolverislandsize_; +} +inline void PhysicsSimulationParameters::set_minimumsolverislandsize(::google::protobuf::int32 value) { + + minimumsolverislandsize_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.PhysicsSimulationParameters.minimumSolverIslandSize) +} + +// ------------------------------------------------------------------- + +// PhysicsSimulationParametersCommand + +// int32 updateFlags = 1; +inline void PhysicsSimulationParametersCommand::clear_updateflags() { + updateflags_ = 0; +} +inline ::google::protobuf::int32 PhysicsSimulationParametersCommand::updateflags() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.PhysicsSimulationParametersCommand.updateFlags) + return updateflags_; +} +inline void PhysicsSimulationParametersCommand::set_updateflags(::google::protobuf::int32 value) { + + updateflags_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.PhysicsSimulationParametersCommand.updateFlags) +} + +// .pybullet_grpc.PhysicsSimulationParameters params = 2; +inline bool PhysicsSimulationParametersCommand::has_params() const { + return this != internal_default_instance() && params_ != NULL; +} +inline void PhysicsSimulationParametersCommand::clear_params() { + if (GetArenaNoVirtual() == NULL && params_ != NULL) delete params_; + params_ = NULL; +} +inline const ::pybullet_grpc::PhysicsSimulationParameters& PhysicsSimulationParametersCommand::params() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.PhysicsSimulationParametersCommand.params) + return params_ != NULL ? *params_ + : *::pybullet_grpc::PhysicsSimulationParameters::internal_default_instance(); +} +inline ::pybullet_grpc::PhysicsSimulationParameters* PhysicsSimulationParametersCommand::mutable_params() { + + if (params_ == NULL) { + params_ = new ::pybullet_grpc::PhysicsSimulationParameters; + } + // @@protoc_insertion_point(field_mutable:pybullet_grpc.PhysicsSimulationParametersCommand.params) + return params_; +} +inline ::pybullet_grpc::PhysicsSimulationParameters* PhysicsSimulationParametersCommand::release_params() { + // @@protoc_insertion_point(field_release:pybullet_grpc.PhysicsSimulationParametersCommand.params) + + ::pybullet_grpc::PhysicsSimulationParameters* temp = params_; + params_ = NULL; + return temp; +} +inline void PhysicsSimulationParametersCommand::set_allocated_params(::pybullet_grpc::PhysicsSimulationParameters* params) { + delete params_; + params_ = params; + if (params) { + + } else { + + } + // @@protoc_insertion_point(field_set_allocated:pybullet_grpc.PhysicsSimulationParametersCommand.params) +} + +// ------------------------------------------------------------------- + +// JointMotorControlCommand + +// int32 bodyUniqueId = 1; +inline void JointMotorControlCommand::clear_bodyuniqueid() { + bodyuniqueid_ = 0; +} +inline ::google::protobuf::int32 JointMotorControlCommand::bodyuniqueid() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.JointMotorControlCommand.bodyUniqueId) + return bodyuniqueid_; +} +inline void JointMotorControlCommand::set_bodyuniqueid(::google::protobuf::int32 value) { + + bodyuniqueid_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.JointMotorControlCommand.bodyUniqueId) +} + +// int32 controlMode = 2; +inline void JointMotorControlCommand::clear_controlmode() { + controlmode_ = 0; +} +inline ::google::protobuf::int32 JointMotorControlCommand::controlmode() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.JointMotorControlCommand.controlMode) + return controlmode_; +} +inline void JointMotorControlCommand::set_controlmode(::google::protobuf::int32 value) { + + controlmode_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.JointMotorControlCommand.controlMode) +} + +// int32 updateFlags = 3; +inline void JointMotorControlCommand::clear_updateflags() { + updateflags_ = 0; +} +inline ::google::protobuf::int32 JointMotorControlCommand::updateflags() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.JointMotorControlCommand.updateFlags) + return updateflags_; +} +inline void JointMotorControlCommand::set_updateflags(::google::protobuf::int32 value) { + + updateflags_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.JointMotorControlCommand.updateFlags) +} + +// repeated double Kp = 4; +inline int JointMotorControlCommand::kp_size() const { + return kp_.size(); +} +inline void JointMotorControlCommand::clear_kp() { + kp_.Clear(); +} +inline double JointMotorControlCommand::kp(int index) const { + // @@protoc_insertion_point(field_get:pybullet_grpc.JointMotorControlCommand.Kp) + return kp_.Get(index); +} +inline void JointMotorControlCommand::set_kp(int index, double value) { + kp_.Set(index, value); + // @@protoc_insertion_point(field_set:pybullet_grpc.JointMotorControlCommand.Kp) +} +inline void JointMotorControlCommand::add_kp(double value) { + kp_.Add(value); + // @@protoc_insertion_point(field_add:pybullet_grpc.JointMotorControlCommand.Kp) +} +inline const ::google::protobuf::RepeatedField< double >& +JointMotorControlCommand::kp() const { + // @@protoc_insertion_point(field_list:pybullet_grpc.JointMotorControlCommand.Kp) + return kp_; +} +inline ::google::protobuf::RepeatedField< double >* +JointMotorControlCommand::mutable_kp() { + // @@protoc_insertion_point(field_mutable_list:pybullet_grpc.JointMotorControlCommand.Kp) + return &kp_; +} + +// repeated double Kd = 5; +inline int JointMotorControlCommand::kd_size() const { + return kd_.size(); +} +inline void JointMotorControlCommand::clear_kd() { + kd_.Clear(); +} +inline double JointMotorControlCommand::kd(int index) const { + // @@protoc_insertion_point(field_get:pybullet_grpc.JointMotorControlCommand.Kd) + return kd_.Get(index); +} +inline void JointMotorControlCommand::set_kd(int index, double value) { + kd_.Set(index, value); + // @@protoc_insertion_point(field_set:pybullet_grpc.JointMotorControlCommand.Kd) +} +inline void JointMotorControlCommand::add_kd(double value) { + kd_.Add(value); + // @@protoc_insertion_point(field_add:pybullet_grpc.JointMotorControlCommand.Kd) +} +inline const ::google::protobuf::RepeatedField< double >& +JointMotorControlCommand::kd() const { + // @@protoc_insertion_point(field_list:pybullet_grpc.JointMotorControlCommand.Kd) + return kd_; +} +inline ::google::protobuf::RepeatedField< double >* +JointMotorControlCommand::mutable_kd() { + // @@protoc_insertion_point(field_mutable_list:pybullet_grpc.JointMotorControlCommand.Kd) + return &kd_; +} + +// repeated double maxVelocity = 6; +inline int JointMotorControlCommand::maxvelocity_size() const { + return maxvelocity_.size(); +} +inline void JointMotorControlCommand::clear_maxvelocity() { + maxvelocity_.Clear(); +} +inline double JointMotorControlCommand::maxvelocity(int index) const { + // @@protoc_insertion_point(field_get:pybullet_grpc.JointMotorControlCommand.maxVelocity) + return maxvelocity_.Get(index); +} +inline void JointMotorControlCommand::set_maxvelocity(int index, double value) { + maxvelocity_.Set(index, value); + // @@protoc_insertion_point(field_set:pybullet_grpc.JointMotorControlCommand.maxVelocity) +} +inline void JointMotorControlCommand::add_maxvelocity(double value) { + maxvelocity_.Add(value); + // @@protoc_insertion_point(field_add:pybullet_grpc.JointMotorControlCommand.maxVelocity) +} +inline const ::google::protobuf::RepeatedField< double >& +JointMotorControlCommand::maxvelocity() const { + // @@protoc_insertion_point(field_list:pybullet_grpc.JointMotorControlCommand.maxVelocity) + return maxvelocity_; +} +inline ::google::protobuf::RepeatedField< double >* +JointMotorControlCommand::mutable_maxvelocity() { + // @@protoc_insertion_point(field_mutable_list:pybullet_grpc.JointMotorControlCommand.maxVelocity) + return &maxvelocity_; +} + +// repeated int32 hasDesiredStateFlags = 7; +inline int JointMotorControlCommand::hasdesiredstateflags_size() const { + return hasdesiredstateflags_.size(); +} +inline void JointMotorControlCommand::clear_hasdesiredstateflags() { + hasdesiredstateflags_.Clear(); +} +inline ::google::protobuf::int32 JointMotorControlCommand::hasdesiredstateflags(int index) const { + // @@protoc_insertion_point(field_get:pybullet_grpc.JointMotorControlCommand.hasDesiredStateFlags) + return hasdesiredstateflags_.Get(index); +} +inline void JointMotorControlCommand::set_hasdesiredstateflags(int index, ::google::protobuf::int32 value) { + hasdesiredstateflags_.Set(index, value); + // @@protoc_insertion_point(field_set:pybullet_grpc.JointMotorControlCommand.hasDesiredStateFlags) +} +inline void JointMotorControlCommand::add_hasdesiredstateflags(::google::protobuf::int32 value) { + hasdesiredstateflags_.Add(value); + // @@protoc_insertion_point(field_add:pybullet_grpc.JointMotorControlCommand.hasDesiredStateFlags) +} +inline const ::google::protobuf::RepeatedField< ::google::protobuf::int32 >& +JointMotorControlCommand::hasdesiredstateflags() const { + // @@protoc_insertion_point(field_list:pybullet_grpc.JointMotorControlCommand.hasDesiredStateFlags) + return hasdesiredstateflags_; +} +inline ::google::protobuf::RepeatedField< ::google::protobuf::int32 >* +JointMotorControlCommand::mutable_hasdesiredstateflags() { + // @@protoc_insertion_point(field_mutable_list:pybullet_grpc.JointMotorControlCommand.hasDesiredStateFlags) + return &hasdesiredstateflags_; +} + +// repeated double desiredStateQ = 8; +inline int JointMotorControlCommand::desiredstateq_size() const { + return desiredstateq_.size(); +} +inline void JointMotorControlCommand::clear_desiredstateq() { + desiredstateq_.Clear(); +} +inline double JointMotorControlCommand::desiredstateq(int index) const { + // @@protoc_insertion_point(field_get:pybullet_grpc.JointMotorControlCommand.desiredStateQ) + return desiredstateq_.Get(index); +} +inline void JointMotorControlCommand::set_desiredstateq(int index, double value) { + desiredstateq_.Set(index, value); + // @@protoc_insertion_point(field_set:pybullet_grpc.JointMotorControlCommand.desiredStateQ) +} +inline void JointMotorControlCommand::add_desiredstateq(double value) { + desiredstateq_.Add(value); + // @@protoc_insertion_point(field_add:pybullet_grpc.JointMotorControlCommand.desiredStateQ) +} +inline const ::google::protobuf::RepeatedField< double >& +JointMotorControlCommand::desiredstateq() const { + // @@protoc_insertion_point(field_list:pybullet_grpc.JointMotorControlCommand.desiredStateQ) + return desiredstateq_; +} +inline ::google::protobuf::RepeatedField< double >* +JointMotorControlCommand::mutable_desiredstateq() { + // @@protoc_insertion_point(field_mutable_list:pybullet_grpc.JointMotorControlCommand.desiredStateQ) + return &desiredstateq_; +} + +// repeated double desiredStateQdot = 9; +inline int JointMotorControlCommand::desiredstateqdot_size() const { + return desiredstateqdot_.size(); +} +inline void JointMotorControlCommand::clear_desiredstateqdot() { + desiredstateqdot_.Clear(); +} +inline double JointMotorControlCommand::desiredstateqdot(int index) const { + // @@protoc_insertion_point(field_get:pybullet_grpc.JointMotorControlCommand.desiredStateQdot) + return desiredstateqdot_.Get(index); +} +inline void JointMotorControlCommand::set_desiredstateqdot(int index, double value) { + desiredstateqdot_.Set(index, value); + // @@protoc_insertion_point(field_set:pybullet_grpc.JointMotorControlCommand.desiredStateQdot) +} +inline void JointMotorControlCommand::add_desiredstateqdot(double value) { + desiredstateqdot_.Add(value); + // @@protoc_insertion_point(field_add:pybullet_grpc.JointMotorControlCommand.desiredStateQdot) +} +inline const ::google::protobuf::RepeatedField< double >& +JointMotorControlCommand::desiredstateqdot() const { + // @@protoc_insertion_point(field_list:pybullet_grpc.JointMotorControlCommand.desiredStateQdot) + return desiredstateqdot_; +} +inline ::google::protobuf::RepeatedField< double >* +JointMotorControlCommand::mutable_desiredstateqdot() { + // @@protoc_insertion_point(field_mutable_list:pybullet_grpc.JointMotorControlCommand.desiredStateQdot) + return &desiredstateqdot_; +} + +// repeated double desiredStateForceTorque = 10; +inline int JointMotorControlCommand::desiredstateforcetorque_size() const { + return desiredstateforcetorque_.size(); +} +inline void JointMotorControlCommand::clear_desiredstateforcetorque() { + desiredstateforcetorque_.Clear(); +} +inline double JointMotorControlCommand::desiredstateforcetorque(int index) const { + // @@protoc_insertion_point(field_get:pybullet_grpc.JointMotorControlCommand.desiredStateForceTorque) + return desiredstateforcetorque_.Get(index); +} +inline void JointMotorControlCommand::set_desiredstateforcetorque(int index, double value) { + desiredstateforcetorque_.Set(index, value); + // @@protoc_insertion_point(field_set:pybullet_grpc.JointMotorControlCommand.desiredStateForceTorque) +} +inline void JointMotorControlCommand::add_desiredstateforcetorque(double value) { + desiredstateforcetorque_.Add(value); + // @@protoc_insertion_point(field_add:pybullet_grpc.JointMotorControlCommand.desiredStateForceTorque) +} +inline const ::google::protobuf::RepeatedField< double >& +JointMotorControlCommand::desiredstateforcetorque() const { + // @@protoc_insertion_point(field_list:pybullet_grpc.JointMotorControlCommand.desiredStateForceTorque) + return desiredstateforcetorque_; +} +inline ::google::protobuf::RepeatedField< double >* +JointMotorControlCommand::mutable_desiredstateforcetorque() { + // @@protoc_insertion_point(field_mutable_list:pybullet_grpc.JointMotorControlCommand.desiredStateForceTorque) + return &desiredstateforcetorque_; +} + +// ------------------------------------------------------------------- + +// UserConstraintCommand + +// int32 parentBodyIndex = 1; +inline void UserConstraintCommand::clear_parentbodyindex() { + parentbodyindex_ = 0; +} +inline ::google::protobuf::int32 UserConstraintCommand::parentbodyindex() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.UserConstraintCommand.parentBodyIndex) + return parentbodyindex_; +} +inline void UserConstraintCommand::set_parentbodyindex(::google::protobuf::int32 value) { + + parentbodyindex_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.UserConstraintCommand.parentBodyIndex) +} + +// int32 parentJointIndex = 2; +inline void UserConstraintCommand::clear_parentjointindex() { + parentjointindex_ = 0; +} +inline ::google::protobuf::int32 UserConstraintCommand::parentjointindex() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.UserConstraintCommand.parentJointIndex) + return parentjointindex_; +} +inline void UserConstraintCommand::set_parentjointindex(::google::protobuf::int32 value) { + + parentjointindex_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.UserConstraintCommand.parentJointIndex) +} + +// int32 childBodyIndex = 3; +inline void UserConstraintCommand::clear_childbodyindex() { + childbodyindex_ = 0; +} +inline ::google::protobuf::int32 UserConstraintCommand::childbodyindex() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.UserConstraintCommand.childBodyIndex) + return childbodyindex_; +} +inline void UserConstraintCommand::set_childbodyindex(::google::protobuf::int32 value) { + + childbodyindex_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.UserConstraintCommand.childBodyIndex) +} + +// int32 childJointIndex = 4; +inline void UserConstraintCommand::clear_childjointindex() { + childjointindex_ = 0; +} +inline ::google::protobuf::int32 UserConstraintCommand::childjointindex() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.UserConstraintCommand.childJointIndex) + return childjointindex_; +} +inline void UserConstraintCommand::set_childjointindex(::google::protobuf::int32 value) { + + childjointindex_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.UserConstraintCommand.childJointIndex) +} + +// .pybullet_grpc.transform parentFrame = 5; +inline bool UserConstraintCommand::has_parentframe() const { + return this != internal_default_instance() && parentframe_ != NULL; +} +inline void UserConstraintCommand::clear_parentframe() { + if (GetArenaNoVirtual() == NULL && parentframe_ != NULL) delete parentframe_; + parentframe_ = NULL; +} +inline const ::pybullet_grpc::transform& UserConstraintCommand::parentframe() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.UserConstraintCommand.parentFrame) + return parentframe_ != NULL ? *parentframe_ + : *::pybullet_grpc::transform::internal_default_instance(); +} +inline ::pybullet_grpc::transform* UserConstraintCommand::mutable_parentframe() { + + if (parentframe_ == NULL) { + parentframe_ = new ::pybullet_grpc::transform; + } + // @@protoc_insertion_point(field_mutable:pybullet_grpc.UserConstraintCommand.parentFrame) + return parentframe_; +} +inline ::pybullet_grpc::transform* UserConstraintCommand::release_parentframe() { + // @@protoc_insertion_point(field_release:pybullet_grpc.UserConstraintCommand.parentFrame) + + ::pybullet_grpc::transform* temp = parentframe_; + parentframe_ = NULL; + return temp; +} +inline void UserConstraintCommand::set_allocated_parentframe(::pybullet_grpc::transform* parentframe) { + delete parentframe_; + parentframe_ = parentframe; + if (parentframe) { + + } else { + + } + // @@protoc_insertion_point(field_set_allocated:pybullet_grpc.UserConstraintCommand.parentFrame) +} + +// .pybullet_grpc.transform childFrame = 6; +inline bool UserConstraintCommand::has_childframe() const { + return this != internal_default_instance() && childframe_ != NULL; +} +inline void UserConstraintCommand::clear_childframe() { + if (GetArenaNoVirtual() == NULL && childframe_ != NULL) delete childframe_; + childframe_ = NULL; +} +inline const ::pybullet_grpc::transform& UserConstraintCommand::childframe() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.UserConstraintCommand.childFrame) + return childframe_ != NULL ? *childframe_ + : *::pybullet_grpc::transform::internal_default_instance(); +} +inline ::pybullet_grpc::transform* UserConstraintCommand::mutable_childframe() { + + if (childframe_ == NULL) { + childframe_ = new ::pybullet_grpc::transform; + } + // @@protoc_insertion_point(field_mutable:pybullet_grpc.UserConstraintCommand.childFrame) + return childframe_; +} +inline ::pybullet_grpc::transform* UserConstraintCommand::release_childframe() { + // @@protoc_insertion_point(field_release:pybullet_grpc.UserConstraintCommand.childFrame) + + ::pybullet_grpc::transform* temp = childframe_; + childframe_ = NULL; + return temp; +} +inline void UserConstraintCommand::set_allocated_childframe(::pybullet_grpc::transform* childframe) { + delete childframe_; + childframe_ = childframe; + if (childframe) { + + } else { + + } + // @@protoc_insertion_point(field_set_allocated:pybullet_grpc.UserConstraintCommand.childFrame) +} + +// .pybullet_grpc.vec3 jointAxis = 7; +inline bool UserConstraintCommand::has_jointaxis() const { + return this != internal_default_instance() && jointaxis_ != NULL; +} +inline void UserConstraintCommand::clear_jointaxis() { + if (GetArenaNoVirtual() == NULL && jointaxis_ != NULL) delete jointaxis_; + jointaxis_ = NULL; +} +inline const ::pybullet_grpc::vec3& UserConstraintCommand::jointaxis() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.UserConstraintCommand.jointAxis) + return jointaxis_ != NULL ? *jointaxis_ + : *::pybullet_grpc::vec3::internal_default_instance(); +} +inline ::pybullet_grpc::vec3* UserConstraintCommand::mutable_jointaxis() { + + if (jointaxis_ == NULL) { + jointaxis_ = new ::pybullet_grpc::vec3; + } + // @@protoc_insertion_point(field_mutable:pybullet_grpc.UserConstraintCommand.jointAxis) + return jointaxis_; +} +inline ::pybullet_grpc::vec3* UserConstraintCommand::release_jointaxis() { + // @@protoc_insertion_point(field_release:pybullet_grpc.UserConstraintCommand.jointAxis) + + ::pybullet_grpc::vec3* temp = jointaxis_; + jointaxis_ = NULL; + return temp; +} +inline void UserConstraintCommand::set_allocated_jointaxis(::pybullet_grpc::vec3* jointaxis) { + delete jointaxis_; + jointaxis_ = jointaxis; + if (jointaxis) { + + } else { + + } + // @@protoc_insertion_point(field_set_allocated:pybullet_grpc.UserConstraintCommand.jointAxis) +} + +// int32 jointType = 8; +inline void UserConstraintCommand::clear_jointtype() { + jointtype_ = 0; +} +inline ::google::protobuf::int32 UserConstraintCommand::jointtype() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.UserConstraintCommand.jointType) + return jointtype_; +} +inline void UserConstraintCommand::set_jointtype(::google::protobuf::int32 value) { + + jointtype_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.UserConstraintCommand.jointType) +} + +// double maxAppliedForce = 9; +inline void UserConstraintCommand::clear_maxappliedforce() { + maxappliedforce_ = 0; +} +inline double UserConstraintCommand::maxappliedforce() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.UserConstraintCommand.maxAppliedForce) + return maxappliedforce_; +} +inline void UserConstraintCommand::set_maxappliedforce(double value) { + + maxappliedforce_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.UserConstraintCommand.maxAppliedForce) +} + +// int32 userConstraintUniqueId = 10; +inline void UserConstraintCommand::clear_userconstraintuniqueid() { + userconstraintuniqueid_ = 0; +} +inline ::google::protobuf::int32 UserConstraintCommand::userconstraintuniqueid() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.UserConstraintCommand.userConstraintUniqueId) + return userconstraintuniqueid_; +} +inline void UserConstraintCommand::set_userconstraintuniqueid(::google::protobuf::int32 value) { + + userconstraintuniqueid_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.UserConstraintCommand.userConstraintUniqueId) +} + +// double gearRatio = 11; +inline void UserConstraintCommand::clear_gearratio() { + gearratio_ = 0; +} +inline double UserConstraintCommand::gearratio() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.UserConstraintCommand.gearRatio) + return gearratio_; +} +inline void UserConstraintCommand::set_gearratio(double value) { + + gearratio_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.UserConstraintCommand.gearRatio) +} + +// int32 gearAuxLink = 12; +inline void UserConstraintCommand::clear_gearauxlink() { + gearauxlink_ = 0; +} +inline ::google::protobuf::int32 UserConstraintCommand::gearauxlink() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.UserConstraintCommand.gearAuxLink) + return gearauxlink_; +} +inline void UserConstraintCommand::set_gearauxlink(::google::protobuf::int32 value) { + + gearauxlink_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.UserConstraintCommand.gearAuxLink) +} + +// double relativePositionTarget = 13; +inline void UserConstraintCommand::clear_relativepositiontarget() { + relativepositiontarget_ = 0; +} +inline double UserConstraintCommand::relativepositiontarget() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.UserConstraintCommand.relativePositionTarget) + return relativepositiontarget_; +} +inline void UserConstraintCommand::set_relativepositiontarget(double value) { + + relativepositiontarget_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.UserConstraintCommand.relativePositionTarget) +} + +// double erp = 14; +inline void UserConstraintCommand::clear_erp() { + erp_ = 0; +} +inline double UserConstraintCommand::erp() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.UserConstraintCommand.erp) + return erp_; +} +inline void UserConstraintCommand::set_erp(double value) { + + erp_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.UserConstraintCommand.erp) +} + +// int32 updateFlags = 15; +inline void UserConstraintCommand::clear_updateflags() { + updateflags_ = 0; +} +inline ::google::protobuf::int32 UserConstraintCommand::updateflags() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.UserConstraintCommand.updateFlags) + return updateflags_; +} +inline void UserConstraintCommand::set_updateflags(::google::protobuf::int32 value) { + + updateflags_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.UserConstraintCommand.updateFlags) +} + +// ------------------------------------------------------------------- + +// UserConstraintStatus + +// double maxAppliedForce = 9; +inline void UserConstraintStatus::clear_maxappliedforce() { + maxappliedforce_ = 0; +} +inline double UserConstraintStatus::maxappliedforce() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.UserConstraintStatus.maxAppliedForce) + return maxappliedforce_; +} +inline void UserConstraintStatus::set_maxappliedforce(double value) { + + maxappliedforce_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.UserConstraintStatus.maxAppliedForce) +} + +// int32 userConstraintUniqueId = 10; +inline void UserConstraintStatus::clear_userconstraintuniqueid() { + userconstraintuniqueid_ = 0; +} +inline ::google::protobuf::int32 UserConstraintStatus::userconstraintuniqueid() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.UserConstraintStatus.userConstraintUniqueId) + return userconstraintuniqueid_; +} +inline void UserConstraintStatus::set_userconstraintuniqueid(::google::protobuf::int32 value) { + + userconstraintuniqueid_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.UserConstraintStatus.userConstraintUniqueId) +} + +// ------------------------------------------------------------------- + +// UserConstraintStateStatus + +// .pybullet_grpc.vec3 appliedConstraintForcesLinear = 1; +inline bool UserConstraintStateStatus::has_appliedconstraintforceslinear() const { + return this != internal_default_instance() && appliedconstraintforceslinear_ != NULL; +} +inline void UserConstraintStateStatus::clear_appliedconstraintforceslinear() { + if (GetArenaNoVirtual() == NULL && appliedconstraintforceslinear_ != NULL) delete appliedconstraintforceslinear_; + appliedconstraintforceslinear_ = NULL; +} +inline const ::pybullet_grpc::vec3& UserConstraintStateStatus::appliedconstraintforceslinear() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.UserConstraintStateStatus.appliedConstraintForcesLinear) + return appliedconstraintforceslinear_ != NULL ? *appliedconstraintforceslinear_ + : *::pybullet_grpc::vec3::internal_default_instance(); +} +inline ::pybullet_grpc::vec3* UserConstraintStateStatus::mutable_appliedconstraintforceslinear() { + + if (appliedconstraintforceslinear_ == NULL) { + appliedconstraintforceslinear_ = new ::pybullet_grpc::vec3; + } + // @@protoc_insertion_point(field_mutable:pybullet_grpc.UserConstraintStateStatus.appliedConstraintForcesLinear) + return appliedconstraintforceslinear_; +} +inline ::pybullet_grpc::vec3* UserConstraintStateStatus::release_appliedconstraintforceslinear() { + // @@protoc_insertion_point(field_release:pybullet_grpc.UserConstraintStateStatus.appliedConstraintForcesLinear) + + ::pybullet_grpc::vec3* temp = appliedconstraintforceslinear_; + appliedconstraintforceslinear_ = NULL; + return temp; +} +inline void UserConstraintStateStatus::set_allocated_appliedconstraintforceslinear(::pybullet_grpc::vec3* appliedconstraintforceslinear) { + delete appliedconstraintforceslinear_; + appliedconstraintforceslinear_ = appliedconstraintforceslinear; + if (appliedconstraintforceslinear) { + + } else { + + } + // @@protoc_insertion_point(field_set_allocated:pybullet_grpc.UserConstraintStateStatus.appliedConstraintForcesLinear) +} + +// .pybullet_grpc.vec3 appliedConstraintForcesAngular = 2; +inline bool UserConstraintStateStatus::has_appliedconstraintforcesangular() const { + return this != internal_default_instance() && appliedconstraintforcesangular_ != NULL; +} +inline void UserConstraintStateStatus::clear_appliedconstraintforcesangular() { + if (GetArenaNoVirtual() == NULL && appliedconstraintforcesangular_ != NULL) delete appliedconstraintforcesangular_; + appliedconstraintforcesangular_ = NULL; +} +inline const ::pybullet_grpc::vec3& UserConstraintStateStatus::appliedconstraintforcesangular() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.UserConstraintStateStatus.appliedConstraintForcesAngular) + return appliedconstraintforcesangular_ != NULL ? *appliedconstraintforcesangular_ + : *::pybullet_grpc::vec3::internal_default_instance(); +} +inline ::pybullet_grpc::vec3* UserConstraintStateStatus::mutable_appliedconstraintforcesangular() { + + if (appliedconstraintforcesangular_ == NULL) { + appliedconstraintforcesangular_ = new ::pybullet_grpc::vec3; + } + // @@protoc_insertion_point(field_mutable:pybullet_grpc.UserConstraintStateStatus.appliedConstraintForcesAngular) + return appliedconstraintforcesangular_; +} +inline ::pybullet_grpc::vec3* UserConstraintStateStatus::release_appliedconstraintforcesangular() { + // @@protoc_insertion_point(field_release:pybullet_grpc.UserConstraintStateStatus.appliedConstraintForcesAngular) + + ::pybullet_grpc::vec3* temp = appliedconstraintforcesangular_; + appliedconstraintforcesangular_ = NULL; + return temp; +} +inline void UserConstraintStateStatus::set_allocated_appliedconstraintforcesangular(::pybullet_grpc::vec3* appliedconstraintforcesangular) { + delete appliedconstraintforcesangular_; + appliedconstraintforcesangular_ = appliedconstraintforcesangular; + if (appliedconstraintforcesangular) { + + } else { + + } + // @@protoc_insertion_point(field_set_allocated:pybullet_grpc.UserConstraintStateStatus.appliedConstraintForcesAngular) +} + +// int32 numDofs = 3; +inline void UserConstraintStateStatus::clear_numdofs() { + numdofs_ = 0; +} +inline ::google::protobuf::int32 UserConstraintStateStatus::numdofs() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.UserConstraintStateStatus.numDofs) + return numdofs_; +} +inline void UserConstraintStateStatus::set_numdofs(::google::protobuf::int32 value) { + + numdofs_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.UserConstraintStateStatus.numDofs) +} + +// ------------------------------------------------------------------- + +// RequestKeyboardEventsCommand + +// ------------------------------------------------------------------- + +// KeyboardEvent + +// int32 keyCode = 1; +inline void KeyboardEvent::clear_keycode() { + keycode_ = 0; +} +inline ::google::protobuf::int32 KeyboardEvent::keycode() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.KeyboardEvent.keyCode) + return keycode_; +} +inline void KeyboardEvent::set_keycode(::google::protobuf::int32 value) { + + keycode_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.KeyboardEvent.keyCode) +} + +// int32 keyState = 2; +inline void KeyboardEvent::clear_keystate() { + keystate_ = 0; +} +inline ::google::protobuf::int32 KeyboardEvent::keystate() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.KeyboardEvent.keyState) + return keystate_; +} +inline void KeyboardEvent::set_keystate(::google::protobuf::int32 value) { + + keystate_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.KeyboardEvent.keyState) +} + +// ------------------------------------------------------------------- + +// KeyboardEventsStatus + +// repeated .pybullet_grpc.KeyboardEvent keyboardEvents = 1; +inline int KeyboardEventsStatus::keyboardevents_size() const { + return keyboardevents_.size(); +} +inline void KeyboardEventsStatus::clear_keyboardevents() { + keyboardevents_.Clear(); +} +inline const ::pybullet_grpc::KeyboardEvent& KeyboardEventsStatus::keyboardevents(int index) const { + // @@protoc_insertion_point(field_get:pybullet_grpc.KeyboardEventsStatus.keyboardEvents) + return keyboardevents_.Get(index); +} +inline ::pybullet_grpc::KeyboardEvent* KeyboardEventsStatus::mutable_keyboardevents(int index) { + // @@protoc_insertion_point(field_mutable:pybullet_grpc.KeyboardEventsStatus.keyboardEvents) + return keyboardevents_.Mutable(index); +} +inline ::pybullet_grpc::KeyboardEvent* KeyboardEventsStatus::add_keyboardevents() { + // @@protoc_insertion_point(field_add:pybullet_grpc.KeyboardEventsStatus.keyboardEvents) + return keyboardevents_.Add(); +} +inline ::google::protobuf::RepeatedPtrField< ::pybullet_grpc::KeyboardEvent >* +KeyboardEventsStatus::mutable_keyboardevents() { + // @@protoc_insertion_point(field_mutable_list:pybullet_grpc.KeyboardEventsStatus.keyboardEvents) + return &keyboardevents_; +} +inline const ::google::protobuf::RepeatedPtrField< ::pybullet_grpc::KeyboardEvent >& +KeyboardEventsStatus::keyboardevents() const { + // @@protoc_insertion_point(field_list:pybullet_grpc.KeyboardEventsStatus.keyboardEvents) + return keyboardevents_; +} + +// ------------------------------------------------------------------- + +// RequestCameraImageCommand + +// int32 updateFlags = 1; +inline void RequestCameraImageCommand::clear_updateflags() { + updateflags_ = 0; +} +inline ::google::protobuf::int32 RequestCameraImageCommand::updateflags() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.RequestCameraImageCommand.updateFlags) + return updateflags_; +} +inline void RequestCameraImageCommand::set_updateflags(::google::protobuf::int32 value) { + + updateflags_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.RequestCameraImageCommand.updateFlags) +} + +// int32 cameraFlags = 2; +inline void RequestCameraImageCommand::clear_cameraflags() { + cameraflags_ = 0; +} +inline ::google::protobuf::int32 RequestCameraImageCommand::cameraflags() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.RequestCameraImageCommand.cameraFlags) + return cameraflags_; +} +inline void RequestCameraImageCommand::set_cameraflags(::google::protobuf::int32 value) { + + cameraflags_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.RequestCameraImageCommand.cameraFlags) +} + +// .pybullet_grpc.matrix4x4 viewMatrix = 3; +inline bool RequestCameraImageCommand::has_viewmatrix() const { + return this != internal_default_instance() && viewmatrix_ != NULL; +} +inline void RequestCameraImageCommand::clear_viewmatrix() { + if (GetArenaNoVirtual() == NULL && viewmatrix_ != NULL) delete viewmatrix_; + viewmatrix_ = NULL; +} +inline const ::pybullet_grpc::matrix4x4& RequestCameraImageCommand::viewmatrix() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.RequestCameraImageCommand.viewMatrix) + return viewmatrix_ != NULL ? *viewmatrix_ + : *::pybullet_grpc::matrix4x4::internal_default_instance(); +} +inline ::pybullet_grpc::matrix4x4* RequestCameraImageCommand::mutable_viewmatrix() { + + if (viewmatrix_ == NULL) { + viewmatrix_ = new ::pybullet_grpc::matrix4x4; + } + // @@protoc_insertion_point(field_mutable:pybullet_grpc.RequestCameraImageCommand.viewMatrix) + return viewmatrix_; +} +inline ::pybullet_grpc::matrix4x4* RequestCameraImageCommand::release_viewmatrix() { + // @@protoc_insertion_point(field_release:pybullet_grpc.RequestCameraImageCommand.viewMatrix) + + ::pybullet_grpc::matrix4x4* temp = viewmatrix_; + viewmatrix_ = NULL; + return temp; +} +inline void RequestCameraImageCommand::set_allocated_viewmatrix(::pybullet_grpc::matrix4x4* viewmatrix) { + delete viewmatrix_; + viewmatrix_ = viewmatrix; + if (viewmatrix) { + + } else { + + } + // @@protoc_insertion_point(field_set_allocated:pybullet_grpc.RequestCameraImageCommand.viewMatrix) +} + +// .pybullet_grpc.matrix4x4 projectionMatrix = 4; +inline bool RequestCameraImageCommand::has_projectionmatrix() const { + return this != internal_default_instance() && projectionmatrix_ != NULL; +} +inline void RequestCameraImageCommand::clear_projectionmatrix() { + if (GetArenaNoVirtual() == NULL && projectionmatrix_ != NULL) delete projectionmatrix_; + projectionmatrix_ = NULL; +} +inline const ::pybullet_grpc::matrix4x4& RequestCameraImageCommand::projectionmatrix() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.RequestCameraImageCommand.projectionMatrix) + return projectionmatrix_ != NULL ? *projectionmatrix_ + : *::pybullet_grpc::matrix4x4::internal_default_instance(); +} +inline ::pybullet_grpc::matrix4x4* RequestCameraImageCommand::mutable_projectionmatrix() { + + if (projectionmatrix_ == NULL) { + projectionmatrix_ = new ::pybullet_grpc::matrix4x4; + } + // @@protoc_insertion_point(field_mutable:pybullet_grpc.RequestCameraImageCommand.projectionMatrix) + return projectionmatrix_; +} +inline ::pybullet_grpc::matrix4x4* RequestCameraImageCommand::release_projectionmatrix() { + // @@protoc_insertion_point(field_release:pybullet_grpc.RequestCameraImageCommand.projectionMatrix) + + ::pybullet_grpc::matrix4x4* temp = projectionmatrix_; + projectionmatrix_ = NULL; + return temp; +} +inline void RequestCameraImageCommand::set_allocated_projectionmatrix(::pybullet_grpc::matrix4x4* projectionmatrix) { + delete projectionmatrix_; + projectionmatrix_ = projectionmatrix; + if (projectionmatrix) { + + } else { + + } + // @@protoc_insertion_point(field_set_allocated:pybullet_grpc.RequestCameraImageCommand.projectionMatrix) +} + +// int32 startPixelIndex = 5; +inline void RequestCameraImageCommand::clear_startpixelindex() { + startpixelindex_ = 0; +} +inline ::google::protobuf::int32 RequestCameraImageCommand::startpixelindex() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.RequestCameraImageCommand.startPixelIndex) + return startpixelindex_; +} +inline void RequestCameraImageCommand::set_startpixelindex(::google::protobuf::int32 value) { + + startpixelindex_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.RequestCameraImageCommand.startPixelIndex) +} + +// int32 pixelWidth = 6; +inline void RequestCameraImageCommand::clear_pixelwidth() { + pixelwidth_ = 0; +} +inline ::google::protobuf::int32 RequestCameraImageCommand::pixelwidth() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.RequestCameraImageCommand.pixelWidth) + return pixelwidth_; +} +inline void RequestCameraImageCommand::set_pixelwidth(::google::protobuf::int32 value) { + + pixelwidth_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.RequestCameraImageCommand.pixelWidth) +} + +// int32 pixelHeight = 7; +inline void RequestCameraImageCommand::clear_pixelheight() { + pixelheight_ = 0; +} +inline ::google::protobuf::int32 RequestCameraImageCommand::pixelheight() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.RequestCameraImageCommand.pixelHeight) + return pixelheight_; +} +inline void RequestCameraImageCommand::set_pixelheight(::google::protobuf::int32 value) { + + pixelheight_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.RequestCameraImageCommand.pixelHeight) +} + +// .pybullet_grpc.vec3 lightDirection = 8; +inline bool RequestCameraImageCommand::has_lightdirection() const { + return this != internal_default_instance() && lightdirection_ != NULL; +} +inline void RequestCameraImageCommand::clear_lightdirection() { + if (GetArenaNoVirtual() == NULL && lightdirection_ != NULL) delete lightdirection_; + lightdirection_ = NULL; +} +inline const ::pybullet_grpc::vec3& RequestCameraImageCommand::lightdirection() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.RequestCameraImageCommand.lightDirection) + return lightdirection_ != NULL ? *lightdirection_ + : *::pybullet_grpc::vec3::internal_default_instance(); +} +inline ::pybullet_grpc::vec3* RequestCameraImageCommand::mutable_lightdirection() { + + if (lightdirection_ == NULL) { + lightdirection_ = new ::pybullet_grpc::vec3; + } + // @@protoc_insertion_point(field_mutable:pybullet_grpc.RequestCameraImageCommand.lightDirection) + return lightdirection_; +} +inline ::pybullet_grpc::vec3* RequestCameraImageCommand::release_lightdirection() { + // @@protoc_insertion_point(field_release:pybullet_grpc.RequestCameraImageCommand.lightDirection) + + ::pybullet_grpc::vec3* temp = lightdirection_; + lightdirection_ = NULL; + return temp; +} +inline void RequestCameraImageCommand::set_allocated_lightdirection(::pybullet_grpc::vec3* lightdirection) { + delete lightdirection_; + lightdirection_ = lightdirection; + if (lightdirection) { + + } else { + + } + // @@protoc_insertion_point(field_set_allocated:pybullet_grpc.RequestCameraImageCommand.lightDirection) +} + +// .pybullet_grpc.vec3 lightColor = 9; +inline bool RequestCameraImageCommand::has_lightcolor() const { + return this != internal_default_instance() && lightcolor_ != NULL; +} +inline void RequestCameraImageCommand::clear_lightcolor() { + if (GetArenaNoVirtual() == NULL && lightcolor_ != NULL) delete lightcolor_; + lightcolor_ = NULL; +} +inline const ::pybullet_grpc::vec3& RequestCameraImageCommand::lightcolor() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.RequestCameraImageCommand.lightColor) + return lightcolor_ != NULL ? *lightcolor_ + : *::pybullet_grpc::vec3::internal_default_instance(); +} +inline ::pybullet_grpc::vec3* RequestCameraImageCommand::mutable_lightcolor() { + + if (lightcolor_ == NULL) { + lightcolor_ = new ::pybullet_grpc::vec3; + } + // @@protoc_insertion_point(field_mutable:pybullet_grpc.RequestCameraImageCommand.lightColor) + return lightcolor_; +} +inline ::pybullet_grpc::vec3* RequestCameraImageCommand::release_lightcolor() { + // @@protoc_insertion_point(field_release:pybullet_grpc.RequestCameraImageCommand.lightColor) + + ::pybullet_grpc::vec3* temp = lightcolor_; + lightcolor_ = NULL; + return temp; +} +inline void RequestCameraImageCommand::set_allocated_lightcolor(::pybullet_grpc::vec3* lightcolor) { + delete lightcolor_; + lightcolor_ = lightcolor; + if (lightcolor) { + + } else { + + } + // @@protoc_insertion_point(field_set_allocated:pybullet_grpc.RequestCameraImageCommand.lightColor) +} + +// double lightDistance = 10; +inline void RequestCameraImageCommand::clear_lightdistance() { + lightdistance_ = 0; +} +inline double RequestCameraImageCommand::lightdistance() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.RequestCameraImageCommand.lightDistance) + return lightdistance_; +} +inline void RequestCameraImageCommand::set_lightdistance(double value) { + + lightdistance_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.RequestCameraImageCommand.lightDistance) +} + +// double lightAmbientCoeff = 11; +inline void RequestCameraImageCommand::clear_lightambientcoeff() { + lightambientcoeff_ = 0; +} +inline double RequestCameraImageCommand::lightambientcoeff() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.RequestCameraImageCommand.lightAmbientCoeff) + return lightambientcoeff_; +} +inline void RequestCameraImageCommand::set_lightambientcoeff(double value) { + + lightambientcoeff_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.RequestCameraImageCommand.lightAmbientCoeff) +} + +// double lightDiffuseCoeff = 12; +inline void RequestCameraImageCommand::clear_lightdiffusecoeff() { + lightdiffusecoeff_ = 0; +} +inline double RequestCameraImageCommand::lightdiffusecoeff() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.RequestCameraImageCommand.lightDiffuseCoeff) + return lightdiffusecoeff_; +} +inline void RequestCameraImageCommand::set_lightdiffusecoeff(double value) { + + lightdiffusecoeff_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.RequestCameraImageCommand.lightDiffuseCoeff) +} + +// double lightSpecularCoeff = 13; +inline void RequestCameraImageCommand::clear_lightspecularcoeff() { + lightspecularcoeff_ = 0; +} +inline double RequestCameraImageCommand::lightspecularcoeff() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.RequestCameraImageCommand.lightSpecularCoeff) + return lightspecularcoeff_; +} +inline void RequestCameraImageCommand::set_lightspecularcoeff(double value) { + + lightspecularcoeff_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.RequestCameraImageCommand.lightSpecularCoeff) +} + +// int32 hasShadow = 14; +inline void RequestCameraImageCommand::clear_hasshadow() { + hasshadow_ = 0; +} +inline ::google::protobuf::int32 RequestCameraImageCommand::hasshadow() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.RequestCameraImageCommand.hasShadow) + return hasshadow_; +} +inline void RequestCameraImageCommand::set_hasshadow(::google::protobuf::int32 value) { + + hasshadow_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.RequestCameraImageCommand.hasShadow) +} + +// .pybullet_grpc.matrix4x4 projectiveTextureViewMatrix = 15; +inline bool RequestCameraImageCommand::has_projectivetextureviewmatrix() const { + return this != internal_default_instance() && projectivetextureviewmatrix_ != NULL; +} +inline void RequestCameraImageCommand::clear_projectivetextureviewmatrix() { + if (GetArenaNoVirtual() == NULL && projectivetextureviewmatrix_ != NULL) delete projectivetextureviewmatrix_; + projectivetextureviewmatrix_ = NULL; +} +inline const ::pybullet_grpc::matrix4x4& RequestCameraImageCommand::projectivetextureviewmatrix() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.RequestCameraImageCommand.projectiveTextureViewMatrix) + return projectivetextureviewmatrix_ != NULL ? *projectivetextureviewmatrix_ + : *::pybullet_grpc::matrix4x4::internal_default_instance(); +} +inline ::pybullet_grpc::matrix4x4* RequestCameraImageCommand::mutable_projectivetextureviewmatrix() { + + if (projectivetextureviewmatrix_ == NULL) { + projectivetextureviewmatrix_ = new ::pybullet_grpc::matrix4x4; + } + // @@protoc_insertion_point(field_mutable:pybullet_grpc.RequestCameraImageCommand.projectiveTextureViewMatrix) + return projectivetextureviewmatrix_; +} +inline ::pybullet_grpc::matrix4x4* RequestCameraImageCommand::release_projectivetextureviewmatrix() { + // @@protoc_insertion_point(field_release:pybullet_grpc.RequestCameraImageCommand.projectiveTextureViewMatrix) + + ::pybullet_grpc::matrix4x4* temp = projectivetextureviewmatrix_; + projectivetextureviewmatrix_ = NULL; + return temp; +} +inline void RequestCameraImageCommand::set_allocated_projectivetextureviewmatrix(::pybullet_grpc::matrix4x4* projectivetextureviewmatrix) { + delete projectivetextureviewmatrix_; + projectivetextureviewmatrix_ = projectivetextureviewmatrix; + if (projectivetextureviewmatrix) { + + } else { + + } + // @@protoc_insertion_point(field_set_allocated:pybullet_grpc.RequestCameraImageCommand.projectiveTextureViewMatrix) +} + +// .pybullet_grpc.matrix4x4 projectiveTextureProjectionMatrix = 16; +inline bool RequestCameraImageCommand::has_projectivetextureprojectionmatrix() const { + return this != internal_default_instance() && projectivetextureprojectionmatrix_ != NULL; +} +inline void RequestCameraImageCommand::clear_projectivetextureprojectionmatrix() { + if (GetArenaNoVirtual() == NULL && projectivetextureprojectionmatrix_ != NULL) delete projectivetextureprojectionmatrix_; + projectivetextureprojectionmatrix_ = NULL; +} +inline const ::pybullet_grpc::matrix4x4& RequestCameraImageCommand::projectivetextureprojectionmatrix() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.RequestCameraImageCommand.projectiveTextureProjectionMatrix) + return projectivetextureprojectionmatrix_ != NULL ? *projectivetextureprojectionmatrix_ + : *::pybullet_grpc::matrix4x4::internal_default_instance(); +} +inline ::pybullet_grpc::matrix4x4* RequestCameraImageCommand::mutable_projectivetextureprojectionmatrix() { + + if (projectivetextureprojectionmatrix_ == NULL) { + projectivetextureprojectionmatrix_ = new ::pybullet_grpc::matrix4x4; + } + // @@protoc_insertion_point(field_mutable:pybullet_grpc.RequestCameraImageCommand.projectiveTextureProjectionMatrix) + return projectivetextureprojectionmatrix_; +} +inline ::pybullet_grpc::matrix4x4* RequestCameraImageCommand::release_projectivetextureprojectionmatrix() { + // @@protoc_insertion_point(field_release:pybullet_grpc.RequestCameraImageCommand.projectiveTextureProjectionMatrix) + + ::pybullet_grpc::matrix4x4* temp = projectivetextureprojectionmatrix_; + projectivetextureprojectionmatrix_ = NULL; + return temp; +} +inline void RequestCameraImageCommand::set_allocated_projectivetextureprojectionmatrix(::pybullet_grpc::matrix4x4* projectivetextureprojectionmatrix) { + delete projectivetextureprojectionmatrix_; + projectivetextureprojectionmatrix_ = projectivetextureprojectionmatrix; + if (projectivetextureprojectionmatrix) { + + } else { + + } + // @@protoc_insertion_point(field_set_allocated:pybullet_grpc.RequestCameraImageCommand.projectiveTextureProjectionMatrix) +} + +// ------------------------------------------------------------------- + +// RequestCameraImageStatus + +// int32 imageWidth = 1; +inline void RequestCameraImageStatus::clear_imagewidth() { + imagewidth_ = 0; +} +inline ::google::protobuf::int32 RequestCameraImageStatus::imagewidth() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.RequestCameraImageStatus.imageWidth) + return imagewidth_; +} +inline void RequestCameraImageStatus::set_imagewidth(::google::protobuf::int32 value) { + + imagewidth_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.RequestCameraImageStatus.imageWidth) +} + +// int32 imageHeight = 2; +inline void RequestCameraImageStatus::clear_imageheight() { + imageheight_ = 0; +} +inline ::google::protobuf::int32 RequestCameraImageStatus::imageheight() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.RequestCameraImageStatus.imageHeight) + return imageheight_; +} +inline void RequestCameraImageStatus::set_imageheight(::google::protobuf::int32 value) { + + imageheight_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.RequestCameraImageStatus.imageHeight) +} + +// int32 startingPixelIndex = 3; +inline void RequestCameraImageStatus::clear_startingpixelindex() { + startingpixelindex_ = 0; +} +inline ::google::protobuf::int32 RequestCameraImageStatus::startingpixelindex() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.RequestCameraImageStatus.startingPixelIndex) + return startingpixelindex_; +} +inline void RequestCameraImageStatus::set_startingpixelindex(::google::protobuf::int32 value) { + + startingpixelindex_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.RequestCameraImageStatus.startingPixelIndex) +} + +// int32 numPixelsCopied = 4; +inline void RequestCameraImageStatus::clear_numpixelscopied() { + numpixelscopied_ = 0; +} +inline ::google::protobuf::int32 RequestCameraImageStatus::numpixelscopied() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.RequestCameraImageStatus.numPixelsCopied) + return numpixelscopied_; +} +inline void RequestCameraImageStatus::set_numpixelscopied(::google::protobuf::int32 value) { + + numpixelscopied_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.RequestCameraImageStatus.numPixelsCopied) +} + +// int32 numRemainingPixels = 5; +inline void RequestCameraImageStatus::clear_numremainingpixels() { + numremainingpixels_ = 0; +} +inline ::google::protobuf::int32 RequestCameraImageStatus::numremainingpixels() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.RequestCameraImageStatus.numRemainingPixels) + return numremainingpixels_; +} +inline void RequestCameraImageStatus::set_numremainingpixels(::google::protobuf::int32 value) { + + numremainingpixels_ = value; + // @@protoc_insertion_point(field_set:pybullet_grpc.RequestCameraImageStatus.numRemainingPixels) +} + +// ------------------------------------------------------------------- + // PyBulletCommand // int32 commandType = 1; @@ -4732,7 +9811,117 @@ inline void PyBulletCommand::set_commandtype(::google::protobuf::int32 value) { // @@protoc_insertion_point(field_set:pybullet_grpc.PyBulletCommand.commandType) } -// .pybullet_grpc.LoadUrdfCommand loadUrdfCommand = 3; +// repeated bytes binaryBlob = 2; +inline int PyBulletCommand::binaryblob_size() const { + return binaryblob_.size(); +} +inline void PyBulletCommand::clear_binaryblob() { + binaryblob_.Clear(); +} +inline const ::std::string& PyBulletCommand::binaryblob(int index) const { + // @@protoc_insertion_point(field_get:pybullet_grpc.PyBulletCommand.binaryBlob) + return binaryblob_.Get(index); +} +inline ::std::string* PyBulletCommand::mutable_binaryblob(int index) { + // @@protoc_insertion_point(field_mutable:pybullet_grpc.PyBulletCommand.binaryBlob) + return binaryblob_.Mutable(index); +} +inline void PyBulletCommand::set_binaryblob(int index, const ::std::string& value) { + // @@protoc_insertion_point(field_set:pybullet_grpc.PyBulletCommand.binaryBlob) + binaryblob_.Mutable(index)->assign(value); +} +inline void PyBulletCommand::set_binaryblob(int index, const char* value) { + binaryblob_.Mutable(index)->assign(value); + // @@protoc_insertion_point(field_set_char:pybullet_grpc.PyBulletCommand.binaryBlob) +} +inline void PyBulletCommand::set_binaryblob(int index, const void* value, size_t size) { + binaryblob_.Mutable(index)->assign( + reinterpret_cast(value), size); + // @@protoc_insertion_point(field_set_pointer:pybullet_grpc.PyBulletCommand.binaryBlob) +} +inline ::std::string* PyBulletCommand::add_binaryblob() { + // @@protoc_insertion_point(field_add_mutable:pybullet_grpc.PyBulletCommand.binaryBlob) + return binaryblob_.Add(); +} +inline void PyBulletCommand::add_binaryblob(const ::std::string& value) { + binaryblob_.Add()->assign(value); + // @@protoc_insertion_point(field_add:pybullet_grpc.PyBulletCommand.binaryBlob) +} +inline void PyBulletCommand::add_binaryblob(const char* value) { + binaryblob_.Add()->assign(value); + // @@protoc_insertion_point(field_add_char:pybullet_grpc.PyBulletCommand.binaryBlob) +} +inline void PyBulletCommand::add_binaryblob(const void* value, size_t size) { + binaryblob_.Add()->assign(reinterpret_cast(value), size); + // @@protoc_insertion_point(field_add_pointer:pybullet_grpc.PyBulletCommand.binaryBlob) +} +inline const ::google::protobuf::RepeatedPtrField< ::std::string>& +PyBulletCommand::binaryblob() const { + // @@protoc_insertion_point(field_list:pybullet_grpc.PyBulletCommand.binaryBlob) + return binaryblob_; +} +inline ::google::protobuf::RepeatedPtrField< ::std::string>* +PyBulletCommand::mutable_binaryblob() { + // @@protoc_insertion_point(field_mutable_list:pybullet_grpc.PyBulletCommand.binaryBlob) + return &binaryblob_; +} + +// repeated bytes unknownCommandBinaryBlob = 3; +inline int PyBulletCommand::unknowncommandbinaryblob_size() const { + return unknowncommandbinaryblob_.size(); +} +inline void PyBulletCommand::clear_unknowncommandbinaryblob() { + unknowncommandbinaryblob_.Clear(); +} +inline const ::std::string& PyBulletCommand::unknowncommandbinaryblob(int index) const { + // @@protoc_insertion_point(field_get:pybullet_grpc.PyBulletCommand.unknownCommandBinaryBlob) + return unknowncommandbinaryblob_.Get(index); +} +inline ::std::string* PyBulletCommand::mutable_unknowncommandbinaryblob(int index) { + // @@protoc_insertion_point(field_mutable:pybullet_grpc.PyBulletCommand.unknownCommandBinaryBlob) + return unknowncommandbinaryblob_.Mutable(index); +} +inline void PyBulletCommand::set_unknowncommandbinaryblob(int index, const ::std::string& value) { + // @@protoc_insertion_point(field_set:pybullet_grpc.PyBulletCommand.unknownCommandBinaryBlob) + unknowncommandbinaryblob_.Mutable(index)->assign(value); +} +inline void PyBulletCommand::set_unknowncommandbinaryblob(int index, const char* value) { + unknowncommandbinaryblob_.Mutable(index)->assign(value); + // @@protoc_insertion_point(field_set_char:pybullet_grpc.PyBulletCommand.unknownCommandBinaryBlob) +} +inline void PyBulletCommand::set_unknowncommandbinaryblob(int index, const void* value, size_t size) { + unknowncommandbinaryblob_.Mutable(index)->assign( + reinterpret_cast(value), size); + // @@protoc_insertion_point(field_set_pointer:pybullet_grpc.PyBulletCommand.unknownCommandBinaryBlob) +} +inline ::std::string* PyBulletCommand::add_unknowncommandbinaryblob() { + // @@protoc_insertion_point(field_add_mutable:pybullet_grpc.PyBulletCommand.unknownCommandBinaryBlob) + return unknowncommandbinaryblob_.Add(); +} +inline void PyBulletCommand::add_unknowncommandbinaryblob(const ::std::string& value) { + unknowncommandbinaryblob_.Add()->assign(value); + // @@protoc_insertion_point(field_add:pybullet_grpc.PyBulletCommand.unknownCommandBinaryBlob) +} +inline void PyBulletCommand::add_unknowncommandbinaryblob(const char* value) { + unknowncommandbinaryblob_.Add()->assign(value); + // @@protoc_insertion_point(field_add_char:pybullet_grpc.PyBulletCommand.unknownCommandBinaryBlob) +} +inline void PyBulletCommand::add_unknowncommandbinaryblob(const void* value, size_t size) { + unknowncommandbinaryblob_.Add()->assign(reinterpret_cast(value), size); + // @@protoc_insertion_point(field_add_pointer:pybullet_grpc.PyBulletCommand.unknownCommandBinaryBlob) +} +inline const ::google::protobuf::RepeatedPtrField< ::std::string>& +PyBulletCommand::unknowncommandbinaryblob() const { + // @@protoc_insertion_point(field_list:pybullet_grpc.PyBulletCommand.unknownCommandBinaryBlob) + return unknowncommandbinaryblob_; +} +inline ::google::protobuf::RepeatedPtrField< ::std::string>* +PyBulletCommand::mutable_unknowncommandbinaryblob() { + // @@protoc_insertion_point(field_mutable_list:pybullet_grpc.PyBulletCommand.unknownCommandBinaryBlob) + return &unknowncommandbinaryblob_; +} + +// .pybullet_grpc.LoadUrdfCommand loadUrdfCommand = 4; inline bool PyBulletCommand::has_loadurdfcommand() const { return commands_case() == kLoadUrdfCommand; } @@ -4780,7 +9969,7 @@ inline void PyBulletCommand::set_allocated_loadurdfcommand(::pybullet_grpc::Load // @@protoc_insertion_point(field_set_allocated:pybullet_grpc.PyBulletCommand.loadUrdfCommand) } -// .pybullet_grpc.TerminateServerCommand terminateServerCommand = 4; +// .pybullet_grpc.TerminateServerCommand terminateServerCommand = 5; inline bool PyBulletCommand::has_terminateservercommand() const { return commands_case() == kTerminateServerCommand; } @@ -4828,7 +10017,7 @@ inline void PyBulletCommand::set_allocated_terminateservercommand(::pybullet_grp // @@protoc_insertion_point(field_set_allocated:pybullet_grpc.PyBulletCommand.terminateServerCommand) } -// .pybullet_grpc.StepSimulationCommand stepSimulationCommand = 5; +// .pybullet_grpc.StepSimulationCommand stepSimulationCommand = 6; inline bool PyBulletCommand::has_stepsimulationcommand() const { return commands_case() == kStepSimulationCommand; } @@ -4876,7 +10065,7 @@ inline void PyBulletCommand::set_allocated_stepsimulationcommand(::pybullet_grpc // @@protoc_insertion_point(field_set_allocated:pybullet_grpc.PyBulletCommand.stepSimulationCommand) } -// .pybullet_grpc.LoadSdfCommand loadSdfCommand = 6; +// .pybullet_grpc.LoadSdfCommand loadSdfCommand = 7; inline bool PyBulletCommand::has_loadsdfcommand() const { return commands_case() == kLoadSdfCommand; } @@ -4924,7 +10113,7 @@ inline void PyBulletCommand::set_allocated_loadsdfcommand(::pybullet_grpc::LoadS // @@protoc_insertion_point(field_set_allocated:pybullet_grpc.PyBulletCommand.loadSdfCommand) } -// .pybullet_grpc.LoadMjcfCommand loadMjcfCommand = 7; +// .pybullet_grpc.LoadMjcfCommand loadMjcfCommand = 8; inline bool PyBulletCommand::has_loadmjcfcommand() const { return commands_case() == kLoadMjcfCommand; } @@ -4972,7 +10161,7 @@ inline void PyBulletCommand::set_allocated_loadmjcfcommand(::pybullet_grpc::Load // @@protoc_insertion_point(field_set_allocated:pybullet_grpc.PyBulletCommand.loadMjcfCommand) } -// .pybullet_grpc.ChangeDynamicsCommand changeDynamicsCommand = 8; +// .pybullet_grpc.ChangeDynamicsCommand changeDynamicsCommand = 9; inline bool PyBulletCommand::has_changedynamicscommand() const { return commands_case() == kChangeDynamicsCommand; } @@ -5020,7 +10209,7 @@ inline void PyBulletCommand::set_allocated_changedynamicscommand(::pybullet_grpc // @@protoc_insertion_point(field_set_allocated:pybullet_grpc.PyBulletCommand.changeDynamicsCommand) } -// .pybullet_grpc.GetDynamicsCommand getDynamicsCommand = 9; +// .pybullet_grpc.GetDynamicsCommand getDynamicsCommand = 10; inline bool PyBulletCommand::has_getdynamicscommand() const { return commands_case() == kGetDynamicsCommand; } @@ -5068,7 +10257,7 @@ inline void PyBulletCommand::set_allocated_getdynamicscommand(::pybullet_grpc::G // @@protoc_insertion_point(field_set_allocated:pybullet_grpc.PyBulletCommand.getDynamicsCommand) } -// .pybullet_grpc.InitPoseCommand initPoseCommand = 10; +// .pybullet_grpc.InitPoseCommand initPoseCommand = 11; inline bool PyBulletCommand::has_initposecommand() const { return commands_case() == kInitPoseCommand; } @@ -5116,7 +10305,7 @@ inline void PyBulletCommand::set_allocated_initposecommand(::pybullet_grpc::Init // @@protoc_insertion_point(field_set_allocated:pybullet_grpc.PyBulletCommand.initPoseCommand) } -// .pybullet_grpc.RequestActualStateCommand requestActualStateCommand = 11; +// .pybullet_grpc.RequestActualStateCommand requestActualStateCommand = 12; inline bool PyBulletCommand::has_requestactualstatecommand() const { return commands_case() == kRequestActualStateCommand; } @@ -5164,6 +10353,438 @@ inline void PyBulletCommand::set_allocated_requestactualstatecommand(::pybullet_ // @@protoc_insertion_point(field_set_allocated:pybullet_grpc.PyBulletCommand.requestActualStateCommand) } +// .pybullet_grpc.ConfigureOpenGLVisualizerCommand configureOpenGLVisualizerCommand = 13; +inline bool PyBulletCommand::has_configureopenglvisualizercommand() const { + return commands_case() == kConfigureOpenGLVisualizerCommand; +} +inline void PyBulletCommand::set_has_configureopenglvisualizercommand() { + _oneof_case_[0] = kConfigureOpenGLVisualizerCommand; +} +inline void PyBulletCommand::clear_configureopenglvisualizercommand() { + if (has_configureopenglvisualizercommand()) { + delete commands_.configureopenglvisualizercommand_; + clear_has_commands(); + } +} +inline const ::pybullet_grpc::ConfigureOpenGLVisualizerCommand& PyBulletCommand::configureopenglvisualizercommand() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.PyBulletCommand.configureOpenGLVisualizerCommand) + return has_configureopenglvisualizercommand() + ? *commands_.configureopenglvisualizercommand_ + : ::pybullet_grpc::ConfigureOpenGLVisualizerCommand::default_instance(); +} +inline ::pybullet_grpc::ConfigureOpenGLVisualizerCommand* PyBulletCommand::mutable_configureopenglvisualizercommand() { + if (!has_configureopenglvisualizercommand()) { + clear_commands(); + set_has_configureopenglvisualizercommand(); + commands_.configureopenglvisualizercommand_ = new ::pybullet_grpc::ConfigureOpenGLVisualizerCommand; + } + // @@protoc_insertion_point(field_mutable:pybullet_grpc.PyBulletCommand.configureOpenGLVisualizerCommand) + return commands_.configureopenglvisualizercommand_; +} +inline ::pybullet_grpc::ConfigureOpenGLVisualizerCommand* PyBulletCommand::release_configureopenglvisualizercommand() { + // @@protoc_insertion_point(field_release:pybullet_grpc.PyBulletCommand.configureOpenGLVisualizerCommand) + if (has_configureopenglvisualizercommand()) { + clear_has_commands(); + ::pybullet_grpc::ConfigureOpenGLVisualizerCommand* temp = commands_.configureopenglvisualizercommand_; + commands_.configureopenglvisualizercommand_ = NULL; + return temp; + } else { + return NULL; + } +} +inline void PyBulletCommand::set_allocated_configureopenglvisualizercommand(::pybullet_grpc::ConfigureOpenGLVisualizerCommand* configureopenglvisualizercommand) { + clear_commands(); + if (configureopenglvisualizercommand) { + set_has_configureopenglvisualizercommand(); + commands_.configureopenglvisualizercommand_ = configureopenglvisualizercommand; + } + // @@protoc_insertion_point(field_set_allocated:pybullet_grpc.PyBulletCommand.configureOpenGLVisualizerCommand) +} + +// .pybullet_grpc.SyncBodiesCommand syncBodiesCommand = 14; +inline bool PyBulletCommand::has_syncbodiescommand() const { + return commands_case() == kSyncBodiesCommand; +} +inline void PyBulletCommand::set_has_syncbodiescommand() { + _oneof_case_[0] = kSyncBodiesCommand; +} +inline void PyBulletCommand::clear_syncbodiescommand() { + if (has_syncbodiescommand()) { + delete commands_.syncbodiescommand_; + clear_has_commands(); + } +} +inline const ::pybullet_grpc::SyncBodiesCommand& PyBulletCommand::syncbodiescommand() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.PyBulletCommand.syncBodiesCommand) + return has_syncbodiescommand() + ? *commands_.syncbodiescommand_ + : ::pybullet_grpc::SyncBodiesCommand::default_instance(); +} +inline ::pybullet_grpc::SyncBodiesCommand* PyBulletCommand::mutable_syncbodiescommand() { + if (!has_syncbodiescommand()) { + clear_commands(); + set_has_syncbodiescommand(); + commands_.syncbodiescommand_ = new ::pybullet_grpc::SyncBodiesCommand; + } + // @@protoc_insertion_point(field_mutable:pybullet_grpc.PyBulletCommand.syncBodiesCommand) + return commands_.syncbodiescommand_; +} +inline ::pybullet_grpc::SyncBodiesCommand* PyBulletCommand::release_syncbodiescommand() { + // @@protoc_insertion_point(field_release:pybullet_grpc.PyBulletCommand.syncBodiesCommand) + if (has_syncbodiescommand()) { + clear_has_commands(); + ::pybullet_grpc::SyncBodiesCommand* temp = commands_.syncbodiescommand_; + commands_.syncbodiescommand_ = NULL; + return temp; + } else { + return NULL; + } +} +inline void PyBulletCommand::set_allocated_syncbodiescommand(::pybullet_grpc::SyncBodiesCommand* syncbodiescommand) { + clear_commands(); + if (syncbodiescommand) { + set_has_syncbodiescommand(); + commands_.syncbodiescommand_ = syncbodiescommand; + } + // @@protoc_insertion_point(field_set_allocated:pybullet_grpc.PyBulletCommand.syncBodiesCommand) +} + +// .pybullet_grpc.RequestBodyInfoCommand requestBodyInfoCommand = 15; +inline bool PyBulletCommand::has_requestbodyinfocommand() const { + return commands_case() == kRequestBodyInfoCommand; +} +inline void PyBulletCommand::set_has_requestbodyinfocommand() { + _oneof_case_[0] = kRequestBodyInfoCommand; +} +inline void PyBulletCommand::clear_requestbodyinfocommand() { + if (has_requestbodyinfocommand()) { + delete commands_.requestbodyinfocommand_; + clear_has_commands(); + } +} +inline const ::pybullet_grpc::RequestBodyInfoCommand& PyBulletCommand::requestbodyinfocommand() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.PyBulletCommand.requestBodyInfoCommand) + return has_requestbodyinfocommand() + ? *commands_.requestbodyinfocommand_ + : ::pybullet_grpc::RequestBodyInfoCommand::default_instance(); +} +inline ::pybullet_grpc::RequestBodyInfoCommand* PyBulletCommand::mutable_requestbodyinfocommand() { + if (!has_requestbodyinfocommand()) { + clear_commands(); + set_has_requestbodyinfocommand(); + commands_.requestbodyinfocommand_ = new ::pybullet_grpc::RequestBodyInfoCommand; + } + // @@protoc_insertion_point(field_mutable:pybullet_grpc.PyBulletCommand.requestBodyInfoCommand) + return commands_.requestbodyinfocommand_; +} +inline ::pybullet_grpc::RequestBodyInfoCommand* PyBulletCommand::release_requestbodyinfocommand() { + // @@protoc_insertion_point(field_release:pybullet_grpc.PyBulletCommand.requestBodyInfoCommand) + if (has_requestbodyinfocommand()) { + clear_has_commands(); + ::pybullet_grpc::RequestBodyInfoCommand* temp = commands_.requestbodyinfocommand_; + commands_.requestbodyinfocommand_ = NULL; + return temp; + } else { + return NULL; + } +} +inline void PyBulletCommand::set_allocated_requestbodyinfocommand(::pybullet_grpc::RequestBodyInfoCommand* requestbodyinfocommand) { + clear_commands(); + if (requestbodyinfocommand) { + set_has_requestbodyinfocommand(); + commands_.requestbodyinfocommand_ = requestbodyinfocommand; + } + // @@protoc_insertion_point(field_set_allocated:pybullet_grpc.PyBulletCommand.requestBodyInfoCommand) +} + +// .pybullet_grpc.PhysicsSimulationParametersCommand setPhysicsSimulationParametersCommand = 16; +inline bool PyBulletCommand::has_setphysicssimulationparameterscommand() const { + return commands_case() == kSetPhysicsSimulationParametersCommand; +} +inline void PyBulletCommand::set_has_setphysicssimulationparameterscommand() { + _oneof_case_[0] = kSetPhysicsSimulationParametersCommand; +} +inline void PyBulletCommand::clear_setphysicssimulationparameterscommand() { + if (has_setphysicssimulationparameterscommand()) { + delete commands_.setphysicssimulationparameterscommand_; + clear_has_commands(); + } +} +inline const ::pybullet_grpc::PhysicsSimulationParametersCommand& PyBulletCommand::setphysicssimulationparameterscommand() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.PyBulletCommand.setPhysicsSimulationParametersCommand) + return has_setphysicssimulationparameterscommand() + ? *commands_.setphysicssimulationparameterscommand_ + : ::pybullet_grpc::PhysicsSimulationParametersCommand::default_instance(); +} +inline ::pybullet_grpc::PhysicsSimulationParametersCommand* PyBulletCommand::mutable_setphysicssimulationparameterscommand() { + if (!has_setphysicssimulationparameterscommand()) { + clear_commands(); + set_has_setphysicssimulationparameterscommand(); + commands_.setphysicssimulationparameterscommand_ = new ::pybullet_grpc::PhysicsSimulationParametersCommand; + } + // @@protoc_insertion_point(field_mutable:pybullet_grpc.PyBulletCommand.setPhysicsSimulationParametersCommand) + return commands_.setphysicssimulationparameterscommand_; +} +inline ::pybullet_grpc::PhysicsSimulationParametersCommand* PyBulletCommand::release_setphysicssimulationparameterscommand() { + // @@protoc_insertion_point(field_release:pybullet_grpc.PyBulletCommand.setPhysicsSimulationParametersCommand) + if (has_setphysicssimulationparameterscommand()) { + clear_has_commands(); + ::pybullet_grpc::PhysicsSimulationParametersCommand* temp = commands_.setphysicssimulationparameterscommand_; + commands_.setphysicssimulationparameterscommand_ = NULL; + return temp; + } else { + return NULL; + } +} +inline void PyBulletCommand::set_allocated_setphysicssimulationparameterscommand(::pybullet_grpc::PhysicsSimulationParametersCommand* setphysicssimulationparameterscommand) { + clear_commands(); + if (setphysicssimulationparameterscommand) { + set_has_setphysicssimulationparameterscommand(); + commands_.setphysicssimulationparameterscommand_ = setphysicssimulationparameterscommand; + } + // @@protoc_insertion_point(field_set_allocated:pybullet_grpc.PyBulletCommand.setPhysicsSimulationParametersCommand) +} + +// .pybullet_grpc.JointMotorControlCommand jointMotorControlCommand = 17; +inline bool PyBulletCommand::has_jointmotorcontrolcommand() const { + return commands_case() == kJointMotorControlCommand; +} +inline void PyBulletCommand::set_has_jointmotorcontrolcommand() { + _oneof_case_[0] = kJointMotorControlCommand; +} +inline void PyBulletCommand::clear_jointmotorcontrolcommand() { + if (has_jointmotorcontrolcommand()) { + delete commands_.jointmotorcontrolcommand_; + clear_has_commands(); + } +} +inline const ::pybullet_grpc::JointMotorControlCommand& PyBulletCommand::jointmotorcontrolcommand() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.PyBulletCommand.jointMotorControlCommand) + return has_jointmotorcontrolcommand() + ? *commands_.jointmotorcontrolcommand_ + : ::pybullet_grpc::JointMotorControlCommand::default_instance(); +} +inline ::pybullet_grpc::JointMotorControlCommand* PyBulletCommand::mutable_jointmotorcontrolcommand() { + if (!has_jointmotorcontrolcommand()) { + clear_commands(); + set_has_jointmotorcontrolcommand(); + commands_.jointmotorcontrolcommand_ = new ::pybullet_grpc::JointMotorControlCommand; + } + // @@protoc_insertion_point(field_mutable:pybullet_grpc.PyBulletCommand.jointMotorControlCommand) + return commands_.jointmotorcontrolcommand_; +} +inline ::pybullet_grpc::JointMotorControlCommand* PyBulletCommand::release_jointmotorcontrolcommand() { + // @@protoc_insertion_point(field_release:pybullet_grpc.PyBulletCommand.jointMotorControlCommand) + if (has_jointmotorcontrolcommand()) { + clear_has_commands(); + ::pybullet_grpc::JointMotorControlCommand* temp = commands_.jointmotorcontrolcommand_; + commands_.jointmotorcontrolcommand_ = NULL; + return temp; + } else { + return NULL; + } +} +inline void PyBulletCommand::set_allocated_jointmotorcontrolcommand(::pybullet_grpc::JointMotorControlCommand* jointmotorcontrolcommand) { + clear_commands(); + if (jointmotorcontrolcommand) { + set_has_jointmotorcontrolcommand(); + commands_.jointmotorcontrolcommand_ = jointmotorcontrolcommand; + } + // @@protoc_insertion_point(field_set_allocated:pybullet_grpc.PyBulletCommand.jointMotorControlCommand) +} + +// .pybullet_grpc.UserConstraintCommand userConstraintCommand = 18; +inline bool PyBulletCommand::has_userconstraintcommand() const { + return commands_case() == kUserConstraintCommand; +} +inline void PyBulletCommand::set_has_userconstraintcommand() { + _oneof_case_[0] = kUserConstraintCommand; +} +inline void PyBulletCommand::clear_userconstraintcommand() { + if (has_userconstraintcommand()) { + delete commands_.userconstraintcommand_; + clear_has_commands(); + } +} +inline const ::pybullet_grpc::UserConstraintCommand& PyBulletCommand::userconstraintcommand() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.PyBulletCommand.userConstraintCommand) + return has_userconstraintcommand() + ? *commands_.userconstraintcommand_ + : ::pybullet_grpc::UserConstraintCommand::default_instance(); +} +inline ::pybullet_grpc::UserConstraintCommand* PyBulletCommand::mutable_userconstraintcommand() { + if (!has_userconstraintcommand()) { + clear_commands(); + set_has_userconstraintcommand(); + commands_.userconstraintcommand_ = new ::pybullet_grpc::UserConstraintCommand; + } + // @@protoc_insertion_point(field_mutable:pybullet_grpc.PyBulletCommand.userConstraintCommand) + return commands_.userconstraintcommand_; +} +inline ::pybullet_grpc::UserConstraintCommand* PyBulletCommand::release_userconstraintcommand() { + // @@protoc_insertion_point(field_release:pybullet_grpc.PyBulletCommand.userConstraintCommand) + if (has_userconstraintcommand()) { + clear_has_commands(); + ::pybullet_grpc::UserConstraintCommand* temp = commands_.userconstraintcommand_; + commands_.userconstraintcommand_ = NULL; + return temp; + } else { + return NULL; + } +} +inline void PyBulletCommand::set_allocated_userconstraintcommand(::pybullet_grpc::UserConstraintCommand* userconstraintcommand) { + clear_commands(); + if (userconstraintcommand) { + set_has_userconstraintcommand(); + commands_.userconstraintcommand_ = userconstraintcommand; + } + // @@protoc_insertion_point(field_set_allocated:pybullet_grpc.PyBulletCommand.userConstraintCommand) +} + +// .pybullet_grpc.CheckVersionCommand checkVersionCommand = 19; +inline bool PyBulletCommand::has_checkversioncommand() const { + return commands_case() == kCheckVersionCommand; +} +inline void PyBulletCommand::set_has_checkversioncommand() { + _oneof_case_[0] = kCheckVersionCommand; +} +inline void PyBulletCommand::clear_checkversioncommand() { + if (has_checkversioncommand()) { + delete commands_.checkversioncommand_; + clear_has_commands(); + } +} +inline const ::pybullet_grpc::CheckVersionCommand& PyBulletCommand::checkversioncommand() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.PyBulletCommand.checkVersionCommand) + return has_checkversioncommand() + ? *commands_.checkversioncommand_ + : ::pybullet_grpc::CheckVersionCommand::default_instance(); +} +inline ::pybullet_grpc::CheckVersionCommand* PyBulletCommand::mutable_checkversioncommand() { + if (!has_checkversioncommand()) { + clear_commands(); + set_has_checkversioncommand(); + commands_.checkversioncommand_ = new ::pybullet_grpc::CheckVersionCommand; + } + // @@protoc_insertion_point(field_mutable:pybullet_grpc.PyBulletCommand.checkVersionCommand) + return commands_.checkversioncommand_; +} +inline ::pybullet_grpc::CheckVersionCommand* PyBulletCommand::release_checkversioncommand() { + // @@protoc_insertion_point(field_release:pybullet_grpc.PyBulletCommand.checkVersionCommand) + if (has_checkversioncommand()) { + clear_has_commands(); + ::pybullet_grpc::CheckVersionCommand* temp = commands_.checkversioncommand_; + commands_.checkversioncommand_ = NULL; + return temp; + } else { + return NULL; + } +} +inline void PyBulletCommand::set_allocated_checkversioncommand(::pybullet_grpc::CheckVersionCommand* checkversioncommand) { + clear_commands(); + if (checkversioncommand) { + set_has_checkversioncommand(); + commands_.checkversioncommand_ = checkversioncommand; + } + // @@protoc_insertion_point(field_set_allocated:pybullet_grpc.PyBulletCommand.checkVersionCommand) +} + +// .pybullet_grpc.RequestKeyboardEventsCommand requestKeyboardEventsCommand = 20; +inline bool PyBulletCommand::has_requestkeyboardeventscommand() const { + return commands_case() == kRequestKeyboardEventsCommand; +} +inline void PyBulletCommand::set_has_requestkeyboardeventscommand() { + _oneof_case_[0] = kRequestKeyboardEventsCommand; +} +inline void PyBulletCommand::clear_requestkeyboardeventscommand() { + if (has_requestkeyboardeventscommand()) { + delete commands_.requestkeyboardeventscommand_; + clear_has_commands(); + } +} +inline const ::pybullet_grpc::RequestKeyboardEventsCommand& PyBulletCommand::requestkeyboardeventscommand() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.PyBulletCommand.requestKeyboardEventsCommand) + return has_requestkeyboardeventscommand() + ? *commands_.requestkeyboardeventscommand_ + : ::pybullet_grpc::RequestKeyboardEventsCommand::default_instance(); +} +inline ::pybullet_grpc::RequestKeyboardEventsCommand* PyBulletCommand::mutable_requestkeyboardeventscommand() { + if (!has_requestkeyboardeventscommand()) { + clear_commands(); + set_has_requestkeyboardeventscommand(); + commands_.requestkeyboardeventscommand_ = new ::pybullet_grpc::RequestKeyboardEventsCommand; + } + // @@protoc_insertion_point(field_mutable:pybullet_grpc.PyBulletCommand.requestKeyboardEventsCommand) + return commands_.requestkeyboardeventscommand_; +} +inline ::pybullet_grpc::RequestKeyboardEventsCommand* PyBulletCommand::release_requestkeyboardeventscommand() { + // @@protoc_insertion_point(field_release:pybullet_grpc.PyBulletCommand.requestKeyboardEventsCommand) + if (has_requestkeyboardeventscommand()) { + clear_has_commands(); + ::pybullet_grpc::RequestKeyboardEventsCommand* temp = commands_.requestkeyboardeventscommand_; + commands_.requestkeyboardeventscommand_ = NULL; + return temp; + } else { + return NULL; + } +} +inline void PyBulletCommand::set_allocated_requestkeyboardeventscommand(::pybullet_grpc::RequestKeyboardEventsCommand* requestkeyboardeventscommand) { + clear_commands(); + if (requestkeyboardeventscommand) { + set_has_requestkeyboardeventscommand(); + commands_.requestkeyboardeventscommand_ = requestkeyboardeventscommand; + } + // @@protoc_insertion_point(field_set_allocated:pybullet_grpc.PyBulletCommand.requestKeyboardEventsCommand) +} + +// .pybullet_grpc.RequestCameraImageCommand requestCameraImageCommand = 21; +inline bool PyBulletCommand::has_requestcameraimagecommand() const { + return commands_case() == kRequestCameraImageCommand; +} +inline void PyBulletCommand::set_has_requestcameraimagecommand() { + _oneof_case_[0] = kRequestCameraImageCommand; +} +inline void PyBulletCommand::clear_requestcameraimagecommand() { + if (has_requestcameraimagecommand()) { + delete commands_.requestcameraimagecommand_; + clear_has_commands(); + } +} +inline const ::pybullet_grpc::RequestCameraImageCommand& PyBulletCommand::requestcameraimagecommand() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.PyBulletCommand.requestCameraImageCommand) + return has_requestcameraimagecommand() + ? *commands_.requestcameraimagecommand_ + : ::pybullet_grpc::RequestCameraImageCommand::default_instance(); +} +inline ::pybullet_grpc::RequestCameraImageCommand* PyBulletCommand::mutable_requestcameraimagecommand() { + if (!has_requestcameraimagecommand()) { + clear_commands(); + set_has_requestcameraimagecommand(); + commands_.requestcameraimagecommand_ = new ::pybullet_grpc::RequestCameraImageCommand; + } + // @@protoc_insertion_point(field_mutable:pybullet_grpc.PyBulletCommand.requestCameraImageCommand) + return commands_.requestcameraimagecommand_; +} +inline ::pybullet_grpc::RequestCameraImageCommand* PyBulletCommand::release_requestcameraimagecommand() { + // @@protoc_insertion_point(field_release:pybullet_grpc.PyBulletCommand.requestCameraImageCommand) + if (has_requestcameraimagecommand()) { + clear_has_commands(); + ::pybullet_grpc::RequestCameraImageCommand* temp = commands_.requestcameraimagecommand_; + commands_.requestcameraimagecommand_ = NULL; + return temp; + } else { + return NULL; + } +} +inline void PyBulletCommand::set_allocated_requestcameraimagecommand(::pybullet_grpc::RequestCameraImageCommand* requestcameraimagecommand) { + clear_commands(); + if (requestcameraimagecommand) { + set_has_requestcameraimagecommand(); + commands_.requestcameraimagecommand_ = requestcameraimagecommand; + } + // @@protoc_insertion_point(field_set_allocated:pybullet_grpc.PyBulletCommand.requestCameraImageCommand) +} + inline bool PyBulletCommand::has_commands() const { return commands_case() != COMMANDS_NOT_SET; } @@ -5191,7 +10812,117 @@ inline void PyBulletStatus::set_statustype(::google::protobuf::int32 value) { // @@protoc_insertion_point(field_set:pybullet_grpc.PyBulletStatus.statusType) } -// .pybullet_grpc.LoadUrdfStatus urdfStatus = 2; +// repeated bytes binaryBlob = 2; +inline int PyBulletStatus::binaryblob_size() const { + return binaryblob_.size(); +} +inline void PyBulletStatus::clear_binaryblob() { + binaryblob_.Clear(); +} +inline const ::std::string& PyBulletStatus::binaryblob(int index) const { + // @@protoc_insertion_point(field_get:pybullet_grpc.PyBulletStatus.binaryBlob) + return binaryblob_.Get(index); +} +inline ::std::string* PyBulletStatus::mutable_binaryblob(int index) { + // @@protoc_insertion_point(field_mutable:pybullet_grpc.PyBulletStatus.binaryBlob) + return binaryblob_.Mutable(index); +} +inline void PyBulletStatus::set_binaryblob(int index, const ::std::string& value) { + // @@protoc_insertion_point(field_set:pybullet_grpc.PyBulletStatus.binaryBlob) + binaryblob_.Mutable(index)->assign(value); +} +inline void PyBulletStatus::set_binaryblob(int index, const char* value) { + binaryblob_.Mutable(index)->assign(value); + // @@protoc_insertion_point(field_set_char:pybullet_grpc.PyBulletStatus.binaryBlob) +} +inline void PyBulletStatus::set_binaryblob(int index, const void* value, size_t size) { + binaryblob_.Mutable(index)->assign( + reinterpret_cast(value), size); + // @@protoc_insertion_point(field_set_pointer:pybullet_grpc.PyBulletStatus.binaryBlob) +} +inline ::std::string* PyBulletStatus::add_binaryblob() { + // @@protoc_insertion_point(field_add_mutable:pybullet_grpc.PyBulletStatus.binaryBlob) + return binaryblob_.Add(); +} +inline void PyBulletStatus::add_binaryblob(const ::std::string& value) { + binaryblob_.Add()->assign(value); + // @@protoc_insertion_point(field_add:pybullet_grpc.PyBulletStatus.binaryBlob) +} +inline void PyBulletStatus::add_binaryblob(const char* value) { + binaryblob_.Add()->assign(value); + // @@protoc_insertion_point(field_add_char:pybullet_grpc.PyBulletStatus.binaryBlob) +} +inline void PyBulletStatus::add_binaryblob(const void* value, size_t size) { + binaryblob_.Add()->assign(reinterpret_cast(value), size); + // @@protoc_insertion_point(field_add_pointer:pybullet_grpc.PyBulletStatus.binaryBlob) +} +inline const ::google::protobuf::RepeatedPtrField< ::std::string>& +PyBulletStatus::binaryblob() const { + // @@protoc_insertion_point(field_list:pybullet_grpc.PyBulletStatus.binaryBlob) + return binaryblob_; +} +inline ::google::protobuf::RepeatedPtrField< ::std::string>* +PyBulletStatus::mutable_binaryblob() { + // @@protoc_insertion_point(field_mutable_list:pybullet_grpc.PyBulletStatus.binaryBlob) + return &binaryblob_; +} + +// repeated bytes unknownStatusBinaryBlob = 3; +inline int PyBulletStatus::unknownstatusbinaryblob_size() const { + return unknownstatusbinaryblob_.size(); +} +inline void PyBulletStatus::clear_unknownstatusbinaryblob() { + unknownstatusbinaryblob_.Clear(); +} +inline const ::std::string& PyBulletStatus::unknownstatusbinaryblob(int index) const { + // @@protoc_insertion_point(field_get:pybullet_grpc.PyBulletStatus.unknownStatusBinaryBlob) + return unknownstatusbinaryblob_.Get(index); +} +inline ::std::string* PyBulletStatus::mutable_unknownstatusbinaryblob(int index) { + // @@protoc_insertion_point(field_mutable:pybullet_grpc.PyBulletStatus.unknownStatusBinaryBlob) + return unknownstatusbinaryblob_.Mutable(index); +} +inline void PyBulletStatus::set_unknownstatusbinaryblob(int index, const ::std::string& value) { + // @@protoc_insertion_point(field_set:pybullet_grpc.PyBulletStatus.unknownStatusBinaryBlob) + unknownstatusbinaryblob_.Mutable(index)->assign(value); +} +inline void PyBulletStatus::set_unknownstatusbinaryblob(int index, const char* value) { + unknownstatusbinaryblob_.Mutable(index)->assign(value); + // @@protoc_insertion_point(field_set_char:pybullet_grpc.PyBulletStatus.unknownStatusBinaryBlob) +} +inline void PyBulletStatus::set_unknownstatusbinaryblob(int index, const void* value, size_t size) { + unknownstatusbinaryblob_.Mutable(index)->assign( + reinterpret_cast(value), size); + // @@protoc_insertion_point(field_set_pointer:pybullet_grpc.PyBulletStatus.unknownStatusBinaryBlob) +} +inline ::std::string* PyBulletStatus::add_unknownstatusbinaryblob() { + // @@protoc_insertion_point(field_add_mutable:pybullet_grpc.PyBulletStatus.unknownStatusBinaryBlob) + return unknownstatusbinaryblob_.Add(); +} +inline void PyBulletStatus::add_unknownstatusbinaryblob(const ::std::string& value) { + unknownstatusbinaryblob_.Add()->assign(value); + // @@protoc_insertion_point(field_add:pybullet_grpc.PyBulletStatus.unknownStatusBinaryBlob) +} +inline void PyBulletStatus::add_unknownstatusbinaryblob(const char* value) { + unknownstatusbinaryblob_.Add()->assign(value); + // @@protoc_insertion_point(field_add_char:pybullet_grpc.PyBulletStatus.unknownStatusBinaryBlob) +} +inline void PyBulletStatus::add_unknownstatusbinaryblob(const void* value, size_t size) { + unknownstatusbinaryblob_.Add()->assign(reinterpret_cast(value), size); + // @@protoc_insertion_point(field_add_pointer:pybullet_grpc.PyBulletStatus.unknownStatusBinaryBlob) +} +inline const ::google::protobuf::RepeatedPtrField< ::std::string>& +PyBulletStatus::unknownstatusbinaryblob() const { + // @@protoc_insertion_point(field_list:pybullet_grpc.PyBulletStatus.unknownStatusBinaryBlob) + return unknownstatusbinaryblob_; +} +inline ::google::protobuf::RepeatedPtrField< ::std::string>* +PyBulletStatus::mutable_unknownstatusbinaryblob() { + // @@protoc_insertion_point(field_mutable_list:pybullet_grpc.PyBulletStatus.unknownStatusBinaryBlob) + return &unknownstatusbinaryblob_; +} + +// .pybullet_grpc.LoadUrdfStatus urdfStatus = 4; inline bool PyBulletStatus::has_urdfstatus() const { return status_case() == kUrdfStatus; } @@ -5239,7 +10970,7 @@ inline void PyBulletStatus::set_allocated_urdfstatus(::pybullet_grpc::LoadUrdfSt // @@protoc_insertion_point(field_set_allocated:pybullet_grpc.PyBulletStatus.urdfStatus) } -// .pybullet_grpc.SdfLoadedStatus sdfStatus = 3; +// .pybullet_grpc.SdfLoadedStatus sdfStatus = 5; inline bool PyBulletStatus::has_sdfstatus() const { return status_case() == kSdfStatus; } @@ -5287,7 +11018,7 @@ inline void PyBulletStatus::set_allocated_sdfstatus(::pybullet_grpc::SdfLoadedSt // @@protoc_insertion_point(field_set_allocated:pybullet_grpc.PyBulletStatus.sdfStatus) } -// .pybullet_grpc.MjcfLoadedStatus mjcfStatus = 4; +// .pybullet_grpc.MjcfLoadedStatus mjcfStatus = 6; inline bool PyBulletStatus::has_mjcfstatus() const { return status_case() == kMjcfStatus; } @@ -5335,7 +11066,7 @@ inline void PyBulletStatus::set_allocated_mjcfstatus(::pybullet_grpc::MjcfLoaded // @@protoc_insertion_point(field_set_allocated:pybullet_grpc.PyBulletStatus.mjcfStatus) } -// .pybullet_grpc.GetDynamicsStatus getDynamicsStatus = 5; +// .pybullet_grpc.GetDynamicsStatus getDynamicsStatus = 7; inline bool PyBulletStatus::has_getdynamicsstatus() const { return status_case() == kGetDynamicsStatus; } @@ -5383,7 +11114,7 @@ inline void PyBulletStatus::set_allocated_getdynamicsstatus(::pybullet_grpc::Get // @@protoc_insertion_point(field_set_allocated:pybullet_grpc.PyBulletStatus.getDynamicsStatus) } -// .pybullet_grpc.SendActualStateStatus actualStateStatus = 6; +// .pybullet_grpc.SendActualStateStatus actualStateStatus = 8; inline bool PyBulletStatus::has_actualstatestatus() const { return status_case() == kActualStateStatus; } @@ -5431,6 +11162,390 @@ inline void PyBulletStatus::set_allocated_actualstatestatus(::pybullet_grpc::Sen // @@protoc_insertion_point(field_set_allocated:pybullet_grpc.PyBulletStatus.actualStateStatus) } +// .pybullet_grpc.SyncBodiesStatus syncBodiesStatus = 9; +inline bool PyBulletStatus::has_syncbodiesstatus() const { + return status_case() == kSyncBodiesStatus; +} +inline void PyBulletStatus::set_has_syncbodiesstatus() { + _oneof_case_[0] = kSyncBodiesStatus; +} +inline void PyBulletStatus::clear_syncbodiesstatus() { + if (has_syncbodiesstatus()) { + delete status_.syncbodiesstatus_; + clear_has_status(); + } +} +inline const ::pybullet_grpc::SyncBodiesStatus& PyBulletStatus::syncbodiesstatus() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.PyBulletStatus.syncBodiesStatus) + return has_syncbodiesstatus() + ? *status_.syncbodiesstatus_ + : ::pybullet_grpc::SyncBodiesStatus::default_instance(); +} +inline ::pybullet_grpc::SyncBodiesStatus* PyBulletStatus::mutable_syncbodiesstatus() { + if (!has_syncbodiesstatus()) { + clear_status(); + set_has_syncbodiesstatus(); + status_.syncbodiesstatus_ = new ::pybullet_grpc::SyncBodiesStatus; + } + // @@protoc_insertion_point(field_mutable:pybullet_grpc.PyBulletStatus.syncBodiesStatus) + return status_.syncbodiesstatus_; +} +inline ::pybullet_grpc::SyncBodiesStatus* PyBulletStatus::release_syncbodiesstatus() { + // @@protoc_insertion_point(field_release:pybullet_grpc.PyBulletStatus.syncBodiesStatus) + if (has_syncbodiesstatus()) { + clear_has_status(); + ::pybullet_grpc::SyncBodiesStatus* temp = status_.syncbodiesstatus_; + status_.syncbodiesstatus_ = NULL; + return temp; + } else { + return NULL; + } +} +inline void PyBulletStatus::set_allocated_syncbodiesstatus(::pybullet_grpc::SyncBodiesStatus* syncbodiesstatus) { + clear_status(); + if (syncbodiesstatus) { + set_has_syncbodiesstatus(); + status_.syncbodiesstatus_ = syncbodiesstatus; + } + // @@protoc_insertion_point(field_set_allocated:pybullet_grpc.PyBulletStatus.syncBodiesStatus) +} + +// .pybullet_grpc.RequestBodyInfoStatus requestBodyInfoStatus = 10; +inline bool PyBulletStatus::has_requestbodyinfostatus() const { + return status_case() == kRequestBodyInfoStatus; +} +inline void PyBulletStatus::set_has_requestbodyinfostatus() { + _oneof_case_[0] = kRequestBodyInfoStatus; +} +inline void PyBulletStatus::clear_requestbodyinfostatus() { + if (has_requestbodyinfostatus()) { + delete status_.requestbodyinfostatus_; + clear_has_status(); + } +} +inline const ::pybullet_grpc::RequestBodyInfoStatus& PyBulletStatus::requestbodyinfostatus() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.PyBulletStatus.requestBodyInfoStatus) + return has_requestbodyinfostatus() + ? *status_.requestbodyinfostatus_ + : ::pybullet_grpc::RequestBodyInfoStatus::default_instance(); +} +inline ::pybullet_grpc::RequestBodyInfoStatus* PyBulletStatus::mutable_requestbodyinfostatus() { + if (!has_requestbodyinfostatus()) { + clear_status(); + set_has_requestbodyinfostatus(); + status_.requestbodyinfostatus_ = new ::pybullet_grpc::RequestBodyInfoStatus; + } + // @@protoc_insertion_point(field_mutable:pybullet_grpc.PyBulletStatus.requestBodyInfoStatus) + return status_.requestbodyinfostatus_; +} +inline ::pybullet_grpc::RequestBodyInfoStatus* PyBulletStatus::release_requestbodyinfostatus() { + // @@protoc_insertion_point(field_release:pybullet_grpc.PyBulletStatus.requestBodyInfoStatus) + if (has_requestbodyinfostatus()) { + clear_has_status(); + ::pybullet_grpc::RequestBodyInfoStatus* temp = status_.requestbodyinfostatus_; + status_.requestbodyinfostatus_ = NULL; + return temp; + } else { + return NULL; + } +} +inline void PyBulletStatus::set_allocated_requestbodyinfostatus(::pybullet_grpc::RequestBodyInfoStatus* requestbodyinfostatus) { + clear_status(); + if (requestbodyinfostatus) { + set_has_requestbodyinfostatus(); + status_.requestbodyinfostatus_ = requestbodyinfostatus; + } + // @@protoc_insertion_point(field_set_allocated:pybullet_grpc.PyBulletStatus.requestBodyInfoStatus) +} + +// .pybullet_grpc.PhysicsSimulationParameters requestPhysicsSimulationParametersStatus = 11; +inline bool PyBulletStatus::has_requestphysicssimulationparametersstatus() const { + return status_case() == kRequestPhysicsSimulationParametersStatus; +} +inline void PyBulletStatus::set_has_requestphysicssimulationparametersstatus() { + _oneof_case_[0] = kRequestPhysicsSimulationParametersStatus; +} +inline void PyBulletStatus::clear_requestphysicssimulationparametersstatus() { + if (has_requestphysicssimulationparametersstatus()) { + delete status_.requestphysicssimulationparametersstatus_; + clear_has_status(); + } +} +inline const ::pybullet_grpc::PhysicsSimulationParameters& PyBulletStatus::requestphysicssimulationparametersstatus() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.PyBulletStatus.requestPhysicsSimulationParametersStatus) + return has_requestphysicssimulationparametersstatus() + ? *status_.requestphysicssimulationparametersstatus_ + : ::pybullet_grpc::PhysicsSimulationParameters::default_instance(); +} +inline ::pybullet_grpc::PhysicsSimulationParameters* PyBulletStatus::mutable_requestphysicssimulationparametersstatus() { + if (!has_requestphysicssimulationparametersstatus()) { + clear_status(); + set_has_requestphysicssimulationparametersstatus(); + status_.requestphysicssimulationparametersstatus_ = new ::pybullet_grpc::PhysicsSimulationParameters; + } + // @@protoc_insertion_point(field_mutable:pybullet_grpc.PyBulletStatus.requestPhysicsSimulationParametersStatus) + return status_.requestphysicssimulationparametersstatus_; +} +inline ::pybullet_grpc::PhysicsSimulationParameters* PyBulletStatus::release_requestphysicssimulationparametersstatus() { + // @@protoc_insertion_point(field_release:pybullet_grpc.PyBulletStatus.requestPhysicsSimulationParametersStatus) + if (has_requestphysicssimulationparametersstatus()) { + clear_has_status(); + ::pybullet_grpc::PhysicsSimulationParameters* temp = status_.requestphysicssimulationparametersstatus_; + status_.requestphysicssimulationparametersstatus_ = NULL; + return temp; + } else { + return NULL; + } +} +inline void PyBulletStatus::set_allocated_requestphysicssimulationparametersstatus(::pybullet_grpc::PhysicsSimulationParameters* requestphysicssimulationparametersstatus) { + clear_status(); + if (requestphysicssimulationparametersstatus) { + set_has_requestphysicssimulationparametersstatus(); + status_.requestphysicssimulationparametersstatus_ = requestphysicssimulationparametersstatus; + } + // @@protoc_insertion_point(field_set_allocated:pybullet_grpc.PyBulletStatus.requestPhysicsSimulationParametersStatus) +} + +// .pybullet_grpc.CheckVersionStatus checkVersionStatus = 12; +inline bool PyBulletStatus::has_checkversionstatus() const { + return status_case() == kCheckVersionStatus; +} +inline void PyBulletStatus::set_has_checkversionstatus() { + _oneof_case_[0] = kCheckVersionStatus; +} +inline void PyBulletStatus::clear_checkversionstatus() { + if (has_checkversionstatus()) { + delete status_.checkversionstatus_; + clear_has_status(); + } +} +inline const ::pybullet_grpc::CheckVersionStatus& PyBulletStatus::checkversionstatus() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.PyBulletStatus.checkVersionStatus) + return has_checkversionstatus() + ? *status_.checkversionstatus_ + : ::pybullet_grpc::CheckVersionStatus::default_instance(); +} +inline ::pybullet_grpc::CheckVersionStatus* PyBulletStatus::mutable_checkversionstatus() { + if (!has_checkversionstatus()) { + clear_status(); + set_has_checkversionstatus(); + status_.checkversionstatus_ = new ::pybullet_grpc::CheckVersionStatus; + } + // @@protoc_insertion_point(field_mutable:pybullet_grpc.PyBulletStatus.checkVersionStatus) + return status_.checkversionstatus_; +} +inline ::pybullet_grpc::CheckVersionStatus* PyBulletStatus::release_checkversionstatus() { + // @@protoc_insertion_point(field_release:pybullet_grpc.PyBulletStatus.checkVersionStatus) + if (has_checkversionstatus()) { + clear_has_status(); + ::pybullet_grpc::CheckVersionStatus* temp = status_.checkversionstatus_; + status_.checkversionstatus_ = NULL; + return temp; + } else { + return NULL; + } +} +inline void PyBulletStatus::set_allocated_checkversionstatus(::pybullet_grpc::CheckVersionStatus* checkversionstatus) { + clear_status(); + if (checkversionstatus) { + set_has_checkversionstatus(); + status_.checkversionstatus_ = checkversionstatus; + } + // @@protoc_insertion_point(field_set_allocated:pybullet_grpc.PyBulletStatus.checkVersionStatus) +} + +// .pybullet_grpc.UserConstraintStatus userConstraintStatus = 13; +inline bool PyBulletStatus::has_userconstraintstatus() const { + return status_case() == kUserConstraintStatus; +} +inline void PyBulletStatus::set_has_userconstraintstatus() { + _oneof_case_[0] = kUserConstraintStatus; +} +inline void PyBulletStatus::clear_userconstraintstatus() { + if (has_userconstraintstatus()) { + delete status_.userconstraintstatus_; + clear_has_status(); + } +} +inline const ::pybullet_grpc::UserConstraintStatus& PyBulletStatus::userconstraintstatus() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.PyBulletStatus.userConstraintStatus) + return has_userconstraintstatus() + ? *status_.userconstraintstatus_ + : ::pybullet_grpc::UserConstraintStatus::default_instance(); +} +inline ::pybullet_grpc::UserConstraintStatus* PyBulletStatus::mutable_userconstraintstatus() { + if (!has_userconstraintstatus()) { + clear_status(); + set_has_userconstraintstatus(); + status_.userconstraintstatus_ = new ::pybullet_grpc::UserConstraintStatus; + } + // @@protoc_insertion_point(field_mutable:pybullet_grpc.PyBulletStatus.userConstraintStatus) + return status_.userconstraintstatus_; +} +inline ::pybullet_grpc::UserConstraintStatus* PyBulletStatus::release_userconstraintstatus() { + // @@protoc_insertion_point(field_release:pybullet_grpc.PyBulletStatus.userConstraintStatus) + if (has_userconstraintstatus()) { + clear_has_status(); + ::pybullet_grpc::UserConstraintStatus* temp = status_.userconstraintstatus_; + status_.userconstraintstatus_ = NULL; + return temp; + } else { + return NULL; + } +} +inline void PyBulletStatus::set_allocated_userconstraintstatus(::pybullet_grpc::UserConstraintStatus* userconstraintstatus) { + clear_status(); + if (userconstraintstatus) { + set_has_userconstraintstatus(); + status_.userconstraintstatus_ = userconstraintstatus; + } + // @@protoc_insertion_point(field_set_allocated:pybullet_grpc.PyBulletStatus.userConstraintStatus) +} + +// .pybullet_grpc.UserConstraintStateStatus userConstraintStateStatus = 14; +inline bool PyBulletStatus::has_userconstraintstatestatus() const { + return status_case() == kUserConstraintStateStatus; +} +inline void PyBulletStatus::set_has_userconstraintstatestatus() { + _oneof_case_[0] = kUserConstraintStateStatus; +} +inline void PyBulletStatus::clear_userconstraintstatestatus() { + if (has_userconstraintstatestatus()) { + delete status_.userconstraintstatestatus_; + clear_has_status(); + } +} +inline const ::pybullet_grpc::UserConstraintStateStatus& PyBulletStatus::userconstraintstatestatus() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.PyBulletStatus.userConstraintStateStatus) + return has_userconstraintstatestatus() + ? *status_.userconstraintstatestatus_ + : ::pybullet_grpc::UserConstraintStateStatus::default_instance(); +} +inline ::pybullet_grpc::UserConstraintStateStatus* PyBulletStatus::mutable_userconstraintstatestatus() { + if (!has_userconstraintstatestatus()) { + clear_status(); + set_has_userconstraintstatestatus(); + status_.userconstraintstatestatus_ = new ::pybullet_grpc::UserConstraintStateStatus; + } + // @@protoc_insertion_point(field_mutable:pybullet_grpc.PyBulletStatus.userConstraintStateStatus) + return status_.userconstraintstatestatus_; +} +inline ::pybullet_grpc::UserConstraintStateStatus* PyBulletStatus::release_userconstraintstatestatus() { + // @@protoc_insertion_point(field_release:pybullet_grpc.PyBulletStatus.userConstraintStateStatus) + if (has_userconstraintstatestatus()) { + clear_has_status(); + ::pybullet_grpc::UserConstraintStateStatus* temp = status_.userconstraintstatestatus_; + status_.userconstraintstatestatus_ = NULL; + return temp; + } else { + return NULL; + } +} +inline void PyBulletStatus::set_allocated_userconstraintstatestatus(::pybullet_grpc::UserConstraintStateStatus* userconstraintstatestatus) { + clear_status(); + if (userconstraintstatestatus) { + set_has_userconstraintstatestatus(); + status_.userconstraintstatestatus_ = userconstraintstatestatus; + } + // @@protoc_insertion_point(field_set_allocated:pybullet_grpc.PyBulletStatus.userConstraintStateStatus) +} + +// .pybullet_grpc.KeyboardEventsStatus keyboardEventsStatus = 15; +inline bool PyBulletStatus::has_keyboardeventsstatus() const { + return status_case() == kKeyboardEventsStatus; +} +inline void PyBulletStatus::set_has_keyboardeventsstatus() { + _oneof_case_[0] = kKeyboardEventsStatus; +} +inline void PyBulletStatus::clear_keyboardeventsstatus() { + if (has_keyboardeventsstatus()) { + delete status_.keyboardeventsstatus_; + clear_has_status(); + } +} +inline const ::pybullet_grpc::KeyboardEventsStatus& PyBulletStatus::keyboardeventsstatus() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.PyBulletStatus.keyboardEventsStatus) + return has_keyboardeventsstatus() + ? *status_.keyboardeventsstatus_ + : ::pybullet_grpc::KeyboardEventsStatus::default_instance(); +} +inline ::pybullet_grpc::KeyboardEventsStatus* PyBulletStatus::mutable_keyboardeventsstatus() { + if (!has_keyboardeventsstatus()) { + clear_status(); + set_has_keyboardeventsstatus(); + status_.keyboardeventsstatus_ = new ::pybullet_grpc::KeyboardEventsStatus; + } + // @@protoc_insertion_point(field_mutable:pybullet_grpc.PyBulletStatus.keyboardEventsStatus) + return status_.keyboardeventsstatus_; +} +inline ::pybullet_grpc::KeyboardEventsStatus* PyBulletStatus::release_keyboardeventsstatus() { + // @@protoc_insertion_point(field_release:pybullet_grpc.PyBulletStatus.keyboardEventsStatus) + if (has_keyboardeventsstatus()) { + clear_has_status(); + ::pybullet_grpc::KeyboardEventsStatus* temp = status_.keyboardeventsstatus_; + status_.keyboardeventsstatus_ = NULL; + return temp; + } else { + return NULL; + } +} +inline void PyBulletStatus::set_allocated_keyboardeventsstatus(::pybullet_grpc::KeyboardEventsStatus* keyboardeventsstatus) { + clear_status(); + if (keyboardeventsstatus) { + set_has_keyboardeventsstatus(); + status_.keyboardeventsstatus_ = keyboardeventsstatus; + } + // @@protoc_insertion_point(field_set_allocated:pybullet_grpc.PyBulletStatus.keyboardEventsStatus) +} + +// .pybullet_grpc.RequestCameraImageStatus requestCameraImageStatus = 16; +inline bool PyBulletStatus::has_requestcameraimagestatus() const { + return status_case() == kRequestCameraImageStatus; +} +inline void PyBulletStatus::set_has_requestcameraimagestatus() { + _oneof_case_[0] = kRequestCameraImageStatus; +} +inline void PyBulletStatus::clear_requestcameraimagestatus() { + if (has_requestcameraimagestatus()) { + delete status_.requestcameraimagestatus_; + clear_has_status(); + } +} +inline const ::pybullet_grpc::RequestCameraImageStatus& PyBulletStatus::requestcameraimagestatus() const { + // @@protoc_insertion_point(field_get:pybullet_grpc.PyBulletStatus.requestCameraImageStatus) + return has_requestcameraimagestatus() + ? *status_.requestcameraimagestatus_ + : ::pybullet_grpc::RequestCameraImageStatus::default_instance(); +} +inline ::pybullet_grpc::RequestCameraImageStatus* PyBulletStatus::mutable_requestcameraimagestatus() { + if (!has_requestcameraimagestatus()) { + clear_status(); + set_has_requestcameraimagestatus(); + status_.requestcameraimagestatus_ = new ::pybullet_grpc::RequestCameraImageStatus; + } + // @@protoc_insertion_point(field_mutable:pybullet_grpc.PyBulletStatus.requestCameraImageStatus) + return status_.requestcameraimagestatus_; +} +inline ::pybullet_grpc::RequestCameraImageStatus* PyBulletStatus::release_requestcameraimagestatus() { + // @@protoc_insertion_point(field_release:pybullet_grpc.PyBulletStatus.requestCameraImageStatus) + if (has_requestcameraimagestatus()) { + clear_has_status(); + ::pybullet_grpc::RequestCameraImageStatus* temp = status_.requestcameraimagestatus_; + status_.requestcameraimagestatus_ = NULL; + return temp; + } else { + return NULL; + } +} +inline void PyBulletStatus::set_allocated_requestcameraimagestatus(::pybullet_grpc::RequestCameraImageStatus* requestcameraimagestatus) { + clear_status(); + if (requestcameraimagestatus) { + set_has_requestcameraimagestatus(); + status_.requestcameraimagestatus_ = requestcameraimagestatus; + } + // @@protoc_insertion_point(field_set_allocated:pybullet_grpc.PyBulletStatus.requestCameraImageStatus) +} + inline bool PyBulletStatus::has_status() const { return status_case() != STATUS_NOT_SET; } @@ -5475,6 +11590,48 @@ inline PyBulletStatus::StatusCase PyBulletStatus::status_case() const { // ------------------------------------------------------------------- +// ------------------------------------------------------------------- + +// ------------------------------------------------------------------- + +// ------------------------------------------------------------------- + +// ------------------------------------------------------------------- + +// ------------------------------------------------------------------- + +// ------------------------------------------------------------------- + +// ------------------------------------------------------------------- + +// ------------------------------------------------------------------- + +// ------------------------------------------------------------------- + +// ------------------------------------------------------------------- + +// ------------------------------------------------------------------- + +// ------------------------------------------------------------------- + +// ------------------------------------------------------------------- + +// ------------------------------------------------------------------- + +// ------------------------------------------------------------------- + +// ------------------------------------------------------------------- + +// ------------------------------------------------------------------- + +// ------------------------------------------------------------------- + +// ------------------------------------------------------------------- + +// ------------------------------------------------------------------- + +// ------------------------------------------------------------------- + // @@protoc_insertion_point(namespace_scope) diff --git a/examples/SharedMemory/grpc/pybullet_client.py b/examples/SharedMemory/grpc/pybullet_client.py index a042d668c..147e269f0 100644 --- a/examples/SharedMemory/grpc/pybullet_client.py +++ b/examples/SharedMemory/grpc/pybullet_client.py @@ -12,11 +12,23 @@ MJCF_COLORS_FROM_FILE = 512 def run(): print("grpc.insecure_channel") - channel = grpc.insecure_channel('localhost:50051') + channel = grpc.insecure_channel('localhost:6667') print("pybullet_pb2_grpc.PyBulletAPIStub") stub = pybullet_pb2_grpc.PyBulletAPIStub(channel) response=0 + print("submit CheckVersionCommand") + response = stub.SubmitCommand(pybullet_pb2.PyBulletCommand(checkVersionCommand=pybullet_pb2.CheckVersionCommand(clientVersion=123))) + print("PyBullet client received: " , response) + + + print("submit LoadUrdfCommand ") + response = stub.SubmitCommand(pybullet_pb2.PyBulletCommand(loadUrdfCommand=pybullet_pb2.LoadUrdfCommand(fileName="door.urdf", initialPosition=pybullet_pb2.vec3(x=0,y=0,z=0), useMultiBody=True, useFixedBase=True, globalScaling=2, flags = 1))) + print("PyBullet client received: " , response) + bodyUniqueId = response.urdfStatus.bodyUniqueId + + + print("submit LoadSdfCommand") response = stub.SubmitCommand(pybullet_pb2.PyBulletCommand(loadSdfCommand=pybullet_pb2.LoadSdfCommand(fileName="two_cubes.sdf", useMultiBody=True, globalScaling=2))) print("PyBullet client received: " , response) @@ -27,10 +39,6 @@ def run(): print("PyBullet client received: " , response) - print("submit LoadUrdfCommand ") - response = stub.SubmitCommand(pybullet_pb2.PyBulletCommand(loadUrdfCommand=pybullet_pb2.LoadUrdfCommand(fileName="door.urdf", initialPosition=pybullet_pb2.vec3(x=0,y=0,z=0), useMultiBody=True, useFixedBase=True, globalScaling=2, flags = 1))) - print("PyBullet client received: " , response) - bodyUniqueId = response.urdfStatus.bodyUniqueId print("submit ChangeDynamicsCommand ") response = stub.SubmitCommand(pybullet_pb2.PyBulletCommand(changeDynamicsCommand=pybullet_pb2.ChangeDynamicsCommand(bodyUniqueId=bodyUniqueId, linkIndex=-1, mass=10))) diff --git a/examples/SharedMemory/grpc/pybullet_pb2.py b/examples/SharedMemory/grpc/pybullet_pb2.py index 706179e12..61c5bbeef 100644 --- a/examples/SharedMemory/grpc/pybullet_pb2.py +++ b/examples/SharedMemory/grpc/pybullet_pb2.py @@ -19,7 +19,7 @@ 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\"\x95\x02\n\x0fLoadUrdfCommand\x12\x10\n\x08\x66ileName\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\r\n\x05\x66lags\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\x14\n\x0c\x62odyUniqueId\x18\x01 \x01(\x05\"z\n\x0eLoadSdfCommand\x12\x10\n\x08\x66ileName\x18\x01 \x01(\t\x12\x16\n\x0cuseMultiBody\x18\x02 \x01(\x05H\x00\x12\x17\n\rglobalScaling\x18\x03 \x01(\x01H\x01\x42\x11\n\x0fhasUseMultiBodyB\x12\n\x10hasGlobalScaling\"(\n\x0fSdfLoadedStatus\x12\x15\n\rbodyUniqueIds\x18\x02 \x03(\x05\"2\n\x0fLoadMjcfCommand\x12\x10\n\x08\x66ileName\x18\x01 \x01(\t\x12\r\n\x05\x66lags\x18\x02 \x01(\x05\")\n\x10MjcfLoadedStatus\x12\x15\n\rbodyUniqueIds\x18\x02 \x03(\x05\"\x89\x06\n\x15\x43hangeDynamicsCommand\x12\x14\n\x0c\x62odyUniqueId\x18\x01 \x01(\x05\x12\x11\n\tlinkIndex\x18\x02 \x01(\x05\x12\x0e\n\x04mass\x18\x03 \x01(\x01H\x00\x12\x19\n\x0flateralFriction\x18\x05 \x01(\x01H\x01\x12\x1a\n\x10spinningFriction\x18\x06 \x01(\x01H\x02\x12\x19\n\x0frollingFriction\x18\x07 \x01(\x01H\x03\x12\x15\n\x0brestitution\x18\x08 \x01(\x01H\x04\x12\x17\n\rlinearDamping\x18\t \x01(\x01H\x05\x12\x18\n\x0e\x61ngularDamping\x18\n \x01(\x01H\x06\x12\x1a\n\x10\x63ontactStiffness\x18\x0b \x01(\x01H\x07\x12\x18\n\x0e\x63ontactDamping\x18\x0c \x01(\x01H\x08\x12\x33\n\x14localInertiaDiagonal\x18\r \x01(\x0b\x32\x13.pybullet_grpc.vec3H\t\x12\x18\n\x0e\x66rictionAnchor\x18\x0e \x01(\x05H\n\x12\x1e\n\x14\x63\x63\x64SweptSphereRadius\x18\x0f \x01(\x01H\x0b\x12$\n\x1a\x63ontactProcessingThreshold\x18\x10 \x01(\x01H\x0c\x12\x19\n\x0f\x61\x63tivationState\x18\x11 \x01(\x05H\rB\t\n\x07hasMassB\x14\n\x12hasLateralFrictionB\x15\n\x13hasSpinningFrictionB\x14\n\x12hasRollingFrictionB\x10\n\x0ehasRestitutionB\x12\n\x10haslinearDampingB\x13\n\x11hasangularDampingB\x15\n\x13hasContactStiffnessB\x13\n\x11hasContactDampingB\x19\n\x17hasLocalInertiaDiagonalB\x13\n\x11hasFrictionAnchorB\x19\n\x17hasccdSweptSphereRadiusB\x1f\n\x1dhasContactProcessingThresholdB\x14\n\x12hasActivationState\"=\n\x12GetDynamicsCommand\x12\x14\n\x0c\x62odyUniqueId\x18\x01 \x01(\x05\x12\x11\n\tlinkIndex\x18\x02 \x01(\x05\"\x89\x03\n\x11GetDynamicsStatus\x12\x0c\n\x04mass\x18\x03 \x01(\x01\x12\x17\n\x0flateralFriction\x18\x05 \x01(\x01\x12\x18\n\x10spinningFriction\x18\x06 \x01(\x01\x12\x17\n\x0frollingFriction\x18\x07 \x01(\x01\x12\x13\n\x0brestitution\x18\x08 \x01(\x01\x12\x15\n\rlinearDamping\x18\t \x01(\x01\x12\x16\n\x0e\x61ngularDamping\x18\n \x01(\x01\x12\x18\n\x10\x63ontactStiffness\x18\x0b \x01(\x01\x12\x16\n\x0e\x63ontactDamping\x18\x0c \x01(\x01\x12\x31\n\x14localInertiaDiagonal\x18\r \x01(\x0b\x32\x13.pybullet_grpc.vec3\x12\x16\n\x0e\x66rictionAnchor\x18\x0e \x01(\x05\x12\x1c\n\x14\x63\x63\x64SweptSphereRadius\x18\x0f \x01(\x01\x12\"\n\x1a\x63ontactProcessingThreshold\x18\x10 \x01(\x01\x12\x17\n\x0f\x61\x63tivationState\x18\x11 \x01(\x05\"\x8f\x01\n\x0fInitPoseCommand\x12\x14\n\x0c\x62odyUniqueId\x18\x01 \x01(\x05\x12\x18\n\x10hasInitialStateQ\x18\x02 \x03(\x05\x12\x15\n\rinitialStateQ\x18\x03 \x03(\x01\x12\x1b\n\x13hasInitialStateQdot\x18\x04 \x03(\x05\x12\x18\n\x10initialStateQdot\x18\x05 \x03(\x01\"r\n\x19RequestActualStateCommand\x12\x14\n\x0c\x62odyUniqueId\x18\x01 \x01(\x05\x12 \n\x18\x63omputeForwardKinematics\x18\x02 \x01(\x08\x12\x1d\n\x15\x63omputeLinkVelocities\x18\x03 \x01(\x08\"\xcf\x02\n\x15SendActualStateStatus\x12\x14\n\x0c\x62odyUniqueId\x18\x01 \x01(\x05\x12\x10\n\x08numLinks\x18\x02 \x01(\x05\x12\x1b\n\x13numDegreeOfFreedomQ\x18\x03 \x01(\x05\x12\x1b\n\x13numDegreeOfFreedomU\x18\x04 \x01(\x05\x12\x1e\n\x16rootLocalInertialFrame\x18\x05 \x03(\x01\x12\x14\n\x0c\x61\x63tualStateQ\x18\x06 \x03(\x01\x12\x17\n\x0f\x61\x63tualStateQdot\x18\x07 \x03(\x01\x12\x1b\n\x13jointReactionForces\x18\x08 \x03(\x01\x12\x17\n\x0fjointMotorForce\x18\t \x03(\x01\x12\x11\n\tlinkState\x18\n \x03(\x01\x12\x1b\n\x13linkWorldVelocities\x18\x0b \x03(\x01\x12\x1f\n\x17linkLocalInertialFrames\x18\x0c \x03(\x01\"\x83\x05\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\x12\x37\n\x0eloadSdfCommand\x18\x06 \x01(\x0b\x32\x1d.pybullet_grpc.LoadSdfCommandH\x00\x12\x39\n\x0floadMjcfCommand\x18\x07 \x01(\x0b\x32\x1e.pybullet_grpc.LoadMjcfCommandH\x00\x12\x45\n\x15\x63hangeDynamicsCommand\x18\x08 \x01(\x0b\x32$.pybullet_grpc.ChangeDynamicsCommandH\x00\x12?\n\x12getDynamicsCommand\x18\t \x01(\x0b\x32!.pybullet_grpc.GetDynamicsCommandH\x00\x12\x39\n\x0finitPoseCommand\x18\n \x01(\x0b\x32\x1e.pybullet_grpc.InitPoseCommandH\x00\x12M\n\x19requestActualStateCommand\x18\x0b \x01(\x0b\x32(.pybullet_grpc.RequestActualStateCommandH\x00\x42\n\n\x08\x63ommands\"\xd1\x02\n\x0ePyBulletStatus\x12\x12\n\nstatusType\x18\x01 \x01(\x05\x12\x33\n\nurdfStatus\x18\x02 \x01(\x0b\x32\x1d.pybullet_grpc.LoadUrdfStatusH\x00\x12\x33\n\tsdfStatus\x18\x03 \x01(\x0b\x32\x1e.pybullet_grpc.SdfLoadedStatusH\x00\x12\x35\n\nmjcfStatus\x18\x04 \x01(\x0b\x32\x1f.pybullet_grpc.MjcfLoadedStatusH\x00\x12=\n\x11getDynamicsStatus\x18\x05 \x01(\x0b\x32 .pybullet_grpc.GetDynamicsStatusH\x00\x12\x41\n\x11\x61\x63tualStateStatus\x18\x06 \x01(\x0b\x32$.pybullet_grpc.SendActualStateStatusH\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') + 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\"2\n\x04vec4\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\ttransform\x12#\n\x06origin\x18\x01 \x01(\x0b\x32\x13.pybullet_grpc.vec3\x12)\n\x0borientation\x18\x02 \x01(\x0b\x32\x14.pybullet_grpc.quat4\"\x1a\n\tmatrix4x4\x12\r\n\x05\x65lems\x18\x01 \x03(\x01\",\n\x13\x43heckVersionCommand\x12\x15\n\rclientVersion\x18\x01 \x01(\x05\"+\n\x12\x43heckVersionStatus\x12\x15\n\rserverVersion\x18\x01 \x01(\x05\",\n\x16TerminateServerCommand\x12\x12\n\nexitReason\x18\x01 \x01(\t\"\x17\n\x15StepSimulationCommand\"\x13\n\x11SyncBodiesCommand\"J\n\x10SyncBodiesStatus\x12\x15\n\rbodyUniqueIds\x18\x01 \x03(\x05\x12\x1f\n\x17userConstraintUniqueIds\x18\x02 \x03(\x05\".\n\x16RequestBodyInfoCommand\x12\x14\n\x0c\x62odyUniqueId\x18\x01 \x01(\x05\"?\n\x15RequestBodyInfoStatus\x12\x14\n\x0c\x62odyUniqueId\x18\x01 \x01(\x05\x12\x10\n\x08\x62odyName\x18\x02 \x01(\t\"\x95\x02\n\x0fLoadUrdfCommand\x12\x10\n\x08\x66ileName\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\r\n\x05\x66lags\x18\x06 \x01(\x05\x12\x17\n\rglobalScaling\x18\x07 \x01(\x01H\x02\x42\x11\n\x0fhasUseMultiBodyB\x11\n\x0fhasUseFixedBaseB\x12\n\x10hasGlobalScaling\"J\n\x0eLoadUrdfStatus\x12\x14\n\x0c\x62odyUniqueId\x18\x01 \x01(\x05\x12\x10\n\x08\x62odyName\x18\x02 \x01(\t\x12\x10\n\x08\x66ileName\x18\x03 \x01(\t\"z\n\x0eLoadSdfCommand\x12\x10\n\x08\x66ileName\x18\x01 \x01(\t\x12\x16\n\x0cuseMultiBody\x18\x02 \x01(\x05H\x00\x12\x17\n\rglobalScaling\x18\x03 \x01(\x01H\x01\x42\x11\n\x0fhasUseMultiBodyB\x12\n\x10hasGlobalScaling\"(\n\x0fSdfLoadedStatus\x12\x15\n\rbodyUniqueIds\x18\x02 \x03(\x05\"2\n\x0fLoadMjcfCommand\x12\x10\n\x08\x66ileName\x18\x01 \x01(\t\x12\r\n\x05\x66lags\x18\x02 \x01(\x05\")\n\x10MjcfLoadedStatus\x12\x15\n\rbodyUniqueIds\x18\x02 \x03(\x05\"\x89\x06\n\x15\x43hangeDynamicsCommand\x12\x14\n\x0c\x62odyUniqueId\x18\x01 \x01(\x05\x12\x11\n\tlinkIndex\x18\x02 \x01(\x05\x12\x0e\n\x04mass\x18\x03 \x01(\x01H\x00\x12\x19\n\x0flateralFriction\x18\x05 \x01(\x01H\x01\x12\x1a\n\x10spinningFriction\x18\x06 \x01(\x01H\x02\x12\x19\n\x0frollingFriction\x18\x07 \x01(\x01H\x03\x12\x15\n\x0brestitution\x18\x08 \x01(\x01H\x04\x12\x17\n\rlinearDamping\x18\t \x01(\x01H\x05\x12\x18\n\x0e\x61ngularDamping\x18\n \x01(\x01H\x06\x12\x1a\n\x10\x63ontactStiffness\x18\x0b \x01(\x01H\x07\x12\x18\n\x0e\x63ontactDamping\x18\x0c \x01(\x01H\x08\x12\x33\n\x14localInertiaDiagonal\x18\r \x01(\x0b\x32\x13.pybullet_grpc.vec3H\t\x12\x18\n\x0e\x66rictionAnchor\x18\x0e \x01(\x05H\n\x12\x1e\n\x14\x63\x63\x64SweptSphereRadius\x18\x0f \x01(\x01H\x0b\x12$\n\x1a\x63ontactProcessingThreshold\x18\x10 \x01(\x01H\x0c\x12\x19\n\x0f\x61\x63tivationState\x18\x11 \x01(\x05H\rB\t\n\x07hasMassB\x14\n\x12hasLateralFrictionB\x15\n\x13hasSpinningFrictionB\x14\n\x12hasRollingFrictionB\x10\n\x0ehasRestitutionB\x12\n\x10haslinearDampingB\x13\n\x11hasangularDampingB\x15\n\x13hasContactStiffnessB\x13\n\x11hasContactDampingB\x19\n\x17hasLocalInertiaDiagonalB\x13\n\x11hasFrictionAnchorB\x19\n\x17hasccdSweptSphereRadiusB\x1f\n\x1dhasContactProcessingThresholdB\x14\n\x12hasActivationState\"=\n\x12GetDynamicsCommand\x12\x14\n\x0c\x62odyUniqueId\x18\x01 \x01(\x05\x12\x11\n\tlinkIndex\x18\x02 \x01(\x05\"\x89\x03\n\x11GetDynamicsStatus\x12\x0c\n\x04mass\x18\x03 \x01(\x01\x12\x17\n\x0flateralFriction\x18\x05 \x01(\x01\x12\x18\n\x10spinningFriction\x18\x06 \x01(\x01\x12\x17\n\x0frollingFriction\x18\x07 \x01(\x01\x12\x13\n\x0brestitution\x18\x08 \x01(\x01\x12\x15\n\rlinearDamping\x18\t \x01(\x01\x12\x16\n\x0e\x61ngularDamping\x18\n \x01(\x01\x12\x18\n\x10\x63ontactStiffness\x18\x0b \x01(\x01\x12\x16\n\x0e\x63ontactDamping\x18\x0c \x01(\x01\x12\x31\n\x14localInertiaDiagonal\x18\r \x01(\x0b\x32\x13.pybullet_grpc.vec3\x12\x16\n\x0e\x66rictionAnchor\x18\x0e \x01(\x05\x12\x1c\n\x14\x63\x63\x64SweptSphereRadius\x18\x0f \x01(\x01\x12\"\n\x1a\x63ontactProcessingThreshold\x18\x10 \x01(\x01\x12\x17\n\x0f\x61\x63tivationState\x18\x11 \x01(\x05\"\xa4\x01\n\x0fInitPoseCommand\x12\x14\n\x0c\x62odyUniqueId\x18\x01 \x01(\x05\x12\x13\n\x0bupdateflags\x18\x02 \x01(\x05\x12\x18\n\x10hasInitialStateQ\x18\x03 \x03(\x05\x12\x15\n\rinitialStateQ\x18\x04 \x03(\x01\x12\x1b\n\x13hasInitialStateQdot\x18\x05 \x03(\x05\x12\x18\n\x10initialStateQdot\x18\x06 \x03(\x01\"r\n\x19RequestActualStateCommand\x12\x14\n\x0c\x62odyUniqueId\x18\x01 \x01(\x05\x12 \n\x18\x63omputeForwardKinematics\x18\x02 \x01(\x08\x12\x1d\n\x15\x63omputeLinkVelocities\x18\x03 \x01(\x08\"\xcf\x02\n\x15SendActualStateStatus\x12\x14\n\x0c\x62odyUniqueId\x18\x01 \x01(\x05\x12\x10\n\x08numLinks\x18\x02 \x01(\x05\x12\x1b\n\x13numDegreeOfFreedomQ\x18\x03 \x01(\x05\x12\x1b\n\x13numDegreeOfFreedomU\x18\x04 \x01(\x05\x12\x1e\n\x16rootLocalInertialFrame\x18\x05 \x03(\x01\x12\x14\n\x0c\x61\x63tualStateQ\x18\x06 \x03(\x01\x12\x17\n\x0f\x61\x63tualStateQdot\x18\x07 \x03(\x01\x12\x1b\n\x13jointReactionForces\x18\x08 \x03(\x01\x12\x17\n\x0fjointMotorForce\x18\t \x03(\x01\x12\x11\n\tlinkState\x18\n \x03(\x01\x12\x1b\n\x13linkWorldVelocities\x18\x0b \x03(\x01\x12\x1f\n\x17linkLocalInertialFrames\x18\x0c \x03(\x01\"\xcf\x01\n ConfigureOpenGLVisualizerCommand\x12\x13\n\x0bupdateFlags\x18\x01 \x01(\x05\x12\x16\n\x0e\x63\x61meraDistance\x18\x02 \x01(\x01\x12\x13\n\x0b\x63\x61meraPitch\x18\x03 \x01(\x01\x12\x11\n\tcameraYaw\x18\x04 \x01(\x01\x12\x31\n\x14\x63\x61meraTargetPosition\x18\x05 \x01(\x0b\x32\x13.pybullet_grpc.vec3\x12\x0f\n\x07setFlag\x18\x06 \x01(\x05\x12\x12\n\nsetEnabled\x18\x07 \x01(\x05\"\x9c\x06\n\x1bPhysicsSimulationParameters\x12\x11\n\tdeltaTime\x18\x01 \x01(\x01\x12\x30\n\x13gravityAcceleration\x18\x02 \x01(\x0b\x32\x13.pybullet_grpc.vec3\x12\x1d\n\x15numSimulationSubSteps\x18\x03 \x01(\x05\x12\x1b\n\x13numSolverIterations\x18\x04 \x01(\x05\x12\x1d\n\x15useRealTimeSimulation\x18\x05 \x01(\x05\x12\x17\n\x0fuseSplitImpulse\x18\x06 \x01(\x05\x12(\n splitImpulsePenetrationThreshold\x18\x07 \x01(\x01\x12 \n\x18\x63ontactBreakingThreshold\x18\x08 \x01(\x01\x12\x18\n\x10internalSimFlags\x18\t \x01(\x05\x12\x19\n\x11\x64\x65\x66\x61ultContactERP\x18\n \x01(\x01\x12\x1b\n\x13\x63ollisionFilterMode\x18\x0b \x01(\x05\x12\x19\n\x11\x65nableFileCaching\x18\x0c \x01(\x05\x12$\n\x1crestitutionVelocityThreshold\x18\r \x01(\x01\x12\x1c\n\x14\x64\x65\x66\x61ultNonContactERP\x18\x0e \x01(\x01\x12\x13\n\x0b\x66rictionERP\x18\x0f \x01(\x01\x12\x18\n\x10\x64\x65\x66\x61ultGlobalCFM\x18\x10 \x01(\x01\x12\x13\n\x0b\x66rictionCFM\x18\x11 \x01(\x01\x12\x1a\n\x12\x65nableConeFriction\x18\x12 \x01(\x05\x12%\n\x1d\x64\x65terministicOverlappingPairs\x18\x13 \x01(\x05\x12\x1d\n\x15\x61llowedCcdPenetration\x18\x14 \x01(\x01\x12\x19\n\x11jointFeedbackMode\x18\x15 \x01(\x05\x12\x1f\n\x17solverResidualThreshold\x18\x16 \x01(\x01\x12\x13\n\x0b\x63ontactSlop\x18\x17 \x01(\x01\x12\x11\n\tenableSAT\x18\x18 \x01(\x05\x12\x1c\n\x14\x63onstraintSolverType\x18\x19 \x01(\x05\x12\x1f\n\x17minimumSolverIslandSize\x18\x1a \x01(\x05\"u\n\"PhysicsSimulationParametersCommand\x12\x13\n\x0bupdateFlags\x18\x01 \x01(\x05\x12:\n\x06params\x18\x02 \x01(\x0b\x32*.pybullet_grpc.PhysicsSimulationParameters\"\xf7\x01\n\x18JointMotorControlCommand\x12\x14\n\x0c\x62odyUniqueId\x18\x01 \x01(\x05\x12\x13\n\x0b\x63ontrolMode\x18\x02 \x01(\x05\x12\x13\n\x0bupdateFlags\x18\x03 \x01(\x05\x12\n\n\x02Kp\x18\x04 \x03(\x01\x12\n\n\x02Kd\x18\x05 \x03(\x01\x12\x13\n\x0bmaxVelocity\x18\x06 \x03(\x01\x12\x1c\n\x14hasDesiredStateFlags\x18\x07 \x03(\x05\x12\x15\n\rdesiredStateQ\x18\x08 \x03(\x01\x12\x18\n\x10\x64\x65siredStateQdot\x18\t \x03(\x01\x12\x1f\n\x17\x64\x65siredStateForceTorque\x18\n \x03(\x01\"\xb6\x03\n\x15UserConstraintCommand\x12\x17\n\x0fparentBodyIndex\x18\x01 \x01(\x05\x12\x18\n\x10parentJointIndex\x18\x02 \x01(\x05\x12\x16\n\x0e\x63hildBodyIndex\x18\x03 \x01(\x05\x12\x17\n\x0f\x63hildJointIndex\x18\x04 \x01(\x05\x12-\n\x0bparentFrame\x18\x05 \x01(\x0b\x32\x18.pybullet_grpc.transform\x12,\n\nchildFrame\x18\x06 \x01(\x0b\x32\x18.pybullet_grpc.transform\x12&\n\tjointAxis\x18\x07 \x01(\x0b\x32\x13.pybullet_grpc.vec3\x12\x11\n\tjointType\x18\x08 \x01(\x05\x12\x17\n\x0fmaxAppliedForce\x18\t \x01(\x01\x12\x1e\n\x16userConstraintUniqueId\x18\n \x01(\x05\x12\x11\n\tgearRatio\x18\x0b \x01(\x01\x12\x13\n\x0bgearAuxLink\x18\x0c \x01(\x05\x12\x1e\n\x16relativePositionTarget\x18\r \x01(\x01\x12\x0b\n\x03\x65rp\x18\x0e \x01(\x01\x12\x13\n\x0bupdateFlags\x18\x0f \x01(\x05\"O\n\x14UserConstraintStatus\x12\x17\n\x0fmaxAppliedForce\x18\t \x01(\x01\x12\x1e\n\x16userConstraintUniqueId\x18\n \x01(\x05\"\xa5\x01\n\x19UserConstraintStateStatus\x12:\n\x1d\x61ppliedConstraintForcesLinear\x18\x01 \x01(\x0b\x32\x13.pybullet_grpc.vec3\x12;\n\x1e\x61ppliedConstraintForcesAngular\x18\x02 \x01(\x0b\x32\x13.pybullet_grpc.vec3\x12\x0f\n\x07numDofs\x18\x03 \x01(\x05\"\x1e\n\x1cRequestKeyboardEventsCommand\"2\n\rKeyboardEvent\x12\x0f\n\x07keyCode\x18\x01 \x01(\x05\x12\x10\n\x08keyState\x18\x02 \x01(\x05\"L\n\x14KeyboardEventsStatus\x12\x34\n\x0ekeyboardEvents\x18\x01 \x03(\x0b\x32\x1c.pybullet_grpc.KeyboardEvent\"\xbf\x04\n\x19RequestCameraImageCommand\x12\x13\n\x0bupdateFlags\x18\x01 \x01(\x05\x12\x13\n\x0b\x63\x61meraFlags\x18\x02 \x01(\x05\x12,\n\nviewMatrix\x18\x03 \x01(\x0b\x32\x18.pybullet_grpc.matrix4x4\x12\x32\n\x10projectionMatrix\x18\x04 \x01(\x0b\x32\x18.pybullet_grpc.matrix4x4\x12\x17\n\x0fstartPixelIndex\x18\x05 \x01(\x05\x12\x12\n\npixelWidth\x18\x06 \x01(\x05\x12\x13\n\x0bpixelHeight\x18\x07 \x01(\x05\x12+\n\x0elightDirection\x18\x08 \x01(\x0b\x32\x13.pybullet_grpc.vec3\x12\'\n\nlightColor\x18\t \x01(\x0b\x32\x13.pybullet_grpc.vec3\x12\x15\n\rlightDistance\x18\n \x01(\x01\x12\x19\n\x11lightAmbientCoeff\x18\x0b \x01(\x01\x12\x19\n\x11lightDiffuseCoeff\x18\x0c \x01(\x01\x12\x1a\n\x12lightSpecularCoeff\x18\r \x01(\x01\x12\x11\n\thasShadow\x18\x0e \x01(\x05\x12=\n\x1bprojectiveTextureViewMatrix\x18\x0f \x01(\x0b\x32\x18.pybullet_grpc.matrix4x4\x12\x43\n!projectiveTextureProjectionMatrix\x18\x10 \x01(\x0b\x32\x18.pybullet_grpc.matrix4x4\"\x94\x01\n\x18RequestCameraImageStatus\x12\x12\n\nimageWidth\x18\x01 \x01(\x05\x12\x13\n\x0bimageHeight\x18\x02 \x01(\x05\x12\x1a\n\x12startingPixelIndex\x18\x03 \x01(\x05\x12\x17\n\x0fnumPixelsCopied\x18\x04 \x01(\x05\x12\x1a\n\x12numRemainingPixels\x18\x05 \x01(\x05\"\xfd\n\n\x0fPyBulletCommand\x12\x13\n\x0b\x63ommandType\x18\x01 \x01(\x05\x12\x12\n\nbinaryBlob\x18\x02 \x03(\x0c\x12 \n\x18unknownCommandBinaryBlob\x18\x03 \x03(\x0c\x12\x39\n\x0floadUrdfCommand\x18\x04 \x01(\x0b\x32\x1e.pybullet_grpc.LoadUrdfCommandH\x00\x12G\n\x16terminateServerCommand\x18\x05 \x01(\x0b\x32%.pybullet_grpc.TerminateServerCommandH\x00\x12\x45\n\x15stepSimulationCommand\x18\x06 \x01(\x0b\x32$.pybullet_grpc.StepSimulationCommandH\x00\x12\x37\n\x0eloadSdfCommand\x18\x07 \x01(\x0b\x32\x1d.pybullet_grpc.LoadSdfCommandH\x00\x12\x39\n\x0floadMjcfCommand\x18\x08 \x01(\x0b\x32\x1e.pybullet_grpc.LoadMjcfCommandH\x00\x12\x45\n\x15\x63hangeDynamicsCommand\x18\t \x01(\x0b\x32$.pybullet_grpc.ChangeDynamicsCommandH\x00\x12?\n\x12getDynamicsCommand\x18\n \x01(\x0b\x32!.pybullet_grpc.GetDynamicsCommandH\x00\x12\x39\n\x0finitPoseCommand\x18\x0b \x01(\x0b\x32\x1e.pybullet_grpc.InitPoseCommandH\x00\x12M\n\x19requestActualStateCommand\x18\x0c \x01(\x0b\x32(.pybullet_grpc.RequestActualStateCommandH\x00\x12[\n configureOpenGLVisualizerCommand\x18\r \x01(\x0b\x32/.pybullet_grpc.ConfigureOpenGLVisualizerCommandH\x00\x12=\n\x11syncBodiesCommand\x18\x0e \x01(\x0b\x32 .pybullet_grpc.SyncBodiesCommandH\x00\x12G\n\x16requestBodyInfoCommand\x18\x0f \x01(\x0b\x32%.pybullet_grpc.RequestBodyInfoCommandH\x00\x12\x62\n%setPhysicsSimulationParametersCommand\x18\x10 \x01(\x0b\x32\x31.pybullet_grpc.PhysicsSimulationParametersCommandH\x00\x12K\n\x18jointMotorControlCommand\x18\x11 \x01(\x0b\x32\'.pybullet_grpc.JointMotorControlCommandH\x00\x12\x45\n\x15userConstraintCommand\x18\x12 \x01(\x0b\x32$.pybullet_grpc.UserConstraintCommandH\x00\x12\x41\n\x13\x63heckVersionCommand\x18\x13 \x01(\x0b\x32\".pybullet_grpc.CheckVersionCommandH\x00\x12S\n\x1crequestKeyboardEventsCommand\x18\x14 \x01(\x0b\x32+.pybullet_grpc.RequestKeyboardEventsCommandH\x00\x12M\n\x19requestCameraImageCommand\x18\x15 \x01(\x0b\x32(.pybullet_grpc.RequestCameraImageCommandH\x00\x42\n\n\x08\x63ommands\"\xd1\x07\n\x0ePyBulletStatus\x12\x12\n\nstatusType\x18\x01 \x01(\x05\x12\x12\n\nbinaryBlob\x18\x02 \x03(\x0c\x12\x1f\n\x17unknownStatusBinaryBlob\x18\x03 \x03(\x0c\x12\x33\n\nurdfStatus\x18\x04 \x01(\x0b\x32\x1d.pybullet_grpc.LoadUrdfStatusH\x00\x12\x33\n\tsdfStatus\x18\x05 \x01(\x0b\x32\x1e.pybullet_grpc.SdfLoadedStatusH\x00\x12\x35\n\nmjcfStatus\x18\x06 \x01(\x0b\x32\x1f.pybullet_grpc.MjcfLoadedStatusH\x00\x12=\n\x11getDynamicsStatus\x18\x07 \x01(\x0b\x32 .pybullet_grpc.GetDynamicsStatusH\x00\x12\x41\n\x11\x61\x63tualStateStatus\x18\x08 \x01(\x0b\x32$.pybullet_grpc.SendActualStateStatusH\x00\x12;\n\x10syncBodiesStatus\x18\t \x01(\x0b\x32\x1f.pybullet_grpc.SyncBodiesStatusH\x00\x12\x45\n\x15requestBodyInfoStatus\x18\n \x01(\x0b\x32$.pybullet_grpc.RequestBodyInfoStatusH\x00\x12^\n(requestPhysicsSimulationParametersStatus\x18\x0b \x01(\x0b\x32*.pybullet_grpc.PhysicsSimulationParametersH\x00\x12?\n\x12\x63heckVersionStatus\x18\x0c \x01(\x0b\x32!.pybullet_grpc.CheckVersionStatusH\x00\x12\x43\n\x14userConstraintStatus\x18\r \x01(\x0b\x32#.pybullet_grpc.UserConstraintStatusH\x00\x12M\n\x19userConstraintStateStatus\x18\x0e \x01(\x0b\x32(.pybullet_grpc.UserConstraintStateStatusH\x00\x12\x43\n\x14keyboardEventsStatus\x18\x0f \x01(\x0b\x32#.pybullet_grpc.KeyboardEventsStatusH\x00\x12K\n\x18requestCameraImageStatus\x18\x10 \x01(\x0b\x32\'.pybullet_grpc.RequestCameraImageStatusH\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') ) @@ -122,6 +122,189 @@ _QUAT4 = _descriptor.Descriptor( ) +_VEC4 = _descriptor.Descriptor( + name='vec4', + full_name='pybullet_grpc.vec4', + filename=None, + file=DESCRIPTOR, + containing_type=None, + fields=[ + _descriptor.FieldDescriptor( + name='x', full_name='pybullet_grpc.vec4.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.vec4.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.vec4.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.vec4.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=127, + serialized_end=177, +) + + +_TRANSFORM = _descriptor.Descriptor( + name='transform', + full_name='pybullet_grpc.transform', + filename=None, + file=DESCRIPTOR, + containing_type=None, + fields=[ + _descriptor.FieldDescriptor( + name='origin', full_name='pybullet_grpc.transform.origin', index=0, + number=1, 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='orientation', full_name='pybullet_grpc.transform.orientation', 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=[ + ], + serialized_start=179, + serialized_end=270, +) + + +_MATRIX4X4 = _descriptor.Descriptor( + name='matrix4x4', + full_name='pybullet_grpc.matrix4x4', + filename=None, + file=DESCRIPTOR, + containing_type=None, + fields=[ + _descriptor.FieldDescriptor( + name='elems', full_name='pybullet_grpc.matrix4x4.elems', index=0, + number=1, type=1, cpp_type=5, label=3, + has_default_value=False, default_value=[], + 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=272, + serialized_end=298, +) + + +_CHECKVERSIONCOMMAND = _descriptor.Descriptor( + name='CheckVersionCommand', + full_name='pybullet_grpc.CheckVersionCommand', + filename=None, + file=DESCRIPTOR, + containing_type=None, + fields=[ + _descriptor.FieldDescriptor( + name='clientVersion', full_name='pybullet_grpc.CheckVersionCommand.clientVersion', 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=300, + serialized_end=344, +) + + +_CHECKVERSIONSTATUS = _descriptor.Descriptor( + name='CheckVersionStatus', + full_name='pybullet_grpc.CheckVersionStatus', + filename=None, + file=DESCRIPTOR, + containing_type=None, + fields=[ + _descriptor.FieldDescriptor( + name='serverVersion', full_name='pybullet_grpc.CheckVersionStatus.serverVersion', 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=346, + serialized_end=389, +) + + _TERMINATESERVERCOMMAND = _descriptor.Descriptor( name='TerminateServerCommand', full_name='pybullet_grpc.TerminateServerCommand', @@ -148,8 +331,8 @@ _TERMINATESERVERCOMMAND = _descriptor.Descriptor( extension_ranges=[], oneofs=[ ], - serialized_start=127, - serialized_end=171, + serialized_start=391, + serialized_end=435, ) @@ -172,8 +355,139 @@ _STEPSIMULATIONCOMMAND = _descriptor.Descriptor( extension_ranges=[], oneofs=[ ], - serialized_start=173, - serialized_end=196, + serialized_start=437, + serialized_end=460, +) + + +_SYNCBODIESCOMMAND = _descriptor.Descriptor( + name='SyncBodiesCommand', + full_name='pybullet_grpc.SyncBodiesCommand', + 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=462, + serialized_end=481, +) + + +_SYNCBODIESSTATUS = _descriptor.Descriptor( + name='SyncBodiesStatus', + full_name='pybullet_grpc.SyncBodiesStatus', + filename=None, + file=DESCRIPTOR, + containing_type=None, + fields=[ + _descriptor.FieldDescriptor( + name='bodyUniqueIds', full_name='pybullet_grpc.SyncBodiesStatus.bodyUniqueIds', index=0, + number=1, type=5, cpp_type=1, label=3, + has_default_value=False, default_value=[], + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + options=None, file=DESCRIPTOR), + _descriptor.FieldDescriptor( + name='userConstraintUniqueIds', full_name='pybullet_grpc.SyncBodiesStatus.userConstraintUniqueIds', index=1, + number=2, type=5, cpp_type=1, label=3, + has_default_value=False, default_value=[], + 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=483, + serialized_end=557, +) + + +_REQUESTBODYINFOCOMMAND = _descriptor.Descriptor( + name='RequestBodyInfoCommand', + full_name='pybullet_grpc.RequestBodyInfoCommand', + filename=None, + file=DESCRIPTOR, + containing_type=None, + fields=[ + _descriptor.FieldDescriptor( + name='bodyUniqueId', full_name='pybullet_grpc.RequestBodyInfoCommand.bodyUniqueId', 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=559, + serialized_end=605, +) + + +_REQUESTBODYINFOSTATUS = _descriptor.Descriptor( + name='RequestBodyInfoStatus', + full_name='pybullet_grpc.RequestBodyInfoStatus', + filename=None, + file=DESCRIPTOR, + containing_type=None, + fields=[ + _descriptor.FieldDescriptor( + name='bodyUniqueId', full_name='pybullet_grpc.RequestBodyInfoStatus.bodyUniqueId', 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='bodyName', full_name='pybullet_grpc.RequestBodyInfoStatus.bodyName', index=1, + number=2, 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=607, + serialized_end=670, ) @@ -254,8 +568,8 @@ _LOADURDFCOMMAND = _descriptor.Descriptor( name='hasGlobalScaling', full_name='pybullet_grpc.LoadUrdfCommand.hasGlobalScaling', index=2, containing_type=None, fields=[]), ], - serialized_start=199, - serialized_end=476, + serialized_start=673, + serialized_end=950, ) @@ -273,6 +587,20 @@ _LOADURDFSTATUS = _descriptor.Descriptor( message_type=None, enum_type=None, containing_type=None, is_extension=False, extension_scope=None, options=None, file=DESCRIPTOR), + _descriptor.FieldDescriptor( + name='bodyName', full_name='pybullet_grpc.LoadUrdfStatus.bodyName', index=1, + number=2, 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='fileName', full_name='pybullet_grpc.LoadUrdfStatus.fileName', index=2, + number=3, 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=[ ], @@ -285,8 +613,8 @@ _LOADURDFSTATUS = _descriptor.Descriptor( extension_ranges=[], oneofs=[ ], - serialized_start=478, - serialized_end=516, + serialized_start=952, + serialized_end=1026, ) @@ -336,8 +664,8 @@ _LOADSDFCOMMAND = _descriptor.Descriptor( name='hasGlobalScaling', full_name='pybullet_grpc.LoadSdfCommand.hasGlobalScaling', index=1, containing_type=None, fields=[]), ], - serialized_start=518, - serialized_end=640, + serialized_start=1028, + serialized_end=1150, ) @@ -367,8 +695,8 @@ _SDFLOADEDSTATUS = _descriptor.Descriptor( extension_ranges=[], oneofs=[ ], - serialized_start=642, - serialized_end=682, + serialized_start=1152, + serialized_end=1192, ) @@ -405,8 +733,8 @@ _LOADMJCFCOMMAND = _descriptor.Descriptor( extension_ranges=[], oneofs=[ ], - serialized_start=684, - serialized_end=734, + serialized_start=1194, + serialized_end=1244, ) @@ -436,8 +764,8 @@ _MJCFLOADEDSTATUS = _descriptor.Descriptor( extension_ranges=[], oneofs=[ ], - serialized_start=736, - serialized_end=777, + serialized_start=1246, + serialized_end=1287, ) @@ -614,8 +942,8 @@ _CHANGEDYNAMICSCOMMAND = _descriptor.Descriptor( name='hasActivationState', full_name='pybullet_grpc.ChangeDynamicsCommand.hasActivationState', index=13, containing_type=None, fields=[]), ], - serialized_start=780, - serialized_end=1557, + serialized_start=1290, + serialized_end=2067, ) @@ -652,8 +980,8 @@ _GETDYNAMICSCOMMAND = _descriptor.Descriptor( extension_ranges=[], oneofs=[ ], - serialized_start=1559, - serialized_end=1620, + serialized_start=2069, + serialized_end=2130, ) @@ -774,8 +1102,8 @@ _GETDYNAMICSSTATUS = _descriptor.Descriptor( extension_ranges=[], oneofs=[ ], - serialized_start=1623, - serialized_end=2016, + serialized_start=2133, + serialized_end=2526, ) @@ -794,29 +1122,36 @@ _INITPOSECOMMAND = _descriptor.Descriptor( is_extension=False, extension_scope=None, options=None, file=DESCRIPTOR), _descriptor.FieldDescriptor( - name='hasInitialStateQ', full_name='pybullet_grpc.InitPoseCommand.hasInitialStateQ', index=1, - number=2, type=5, cpp_type=1, label=3, + name='updateflags', full_name='pybullet_grpc.InitPoseCommand.updateflags', index=1, + number=2, 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='hasInitialStateQ', full_name='pybullet_grpc.InitPoseCommand.hasInitialStateQ', index=2, + number=3, type=5, cpp_type=1, label=3, has_default_value=False, default_value=[], message_type=None, enum_type=None, containing_type=None, is_extension=False, extension_scope=None, options=None, file=DESCRIPTOR), _descriptor.FieldDescriptor( - name='initialStateQ', full_name='pybullet_grpc.InitPoseCommand.initialStateQ', index=2, - number=3, type=1, cpp_type=5, label=3, + name='initialStateQ', full_name='pybullet_grpc.InitPoseCommand.initialStateQ', index=3, + number=4, type=1, cpp_type=5, label=3, has_default_value=False, default_value=[], message_type=None, enum_type=None, containing_type=None, is_extension=False, extension_scope=None, options=None, file=DESCRIPTOR), _descriptor.FieldDescriptor( - name='hasInitialStateQdot', full_name='pybullet_grpc.InitPoseCommand.hasInitialStateQdot', index=3, - number=4, type=5, cpp_type=1, label=3, + name='hasInitialStateQdot', full_name='pybullet_grpc.InitPoseCommand.hasInitialStateQdot', index=4, + number=5, type=5, cpp_type=1, label=3, has_default_value=False, default_value=[], message_type=None, enum_type=None, containing_type=None, is_extension=False, extension_scope=None, options=None, file=DESCRIPTOR), _descriptor.FieldDescriptor( - name='initialStateQdot', full_name='pybullet_grpc.InitPoseCommand.initialStateQdot', index=4, - number=5, type=1, cpp_type=5, label=3, + name='initialStateQdot', full_name='pybullet_grpc.InitPoseCommand.initialStateQdot', index=5, + number=6, type=1, cpp_type=5, label=3, has_default_value=False, default_value=[], message_type=None, enum_type=None, containing_type=None, is_extension=False, extension_scope=None, @@ -833,8 +1168,8 @@ _INITPOSECOMMAND = _descriptor.Descriptor( extension_ranges=[], oneofs=[ ], - serialized_start=2019, - serialized_end=2162, + serialized_start=2529, + serialized_end=2693, ) @@ -878,8 +1213,8 @@ _REQUESTACTUALSTATECOMMAND = _descriptor.Descriptor( extension_ranges=[], oneofs=[ ], - serialized_start=2164, - serialized_end=2278, + serialized_start=2695, + serialized_end=2809, ) @@ -986,8 +1321,919 @@ _SENDACTUALSTATESTATUS = _descriptor.Descriptor( extension_ranges=[], oneofs=[ ], - serialized_start=2281, - serialized_end=2616, + serialized_start=2812, + serialized_end=3147, +) + + +_CONFIGUREOPENGLVISUALIZERCOMMAND = _descriptor.Descriptor( + name='ConfigureOpenGLVisualizerCommand', + full_name='pybullet_grpc.ConfigureOpenGLVisualizerCommand', + filename=None, + file=DESCRIPTOR, + containing_type=None, + fields=[ + _descriptor.FieldDescriptor( + name='updateFlags', full_name='pybullet_grpc.ConfigureOpenGLVisualizerCommand.updateFlags', 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='cameraDistance', full_name='pybullet_grpc.ConfigureOpenGLVisualizerCommand.cameraDistance', 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='cameraPitch', full_name='pybullet_grpc.ConfigureOpenGLVisualizerCommand.cameraPitch', 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='cameraYaw', full_name='pybullet_grpc.ConfigureOpenGLVisualizerCommand.cameraYaw', 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), + _descriptor.FieldDescriptor( + name='cameraTargetPosition', full_name='pybullet_grpc.ConfigureOpenGLVisualizerCommand.cameraTargetPosition', index=4, + 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), + _descriptor.FieldDescriptor( + name='setFlag', full_name='pybullet_grpc.ConfigureOpenGLVisualizerCommand.setFlag', 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='setEnabled', full_name='pybullet_grpc.ConfigureOpenGLVisualizerCommand.setEnabled', index=6, + number=7, 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=3150, + serialized_end=3357, +) + + +_PHYSICSSIMULATIONPARAMETERS = _descriptor.Descriptor( + name='PhysicsSimulationParameters', + full_name='pybullet_grpc.PhysicsSimulationParameters', + filename=None, + file=DESCRIPTOR, + containing_type=None, + fields=[ + _descriptor.FieldDescriptor( + name='deltaTime', full_name='pybullet_grpc.PhysicsSimulationParameters.deltaTime', 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='gravityAcceleration', full_name='pybullet_grpc.PhysicsSimulationParameters.gravityAcceleration', 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='numSimulationSubSteps', full_name='pybullet_grpc.PhysicsSimulationParameters.numSimulationSubSteps', index=2, + number=3, 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='numSolverIterations', full_name='pybullet_grpc.PhysicsSimulationParameters.numSolverIterations', 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='useRealTimeSimulation', full_name='pybullet_grpc.PhysicsSimulationParameters.useRealTimeSimulation', index=4, + number=5, 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='useSplitImpulse', full_name='pybullet_grpc.PhysicsSimulationParameters.useSplitImpulse', 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='splitImpulsePenetrationThreshold', full_name='pybullet_grpc.PhysicsSimulationParameters.splitImpulsePenetrationThreshold', 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), + _descriptor.FieldDescriptor( + name='contactBreakingThreshold', full_name='pybullet_grpc.PhysicsSimulationParameters.contactBreakingThreshold', index=7, + number=8, 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='internalSimFlags', full_name='pybullet_grpc.PhysicsSimulationParameters.internalSimFlags', index=8, + number=9, 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='defaultContactERP', full_name='pybullet_grpc.PhysicsSimulationParameters.defaultContactERP', index=9, + number=10, 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='collisionFilterMode', full_name='pybullet_grpc.PhysicsSimulationParameters.collisionFilterMode', index=10, + number=11, 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='enableFileCaching', full_name='pybullet_grpc.PhysicsSimulationParameters.enableFileCaching', index=11, + number=12, 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='restitutionVelocityThreshold', full_name='pybullet_grpc.PhysicsSimulationParameters.restitutionVelocityThreshold', index=12, + number=13, 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='defaultNonContactERP', full_name='pybullet_grpc.PhysicsSimulationParameters.defaultNonContactERP', index=13, + number=14, 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='frictionERP', full_name='pybullet_grpc.PhysicsSimulationParameters.frictionERP', index=14, + number=15, 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='defaultGlobalCFM', full_name='pybullet_grpc.PhysicsSimulationParameters.defaultGlobalCFM', index=15, + number=16, 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='frictionCFM', full_name='pybullet_grpc.PhysicsSimulationParameters.frictionCFM', index=16, + number=17, 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='enableConeFriction', full_name='pybullet_grpc.PhysicsSimulationParameters.enableConeFriction', index=17, + number=18, 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='deterministicOverlappingPairs', full_name='pybullet_grpc.PhysicsSimulationParameters.deterministicOverlappingPairs', index=18, + number=19, 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='allowedCcdPenetration', full_name='pybullet_grpc.PhysicsSimulationParameters.allowedCcdPenetration', index=19, + number=20, 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='jointFeedbackMode', full_name='pybullet_grpc.PhysicsSimulationParameters.jointFeedbackMode', index=20, + number=21, 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='solverResidualThreshold', full_name='pybullet_grpc.PhysicsSimulationParameters.solverResidualThreshold', index=21, + number=22, 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='contactSlop', full_name='pybullet_grpc.PhysicsSimulationParameters.contactSlop', index=22, + number=23, 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='enableSAT', full_name='pybullet_grpc.PhysicsSimulationParameters.enableSAT', index=23, + number=24, 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='constraintSolverType', full_name='pybullet_grpc.PhysicsSimulationParameters.constraintSolverType', index=24, + number=25, 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='minimumSolverIslandSize', full_name='pybullet_grpc.PhysicsSimulationParameters.minimumSolverIslandSize', index=25, + number=26, 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=3360, + serialized_end=4156, +) + + +_PHYSICSSIMULATIONPARAMETERSCOMMAND = _descriptor.Descriptor( + name='PhysicsSimulationParametersCommand', + full_name='pybullet_grpc.PhysicsSimulationParametersCommand', + filename=None, + file=DESCRIPTOR, + containing_type=None, + fields=[ + _descriptor.FieldDescriptor( + name='updateFlags', full_name='pybullet_grpc.PhysicsSimulationParametersCommand.updateFlags', 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='params', full_name='pybullet_grpc.PhysicsSimulationParametersCommand.params', 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=[ + ], + serialized_start=4158, + serialized_end=4275, +) + + +_JOINTMOTORCONTROLCOMMAND = _descriptor.Descriptor( + name='JointMotorControlCommand', + full_name='pybullet_grpc.JointMotorControlCommand', + filename=None, + file=DESCRIPTOR, + containing_type=None, + fields=[ + _descriptor.FieldDescriptor( + name='bodyUniqueId', full_name='pybullet_grpc.JointMotorControlCommand.bodyUniqueId', 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='controlMode', full_name='pybullet_grpc.JointMotorControlCommand.controlMode', index=1, + number=2, 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='updateFlags', full_name='pybullet_grpc.JointMotorControlCommand.updateFlags', index=2, + number=3, 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='Kp', full_name='pybullet_grpc.JointMotorControlCommand.Kp', index=3, + number=4, type=1, cpp_type=5, label=3, + has_default_value=False, default_value=[], + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + options=None, file=DESCRIPTOR), + _descriptor.FieldDescriptor( + name='Kd', full_name='pybullet_grpc.JointMotorControlCommand.Kd', index=4, + number=5, type=1, cpp_type=5, label=3, + has_default_value=False, default_value=[], + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + options=None, file=DESCRIPTOR), + _descriptor.FieldDescriptor( + name='maxVelocity', full_name='pybullet_grpc.JointMotorControlCommand.maxVelocity', index=5, + number=6, type=1, cpp_type=5, label=3, + has_default_value=False, default_value=[], + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + options=None, file=DESCRIPTOR), + _descriptor.FieldDescriptor( + name='hasDesiredStateFlags', full_name='pybullet_grpc.JointMotorControlCommand.hasDesiredStateFlags', index=6, + number=7, type=5, cpp_type=1, label=3, + has_default_value=False, default_value=[], + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + options=None, file=DESCRIPTOR), + _descriptor.FieldDescriptor( + name='desiredStateQ', full_name='pybullet_grpc.JointMotorControlCommand.desiredStateQ', index=7, + number=8, type=1, cpp_type=5, label=3, + has_default_value=False, default_value=[], + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + options=None, file=DESCRIPTOR), + _descriptor.FieldDescriptor( + name='desiredStateQdot', full_name='pybullet_grpc.JointMotorControlCommand.desiredStateQdot', index=8, + number=9, type=1, cpp_type=5, label=3, + has_default_value=False, default_value=[], + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + options=None, file=DESCRIPTOR), + _descriptor.FieldDescriptor( + name='desiredStateForceTorque', full_name='pybullet_grpc.JointMotorControlCommand.desiredStateForceTorque', index=9, + number=10, type=1, cpp_type=5, label=3, + has_default_value=False, default_value=[], + 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=4278, + serialized_end=4525, +) + + +_USERCONSTRAINTCOMMAND = _descriptor.Descriptor( + name='UserConstraintCommand', + full_name='pybullet_grpc.UserConstraintCommand', + filename=None, + file=DESCRIPTOR, + containing_type=None, + fields=[ + _descriptor.FieldDescriptor( + name='parentBodyIndex', full_name='pybullet_grpc.UserConstraintCommand.parentBodyIndex', 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='parentJointIndex', full_name='pybullet_grpc.UserConstraintCommand.parentJointIndex', index=1, + number=2, 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='childBodyIndex', full_name='pybullet_grpc.UserConstraintCommand.childBodyIndex', index=2, + number=3, 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='childJointIndex', full_name='pybullet_grpc.UserConstraintCommand.childJointIndex', 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='parentFrame', full_name='pybullet_grpc.UserConstraintCommand.parentFrame', index=4, + 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), + _descriptor.FieldDescriptor( + name='childFrame', full_name='pybullet_grpc.UserConstraintCommand.childFrame', index=5, + number=6, 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='jointAxis', full_name='pybullet_grpc.UserConstraintCommand.jointAxis', index=6, + number=7, 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='jointType', full_name='pybullet_grpc.UserConstraintCommand.jointType', index=7, + number=8, 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='maxAppliedForce', full_name='pybullet_grpc.UserConstraintCommand.maxAppliedForce', index=8, + number=9, 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='userConstraintUniqueId', full_name='pybullet_grpc.UserConstraintCommand.userConstraintUniqueId', index=9, + number=10, 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='gearRatio', full_name='pybullet_grpc.UserConstraintCommand.gearRatio', index=10, + number=11, 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='gearAuxLink', full_name='pybullet_grpc.UserConstraintCommand.gearAuxLink', index=11, + number=12, 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='relativePositionTarget', full_name='pybullet_grpc.UserConstraintCommand.relativePositionTarget', index=12, + number=13, 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='erp', full_name='pybullet_grpc.UserConstraintCommand.erp', index=13, + number=14, 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='updateFlags', full_name='pybullet_grpc.UserConstraintCommand.updateFlags', index=14, + number=15, 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=4528, + serialized_end=4966, +) + + +_USERCONSTRAINTSTATUS = _descriptor.Descriptor( + name='UserConstraintStatus', + full_name='pybullet_grpc.UserConstraintStatus', + filename=None, + file=DESCRIPTOR, + containing_type=None, + fields=[ + _descriptor.FieldDescriptor( + name='maxAppliedForce', full_name='pybullet_grpc.UserConstraintStatus.maxAppliedForce', index=0, + number=9, 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='userConstraintUniqueId', full_name='pybullet_grpc.UserConstraintStatus.userConstraintUniqueId', index=1, + number=10, 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=4968, + serialized_end=5047, +) + + +_USERCONSTRAINTSTATESTATUS = _descriptor.Descriptor( + name='UserConstraintStateStatus', + full_name='pybullet_grpc.UserConstraintStateStatus', + filename=None, + file=DESCRIPTOR, + containing_type=None, + fields=[ + _descriptor.FieldDescriptor( + name='appliedConstraintForcesLinear', full_name='pybullet_grpc.UserConstraintStateStatus.appliedConstraintForcesLinear', index=0, + number=1, 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='appliedConstraintForcesAngular', full_name='pybullet_grpc.UserConstraintStateStatus.appliedConstraintForcesAngular', 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='numDofs', full_name='pybullet_grpc.UserConstraintStateStatus.numDofs', index=2, + number=3, 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=5050, + serialized_end=5215, +) + + +_REQUESTKEYBOARDEVENTSCOMMAND = _descriptor.Descriptor( + name='RequestKeyboardEventsCommand', + full_name='pybullet_grpc.RequestKeyboardEventsCommand', + 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=5217, + serialized_end=5247, +) + + +_KEYBOARDEVENT = _descriptor.Descriptor( + name='KeyboardEvent', + full_name='pybullet_grpc.KeyboardEvent', + filename=None, + file=DESCRIPTOR, + containing_type=None, + fields=[ + _descriptor.FieldDescriptor( + name='keyCode', full_name='pybullet_grpc.KeyboardEvent.keyCode', 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='keyState', full_name='pybullet_grpc.KeyboardEvent.keyState', index=1, + number=2, 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=5249, + serialized_end=5299, +) + + +_KEYBOARDEVENTSSTATUS = _descriptor.Descriptor( + name='KeyboardEventsStatus', + full_name='pybullet_grpc.KeyboardEventsStatus', + filename=None, + file=DESCRIPTOR, + containing_type=None, + fields=[ + _descriptor.FieldDescriptor( + name='keyboardEvents', full_name='pybullet_grpc.KeyboardEventsStatus.keyboardEvents', index=0, + number=1, type=11, cpp_type=10, label=3, + has_default_value=False, default_value=[], + 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=5301, + serialized_end=5377, +) + + +_REQUESTCAMERAIMAGECOMMAND = _descriptor.Descriptor( + name='RequestCameraImageCommand', + full_name='pybullet_grpc.RequestCameraImageCommand', + filename=None, + file=DESCRIPTOR, + containing_type=None, + fields=[ + _descriptor.FieldDescriptor( + name='updateFlags', full_name='pybullet_grpc.RequestCameraImageCommand.updateFlags', 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='cameraFlags', full_name='pybullet_grpc.RequestCameraImageCommand.cameraFlags', index=1, + number=2, 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='viewMatrix', full_name='pybullet_grpc.RequestCameraImageCommand.viewMatrix', 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='projectionMatrix', full_name='pybullet_grpc.RequestCameraImageCommand.projectionMatrix', index=3, + 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='startPixelIndex', full_name='pybullet_grpc.RequestCameraImageCommand.startPixelIndex', index=4, + number=5, 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='pixelWidth', full_name='pybullet_grpc.RequestCameraImageCommand.pixelWidth', 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='pixelHeight', full_name='pybullet_grpc.RequestCameraImageCommand.pixelHeight', index=6, + number=7, 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='lightDirection', full_name='pybullet_grpc.RequestCameraImageCommand.lightDirection', index=7, + number=8, 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='lightColor', full_name='pybullet_grpc.RequestCameraImageCommand.lightColor', index=8, + number=9, 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='lightDistance', full_name='pybullet_grpc.RequestCameraImageCommand.lightDistance', index=9, + number=10, 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='lightAmbientCoeff', full_name='pybullet_grpc.RequestCameraImageCommand.lightAmbientCoeff', index=10, + number=11, 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='lightDiffuseCoeff', full_name='pybullet_grpc.RequestCameraImageCommand.lightDiffuseCoeff', index=11, + number=12, 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='lightSpecularCoeff', full_name='pybullet_grpc.RequestCameraImageCommand.lightSpecularCoeff', index=12, + number=13, 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='hasShadow', full_name='pybullet_grpc.RequestCameraImageCommand.hasShadow', index=13, + number=14, 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='projectiveTextureViewMatrix', full_name='pybullet_grpc.RequestCameraImageCommand.projectiveTextureViewMatrix', index=14, + number=15, 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='projectiveTextureProjectionMatrix', full_name='pybullet_grpc.RequestCameraImageCommand.projectiveTextureProjectionMatrix', index=15, + number=16, 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=[ + ], + serialized_start=5380, + serialized_end=5955, +) + + +_REQUESTCAMERAIMAGESTATUS = _descriptor.Descriptor( + name='RequestCameraImageStatus', + full_name='pybullet_grpc.RequestCameraImageStatus', + filename=None, + file=DESCRIPTOR, + containing_type=None, + fields=[ + _descriptor.FieldDescriptor( + name='imageWidth', full_name='pybullet_grpc.RequestCameraImageStatus.imageWidth', 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='imageHeight', full_name='pybullet_grpc.RequestCameraImageStatus.imageHeight', index=1, + number=2, 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='startingPixelIndex', full_name='pybullet_grpc.RequestCameraImageStatus.startingPixelIndex', index=2, + number=3, 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='numPixelsCopied', full_name='pybullet_grpc.RequestCameraImageStatus.numPixelsCopied', 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='numRemainingPixels', full_name='pybullet_grpc.RequestCameraImageStatus.numRemainingPixels', index=4, + number=5, 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=5958, + serialized_end=6106, ) @@ -1006,68 +2252,145 @@ _PYBULLETCOMMAND = _descriptor.Descriptor( 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, + name='binaryBlob', full_name='pybullet_grpc.PyBulletCommand.binaryBlob', index=1, + number=2, type=12, cpp_type=9, label=3, + has_default_value=False, default_value=[], 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, + name='unknownCommandBinaryBlob', full_name='pybullet_grpc.PyBulletCommand.unknownCommandBinaryBlob', index=2, + number=3, type=12, cpp_type=9, label=3, + has_default_value=False, default_value=[], + 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=3, 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, + name='terminateServerCommand', full_name='pybullet_grpc.PyBulletCommand.terminateServerCommand', index=4, 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), _descriptor.FieldDescriptor( - name='loadSdfCommand', full_name='pybullet_grpc.PyBulletCommand.loadSdfCommand', index=4, + name='stepSimulationCommand', full_name='pybullet_grpc.PyBulletCommand.stepSimulationCommand', index=5, number=6, 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='loadMjcfCommand', full_name='pybullet_grpc.PyBulletCommand.loadMjcfCommand', index=5, + name='loadSdfCommand', full_name='pybullet_grpc.PyBulletCommand.loadSdfCommand', index=6, number=7, 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='changeDynamicsCommand', full_name='pybullet_grpc.PyBulletCommand.changeDynamicsCommand', index=6, + name='loadMjcfCommand', full_name='pybullet_grpc.PyBulletCommand.loadMjcfCommand', index=7, number=8, 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='getDynamicsCommand', full_name='pybullet_grpc.PyBulletCommand.getDynamicsCommand', index=7, + name='changeDynamicsCommand', full_name='pybullet_grpc.PyBulletCommand.changeDynamicsCommand', index=8, number=9, 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='initPoseCommand', full_name='pybullet_grpc.PyBulletCommand.initPoseCommand', index=8, + name='getDynamicsCommand', full_name='pybullet_grpc.PyBulletCommand.getDynamicsCommand', index=9, number=10, 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='requestActualStateCommand', full_name='pybullet_grpc.PyBulletCommand.requestActualStateCommand', index=9, + name='initPoseCommand', full_name='pybullet_grpc.PyBulletCommand.initPoseCommand', index=10, number=11, 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='requestActualStateCommand', full_name='pybullet_grpc.PyBulletCommand.requestActualStateCommand', index=11, + number=12, 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='configureOpenGLVisualizerCommand', full_name='pybullet_grpc.PyBulletCommand.configureOpenGLVisualizerCommand', index=12, + number=13, 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='syncBodiesCommand', full_name='pybullet_grpc.PyBulletCommand.syncBodiesCommand', index=13, + number=14, 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='requestBodyInfoCommand', full_name='pybullet_grpc.PyBulletCommand.requestBodyInfoCommand', index=14, + number=15, 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='setPhysicsSimulationParametersCommand', full_name='pybullet_grpc.PyBulletCommand.setPhysicsSimulationParametersCommand', index=15, + number=16, 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='jointMotorControlCommand', full_name='pybullet_grpc.PyBulletCommand.jointMotorControlCommand', index=16, + number=17, 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='userConstraintCommand', full_name='pybullet_grpc.PyBulletCommand.userConstraintCommand', index=17, + number=18, 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='checkVersionCommand', full_name='pybullet_grpc.PyBulletCommand.checkVersionCommand', index=18, + number=19, 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='requestKeyboardEventsCommand', full_name='pybullet_grpc.PyBulletCommand.requestKeyboardEventsCommand', index=19, + number=20, 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='requestCameraImageCommand', full_name='pybullet_grpc.PyBulletCommand.requestCameraImageCommand', index=20, + number=21, 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=[ ], @@ -1083,8 +2406,8 @@ _PYBULLETCOMMAND = _descriptor.Descriptor( name='commands', full_name='pybullet_grpc.PyBulletCommand.commands', index=0, containing_type=None, fields=[]), ], - serialized_start=2619, - serialized_end=3262, + serialized_start=6109, + serialized_end=7514, ) @@ -1103,40 +2426,110 @@ _PYBULLETSTATUS = _descriptor.Descriptor( 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, + name='binaryBlob', full_name='pybullet_grpc.PyBulletStatus.binaryBlob', index=1, + number=2, type=12, cpp_type=9, label=3, + has_default_value=False, default_value=[], message_type=None, enum_type=None, containing_type=None, is_extension=False, extension_scope=None, options=None, file=DESCRIPTOR), _descriptor.FieldDescriptor( - name='sdfStatus', full_name='pybullet_grpc.PyBulletStatus.sdfStatus', index=2, - number=3, type=11, cpp_type=10, label=1, - has_default_value=False, default_value=None, + name='unknownStatusBinaryBlob', full_name='pybullet_grpc.PyBulletStatus.unknownStatusBinaryBlob', index=2, + number=3, type=12, cpp_type=9, label=3, + has_default_value=False, default_value=[], message_type=None, enum_type=None, containing_type=None, is_extension=False, extension_scope=None, options=None, file=DESCRIPTOR), _descriptor.FieldDescriptor( - name='mjcfStatus', full_name='pybullet_grpc.PyBulletStatus.mjcfStatus', index=3, + name='urdfStatus', full_name='pybullet_grpc.PyBulletStatus.urdfStatus', index=3, 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='getDynamicsStatus', full_name='pybullet_grpc.PyBulletStatus.getDynamicsStatus', index=4, + name='sdfStatus', full_name='pybullet_grpc.PyBulletStatus.sdfStatus', index=4, 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), _descriptor.FieldDescriptor( - name='actualStateStatus', full_name='pybullet_grpc.PyBulletStatus.actualStateStatus', index=5, + name='mjcfStatus', full_name='pybullet_grpc.PyBulletStatus.mjcfStatus', index=5, number=6, 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='getDynamicsStatus', full_name='pybullet_grpc.PyBulletStatus.getDynamicsStatus', index=6, + number=7, 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='actualStateStatus', full_name='pybullet_grpc.PyBulletStatus.actualStateStatus', index=7, + number=8, 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='syncBodiesStatus', full_name='pybullet_grpc.PyBulletStatus.syncBodiesStatus', index=8, + number=9, 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='requestBodyInfoStatus', full_name='pybullet_grpc.PyBulletStatus.requestBodyInfoStatus', index=9, + number=10, 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='requestPhysicsSimulationParametersStatus', full_name='pybullet_grpc.PyBulletStatus.requestPhysicsSimulationParametersStatus', index=10, + number=11, 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='checkVersionStatus', full_name='pybullet_grpc.PyBulletStatus.checkVersionStatus', index=11, + number=12, 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='userConstraintStatus', full_name='pybullet_grpc.PyBulletStatus.userConstraintStatus', index=12, + number=13, 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='userConstraintStateStatus', full_name='pybullet_grpc.PyBulletStatus.userConstraintStateStatus', index=13, + number=14, 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='keyboardEventsStatus', full_name='pybullet_grpc.PyBulletStatus.keyboardEventsStatus', index=14, + number=15, 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='requestCameraImageStatus', full_name='pybullet_grpc.PyBulletStatus.requestCameraImageStatus', index=15, + number=16, 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=[ ], @@ -1152,10 +2545,12 @@ _PYBULLETSTATUS = _descriptor.Descriptor( name='status', full_name='pybullet_grpc.PyBulletStatus.status', index=0, containing_type=None, fields=[]), ], - serialized_start=3265, - serialized_end=3602, + serialized_start=7517, + serialized_end=8494, ) +_TRANSFORM.fields_by_name['origin'].message_type = _VEC3 +_TRANSFORM.fields_by_name['orientation'].message_type = _QUAT4 _LOADURDFCOMMAND.fields_by_name['initialPosition'].message_type = _VEC3 _LOADURDFCOMMAND.fields_by_name['initialOrientation'].message_type = _QUAT4 _LOADURDFCOMMAND.oneofs_by_name['hasUseMultiBody'].fields.append( @@ -1217,6 +2612,21 @@ _CHANGEDYNAMICSCOMMAND.oneofs_by_name['hasActivationState'].fields.append( _CHANGEDYNAMICSCOMMAND.fields_by_name['activationState']) _CHANGEDYNAMICSCOMMAND.fields_by_name['activationState'].containing_oneof = _CHANGEDYNAMICSCOMMAND.oneofs_by_name['hasActivationState'] _GETDYNAMICSSTATUS.fields_by_name['localInertiaDiagonal'].message_type = _VEC3 +_CONFIGUREOPENGLVISUALIZERCOMMAND.fields_by_name['cameraTargetPosition'].message_type = _VEC3 +_PHYSICSSIMULATIONPARAMETERS.fields_by_name['gravityAcceleration'].message_type = _VEC3 +_PHYSICSSIMULATIONPARAMETERSCOMMAND.fields_by_name['params'].message_type = _PHYSICSSIMULATIONPARAMETERS +_USERCONSTRAINTCOMMAND.fields_by_name['parentFrame'].message_type = _TRANSFORM +_USERCONSTRAINTCOMMAND.fields_by_name['childFrame'].message_type = _TRANSFORM +_USERCONSTRAINTCOMMAND.fields_by_name['jointAxis'].message_type = _VEC3 +_USERCONSTRAINTSTATESTATUS.fields_by_name['appliedConstraintForcesLinear'].message_type = _VEC3 +_USERCONSTRAINTSTATESTATUS.fields_by_name['appliedConstraintForcesAngular'].message_type = _VEC3 +_KEYBOARDEVENTSSTATUS.fields_by_name['keyboardEvents'].message_type = _KEYBOARDEVENT +_REQUESTCAMERAIMAGECOMMAND.fields_by_name['viewMatrix'].message_type = _MATRIX4X4 +_REQUESTCAMERAIMAGECOMMAND.fields_by_name['projectionMatrix'].message_type = _MATRIX4X4 +_REQUESTCAMERAIMAGECOMMAND.fields_by_name['lightDirection'].message_type = _VEC3 +_REQUESTCAMERAIMAGECOMMAND.fields_by_name['lightColor'].message_type = _VEC3 +_REQUESTCAMERAIMAGECOMMAND.fields_by_name['projectiveTextureViewMatrix'].message_type = _MATRIX4X4 +_REQUESTCAMERAIMAGECOMMAND.fields_by_name['projectiveTextureProjectionMatrix'].message_type = _MATRIX4X4 _PYBULLETCOMMAND.fields_by_name['loadUrdfCommand'].message_type = _LOADURDFCOMMAND _PYBULLETCOMMAND.fields_by_name['terminateServerCommand'].message_type = _TERMINATESERVERCOMMAND _PYBULLETCOMMAND.fields_by_name['stepSimulationCommand'].message_type = _STEPSIMULATIONCOMMAND @@ -1226,6 +2636,15 @@ _PYBULLETCOMMAND.fields_by_name['changeDynamicsCommand'].message_type = _CHANGED _PYBULLETCOMMAND.fields_by_name['getDynamicsCommand'].message_type = _GETDYNAMICSCOMMAND _PYBULLETCOMMAND.fields_by_name['initPoseCommand'].message_type = _INITPOSECOMMAND _PYBULLETCOMMAND.fields_by_name['requestActualStateCommand'].message_type = _REQUESTACTUALSTATECOMMAND +_PYBULLETCOMMAND.fields_by_name['configureOpenGLVisualizerCommand'].message_type = _CONFIGUREOPENGLVISUALIZERCOMMAND +_PYBULLETCOMMAND.fields_by_name['syncBodiesCommand'].message_type = _SYNCBODIESCOMMAND +_PYBULLETCOMMAND.fields_by_name['requestBodyInfoCommand'].message_type = _REQUESTBODYINFOCOMMAND +_PYBULLETCOMMAND.fields_by_name['setPhysicsSimulationParametersCommand'].message_type = _PHYSICSSIMULATIONPARAMETERSCOMMAND +_PYBULLETCOMMAND.fields_by_name['jointMotorControlCommand'].message_type = _JOINTMOTORCONTROLCOMMAND +_PYBULLETCOMMAND.fields_by_name['userConstraintCommand'].message_type = _USERCONSTRAINTCOMMAND +_PYBULLETCOMMAND.fields_by_name['checkVersionCommand'].message_type = _CHECKVERSIONCOMMAND +_PYBULLETCOMMAND.fields_by_name['requestKeyboardEventsCommand'].message_type = _REQUESTKEYBOARDEVENTSCOMMAND +_PYBULLETCOMMAND.fields_by_name['requestCameraImageCommand'].message_type = _REQUESTCAMERAIMAGECOMMAND _PYBULLETCOMMAND.oneofs_by_name['commands'].fields.append( _PYBULLETCOMMAND.fields_by_name['loadUrdfCommand']) _PYBULLETCOMMAND.fields_by_name['loadUrdfCommand'].containing_oneof = _PYBULLETCOMMAND.oneofs_by_name['commands'] @@ -1253,11 +2672,46 @@ _PYBULLETCOMMAND.fields_by_name['initPoseCommand'].containing_oneof = _PYBULLETC _PYBULLETCOMMAND.oneofs_by_name['commands'].fields.append( _PYBULLETCOMMAND.fields_by_name['requestActualStateCommand']) _PYBULLETCOMMAND.fields_by_name['requestActualStateCommand'].containing_oneof = _PYBULLETCOMMAND.oneofs_by_name['commands'] +_PYBULLETCOMMAND.oneofs_by_name['commands'].fields.append( + _PYBULLETCOMMAND.fields_by_name['configureOpenGLVisualizerCommand']) +_PYBULLETCOMMAND.fields_by_name['configureOpenGLVisualizerCommand'].containing_oneof = _PYBULLETCOMMAND.oneofs_by_name['commands'] +_PYBULLETCOMMAND.oneofs_by_name['commands'].fields.append( + _PYBULLETCOMMAND.fields_by_name['syncBodiesCommand']) +_PYBULLETCOMMAND.fields_by_name['syncBodiesCommand'].containing_oneof = _PYBULLETCOMMAND.oneofs_by_name['commands'] +_PYBULLETCOMMAND.oneofs_by_name['commands'].fields.append( + _PYBULLETCOMMAND.fields_by_name['requestBodyInfoCommand']) +_PYBULLETCOMMAND.fields_by_name['requestBodyInfoCommand'].containing_oneof = _PYBULLETCOMMAND.oneofs_by_name['commands'] +_PYBULLETCOMMAND.oneofs_by_name['commands'].fields.append( + _PYBULLETCOMMAND.fields_by_name['setPhysicsSimulationParametersCommand']) +_PYBULLETCOMMAND.fields_by_name['setPhysicsSimulationParametersCommand'].containing_oneof = _PYBULLETCOMMAND.oneofs_by_name['commands'] +_PYBULLETCOMMAND.oneofs_by_name['commands'].fields.append( + _PYBULLETCOMMAND.fields_by_name['jointMotorControlCommand']) +_PYBULLETCOMMAND.fields_by_name['jointMotorControlCommand'].containing_oneof = _PYBULLETCOMMAND.oneofs_by_name['commands'] +_PYBULLETCOMMAND.oneofs_by_name['commands'].fields.append( + _PYBULLETCOMMAND.fields_by_name['userConstraintCommand']) +_PYBULLETCOMMAND.fields_by_name['userConstraintCommand'].containing_oneof = _PYBULLETCOMMAND.oneofs_by_name['commands'] +_PYBULLETCOMMAND.oneofs_by_name['commands'].fields.append( + _PYBULLETCOMMAND.fields_by_name['checkVersionCommand']) +_PYBULLETCOMMAND.fields_by_name['checkVersionCommand'].containing_oneof = _PYBULLETCOMMAND.oneofs_by_name['commands'] +_PYBULLETCOMMAND.oneofs_by_name['commands'].fields.append( + _PYBULLETCOMMAND.fields_by_name['requestKeyboardEventsCommand']) +_PYBULLETCOMMAND.fields_by_name['requestKeyboardEventsCommand'].containing_oneof = _PYBULLETCOMMAND.oneofs_by_name['commands'] +_PYBULLETCOMMAND.oneofs_by_name['commands'].fields.append( + _PYBULLETCOMMAND.fields_by_name['requestCameraImageCommand']) +_PYBULLETCOMMAND.fields_by_name['requestCameraImageCommand'].containing_oneof = _PYBULLETCOMMAND.oneofs_by_name['commands'] _PYBULLETSTATUS.fields_by_name['urdfStatus'].message_type = _LOADURDFSTATUS _PYBULLETSTATUS.fields_by_name['sdfStatus'].message_type = _SDFLOADEDSTATUS _PYBULLETSTATUS.fields_by_name['mjcfStatus'].message_type = _MJCFLOADEDSTATUS _PYBULLETSTATUS.fields_by_name['getDynamicsStatus'].message_type = _GETDYNAMICSSTATUS _PYBULLETSTATUS.fields_by_name['actualStateStatus'].message_type = _SENDACTUALSTATESTATUS +_PYBULLETSTATUS.fields_by_name['syncBodiesStatus'].message_type = _SYNCBODIESSTATUS +_PYBULLETSTATUS.fields_by_name['requestBodyInfoStatus'].message_type = _REQUESTBODYINFOSTATUS +_PYBULLETSTATUS.fields_by_name['requestPhysicsSimulationParametersStatus'].message_type = _PHYSICSSIMULATIONPARAMETERS +_PYBULLETSTATUS.fields_by_name['checkVersionStatus'].message_type = _CHECKVERSIONSTATUS +_PYBULLETSTATUS.fields_by_name['userConstraintStatus'].message_type = _USERCONSTRAINTSTATUS +_PYBULLETSTATUS.fields_by_name['userConstraintStateStatus'].message_type = _USERCONSTRAINTSTATESTATUS +_PYBULLETSTATUS.fields_by_name['keyboardEventsStatus'].message_type = _KEYBOARDEVENTSSTATUS +_PYBULLETSTATUS.fields_by_name['requestCameraImageStatus'].message_type = _REQUESTCAMERAIMAGESTATUS _PYBULLETSTATUS.oneofs_by_name['status'].fields.append( _PYBULLETSTATUS.fields_by_name['urdfStatus']) _PYBULLETSTATUS.fields_by_name['urdfStatus'].containing_oneof = _PYBULLETSTATUS.oneofs_by_name['status'] @@ -1273,10 +2727,43 @@ _PYBULLETSTATUS.fields_by_name['getDynamicsStatus'].containing_oneof = _PYBULLET _PYBULLETSTATUS.oneofs_by_name['status'].fields.append( _PYBULLETSTATUS.fields_by_name['actualStateStatus']) _PYBULLETSTATUS.fields_by_name['actualStateStatus'].containing_oneof = _PYBULLETSTATUS.oneofs_by_name['status'] +_PYBULLETSTATUS.oneofs_by_name['status'].fields.append( + _PYBULLETSTATUS.fields_by_name['syncBodiesStatus']) +_PYBULLETSTATUS.fields_by_name['syncBodiesStatus'].containing_oneof = _PYBULLETSTATUS.oneofs_by_name['status'] +_PYBULLETSTATUS.oneofs_by_name['status'].fields.append( + _PYBULLETSTATUS.fields_by_name['requestBodyInfoStatus']) +_PYBULLETSTATUS.fields_by_name['requestBodyInfoStatus'].containing_oneof = _PYBULLETSTATUS.oneofs_by_name['status'] +_PYBULLETSTATUS.oneofs_by_name['status'].fields.append( + _PYBULLETSTATUS.fields_by_name['requestPhysicsSimulationParametersStatus']) +_PYBULLETSTATUS.fields_by_name['requestPhysicsSimulationParametersStatus'].containing_oneof = _PYBULLETSTATUS.oneofs_by_name['status'] +_PYBULLETSTATUS.oneofs_by_name['status'].fields.append( + _PYBULLETSTATUS.fields_by_name['checkVersionStatus']) +_PYBULLETSTATUS.fields_by_name['checkVersionStatus'].containing_oneof = _PYBULLETSTATUS.oneofs_by_name['status'] +_PYBULLETSTATUS.oneofs_by_name['status'].fields.append( + _PYBULLETSTATUS.fields_by_name['userConstraintStatus']) +_PYBULLETSTATUS.fields_by_name['userConstraintStatus'].containing_oneof = _PYBULLETSTATUS.oneofs_by_name['status'] +_PYBULLETSTATUS.oneofs_by_name['status'].fields.append( + _PYBULLETSTATUS.fields_by_name['userConstraintStateStatus']) +_PYBULLETSTATUS.fields_by_name['userConstraintStateStatus'].containing_oneof = _PYBULLETSTATUS.oneofs_by_name['status'] +_PYBULLETSTATUS.oneofs_by_name['status'].fields.append( + _PYBULLETSTATUS.fields_by_name['keyboardEventsStatus']) +_PYBULLETSTATUS.fields_by_name['keyboardEventsStatus'].containing_oneof = _PYBULLETSTATUS.oneofs_by_name['status'] +_PYBULLETSTATUS.oneofs_by_name['status'].fields.append( + _PYBULLETSTATUS.fields_by_name['requestCameraImageStatus']) +_PYBULLETSTATUS.fields_by_name['requestCameraImageStatus'].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['vec4'] = _VEC4 +DESCRIPTOR.message_types_by_name['transform'] = _TRANSFORM +DESCRIPTOR.message_types_by_name['matrix4x4'] = _MATRIX4X4 +DESCRIPTOR.message_types_by_name['CheckVersionCommand'] = _CHECKVERSIONCOMMAND +DESCRIPTOR.message_types_by_name['CheckVersionStatus'] = _CHECKVERSIONSTATUS DESCRIPTOR.message_types_by_name['TerminateServerCommand'] = _TERMINATESERVERCOMMAND DESCRIPTOR.message_types_by_name['StepSimulationCommand'] = _STEPSIMULATIONCOMMAND +DESCRIPTOR.message_types_by_name['SyncBodiesCommand'] = _SYNCBODIESCOMMAND +DESCRIPTOR.message_types_by_name['SyncBodiesStatus'] = _SYNCBODIESSTATUS +DESCRIPTOR.message_types_by_name['RequestBodyInfoCommand'] = _REQUESTBODYINFOCOMMAND +DESCRIPTOR.message_types_by_name['RequestBodyInfoStatus'] = _REQUESTBODYINFOSTATUS DESCRIPTOR.message_types_by_name['LoadUrdfCommand'] = _LOADURDFCOMMAND DESCRIPTOR.message_types_by_name['LoadUrdfStatus'] = _LOADURDFSTATUS DESCRIPTOR.message_types_by_name['LoadSdfCommand'] = _LOADSDFCOMMAND @@ -1289,6 +2776,18 @@ DESCRIPTOR.message_types_by_name['GetDynamicsStatus'] = _GETDYNAMICSSTATUS DESCRIPTOR.message_types_by_name['InitPoseCommand'] = _INITPOSECOMMAND DESCRIPTOR.message_types_by_name['RequestActualStateCommand'] = _REQUESTACTUALSTATECOMMAND DESCRIPTOR.message_types_by_name['SendActualStateStatus'] = _SENDACTUALSTATESTATUS +DESCRIPTOR.message_types_by_name['ConfigureOpenGLVisualizerCommand'] = _CONFIGUREOPENGLVISUALIZERCOMMAND +DESCRIPTOR.message_types_by_name['PhysicsSimulationParameters'] = _PHYSICSSIMULATIONPARAMETERS +DESCRIPTOR.message_types_by_name['PhysicsSimulationParametersCommand'] = _PHYSICSSIMULATIONPARAMETERSCOMMAND +DESCRIPTOR.message_types_by_name['JointMotorControlCommand'] = _JOINTMOTORCONTROLCOMMAND +DESCRIPTOR.message_types_by_name['UserConstraintCommand'] = _USERCONSTRAINTCOMMAND +DESCRIPTOR.message_types_by_name['UserConstraintStatus'] = _USERCONSTRAINTSTATUS +DESCRIPTOR.message_types_by_name['UserConstraintStateStatus'] = _USERCONSTRAINTSTATESTATUS +DESCRIPTOR.message_types_by_name['RequestKeyboardEventsCommand'] = _REQUESTKEYBOARDEVENTSCOMMAND +DESCRIPTOR.message_types_by_name['KeyboardEvent'] = _KEYBOARDEVENT +DESCRIPTOR.message_types_by_name['KeyboardEventsStatus'] = _KEYBOARDEVENTSSTATUS +DESCRIPTOR.message_types_by_name['RequestCameraImageCommand'] = _REQUESTCAMERAIMAGECOMMAND +DESCRIPTOR.message_types_by_name['RequestCameraImageStatus'] = _REQUESTCAMERAIMAGESTATUS DESCRIPTOR.message_types_by_name['PyBulletCommand'] = _PYBULLETCOMMAND DESCRIPTOR.message_types_by_name['PyBulletStatus'] = _PYBULLETSTATUS _sym_db.RegisterFileDescriptor(DESCRIPTOR) @@ -1307,6 +2806,41 @@ quat4 = _reflection.GeneratedProtocolMessageType('quat4', (_message.Message,), d )) _sym_db.RegisterMessage(quat4) +vec4 = _reflection.GeneratedProtocolMessageType('vec4', (_message.Message,), dict( + DESCRIPTOR = _VEC4, + __module__ = 'pybullet_pb2' + # @@protoc_insertion_point(class_scope:pybullet_grpc.vec4) + )) +_sym_db.RegisterMessage(vec4) + +transform = _reflection.GeneratedProtocolMessageType('transform', (_message.Message,), dict( + DESCRIPTOR = _TRANSFORM, + __module__ = 'pybullet_pb2' + # @@protoc_insertion_point(class_scope:pybullet_grpc.transform) + )) +_sym_db.RegisterMessage(transform) + +matrix4x4 = _reflection.GeneratedProtocolMessageType('matrix4x4', (_message.Message,), dict( + DESCRIPTOR = _MATRIX4X4, + __module__ = 'pybullet_pb2' + # @@protoc_insertion_point(class_scope:pybullet_grpc.matrix4x4) + )) +_sym_db.RegisterMessage(matrix4x4) + +CheckVersionCommand = _reflection.GeneratedProtocolMessageType('CheckVersionCommand', (_message.Message,), dict( + DESCRIPTOR = _CHECKVERSIONCOMMAND, + __module__ = 'pybullet_pb2' + # @@protoc_insertion_point(class_scope:pybullet_grpc.CheckVersionCommand) + )) +_sym_db.RegisterMessage(CheckVersionCommand) + +CheckVersionStatus = _reflection.GeneratedProtocolMessageType('CheckVersionStatus', (_message.Message,), dict( + DESCRIPTOR = _CHECKVERSIONSTATUS, + __module__ = 'pybullet_pb2' + # @@protoc_insertion_point(class_scope:pybullet_grpc.CheckVersionStatus) + )) +_sym_db.RegisterMessage(CheckVersionStatus) + TerminateServerCommand = _reflection.GeneratedProtocolMessageType('TerminateServerCommand', (_message.Message,), dict( DESCRIPTOR = _TERMINATESERVERCOMMAND, __module__ = 'pybullet_pb2' @@ -1321,6 +2855,34 @@ StepSimulationCommand = _reflection.GeneratedProtocolMessageType('StepSimulation )) _sym_db.RegisterMessage(StepSimulationCommand) +SyncBodiesCommand = _reflection.GeneratedProtocolMessageType('SyncBodiesCommand', (_message.Message,), dict( + DESCRIPTOR = _SYNCBODIESCOMMAND, + __module__ = 'pybullet_pb2' + # @@protoc_insertion_point(class_scope:pybullet_grpc.SyncBodiesCommand) + )) +_sym_db.RegisterMessage(SyncBodiesCommand) + +SyncBodiesStatus = _reflection.GeneratedProtocolMessageType('SyncBodiesStatus', (_message.Message,), dict( + DESCRIPTOR = _SYNCBODIESSTATUS, + __module__ = 'pybullet_pb2' + # @@protoc_insertion_point(class_scope:pybullet_grpc.SyncBodiesStatus) + )) +_sym_db.RegisterMessage(SyncBodiesStatus) + +RequestBodyInfoCommand = _reflection.GeneratedProtocolMessageType('RequestBodyInfoCommand', (_message.Message,), dict( + DESCRIPTOR = _REQUESTBODYINFOCOMMAND, + __module__ = 'pybullet_pb2' + # @@protoc_insertion_point(class_scope:pybullet_grpc.RequestBodyInfoCommand) + )) +_sym_db.RegisterMessage(RequestBodyInfoCommand) + +RequestBodyInfoStatus = _reflection.GeneratedProtocolMessageType('RequestBodyInfoStatus', (_message.Message,), dict( + DESCRIPTOR = _REQUESTBODYINFOSTATUS, + __module__ = 'pybullet_pb2' + # @@protoc_insertion_point(class_scope:pybullet_grpc.RequestBodyInfoStatus) + )) +_sym_db.RegisterMessage(RequestBodyInfoStatus) + LoadUrdfCommand = _reflection.GeneratedProtocolMessageType('LoadUrdfCommand', (_message.Message,), dict( DESCRIPTOR = _LOADURDFCOMMAND, __module__ = 'pybullet_pb2' @@ -1405,6 +2967,90 @@ SendActualStateStatus = _reflection.GeneratedProtocolMessageType('SendActualStat )) _sym_db.RegisterMessage(SendActualStateStatus) +ConfigureOpenGLVisualizerCommand = _reflection.GeneratedProtocolMessageType('ConfigureOpenGLVisualizerCommand', (_message.Message,), dict( + DESCRIPTOR = _CONFIGUREOPENGLVISUALIZERCOMMAND, + __module__ = 'pybullet_pb2' + # @@protoc_insertion_point(class_scope:pybullet_grpc.ConfigureOpenGLVisualizerCommand) + )) +_sym_db.RegisterMessage(ConfigureOpenGLVisualizerCommand) + +PhysicsSimulationParameters = _reflection.GeneratedProtocolMessageType('PhysicsSimulationParameters', (_message.Message,), dict( + DESCRIPTOR = _PHYSICSSIMULATIONPARAMETERS, + __module__ = 'pybullet_pb2' + # @@protoc_insertion_point(class_scope:pybullet_grpc.PhysicsSimulationParameters) + )) +_sym_db.RegisterMessage(PhysicsSimulationParameters) + +PhysicsSimulationParametersCommand = _reflection.GeneratedProtocolMessageType('PhysicsSimulationParametersCommand', (_message.Message,), dict( + DESCRIPTOR = _PHYSICSSIMULATIONPARAMETERSCOMMAND, + __module__ = 'pybullet_pb2' + # @@protoc_insertion_point(class_scope:pybullet_grpc.PhysicsSimulationParametersCommand) + )) +_sym_db.RegisterMessage(PhysicsSimulationParametersCommand) + +JointMotorControlCommand = _reflection.GeneratedProtocolMessageType('JointMotorControlCommand', (_message.Message,), dict( + DESCRIPTOR = _JOINTMOTORCONTROLCOMMAND, + __module__ = 'pybullet_pb2' + # @@protoc_insertion_point(class_scope:pybullet_grpc.JointMotorControlCommand) + )) +_sym_db.RegisterMessage(JointMotorControlCommand) + +UserConstraintCommand = _reflection.GeneratedProtocolMessageType('UserConstraintCommand', (_message.Message,), dict( + DESCRIPTOR = _USERCONSTRAINTCOMMAND, + __module__ = 'pybullet_pb2' + # @@protoc_insertion_point(class_scope:pybullet_grpc.UserConstraintCommand) + )) +_sym_db.RegisterMessage(UserConstraintCommand) + +UserConstraintStatus = _reflection.GeneratedProtocolMessageType('UserConstraintStatus', (_message.Message,), dict( + DESCRIPTOR = _USERCONSTRAINTSTATUS, + __module__ = 'pybullet_pb2' + # @@protoc_insertion_point(class_scope:pybullet_grpc.UserConstraintStatus) + )) +_sym_db.RegisterMessage(UserConstraintStatus) + +UserConstraintStateStatus = _reflection.GeneratedProtocolMessageType('UserConstraintStateStatus', (_message.Message,), dict( + DESCRIPTOR = _USERCONSTRAINTSTATESTATUS, + __module__ = 'pybullet_pb2' + # @@protoc_insertion_point(class_scope:pybullet_grpc.UserConstraintStateStatus) + )) +_sym_db.RegisterMessage(UserConstraintStateStatus) + +RequestKeyboardEventsCommand = _reflection.GeneratedProtocolMessageType('RequestKeyboardEventsCommand', (_message.Message,), dict( + DESCRIPTOR = _REQUESTKEYBOARDEVENTSCOMMAND, + __module__ = 'pybullet_pb2' + # @@protoc_insertion_point(class_scope:pybullet_grpc.RequestKeyboardEventsCommand) + )) +_sym_db.RegisterMessage(RequestKeyboardEventsCommand) + +KeyboardEvent = _reflection.GeneratedProtocolMessageType('KeyboardEvent', (_message.Message,), dict( + DESCRIPTOR = _KEYBOARDEVENT, + __module__ = 'pybullet_pb2' + # @@protoc_insertion_point(class_scope:pybullet_grpc.KeyboardEvent) + )) +_sym_db.RegisterMessage(KeyboardEvent) + +KeyboardEventsStatus = _reflection.GeneratedProtocolMessageType('KeyboardEventsStatus', (_message.Message,), dict( + DESCRIPTOR = _KEYBOARDEVENTSSTATUS, + __module__ = 'pybullet_pb2' + # @@protoc_insertion_point(class_scope:pybullet_grpc.KeyboardEventsStatus) + )) +_sym_db.RegisterMessage(KeyboardEventsStatus) + +RequestCameraImageCommand = _reflection.GeneratedProtocolMessageType('RequestCameraImageCommand', (_message.Message,), dict( + DESCRIPTOR = _REQUESTCAMERAIMAGECOMMAND, + __module__ = 'pybullet_pb2' + # @@protoc_insertion_point(class_scope:pybullet_grpc.RequestCameraImageCommand) + )) +_sym_db.RegisterMessage(RequestCameraImageCommand) + +RequestCameraImageStatus = _reflection.GeneratedProtocolMessageType('RequestCameraImageStatus', (_message.Message,), dict( + DESCRIPTOR = _REQUESTCAMERAIMAGESTATUS, + __module__ = 'pybullet_pb2' + # @@protoc_insertion_point(class_scope:pybullet_grpc.RequestCameraImageStatus) + )) +_sym_db.RegisterMessage(RequestCameraImageStatus) + PyBulletCommand = _reflection.GeneratedProtocolMessageType('PyBulletCommand', (_message.Message,), dict( DESCRIPTOR = _PYBULLETCOMMAND, __module__ = 'pybullet_pb2' @@ -1429,8 +3075,8 @@ _PYBULLETAPI = _descriptor.ServiceDescriptor( file=DESCRIPTOR, index=0, options=None, - serialized_start=3604, - serialized_end=3699, + serialized_start=8496, + serialized_end=8591, methods=[ _descriptor.MethodDescriptor( name='SubmitCommand', diff --git a/examples/pybullet/pybullet.c b/examples/pybullet/pybullet.c index 142a6902e..6ae55b9d0 100644 --- a/examples/pybullet/pybullet.c +++ b/examples/pybullet/pybullet.c @@ -14,6 +14,9 @@ #include "../SharedMemory/mujoco/MuJoCoPhysicsC_API.h" #endif +#ifdef BT_ENABLE_GRPC +#include "../SharedMemory/PhysicsClientGRPC_C_API.h" +#endif #ifdef BT_ENABLE_CLSOCKET #include "../SharedMemory/PhysicsClientTCP_C_API.h" #endif //BT_ENABLE_CLSOCKET @@ -431,7 +434,15 @@ static PyObject* pybullet_connectPhysicsServer(PyObject* self, PyObject* args, P break; } #endif - + case eCONNECT_GRPC: + { +#ifdef BT_ENABLE_GRPC + sm = b3ConnectPhysicsGRPC(hostName.c_str(), tcpPort); +#else + b3Warning("GRPC is not enabled in this pybullet build"); +#endif + break; + } case eCONNECT_SHARED_MEMORY: { sm = b3ConnectSharedMemory(key); @@ -9625,6 +9636,9 @@ initpybullet(void) #ifdef BT_ENABLE_MUJOCO PyModule_AddIntConstant(m, "MuJoCo", eCONNECT_MUJOCO); // user read #endif +#ifdef BT_ENABLE_GRPC + PyModule_AddIntConstant(m, "GRPC", eCONNECT_GRPC); // user read +#endif PyModule_AddIntConstant(m, "SHARED_MEMORY_KEY", SHARED_MEMORY_KEY); From 9b66074949381eeccc3e0f0667ce3f00e514c1f8 Mon Sep 17 00:00:00 2001 From: erwincoumans Date: Tue, 4 Sep 2018 09:10:57 -0700 Subject: [PATCH 3/3] add some missing GRPC files --- examples/SharedMemory/PhysicsClientGRPC.cpp | 236 ++++++++++++++++++ examples/SharedMemory/PhysicsClientGRPC.h | 41 +++ .../SharedMemory/PhysicsClientGRPC_C_API.cpp | 29 +++ .../SharedMemory/PhysicsClientGRPC_C_API.h | 19 ++ .../SharedMemory/grpc/ConvertGRPCBullet.cpp | 12 +- examples/pybullet/pybullet.c | 2 +- 6 files changed, 332 insertions(+), 7 deletions(-) create mode 100644 examples/SharedMemory/PhysicsClientGRPC.cpp create mode 100644 examples/SharedMemory/PhysicsClientGRPC.h create mode 100644 examples/SharedMemory/PhysicsClientGRPC_C_API.cpp create mode 100644 examples/SharedMemory/PhysicsClientGRPC_C_API.h diff --git a/examples/SharedMemory/PhysicsClientGRPC.cpp b/examples/SharedMemory/PhysicsClientGRPC.cpp new file mode 100644 index 000000000..05198b30f --- /dev/null +++ b/examples/SharedMemory/PhysicsClientGRPC.cpp @@ -0,0 +1,236 @@ +#ifdef BT_ENABLE_GRPC +#include "PhysicsClientGRPC.h" +#include "grpc/pybullet.grpc.pb.h" +#include +using grpc::Channel; +#include +#include +#include "../Utils/b3Clock.h" +#include "PhysicsClient.h" +//#include "LinearMath/btVector3.h" +#include "SharedMemoryCommands.h" +#include +#include "Bullet3Common/b3Logging.h" +#include "Bullet3Common/b3AlignedObjectArray.h" +#include "grpc/ConvertGRPCBullet.h" + + +static unsigned int b3DeserializeInt2(const unsigned char* input) +{ + unsigned int tmp = (input[3] << 24) + (input[2] << 16) + (input[1] << 8) + input[0]; + return tmp; +} + +bool gVerboseNetworkMessagesClient3 = false; + + +struct GRPCNetworkedInternalData +{ + std::shared_ptr m_grpcChannel; + std::unique_ptr< pybullet_grpc::PyBulletAPI::Stub> m_stub; + + + bool m_isConnected; + + SharedMemoryCommand m_clientCmd; + bool m_hasCommand; + + SharedMemoryStatus m_lastStatus; + b3AlignedObjectArray m_stream; + + std::string m_hostName; + int m_port; + + b3AlignedObjectArray m_tempBuffer; + double m_timeOutInSeconds; + + GRPCNetworkedInternalData() + : + m_isConnected(false), + m_hasCommand(false), + m_timeOutInSeconds(60) + { + + } + + void disconnect() + { + if (m_isConnected) + { + m_stub = 0; + m_grpcChannel = 0; + m_isConnected = false; + } + } + bool connectGRPC() + { + if (m_isConnected) + return true; + std::string hostport = m_hostName + ':' + std::to_string(m_port); + m_grpcChannel = grpc::CreateChannel( + hostport, grpc::InsecureChannelCredentials()); + + m_stub = pybullet_grpc::PyBulletAPI::NewStub(m_grpcChannel); + + + + // Set timeout for API + std::chrono::system_clock::time_point deadline = + std::chrono::system_clock::now()+std::chrono::seconds((long long)m_timeOutInSeconds); + grpc::ClientContext context; + context.set_deadline(deadline); + ::pybullet_grpc::PyBulletCommand request; + pybullet_grpc::CheckVersionCommand* cmd1 = request.mutable_checkversioncommand(); + cmd1->set_clientversion(SHARED_MEMORY_MAGIC_NUMBER); + ::pybullet_grpc::PyBulletStatus response; + // The actual RPC. + grpc::Status status = m_stub->SubmitCommand(&context, request, &response); + if (response.has_checkversionstatus()) + { + if (response.checkversionstatus().serverversion() == SHARED_MEMORY_MAGIC_NUMBER) + { + m_isConnected = true; + } + else + { + printf("Error: Client version (%d) is different from server version (%d)", SHARED_MEMORY_MAGIC_NUMBER, response.checkversionstatus().serverversion()); + } + } + else + { + printf("Error: cannot connect to GRPC server\n"); + } + + + + return m_isConnected; + } + + bool checkData() + { + + bool hasStatus = false; + return hasStatus; + } + +}; + + +GRPCNetworkedPhysicsProcessor::GRPCNetworkedPhysicsProcessor(const char* hostName, int port) +{ + m_data = new GRPCNetworkedInternalData; + if (hostName) + { + m_data->m_hostName = hostName; + } + m_data->m_port = port; + +} + +GRPCNetworkedPhysicsProcessor::~GRPCNetworkedPhysicsProcessor() +{ + disconnect(); + delete m_data; +} + +bool GRPCNetworkedPhysicsProcessor::processCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes) +{ + if(gVerboseNetworkMessagesClient3) + { + printf("GRPCNetworkedPhysicsProcessor::processCommand\n"); + } + + ::pybullet_grpc::PyBulletCommand grpcCommand; + pybullet_grpc::PyBulletCommand* grpcCmdPtr = convertBulletToGRPCCommand(clientCmd, grpcCommand); + + if (grpcCmdPtr) + { + grpc::ClientContext context; + std::chrono::system_clock::time_point deadline = + std::chrono::system_clock::now() + std::chrono::seconds((long long)m_data->m_timeOutInSeconds); + context.set_deadline(deadline); + ::pybullet_grpc::PyBulletStatus status; + // The actual RPC. + grpc::Status grpcStatus = m_data->m_stub->SubmitCommand(&context, grpcCommand, &status); + + //convert grpc status to Bullet status + bool convertedOk = convertGRPCToStatus(status, serverStatusOut, bufferServerToClient, bufferSizeInBytes); + return convertedOk; + + } + + return false; +} + +bool GRPCNetworkedPhysicsProcessor::receiveStatus(struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes) +{ + bool hasStatus = m_data->checkData(); + + if (hasStatus) + { + if (gVerboseNetworkMessagesClient3) + { + printf("GRPCNetworkedPhysicsProcessor::receiveStatus\n"); + } + + serverStatusOut = m_data->m_lastStatus; + int numStreamBytes = m_data->m_stream.size(); + + if (numStreamBytes < bufferSizeInBytes) + { + for (int i = 0; i < numStreamBytes; i++) + { + bufferServerToClient[i] = m_data->m_stream[i]; + } + } + else + { + printf("Error: steam buffer overflow\n"); + } + + } + + + return hasStatus; + +} + + +void GRPCNetworkedPhysicsProcessor::renderScene(int renderFlags) +{ +} + +void GRPCNetworkedPhysicsProcessor::physicsDebugDraw(int debugDrawFlags) +{ +} + +void GRPCNetworkedPhysicsProcessor::setGuiHelper(struct GUIHelperInterface* guiHelper) +{ +} + +bool GRPCNetworkedPhysicsProcessor::isConnected() const +{ + return m_data->m_isConnected; +} + + +bool GRPCNetworkedPhysicsProcessor::connect() +{ + bool isConnected = m_data->connectGRPC(); + return isConnected; +} + +void GRPCNetworkedPhysicsProcessor::disconnect() +{ + m_data->disconnect(); + +} + + +void GRPCNetworkedPhysicsProcessor::setTimeOut(double timeOutInSeconds) +{ + m_data->m_timeOutInSeconds = timeOutInSeconds; +} + +#endif //BT_ENABLE_GRPC + diff --git a/examples/SharedMemory/PhysicsClientGRPC.h b/examples/SharedMemory/PhysicsClientGRPC.h new file mode 100644 index 000000000..e146666f4 --- /dev/null +++ b/examples/SharedMemory/PhysicsClientGRPC.h @@ -0,0 +1,41 @@ +#ifndef PHYSICS_CLIENT_GRPC_H +#define PHYSICS_CLIENT_GRPC_H + +#include "PhysicsDirect.h" +#include "PhysicsCommandProcessorInterface.h" + +class GRPCNetworkedPhysicsProcessor : public PhysicsCommandProcessorInterface +{ + + struct GRPCNetworkedInternalData* m_data; + +public: + GRPCNetworkedPhysicsProcessor(const char* hostName, int port); + + virtual ~GRPCNetworkedPhysicsProcessor(); + + virtual bool connect(); + + virtual void disconnect(); + + virtual bool isConnected() const; + + virtual bool processCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes); + + virtual bool receiveStatus(struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes); + + virtual void renderScene(int renderFlags); + + virtual void physicsDebugDraw(int debugDrawFlags); + + virtual void setGuiHelper(struct GUIHelperInterface* guiHelper); + + virtual void setTimeOut(double timeOutInSeconds); + + virtual void reportNotifications() {} + +}; + + +#endif //PHYSICS_CLIENT_GRPC_H + diff --git a/examples/SharedMemory/PhysicsClientGRPC_C_API.cpp b/examples/SharedMemory/PhysicsClientGRPC_C_API.cpp new file mode 100644 index 000000000..4289d0335 --- /dev/null +++ b/examples/SharedMemory/PhysicsClientGRPC_C_API.cpp @@ -0,0 +1,29 @@ +#ifdef BT_ENABLE_GRPC + +#include "PhysicsClientGRPC_C_API.h" +#include "PhysicsClientGRPC.h" +#include "PhysicsDirect.h" +#include + +B3_SHARED_API b3PhysicsClientHandle b3ConnectPhysicsGRPC(const char* hostName, int port) +{ + + GRPCNetworkedPhysicsProcessor* tcp = new GRPCNetworkedPhysicsProcessor(hostName, port); + + PhysicsDirect* direct = new PhysicsDirect(tcp, true); + + bool connected; + connected = direct->connect(); + if (connected) + { + printf("b3ConnectPhysicsGRPC connected successfully.\n"); + } + else + { + printf("b3ConnectPhysicsGRPC connection failed.\n"); + + } + return (b3PhysicsClientHandle)direct; +} + +#endif //BT_ENABLE_GRPC \ No newline at end of file diff --git a/examples/SharedMemory/PhysicsClientGRPC_C_API.h b/examples/SharedMemory/PhysicsClientGRPC_C_API.h new file mode 100644 index 000000000..1e801e18e --- /dev/null +++ b/examples/SharedMemory/PhysicsClientGRPC_C_API.h @@ -0,0 +1,19 @@ +#ifndef PHYSICS_CLIENT_GRPC_C_API_H +#define PHYSICS_CLIENT_GRPC_C_API_H + +#include "PhysicsClientC_API.h" + +#ifdef __cplusplus +extern "C" { +#endif + + +///send physics commands using GRPC connection +B3_SHARED_API b3PhysicsClientHandle b3ConnectPhysicsGRPC(const char* hostName, int port); + + +#ifdef __cplusplus +} +#endif + +#endif //PHYSICS_CLIENT_GRPC_C_API_H diff --git a/examples/SharedMemory/grpc/ConvertGRPCBullet.cpp b/examples/SharedMemory/grpc/ConvertGRPCBullet.cpp index 163aba08a..00bf11096 100644 --- a/examples/SharedMemory/grpc/ConvertGRPCBullet.cpp +++ b/examples/SharedMemory/grpc/ConvertGRPCBullet.cpp @@ -10,7 +10,7 @@ #include "pybullet.grpc.pb.h" #include "LinearMath/btMinMax.h" -//#define ALLOW_GRPC_COMMAND_CONVERSION +#define ALLOW_GRPC_COMMAND_CONVERSION #define ALLOW_GRPC_STATUS_CONVERSION using grpc::Server; @@ -483,7 +483,7 @@ pybullet_grpc::PyBulletCommand* convertBulletToGRPCCommand(const struct SharedMe if (0 == grpcCmdPtr) { grpcCmdPtr = &grpcCommand; - printf("Warning: slow fallback of convertBulletToGRPCCommand (%d)", clientCmd.m_type); + //printf("Warning: slow fallback of convertBulletToGRPCCommand (%d)", clientCmd.m_type); //convert an unknown command as binary blob int sz = sizeof(SharedMemoryCommand); if (sz > 0) @@ -559,7 +559,7 @@ SharedMemoryCommand* convertGRPCToBulletCommand(const PyBulletCommand& grpcComma { memcpy(&cmd, data, numBytes); } - printf("slow fallback on command type %d\n", cmd.m_type); + //printf("slow fallback on command type %d\n", cmd.m_type); } else { @@ -1491,7 +1491,7 @@ bool convertGRPCToStatus(const PyBulletStatus& grpcReply, SharedMemoryStatus& se { if (grpcReply.unknownstatusbinaryblob_size() == 1) { - printf("convertStatusToGRPC: slow fallback status (%d), slow fallback", grpcReply.statustype()); + //printf("convertStatusToGRPC: slow fallback status (%d), slow fallback", grpcReply.statustype()); const char* data = grpcReply.unknownstatusbinaryblob().Get(0).c_str(); int numBytes = grpcReply.unknownstatusbinaryblob().Get(0).size(); @@ -1501,7 +1501,7 @@ bool convertGRPCToStatus(const PyBulletStatus& grpcReply, SharedMemoryStatus& se { memcpy(&serverStatus, data, numBytes); } - printf("slow fallback on command type %d\n", serverStatus.m_type); + //printf("slow fallback on command type %d\n", serverStatus.m_type); btAssert(grpcReply.statustype() == serverStatus.m_type); converted = true; } @@ -1822,7 +1822,7 @@ bool convertStatusToGRPC(const SharedMemoryStatus& serverStatus, char* bufferSer default: { #endif //ALLOW_GRPC_STATUS_CONVERSION - printf("convertStatusToGRPC: unknown status (%d), slow fallback", serverStatus.m_type); + //printf("convertStatusToGRPC: unknown status (%d), slow fallback", serverStatus.m_type); int sz = sizeof(SharedMemoryStatus); grpcReply.add_unknownstatusbinaryblob((const char*)&serverStatus, sz); converted = true; diff --git a/examples/pybullet/pybullet.c b/examples/pybullet/pybullet.c index 6ae55b9d0..5697ec0e9 100644 --- a/examples/pybullet/pybullet.c +++ b/examples/pybullet/pybullet.c @@ -439,7 +439,7 @@ static PyObject* pybullet_connectPhysicsServer(PyObject* self, PyObject* args, P #ifdef BT_ENABLE_GRPC sm = b3ConnectPhysicsGRPC(hostName.c_str(), tcpPort); #else - b3Warning("GRPC is not enabled in this pybullet build"); + PyErr_SetString(SpamError, "GRPC is not enabled in this pybullet build"); #endif break; }