Separate SharedMemoryStatus from SharedMemoryCommand

Added CMD_CMD_SEND_PHYSICS_SIMULATION_PARAMETERS (set gravity as example)
and CMD_INIT_POSE, not fully implemented yet.
This commit is contained in:
Erwin Coumans
2015-07-21 21:46:28 -07:00
parent 8e163c984d
commit 05fc203ec1
5 changed files with 165 additions and 33 deletions

View File

@@ -97,6 +97,27 @@ void MyCallback2(int buttonId, bool buttonState, void* userPtr)
cl->enqueueCommand(command);
break;
}
case CMD_SEND_PHYSICS_SIMULATION_PARAMETERS:
{
command.m_type = CMD_SEND_PHYSICS_SIMULATION_PARAMETERS;
command.m_physSimParamArgs.m_gravityAcceleration[0] = 0;
command.m_physSimParamArgs.m_gravityAcceleration[1] = 0;
command.m_physSimParamArgs.m_gravityAcceleration[2] = -10;
command.m_physSimParamArgs.m_updateFlags = SIM_PARAM_UPDATE_GRAVITY;
cl->enqueueCommand(command);
break;
};
case CMD_INIT_POSE:
{
///@todo: implement this
command.m_type = CMD_INIT_POSE;
cl->enqueueCommand(command);
break;
}
case CMD_CREATE_BOX_COLLISION_SHAPE:
{
command.m_type =CMD_CREATE_BOX_COLLISION_SHAPE;
@@ -225,7 +246,8 @@ void RobotControlExample::initPhysics()
createButton("Get State",CMD_REQUEST_ACTUAL_STATE, isTrigger);
createButton("Send Desired State",CMD_SEND_DESIRED_STATE, isTrigger);
createButton("Create Box Collider",CMD_CREATE_BOX_COLLISION_SHAPE,isTrigger);
createButton("Set Physics Params",CMD_SEND_PHYSICS_SIMULATION_PARAMETERS,isTrigger);
createButton("Init Pose",CMD_INIT_POSE,isTrigger);
} else
{
/*