Physics SharedMemory:
Add flags BOX_SHAPE_HAS_MASS and BOX_SHAPE_HAS_COLLISION_SHAPE_TYPE to CMD_CREATE_RIGID_BODY (which maps to CMD_CREATE_BOX_COLLISION_SHAPE for backward compatibility for now) Need to add way to receive world transform
This commit is contained in:
@@ -194,7 +194,7 @@ void PhysicsClientExample::prepareAndSubmitCommand(int commandId)
|
||||
case CMD_LOAD_URDF:
|
||||
{
|
||||
|
||||
b3SharedMemoryCommandHandle commandHandle = b3LoadUrdfCommandInit(m_physicsClientHandle, "r2d2.urdf");//kuka_lwr/kuka.urdf");
|
||||
b3SharedMemoryCommandHandle commandHandle = b3LoadUrdfCommandInit(m_physicsClientHandle, "kuka_lwr/kuka.urdf");
|
||||
|
||||
//setting the initial position, orientation and other arguments are optional
|
||||
double startPosX = 0;
|
||||
@@ -214,6 +214,19 @@ void PhysicsClientExample::prepareAndSubmitCommand(int commandId)
|
||||
b3SubmitClientCommand(m_physicsClientHandle, commandHandle);
|
||||
break;
|
||||
}
|
||||
case CMD_CREATE_RIGID_BODY:
|
||||
{
|
||||
b3SharedMemoryCommandHandle commandHandle = b3CreateBoxShapeCommandInit(m_physicsClientHandle);
|
||||
b3CreateBoxCommandSetStartPosition(commandHandle,0,0,0);
|
||||
b3CreateBoxCommandSetMass(commandHandle,1);
|
||||
b3CreateBoxCommandSetCollisionShapeType(commandHandle,COLLISION_SHAPE_TYPE_CYLINDER_Y);
|
||||
double radius = 0.2;
|
||||
double halfHeight = 0.5;
|
||||
b3CreateBoxCommandSetHalfExtents(commandHandle,radius,halfHeight,radius);
|
||||
b3SubmitClientCommand(m_physicsClientHandle, commandHandle);
|
||||
break;
|
||||
}
|
||||
|
||||
case CMD_REQUEST_ACTUAL_STATE:
|
||||
{
|
||||
b3SharedMemoryCommandHandle commandHandle = b3RequestActualStateCommandInit(m_physicsClientHandle);
|
||||
@@ -360,6 +373,7 @@ void PhysicsClientExample::createButtons()
|
||||
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("Create Cylinder Body",CMD_CREATE_RIGID_BODY,isTrigger);
|
||||
createButton("Reset Simulation",CMD_RESET_SIMULATION,isTrigger);
|
||||
createButton("Initialize Pose",CMD_INIT_POSE, isTrigger);
|
||||
|
||||
@@ -515,8 +529,8 @@ void PhysicsClientExample::stepSimulation(float deltaTime)
|
||||
{
|
||||
enqueueCommand(CMD_SEND_DESIRED_STATE);
|
||||
enqueueCommand(CMD_STEP_FORWARD_SIMULATION);
|
||||
enqueueCommand(CMD_REQUEST_DEBUG_LINES);
|
||||
enqueueCommand(CMD_REQUEST_ACTUAL_STATE);
|
||||
//enqueueCommand(CMD_REQUEST_DEBUG_LINES);
|
||||
//enqueueCommand(CMD_REQUEST_ACTUAL_STATE);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
Reference in New Issue
Block a user