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',