Merge pull request #1855 from erwincoumans/master

more work on grpc/proto/pybullet.proto
This commit is contained in:
erwincoumans
2018-09-04 12:11:03 -07:00
committed by GitHub
27 changed files with 36029 additions and 476 deletions

View File

@@ -201,6 +201,10 @@ end
defines {"BT_USE_DOUBLE_PRECISION"}
end
if _OPTIONS["grpc"] then
defines {"BT_ENABLE_GRPC"}
end
configurations {"Release", "Debug"}
configuration "Release"
flags { "Optimize", "EnableSSE2","StaticRuntime", "NoMinimalRebuild", "FloatFast"}

View File

@@ -19,6 +19,7 @@ cd build3
premake4 --double --enable_multithreading --midi --enable_static_vr_plugin --enable_openvr --enable_pybullet --python_include_dir="%myvar%/include" --python_lib_dir="%myvar%/libs" --targetdir="../bin" vs2010
#premake4 --double --grpc --enable_multithreading --midi --enable_static_vr_plugin --enable_openvr --enable_pybullet --python_include_dir="%myvar%/include" --python_lib_dir="%myvar%/libs" --targetdir="../binserver" vs2010
#premake4 --serial --audio --double --midi --enable_openvr --enable_pybullet --python_include_dir="%myvar%/include" --python_lib_dir="%myvar%/libs" --targetdir="../bin" vs2010

View File

@@ -17,6 +17,9 @@
#include "../SharedMemory/SharedMemoryPublic.h"
#include "Bullet3Common/b3Logging.h"
#ifdef BT_ENABLE_GRPC
#include "../SharedMemory/PhysicsClientGRPC_C_API.h"
#endif
b3RobotSimulatorClientAPI::b3RobotSimulatorClientAPI()
{
@@ -170,7 +173,15 @@ bool b3RobotSimulatorClientAPI::connect(int mode, const std::string& hostName, i
#endif //BT_ENABLE_CLSOCKET
break;
}
case eCONNECT_GRPC:
{
#ifdef BT_ENABLE_GRPC
sm = b3ConnectPhysicsGRPC(hostName.c_str(), tcpPort);
#else
b3Warning("GRPC is not enabled in this pybullet build");
#endif
break;
}
default:
{
b3Warning("connectPhysicsServer unexpected argument");

View File

@@ -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 (len<MAX_SDF_FILENAME_LENGTH)
{
strcpy(command->m_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;
@@ -480,11 +495,18 @@ B3_SHARED_API b3SharedMemoryCommandHandle b3InitPhysicsParamCommand(b3Physic
b3Assert(cl->canSubmitCommand());
struct SharedMemoryCommand* command = cl->getAvailableSharedMemoryCommand();
b3Assert(command);
return b3InitPhysicsParamCommand2((b3SharedMemoryCommandHandle) command);
}
B3_SHARED_API b3SharedMemoryCommandHandle b3InitPhysicsParamCommand2(b3SharedMemoryCommandHandle commandHandle)
{
struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
command->m_type = CMD_SEND_PHYSICS_SIMULATION_PARAMETERS;
command->m_updateFlags = 0;
return (b3SharedMemoryCommandHandle) command;
return (b3SharedMemoryCommandHandle)command;
}
B3_SHARED_API int b3PhysicsParamSetGravity(b3SharedMemoryCommandHandle commandHandle, double gravx,double gravy, double gravz)
{
struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
@@ -763,13 +785,21 @@ B3_SHARED_API b3SharedMemoryCommandHandle b3InitResetSimulationCommand(b3Phy
b3Assert(cl->canSubmitCommand());
struct SharedMemoryCommand* command = cl->getAvailableSharedMemoryCommand();
b3Assert(command);
command->m_type = CMD_RESET_SIMULATION;
command->m_updateFlags = 0;
return (b3SharedMemoryCommandHandle) command;
return b3InitResetSimulationCommand2((b3SharedMemoryCommandHandle)command);
}
B3_SHARED_API b3SharedMemoryCommandHandle b3InitResetSimulationCommand2(b3SharedMemoryCommandHandle commandHandle)
{
struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
b3Assert(command);
command->m_type = CMD_RESET_SIMULATION;
command->m_updateFlags = 0;
return (b3SharedMemoryCommandHandle)command;
}
B3_SHARED_API b3SharedMemoryCommandHandle b3JointControlCommandInit(b3PhysicsClientHandle physClient, int controlMode)
{
@@ -783,15 +813,22 @@ B3_SHARED_API b3SharedMemoryCommandHandle b3JointControlCommandInit2( b3PhysicsC
b3Assert(cl->canSubmitCommand());
struct SharedMemoryCommand* command = cl->getAvailableSharedMemoryCommand();
b3Assert(command);
return b3JointControlCommandInit2Internal((b3SharedMemoryCommandHandle)command, bodyUniqueId, controlMode);
}
B3_SHARED_API b3SharedMemoryCommandHandle b3JointControlCommandInit2Internal(b3SharedMemoryCommandHandle commandHandle, int bodyUniqueId, int controlMode)
{
struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
command->m_type = CMD_SEND_DESIRED_STATE;
command->m_sendDesiredStateCommandArgument.m_controlMode = controlMode;
command->m_sendDesiredStateCommandArgument.m_controlMode = controlMode;
command->m_sendDesiredStateCommandArgument.m_bodyUniqueId = bodyUniqueId;
command->m_updateFlags = 0;
for (int i=0;i<MAX_DEGREE_OF_FREEDOM;i++)
{
command->m_sendDesiredStateCommandArgument.m_hasDesiredStateFlags[i] = 0;
}
return (b3SharedMemoryCommandHandle) command;
for (int i = 0; i<MAX_DEGREE_OF_FREEDOM; i++)
{
command->m_sendDesiredStateCommandArgument.m_hasDesiredStateFlags[i] = 0;
}
return (b3SharedMemoryCommandHandle)command;
}
B3_SHARED_API int b3JointControlSetDesiredPosition(b3SharedMemoryCommandHandle commandHandle, int qIndex, double value)
@@ -893,10 +930,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 +1638,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;i<MAX_DEGREE_OF_FREEDOM;i++)
{
command->m_initPoseArgs.m_hasInitialStateQ[i] = 0;
for (int i = 0; i<MAX_DEGREE_OF_FREEDOM; i++)
{
command->m_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 +1744,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; i<numJointPositions; i++)
{
if ((i)<MAX_DEGREE_OF_FREEDOM)
{
command->m_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 +1798,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; i<numJointVelocities; i++)
{
if (i<MAX_DEGREE_OF_FREEDOM)
{
command->m_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 +2034,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;
}
return 1;
}
B3_SHARED_API int b3GetStatusActualState(b3SharedMemoryStatusHandle statusHandle,
int* bodyUniqueId,
int* numDegreeOfFreedomQ,
@@ -2317,10 +2449,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 +2484,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)
@@ -2512,23 +2656,29 @@ B3_SHARED_API b3SharedMemoryCommandHandle b3InitCreateUserConstraintCommand(b3Ph
b3Assert(cl->canSubmitCommand());
struct SharedMemoryCommand* command = cl->getAvailableSharedMemoryCommand();
b3Assert(command);
return b3InitCreateUserConstraintCommand2((b3SharedMemoryCommandHandle)command, parentBodyUniqueId, parentJointIndex, childBodyUniqueId, childJointIndex, info);
command->m_type = CMD_USER_CONSTRAINT;
}
B3_SHARED_API b3SharedMemoryCommandHandle b3InitCreateUserConstraintCommand2(b3SharedMemoryCommandHandle commandHandle, int parentBodyUniqueId, int parentJointIndex, int childBodyUniqueId, int childJointIndex, struct b3JointInfo* info)
{
struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
command->m_type = CMD_USER_CONSTRAINT;
command->m_updateFlags = USER_CONSTRAINT_ADD_CONSTRAINT;
command->m_userConstraintArguments.m_parentBodyIndex = parentBodyUniqueId;
command->m_userConstraintArguments.m_parentJointIndex = parentJointIndex;
command->m_userConstraintArguments.m_childBodyIndex = childBodyUniqueId;
command->m_userConstraintArguments.m_childJointIndex = childJointIndex;
for (int i = 0; i < 7; ++i) {
command->m_userConstraintArguments.m_parentFrame[i] = info->m_parentFrame[i];
command->m_userConstraintArguments.m_childFrame[i] = info->m_childFrame[i];
}
for (int i = 0; i < 3; ++i) {
command->m_userConstraintArguments.m_jointAxis[i] = info->m_jointAxis[i];
}
command->m_userConstraintArguments.m_jointType = info->m_jointType;
return (b3SharedMemoryCommandHandle)command;
command->m_userConstraintArguments.m_parentBodyIndex = parentBodyUniqueId;
command->m_userConstraintArguments.m_parentJointIndex = parentJointIndex;
command->m_userConstraintArguments.m_childBodyIndex = childBodyUniqueId;
command->m_userConstraintArguments.m_childJointIndex = childJointIndex;
for (int i = 0; i < 7; ++i) {
command->m_userConstraintArguments.m_parentFrame[i] = info->m_parentFrame[i];
command->m_userConstraintArguments.m_childFrame[i] = info->m_childFrame[i];
}
for (int i = 0; i < 3; ++i) {
command->m_userConstraintArguments.m_jointAxis[i] = info->m_jointAxis[i];
}
command->m_userConstraintArguments.m_jointType = info->m_jointType;
return (b3SharedMemoryCommandHandle)command;
}
B3_SHARED_API b3SharedMemoryCommandHandle b3InitChangeUserConstraintCommand(b3PhysicsClientHandle physClient, int userConstraintUniqueId)
@@ -3270,10 +3420,16 @@ B3_SHARED_API b3SharedMemoryCommandHandle b3InitRequestCameraImage(b3PhysicsClie
b3Assert(cl->canSubmitCommand());
struct SharedMemoryCommand* command = cl->getAvailableSharedMemoryCommand();
b3Assert(command);
command->m_type =CMD_REQUEST_CAMERA_IMAGE_DATA;
return b3InitRequestCameraImage2((b3SharedMemoryCommandHandle)command);
}
B3_SHARED_API b3SharedMemoryCommandHandle b3InitRequestCameraImage2(b3SharedMemoryCommandHandle commandHandle)
{
struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
command->m_type = CMD_REQUEST_CAMERA_IMAGE_DATA;
command->m_requestPixelDataArguments.m_startPixelIndex = 0;
command->m_updateFlags = 0;//REQUEST_PIXEL_ARGS_USE_HARDWARE_OPENGL;
return (b3SharedMemoryCommandHandle) command;
command->m_updateFlags = 0;//REQUEST_PIXEL_ARGS_USE_HARDWARE_OPENGL;
return (b3SharedMemoryCommandHandle)command;
}
B3_SHARED_API void b3RequestCameraImageSelectRenderer(b3SharedMemoryCommandHandle commandHandle, int renderer)
@@ -4437,7 +4593,13 @@ B3_SHARED_API b3SharedMemoryCommandHandle b3RequestKeyboardEventsCommandInit(b3P
b3Assert(cl->canSubmitCommand());
struct SharedMemoryCommand* command = cl->getAvailableSharedMemoryCommand();
b3Assert(command);
return b3RequestKeyboardEventsCommandInit2((b3SharedMemoryCommandHandle)command);
}
B3_SHARED_API b3SharedMemoryCommandHandle b3RequestKeyboardEventsCommandInit2(b3SharedMemoryCommandHandle commandHandle)
{
struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
command->m_type = CMD_REQUEST_KEYBOARD_EVENTS_DATA;
command->m_updateFlags = 0;
@@ -4714,10 +4876,16 @@ B3_SHARED_API b3SharedMemoryCommandHandle b3InitConfigureOpenGLVisualizer(b3Phys
struct SharedMemoryCommand* command = cl->getAvailableSharedMemoryCommand();
b3Assert(command);
command->m_type = CMD_CONFIGURE_OPENGL_VISUALIZER;
command->m_updateFlags = 0;
return b3InitConfigureOpenGLVisualizer2((b3SharedMemoryCommandHandle)command);
}
return (b3SharedMemoryCommandHandle)command;
B3_SHARED_API b3SharedMemoryCommandHandle b3InitConfigureOpenGLVisualizer2(b3SharedMemoryCommandHandle commandHandle)
{
struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
command->m_type = CMD_CONFIGURE_OPENGL_VISUALIZER;
command->m_updateFlags = 0;
return (b3SharedMemoryCommandHandle)command;
}
B3_SHARED_API void b3ConfigureOpenGLVisualizerSetVisualizationFlags(b3SharedMemoryCommandHandle commandHandle, int flag, int enabled)

View File

@@ -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[]);
@@ -145,6 +163,7 @@ B3_SHARED_API int b3ChangeDynamicsInfoSetContactProcessingThreshold(b3SharedMemo
B3_SHARED_API int b3ChangeDynamicsInfoSetActivationState(b3SharedMemoryCommandHandle commandHandle, int bodyUniqueId, int activationState);
B3_SHARED_API b3SharedMemoryCommandHandle b3InitCreateUserConstraintCommand(b3PhysicsClientHandle physClient, int parentBodyUniqueId, int parentJointIndex, int childBodyUniqueId, int childJointIndex, struct b3JointInfo* info);
B3_SHARED_API b3SharedMemoryCommandHandle b3InitCreateUserConstraintCommand2(b3SharedMemoryCommandHandle commandHandle, int parentBodyUniqueId, int parentJointIndex, int childBodyUniqueId, int childJointIndex, struct b3JointInfo* info);
///return a unique id for the user constraint, after successful creation, or -1 for an invalid constraint id
B3_SHARED_API int b3GetStatusUserConstraintUniqueId(b3SharedMemoryStatusHandle statusHandle);
@@ -181,6 +200,7 @@ B3_SHARED_API void b3GetDebugLines(b3PhysicsClientHandle physClient, struct b
///configure the 3D OpenGL debug visualizer (enable/disable GUI widgets, shadows, position camera etc)
B3_SHARED_API b3SharedMemoryCommandHandle b3InitConfigureOpenGLVisualizer(b3PhysicsClientHandle physClient);
B3_SHARED_API b3SharedMemoryCommandHandle b3InitConfigureOpenGLVisualizer2(b3SharedMemoryCommandHandle commandHandle);
B3_SHARED_API void b3ConfigureOpenGLVisualizerSetVisualizationFlags(b3SharedMemoryCommandHandle commandHandle, int flag, int enabled);
B3_SHARED_API void b3ConfigureOpenGLVisualizerSetViewMatrix(b3SharedMemoryCommandHandle commandHandle, float cameraDistance, float cameraPitch, float cameraYaw, const float cameraTargetPosition[/*3*/]);
@@ -216,6 +236,7 @@ B3_SHARED_API int b3GetDebugItemUniqueId(b3SharedMemoryStatusHandle statusHandle
///request an image from a simulated camera, using a software renderer.
B3_SHARED_API b3SharedMemoryCommandHandle b3InitRequestCameraImage(b3PhysicsClientHandle physClient);
B3_SHARED_API b3SharedMemoryCommandHandle b3InitRequestCameraImage2(b3SharedMemoryCommandHandle commandHandle);
B3_SHARED_API void b3RequestCameraImageSetCameraMatrices(b3SharedMemoryCommandHandle commandHandle, float viewMatrix[/*16*/], float projectionMatrix[/*16*/]);
B3_SHARED_API void b3RequestCameraImageSetPixelResolution(b3SharedMemoryCommandHandle commandHandle, int width, int height );
B3_SHARED_API void b3RequestCameraImageSetLightDirection(b3SharedMemoryCommandHandle commandHandle, const float lightDirection[/*3*/]);
@@ -295,6 +316,7 @@ B3_SHARED_API void b3UpdateVisualShapeSpecularColor(b3SharedMemoryCommandHandle
B3_SHARED_API b3SharedMemoryCommandHandle b3InitPhysicsParamCommand(b3PhysicsClientHandle physClient);
B3_SHARED_API b3SharedMemoryCommandHandle b3InitPhysicsParamCommand2(b3SharedMemoryCommandHandle commandHandle);
B3_SHARED_API int b3PhysicsParamSetGravity(b3SharedMemoryCommandHandle commandHandle, double gravx,double gravy, double gravz);
B3_SHARED_API int b3PhysicsParamSetTimeStep(b3SharedMemoryCommandHandle commandHandle, double timeStep);
B3_SHARED_API int b3PhysicsParamSetDefaultContactERP(b3SharedMemoryCommandHandle commandHandle, double defaultContactERP);
@@ -341,6 +363,7 @@ B3_SHARED_API b3SharedMemoryCommandHandle b3InitStepSimulationCommand(b3PhysicsC
B3_SHARED_API b3SharedMemoryCommandHandle b3InitStepSimulationCommand2(b3SharedMemoryCommandHandle commandHandle);
B3_SHARED_API b3SharedMemoryCommandHandle b3InitResetSimulationCommand(b3PhysicsClientHandle physClient);
B3_SHARED_API b3SharedMemoryCommandHandle b3InitResetSimulationCommand2(b3SharedMemoryCommandHandle commandHandle);
///Load a robot from a URDF file. Status type will CMD_URDF_LOADING_COMPLETED.
///Access the robot from the unique body index, through b3GetStatusBodyIndex(statusHandle);
@@ -367,6 +390,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 +432,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);
@@ -423,6 +449,7 @@ B3_SHARED_API b3SharedMemoryCommandHandle b3JointControlCommandInit(b3PhysicsCl
///Set joint motor control variables such as desired position/angle, desired velocity,
///applied joint forces, dependent on the control mode (CONTROL_MODE_VELOCITY or CONTROL_MODE_TORQUE)
B3_SHARED_API b3SharedMemoryCommandHandle b3JointControlCommandInit2(b3PhysicsClientHandle physClient, int bodyUniqueId, int controlMode);
B3_SHARED_API b3SharedMemoryCommandHandle b3JointControlCommandInit2Internal(b3SharedMemoryCommandHandle commandHandle, int bodyUniqueId, int controlMode);
///Only use when controlMode is CONTROL_MODE_POSITION_VELOCITY_PD
B3_SHARED_API int b3JointControlSetDesiredPosition(b3SharedMemoryCommandHandle commandHandle, int qIndex, double value);
@@ -505,6 +532,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 +542,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 +557,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);
@@ -581,6 +615,7 @@ B3_SHARED_API int b3SetVRCameraTrackingObject(b3SharedMemoryCommandHandle comman
B3_SHARED_API int b3SetVRCameraTrackingObjectFlag(b3SharedMemoryCommandHandle commandHandle, int flag);
B3_SHARED_API b3SharedMemoryCommandHandle b3RequestKeyboardEventsCommandInit(b3PhysicsClientHandle physClient);
B3_SHARED_API b3SharedMemoryCommandHandle b3RequestKeyboardEventsCommandInit2(b3SharedMemoryCommandHandle commandHandle);
B3_SHARED_API void b3GetKeyboardEventsData(b3PhysicsClientHandle physClient, struct b3KeyboardEventsData* keyboardEventsData);
B3_SHARED_API b3SharedMemoryCommandHandle b3RequestMouseEventsCommandInit(b3PhysicsClientHandle physClient);

View File

@@ -0,0 +1,236 @@
#ifdef BT_ENABLE_GRPC
#include "PhysicsClientGRPC.h"
#include "grpc/pybullet.grpc.pb.h"
#include <grpc++/grpc++.h>
using grpc::Channel;
#include <stdio.h>
#include <string.h>
#include "../Utils/b3Clock.h"
#include "PhysicsClient.h"
//#include "LinearMath/btVector3.h"
#include "SharedMemoryCommands.h"
#include <string>
#include "Bullet3Common/b3Logging.h"
#include "Bullet3Common/b3AlignedObjectArray.h"
#include "grpc/ConvertGRPCBullet.h"
static unsigned int b3DeserializeInt2(const unsigned char* input)
{
unsigned int tmp = (input[3] << 24) + (input[2] << 16) + (input[1] << 8) + input[0];
return tmp;
}
bool gVerboseNetworkMessagesClient3 = false;
struct GRPCNetworkedInternalData
{
std::shared_ptr<grpc::Channel> m_grpcChannel;
std::unique_ptr< pybullet_grpc::PyBulletAPI::Stub> m_stub;
bool m_isConnected;
SharedMemoryCommand m_clientCmd;
bool m_hasCommand;
SharedMemoryStatus m_lastStatus;
b3AlignedObjectArray<char> m_stream;
std::string m_hostName;
int m_port;
b3AlignedObjectArray<unsigned char> m_tempBuffer;
double m_timeOutInSeconds;
GRPCNetworkedInternalData()
:
m_isConnected(false),
m_hasCommand(false),
m_timeOutInSeconds(60)
{
}
void disconnect()
{
if (m_isConnected)
{
m_stub = 0;
m_grpcChannel = 0;
m_isConnected = false;
}
}
bool connectGRPC()
{
if (m_isConnected)
return true;
std::string hostport = m_hostName + ':' + std::to_string(m_port);
m_grpcChannel = grpc::CreateChannel(
hostport, grpc::InsecureChannelCredentials());
m_stub = pybullet_grpc::PyBulletAPI::NewStub(m_grpcChannel);
// Set timeout for API
std::chrono::system_clock::time_point deadline =
std::chrono::system_clock::now()+std::chrono::seconds((long long)m_timeOutInSeconds);
grpc::ClientContext context;
context.set_deadline(deadline);
::pybullet_grpc::PyBulletCommand request;
pybullet_grpc::CheckVersionCommand* cmd1 = request.mutable_checkversioncommand();
cmd1->set_clientversion(SHARED_MEMORY_MAGIC_NUMBER);
::pybullet_grpc::PyBulletStatus response;
// The actual RPC.
grpc::Status status = m_stub->SubmitCommand(&context, request, &response);
if (response.has_checkversionstatus())
{
if (response.checkversionstatus().serverversion() == SHARED_MEMORY_MAGIC_NUMBER)
{
m_isConnected = true;
}
else
{
printf("Error: Client version (%d) is different from server version (%d)", SHARED_MEMORY_MAGIC_NUMBER, response.checkversionstatus().serverversion());
}
}
else
{
printf("Error: cannot connect to GRPC server\n");
}
return m_isConnected;
}
bool checkData()
{
bool hasStatus = false;
return hasStatus;
}
};
GRPCNetworkedPhysicsProcessor::GRPCNetworkedPhysicsProcessor(const char* hostName, int port)
{
m_data = new GRPCNetworkedInternalData;
if (hostName)
{
m_data->m_hostName = hostName;
}
m_data->m_port = port;
}
GRPCNetworkedPhysicsProcessor::~GRPCNetworkedPhysicsProcessor()
{
disconnect();
delete m_data;
}
bool GRPCNetworkedPhysicsProcessor::processCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes)
{
if(gVerboseNetworkMessagesClient3)
{
printf("GRPCNetworkedPhysicsProcessor::processCommand\n");
}
::pybullet_grpc::PyBulletCommand grpcCommand;
pybullet_grpc::PyBulletCommand* grpcCmdPtr = convertBulletToGRPCCommand(clientCmd, grpcCommand);
if (grpcCmdPtr)
{
grpc::ClientContext context;
std::chrono::system_clock::time_point deadline =
std::chrono::system_clock::now() + std::chrono::seconds((long long)m_data->m_timeOutInSeconds);
context.set_deadline(deadline);
::pybullet_grpc::PyBulletStatus status;
// The actual RPC.
grpc::Status grpcStatus = m_data->m_stub->SubmitCommand(&context, grpcCommand, &status);
//convert grpc status to Bullet status
bool convertedOk = convertGRPCToStatus(status, serverStatusOut, bufferServerToClient, bufferSizeInBytes);
return convertedOk;
}
return false;
}
bool GRPCNetworkedPhysicsProcessor::receiveStatus(struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes)
{
bool hasStatus = m_data->checkData();
if (hasStatus)
{
if (gVerboseNetworkMessagesClient3)
{
printf("GRPCNetworkedPhysicsProcessor::receiveStatus\n");
}
serverStatusOut = m_data->m_lastStatus;
int numStreamBytes = m_data->m_stream.size();
if (numStreamBytes < bufferSizeInBytes)
{
for (int i = 0; i < numStreamBytes; i++)
{
bufferServerToClient[i] = m_data->m_stream[i];
}
}
else
{
printf("Error: steam buffer overflow\n");
}
}
return hasStatus;
}
void GRPCNetworkedPhysicsProcessor::renderScene(int renderFlags)
{
}
void GRPCNetworkedPhysicsProcessor::physicsDebugDraw(int debugDrawFlags)
{
}
void GRPCNetworkedPhysicsProcessor::setGuiHelper(struct GUIHelperInterface* guiHelper)
{
}
bool GRPCNetworkedPhysicsProcessor::isConnected() const
{
return m_data->m_isConnected;
}
bool GRPCNetworkedPhysicsProcessor::connect()
{
bool isConnected = m_data->connectGRPC();
return isConnected;
}
void GRPCNetworkedPhysicsProcessor::disconnect()
{
m_data->disconnect();
}
void GRPCNetworkedPhysicsProcessor::setTimeOut(double timeOutInSeconds)
{
m_data->m_timeOutInSeconds = timeOutInSeconds;
}
#endif //BT_ENABLE_GRPC

View File

@@ -0,0 +1,41 @@
#ifndef PHYSICS_CLIENT_GRPC_H
#define PHYSICS_CLIENT_GRPC_H
#include "PhysicsDirect.h"
#include "PhysicsCommandProcessorInterface.h"
class GRPCNetworkedPhysicsProcessor : public PhysicsCommandProcessorInterface
{
struct GRPCNetworkedInternalData* m_data;
public:
GRPCNetworkedPhysicsProcessor(const char* hostName, int port);
virtual ~GRPCNetworkedPhysicsProcessor();
virtual bool connect();
virtual void disconnect();
virtual bool isConnected() const;
virtual bool processCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes);
virtual bool receiveStatus(struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes);
virtual void renderScene(int renderFlags);
virtual void physicsDebugDraw(int debugDrawFlags);
virtual void setGuiHelper(struct GUIHelperInterface* guiHelper);
virtual void setTimeOut(double timeOutInSeconds);
virtual void reportNotifications() {}
};
#endif //PHYSICS_CLIENT_GRPC_H

View File

@@ -0,0 +1,29 @@
#ifdef BT_ENABLE_GRPC
#include "PhysicsClientGRPC_C_API.h"
#include "PhysicsClientGRPC.h"
#include "PhysicsDirect.h"
#include <stdio.h>
B3_SHARED_API b3PhysicsClientHandle b3ConnectPhysicsGRPC(const char* hostName, int port)
{
GRPCNetworkedPhysicsProcessor* tcp = new GRPCNetworkedPhysicsProcessor(hostName, port);
PhysicsDirect* direct = new PhysicsDirect(tcp, true);
bool connected;
connected = direct->connect();
if (connected)
{
printf("b3ConnectPhysicsGRPC connected successfully.\n");
}
else
{
printf("b3ConnectPhysicsGRPC connection failed.\n");
}
return (b3PhysicsClientHandle)direct;
}
#endif //BT_ENABLE_GRPC

View File

@@ -0,0 +1,19 @@
#ifndef PHYSICS_CLIENT_GRPC_C_API_H
#define PHYSICS_CLIENT_GRPC_C_API_H
#include "PhysicsClientC_API.h"
#ifdef __cplusplus
extern "C" {
#endif
///send physics commands using GRPC connection
B3_SHARED_API b3PhysicsClientHandle b3ConnectPhysicsGRPC(const char* hostName, int port);
#ifdef __cplusplus
}
#endif
#endif //PHYSICS_CLIENT_GRPC_C_API_H

View File

@@ -32,6 +32,7 @@ public:
virtual void setTimeOut(double timeOutInSeconds);
virtual void reportNotifications() {}
};

View File

@@ -31,6 +31,8 @@ public:
virtual void setGuiHelper(struct GUIHelperInterface* guiHelper);
virtual void setTimeOut(double timeOutInSeconds);
virtual void reportNotifications() {}
};

View File

@@ -27,6 +27,7 @@ public:
virtual void setGuiHelper(struct GUIHelperInterface* guiHelper) = 0;
virtual void setTimeOut(double timeOutInSeconds) = 0;
virtual void reportNotifications() = 0;
};
@@ -44,7 +45,7 @@ public:
virtual void enableRealTimeSimulation(bool enableRealTimeSim)=0;
virtual bool isRealTimeSimulationEnabled() const=0;
virtual void reportNotifications() = 0;
virtual void enableCommandLogging(bool enable, const char* fileName)=0;
virtual void replayFromLogFile(const char* fileName)=0;

View File

@@ -1217,8 +1217,7 @@ bool PhysicsDirect::submitClientCommand(const struct SharedMemoryCommand& comman
if (m_data->m_ownsCommandProcessor)
{
CommandProcessorInterface *commandProcessor = (CommandProcessorInterface *)m_data->m_commandProcessor;
commandProcessor->reportNotifications();
m_data->m_commandProcessor->reportNotifications();
}
/*if (hasStatus)
{

View File

@@ -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();

View File

@@ -31,6 +31,7 @@ public:
void setSharedMemoryKey(int key);
virtual void setTimeOut(double timeOutInSeconds);
virtual void reportNotifications() {}
};
#endif //SHARED_MEMORY_COMMAND_PROCESSOR_H

View File

@@ -7,7 +7,8 @@
//Please don't replace an existing magic number:
//instead, only ADD a new one at the top, comment-out previous one
#define SHARED_MEMORY_MAGIC_NUMBER 201809010
#define SHARED_MEMORY_MAGIC_NUMBER 2018090300
//#define SHARED_MEMORY_MAGIC_NUMBER 201809010
//#define SHARED_MEMORY_MAGIC_NUMBER 201807040
//#define SHARED_MEMORY_MAGIC_NUMBER 201806150
//#define SHARED_MEMORY_MAGIC_NUMBER 201806020
@@ -26,6 +27,7 @@
enum EnumSharedMemoryClientCommand
{
CMD_INVALID=0,
CMD_LOAD_SDF,
CMD_LOAD_URDF,
CMD_LOAD_BULLET,
@@ -334,6 +336,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
@@ -805,6 +814,7 @@ enum eCONNECT_METHOD {
eCONNECT_SHARED_MEMORY_SERVER=9,
eCONNECT_DART=10,
eCONNECT_MUJOCO=11,
eCONNECT_GRPC=12,
};
enum eURDF_Flags

View File

@@ -789,10 +789,13 @@ void b3RobotSimulatorClientAPI_NoDirect::setJointMotorControl(int bodyUniqueId,
b3JointInfo jointInfo;
b3GetJointInfo(m_data->m_physicsClientHandle, bodyUniqueId, jointIndex, &jointInfo);
int uIndex = jointInfo.m_uIndex;
b3JointControlSetKd(command, uIndex, args.m_kd);
b3JointControlSetDesiredVelocity(command, uIndex, args.m_targetVelocity);
b3JointControlSetMaximumForce(command, uIndex, args.m_maxTorqueValue);
statusHandle = b3SubmitClientCommandAndWaitStatus(m_data->m_physicsClientHandle, command);
if (uIndex >= 0)
{
b3JointControlSetKd(command, uIndex, args.m_kd);
b3JointControlSetDesiredVelocity(command, uIndex, args.m_targetVelocity);
b3JointControlSetMaximumForce(command, uIndex, args.m_maxTorqueValue);
statusHandle = b3SubmitClientCommandAndWaitStatus(m_data->m_physicsClientHandle, command);
}
break;
}
case CONTROL_MODE_POSITION_VELOCITY_PD:
@@ -817,8 +820,11 @@ void b3RobotSimulatorClientAPI_NoDirect::setJointMotorControl(int bodyUniqueId,
b3JointInfo jointInfo;
b3GetJointInfo(m_data->m_physicsClientHandle, bodyUniqueId, jointIndex, &jointInfo);
int uIndex = jointInfo.m_uIndex;
b3JointControlSetDesiredForceTorque(command, uIndex, args.m_maxTorqueValue);
statusHandle = b3SubmitClientCommandAndWaitStatus(m_data->m_physicsClientHandle, command);
if (uIndex >= 0)
{
b3JointControlSetDesiredForceTorque(command, uIndex, args.m_maxTorqueValue);
statusHandle = b3SubmitClientCommandAndWaitStatus(m_data->m_physicsClientHandle, command);
}
break;
}
case CONTROL_MODE_PD:

File diff suppressed because it is too large Load Diff

View File

@@ -10,7 +10,11 @@ namespace pybullet_grpc
class PyBulletStatus;
};
struct SharedMemoryCommand* convertGRPCAndSubmitCommand(pybullet_grpc::PyBulletCommand& grpcCommand, struct SharedMemoryCommand& cmd);
struct SharedMemoryCommand* convertGRPCToBulletCommand(const pybullet_grpc::PyBulletCommand& grpcCommand, struct SharedMemoryCommand& cmd);
pybullet_grpc::PyBulletCommand* convertBulletToGRPCCommand(const struct SharedMemoryCommand& clientCmd, pybullet_grpc::PyBulletCommand& grpcCommand);
bool convertGRPCToStatus(const pybullet_grpc::PyBulletStatus& grpcReply, struct SharedMemoryStatus& serverStatus, char* bufferServerToClient, int bufferSizeInBytes);
bool convertStatusToGRPC(const struct SharedMemoryStatus& serverStatus, char* bufferServerToClient, int bufferSizeInBytes, pybullet_grpc::PyBulletStatus& grpcReply);

View File

@@ -53,12 +53,12 @@ public:
}
void Run(MyCommandProcessor* comProc) {
std::string server_address("0.0.0.0:50051");
void Run(MyCommandProcessor* comProc, const std::string& hostNamePort) {
ServerBuilder builder;
// Listen on the given address without any authentication mechanism.
builder.AddListeningPort(server_address, grpc::InsecureServerCredentials());
builder.AddListeningPort(hostNamePort, grpc::InsecureServerCredentials());
// Register "service_" as the instance through which we'll communicate with
// clients. In this case it corresponds to an *asynchronous* service.
builder.RegisterService(&service_);
@@ -67,7 +67,7 @@ public:
cq_ = builder.AddCompletionQueue();
// Finally assemble the server.
server_ = builder.BuildAndStart();
std::cout << "Server listening on " << server_address << std::endl;
std::cout << "Server listening on " << hostNamePort << std::endl;
// Proceed to the server's main loop.
HandleRpcs(comProc);
@@ -121,42 +121,50 @@ private:
m_status.set_statustype(CMD_UNKNOWN_COMMAND_FLUSHED);
cmdPtr = convertGRPCAndSubmitCommand(m_command, cmd);
if (cmdPtr)
if (m_command.has_checkversioncommand())
{
bool hasStatus = m_comProc->processCommand(*cmdPtr, serverStatus, &buffer[0], buffer.size());
double timeOutInSeconds = 10;
b3Clock clock;
double startTimeSeconds = clock.getTimeInSeconds();
double curTimeSeconds = clock.getTimeInSeconds();
m_status.set_statustype(CMD_CLIENT_COMMAND_COMPLETED);
m_status.mutable_checkversionstatus()->set_serverversion(SHARED_MEMORY_MAGIC_NUMBER);
}
else
{
cmdPtr = convertGRPCToBulletCommand(m_command, cmd);
while ((!hasStatus) && ((curTimeSeconds - startTimeSeconds) <timeOutInSeconds))
{
hasStatus = m_comProc->receiveStatus(serverStatus, &buffer[0], buffer.size());
curTimeSeconds = clock.getTimeInSeconds();
}
if (gVerboseNetworkMessagesServer)
{
//printf("buffer.size = %d\n", buffer.size());
printf("serverStatus.m_numDataStreamBytes = %d\n", serverStatus.m_numDataStreamBytes);
}
if (hasStatus)
{
b3AlignedObjectArray<unsigned char> packetData;
unsigned char* statBytes = (unsigned char*)&serverStatus;
convertStatusToGRPC(serverStatus, &buffer[0], buffer.size(), m_status);
if (cmdPtr)
{
bool hasStatus = m_comProc->processCommand(*cmdPtr, serverStatus, &buffer[0], buffer.size());
double timeOutInSeconds = 10;
b3Clock clock;
double startTimeSeconds = clock.getTimeInSeconds();
double curTimeSeconds = clock.getTimeInSeconds();
while ((!hasStatus) && ((curTimeSeconds - startTimeSeconds) < timeOutInSeconds))
{
hasStatus = m_comProc->receiveStatus(serverStatus, &buffer[0], buffer.size());
curTimeSeconds = clock.getTimeInSeconds();
}
if (gVerboseNetworkMessagesServer)
{
//printf("buffer.size = %d\n", buffer.size());
printf("serverStatus.m_numDataStreamBytes = %d\n", serverStatus.m_numDataStreamBytes);
}
if (hasStatus)
{
b3AlignedObjectArray<unsigned char> packetData;
unsigned char* statBytes = (unsigned char*)&serverStatus;
convertStatusToGRPC(serverStatus, &buffer[0], buffer.size(), m_status);
}
}
if (m_command.has_terminateservercommand())
{
status_ = TERMINATE;
}
}
if (m_command.has_terminateservercommand())
{
status_ = TERMINATE;
}
// And we are done! Let the gRPC runtime know we've finished, using the
// memory address of this instance as the uniquely identifying tag for
// the event.
@@ -245,6 +253,8 @@ int main(int argc, char** argv)
int port = 6667;
parseArgs.GetCmdLineArgument("port", port);
std::string hostName = "localhost";
std::string hostNamePort = hostName + ":" + std::to_string(port);
gVerboseNetworkMessagesServer = parseArgs.CheckCmdLineFlag("verbose");
@@ -263,7 +273,7 @@ int main(int argc, char** argv)
{
ServerImpl server;
server.Run(sm);
server.Run(sm, hostNamePort);
}
else
{

View File

@@ -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",
}

View File

@@ -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";
@@ -21,6 +24,7 @@ message vec3
double z=3;
};
message quat4
{
double x=1;
@@ -29,6 +33,38 @@ message quat4
double w=4;
};
message vec4
{
double x=1;
double y=2;
double z=3;
double w=4;
};
message transform
{
vec3 origin=1;
quat4 orientation=2;
};
message matrix4x4
{
//assume 16 elements, with translation in 12,13,14,
//'right' vector is elements 0,1,3 and 4
repeated double elems=1;
};
message CheckVersionCommand
{
int32 clientVersion=1;
};
message CheckVersionStatus
{
int32 serverVersion=1;
};
message TerminateServerCommand
{
@@ -39,34 +75,357 @@ message StepSimulationCommand
{
};
message SyncBodiesCommand
{
};
message SyncBodiesStatus
{
repeated int32 bodyUniqueIds=1;
repeated int32 userConstraintUniqueIds=2;
};
message RequestBodyInfoCommand
{
int32 bodyUniqueId=1;
};
message RequestBodyInfoStatus
{
int32 bodyUniqueId=1;
string bodyName=2;
};
message LoadUrdfCommand {
string 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;
string bodyName=2;
string fileName=3;
}
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;
int32 updateflags=2;
repeated int32 hasInitialStateQ=3;
repeated double initialStateQ=4;
repeated int32 hasInitialStateQdot=5;
repeated double initialStateQdot=6;
};
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;
};
message ConfigureOpenGLVisualizerCommand
{
int32 updateFlags=1;
double cameraDistance=2;
double cameraPitch=3;
double cameraYaw=4;
vec3 cameraTargetPosition=5;
int32 setFlag=6;
int32 setEnabled=7;
};
message PhysicsSimulationParameters
{
double deltaTime=1;
vec3 gravityAcceleration=2;
int32 numSimulationSubSteps=3;
int32 numSolverIterations=4;
int32 useRealTimeSimulation=5;
int32 useSplitImpulse=6;
double splitImpulsePenetrationThreshold=7;
double contactBreakingThreshold=8;
int32 internalSimFlags=9;
double defaultContactERP=10;
int32 collisionFilterMode=11;
int32 enableFileCaching=12;
double restitutionVelocityThreshold=13;
double defaultNonContactERP=14;
double frictionERP=15;
double defaultGlobalCFM=16;
double frictionCFM=17;
int32 enableConeFriction=18;
int32 deterministicOverlappingPairs=19;
double allowedCcdPenetration=20;
int32 jointFeedbackMode=21;
double solverResidualThreshold=22;
double contactSlop=23;
int32 enableSAT=24;
int32 constraintSolverType=25;
int32 minimumSolverIslandSize=26;
};
message PhysicsSimulationParametersCommand
{
int32 updateFlags=1;
PhysicsSimulationParameters params=2;
};
message JointMotorControlCommand
{
int32 bodyUniqueId=1;
int32 controlMode=2;
int32 updateFlags=3;
//PD parameters in case controlMode == CONTROL_MODE_POSITION_VELOCITY_PD
repeated double Kp=4;//indexed by degree of freedom, 6 for base, and then the dofs for each link
repeated double Kd=5;//indexed by degree of freedom, 6 for base, and then the dofs for each link
repeated double maxVelocity=6;
repeated int32 hasDesiredStateFlags=7;
//desired state is only written by the client, read-only access by server is expected
//desiredStateQ is indexed by position variables,
//starting with 3 base position variables, 4 base orientation variables (quaternion), then link position variables
repeated double desiredStateQ=8;
//desiredStateQdot is index by velocity degrees of freedom, 3 linear and 3 angular variables for the base and then link velocity variables
repeated double desiredStateQdot=9;
//desiredStateForceTorque is either the actual applied force/torque (in CONTROL_MODE_TORQUE) or
//or the maximum applied force/torque for the PD/motor/constraint to reach the desired velocity in CONTROL_MODE_VELOCITY and CONTROL_MODE_POSITION_VELOCITY_PD mode
//indexed by degree of freedom, 6 dof base, and then dofs for each link
repeated double desiredStateForceTorque=10;
};
message UserConstraintCommand
{
int32 parentBodyIndex=1;
int32 parentJointIndex=2;
int32 childBodyIndex=3;
int32 childJointIndex=4;
transform parentFrame=5;
transform childFrame=6;
vec3 jointAxis=7;
int32 jointType=8;
double maxAppliedForce=9;
int32 userConstraintUniqueId=10;
double gearRatio=11;
int32 gearAuxLink=12;
double relativePositionTarget=13;
double erp=14;
int32 updateFlags=15;
};
message UserConstraintStatus
{
double maxAppliedForce=9;
int32 userConstraintUniqueId=10;
};
message UserConstraintStateStatus
{
vec3 appliedConstraintForcesLinear=1;
vec3 appliedConstraintForcesAngular=2;
int32 numDofs=3;
};
message RequestKeyboardEventsCommand
{
};
message KeyboardEvent
{
int32 keyCode=1;//ascii
int32 keyState=2;// see b3VRButtonInfo
};
message KeyboardEventsStatus
{
repeated KeyboardEvent keyboardEvents=1;
};
message RequestCameraImageCommand
{
int32 updateFlags=1;
int32 cameraFlags=2;
matrix4x4 viewMatrix=3;
matrix4x4 projectionMatrix=4;
int32 startPixelIndex=5;
int32 pixelWidth=6;
int32 pixelHeight=7;
vec3 lightDirection=8;
vec3 lightColor=9;
double lightDistance=10;
double lightAmbientCoeff=11;
double lightDiffuseCoeff=12;
double lightSpecularCoeff=13;
int32 hasShadow=14;
matrix4x4 projectiveTextureViewMatrix=15;
matrix4x4 projectiveTextureProjectionMatrix=16;
};
message RequestCameraImageStatus
{
int32 imageWidth=1;
int32 imageHeight=2;
int32 startingPixelIndex=3;
int32 numPixelsCopied=4;
int32 numRemainingPixels=5;
};
// The request message containing the command
message PyBulletCommand {
int32 commandType=1;
repeated bytes binaryBlob=2;
repeated bytes unknownCommandBinaryBlob=3;
oneof commands {
LoadUrdfCommand loadUrdfCommand = 3;
TerminateServerCommand terminateServerCommand=4;
StepSimulationCommand stepSimulationCommand= 5;
LoadUrdfCommand loadUrdfCommand = 4;
TerminateServerCommand terminateServerCommand=5;
StepSimulationCommand stepSimulationCommand= 6;
LoadSdfCommand loadSdfCommand=7;
LoadMjcfCommand loadMjcfCommand=8;
ChangeDynamicsCommand changeDynamicsCommand=9;
GetDynamicsCommand getDynamicsCommand=10;
InitPoseCommand initPoseCommand=11;
RequestActualStateCommand requestActualStateCommand=12;
ConfigureOpenGLVisualizerCommand configureOpenGLVisualizerCommand =13;
SyncBodiesCommand syncBodiesCommand=14;
RequestBodyInfoCommand requestBodyInfoCommand=15;
PhysicsSimulationParametersCommand setPhysicsSimulationParametersCommand=16;
JointMotorControlCommand jointMotorControlCommand=17;
UserConstraintCommand userConstraintCommand=18;
CheckVersionCommand checkVersionCommand=19;
RequestKeyboardEventsCommand requestKeyboardEventsCommand=20;
RequestCameraImageCommand requestCameraImageCommand=21;
}
@@ -76,10 +435,29 @@ message PyBulletCommand {
message PyBulletStatus {
int32 statusType=1;
repeated bytes binaryBlob=2;
repeated bytes unknownStatusBinaryBlob=3;
oneof status
{
LoadUrdfStatus urdfStatus = 2;
LoadUrdfStatus urdfStatus = 4;
SdfLoadedStatus sdfStatus = 5;
MjcfLoadedStatus mjcfStatus = 6;
GetDynamicsStatus getDynamicsStatus = 7;
SendActualStateStatus actualStateStatus = 8;
SyncBodiesStatus syncBodiesStatus=9;
RequestBodyInfoStatus requestBodyInfoStatus = 10;
PhysicsSimulationParameters requestPhysicsSimulationParametersStatus=11;
CheckVersionStatus checkVersionStatus=12;
UserConstraintStatus userConstraintStatus=13;
UserConstraintStateStatus userConstraintStateStatus=14;
KeyboardEventsStatus keyboardEventsStatus=15;
RequestCameraImageStatus requestCameraImageStatus=16;
}
}

File diff suppressed because it is too large Load Diff

File diff suppressed because it is too large Load Diff

View File

@@ -7,22 +7,66 @@ 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:6667')
print("pybullet_pb2_grpc.PyBulletAPIStub")
stub = pybullet_pb2_grpc.PyBulletAPIStub(channel)
response=0
print("submit CheckVersionCommand")
response = stub.SubmitCommand(pybullet_pb2.PyBulletCommand(checkVersionCommand=pybullet_pb2.CheckVersionCommand(clientVersion=123)))
print("PyBullet client received: " , response)
response = stub.SubmitCommand(pybullet_pb2.PyBulletCommand(stepSimulationCommand=pybullet_pb2.StepSimulationCommand()))
print("PyBullet client received: " , response.statusType)
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
#response = stub.SubmitCommand(pybullet_pb2.PyBulletCommand(terminateServerCommand=pybullet_pb2.TerminateServerCommand()))
#print("PyBullet client received: " , response.statusType)
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)
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 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)
#print("TerminateServerCommand")
#response = stub.SubmitCommand(pybullet_pb2.PyBulletCommand(terminateServerCommand=pybullet_pb2.TerminateServerCommand()))
#print("PyBullet client received: " , response.statusType)
if __name__ == '__main__':
run()
run()

File diff suppressed because one or more lines are too long

View File

@@ -14,6 +14,9 @@
#include "../SharedMemory/mujoco/MuJoCoPhysicsC_API.h"
#endif
#ifdef BT_ENABLE_GRPC
#include "../SharedMemory/PhysicsClientGRPC_C_API.h"
#endif
#ifdef BT_ENABLE_CLSOCKET
#include "../SharedMemory/PhysicsClientTCP_C_API.h"
#endif //BT_ENABLE_CLSOCKET
@@ -431,7 +434,15 @@ static PyObject* pybullet_connectPhysicsServer(PyObject* self, PyObject* args, P
break;
}
#endif
case eCONNECT_GRPC:
{
#ifdef BT_ENABLE_GRPC
sm = b3ConnectPhysicsGRPC(hostName.c_str(), tcpPort);
#else
PyErr_SetString(SpamError, "GRPC is not enabled in this pybullet build");
#endif
break;
}
case eCONNECT_SHARED_MEMORY:
{
sm = b3ConnectSharedMemory(key);
@@ -9625,6 +9636,9 @@ initpybullet(void)
#ifdef BT_ENABLE_MUJOCO
PyModule_AddIntConstant(m, "MuJoCo", eCONNECT_MUJOCO); // user read
#endif
#ifdef BT_ENABLE_GRPC
PyModule_AddIntConstant(m, "GRPC", eCONNECT_GRPC); // user read
#endif
PyModule_AddIntConstant(m, "SHARED_MEMORY_KEY", SHARED_MEMORY_KEY);