b3SharedMemoryStatusHandle b3SubmitClientCommandAndWaitStatus(b3PhysicsClientHandle physClient, const b3SharedMemoryCommandHandle commandHandle) { int timeout = 1024*1024*1024; b3SharedMemoryStatusHandle statusHandle=0; b3SubmitClientCommand(physClient,commandHandle); while ((statusHandle==0) && (timeout-- > 0)) { statusHandle =b3ProcessServerStatus(physClient); } return (b3SharedMemoryStatusHandle) statusHandle; }
void PhysicsClientExample::stepSimulation(float deltaTime) { if (m_options == eCLIENTEXAMPLE_SERVER) { for (int i=0;i<100;i++) { m_physicsServer.processClientCommands(); } } if (m_prevSelectedBody != m_selectedBody) { createButtons(); m_prevSelectedBody = m_selectedBody; } //while (!b3CanSubmitCommand(m_physicsClientHandle)) { b3SharedMemoryStatusHandle status = b3ProcessServerStatus(m_physicsClientHandle); bool hasStatus = (status != 0); if (hasStatus) { int statusType = b3GetStatusType(status); if (statusType == CMD_ACTUAL_STATE_UPDATE_COMPLETED) { //b3Printf("bla\n"); } if (statusType ==CMD_CAMERA_IMAGE_COMPLETED) { static int counter=0; char msg[1024]; sprintf(msg,"Camera image %d OK\n",counter++); b3CameraImageData imageData; b3GetCameraImageData(m_physicsClientHandle,&imageData); if (m_canvas && m_canvasIndex >=0) { for (int i=0;i<imageData.m_pixelWidth;i++) { for (int j=0;j<imageData.m_pixelHeight;j++) { int xIndex = int(float(i)*(float(camVisualizerWidth)/float(imageData.m_pixelWidth))); int yIndex = int(float(j)*(float(camVisualizerHeight)/float(imageData.m_pixelHeight))); btClamp(yIndex,0,imageData.m_pixelHeight); btClamp(xIndex,0,imageData.m_pixelWidth); int bytesPerPixel = 4; int pixelIndex = (i+j*imageData.m_pixelWidth)*bytesPerPixel; m_canvas->setPixel(m_canvasIndex,xIndex,camVisualizerHeight-1-yIndex, imageData.m_rgbColorData[pixelIndex], imageData.m_rgbColorData[pixelIndex+1], imageData.m_rgbColorData[pixelIndex+2], 255); // imageData.m_rgbColorData[pixelIndex+3]); } } m_canvas->refreshImageData(m_canvasIndex); } b3Printf(msg); } if (statusType == CMD_CAMERA_IMAGE_FAILED) { b3Printf("Camera image FAILED\n"); } if (statusType == CMD_URDF_LOADING_COMPLETED) { int bodyIndex = b3GetStatusBodyIndex(status); if (bodyIndex>=0) { int numJoints = b3GetNumJoints(m_physicsClientHandle,bodyIndex); for (int i=0;i<numJoints;i++) { b3JointInfo info; b3GetJointInfo(m_physicsClientHandle,bodyIndex,i,&info); b3Printf("Joint %s at q-index %d and u-index %d\n",info.m_jointName,info.m_qIndex,info.m_uIndex); } ComboBoxParams comboParams; comboParams.m_comboboxId = bodyIndex; comboParams.m_numItems = 1; comboParams.m_startItem = 0; comboParams.m_callback = MyComboBoxCallback; comboParams.m_userPointer = this; const char* bla = "bla"; const char* blarray[1]; blarray[0] = bla; comboParams.m_items=blarray;//{&bla}; m_guiHelper->getParameterInterface()->registerComboBox(comboParams); } } } } if (b3CanSubmitCommand(m_physicsClientHandle)) { if (m_userCommandRequests.size()) { //b3Printf("Outstanding user command requests: %d\n", m_userCommandRequests.size()); int commandId = m_userCommandRequests[0]; //a manual 'pop_front', we don't use 'remove' because it will re-order the commands for (int i=1;i<m_userCommandRequests.size();i++) { m_userCommandRequests[i-1] = m_userCommandRequests[i]; } m_userCommandRequests.pop_back(); //for the CMD_RESET_SIMULATION we need to do something special: clear the GUI sliders if (commandId ==CMD_RESET_SIMULATION) { m_selectedBody = -1; m_numMotors=0; createButtons(); b3SharedMemoryCommandHandle commandHandle = b3InitResetSimulationCommand(m_physicsClientHandle); if (m_options == eCLIENTEXAMPLE_SERVER) { b3SubmitClientCommand(m_physicsClientHandle, commandHandle); while (!b3CanSubmitCommand(m_physicsClientHandle)) { m_physicsServer.processClientCommands(); b3SharedMemoryStatusHandle status = b3ProcessServerStatus(m_physicsClientHandle); bool hasStatus = (status != 0); if (hasStatus) { int statusType = b3GetStatusType(status); b3Printf("Status after reset: %d",statusType); } } } else { prepareAndSubmitCommand(commandId); } } else { prepareAndSubmitCommand(commandId); } } else { if (m_numMotors) { enqueueCommand(CMD_SEND_DESIRED_STATE); enqueueCommand(CMD_STEP_FORWARD_SIMULATION); if (m_options != eCLIENTEXAMPLE_SERVER) { enqueueCommand(CMD_REQUEST_DEBUG_LINES); } //enqueueCommand(CMD_REQUEST_ACTUAL_STATE); } } } }
void PhysicsClientExample::prepareAndSubmitCommand(int commandId) { switch (commandId) { case CMD_LOAD_URDF: { b3SharedMemoryCommandHandle commandHandle = b3LoadUrdfCommandInit(m_physicsClientHandle, "kuka_iiwa/model.urdf"); //setting the initial position, orientation and other arguments are optional double startPosX = 0; static double startPosY = 0; double startPosZ = 0; b3LoadUrdfCommandSetStartPosition(commandHandle, startPosX, startPosY, startPosZ); startPosY += 2.f; // ret = b3LoadUrdfCommandSetUseFixedBase(commandHandle, 1); b3SubmitClientCommand(m_physicsClientHandle, commandHandle); break; } case CMD_LOAD_SDF: { #ifdef BT_DEBUG b3SharedMemoryCommandHandle commandHandle = b3LoadSdfCommandInit(m_physicsClientHandle, "two_cubes.sdf"); #else b3SharedMemoryCommandHandle commandHandle = b3LoadSdfCommandInit(m_physicsClientHandle, "kitchens/1.sdf"); //two_cubes.sdf");//kitchens/1.sdf");//kuka_iiwa/model.sdf"); #endif b3SubmitClientCommand(m_physicsClientHandle, commandHandle); break; } case CMD_REQUEST_CAMERA_IMAGE_DATA: { ///request an image from a simulated camera, using a software renderer. b3SharedMemoryCommandHandle commandHandle = b3InitRequestCameraImage(m_physicsClientHandle); //b3RequestCameraImageSelectRenderer(commandHandle,ER_BULLET_HARDWARE_OPENGL); float viewMatrix[16]; float projectionMatrix[16]; m_guiHelper->getRenderInterface()->getActiveCamera()->getCameraProjectionMatrix(projectionMatrix); m_guiHelper->getRenderInterface()->getActiveCamera()->getCameraViewMatrix(viewMatrix); b3RequestCameraImageSetCameraMatrices(commandHandle, viewMatrix, projectionMatrix); b3RequestCameraImageSetPixelResolution(commandHandle, camVisualizerWidth, camVisualizerHeight); float lightPos[3]; lightPos[0] = m_lightPos[0]; lightPos[1] = m_lightPos[1]; lightPos[2] = m_lightPos[2]; b3RequestCameraImageSetLightDirection(commandHandle, lightPos); b3RequestCameraImageSetLightSpecularCoeff(commandHandle, m_specularCoeff); b3SubmitClientCommand(m_physicsClientHandle, commandHandle); break; } case CMD_CREATE_BOX_COLLISION_SHAPE: { b3SharedMemoryCommandHandle commandHandle = b3CreateBoxShapeCommandInit(m_physicsClientHandle); b3CreateBoxCommandSetStartPosition(commandHandle, 0, 0, -1.5); b3CreateBoxCommandSetColorRGBA(commandHandle, 0, 0, 1, 1); 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); b3CreateBoxCommandSetColorRGBA(commandHandle, 1, 1, 0, 1); double radius = 0.2; double halfHeight = 0.5; b3CreateBoxCommandSetHalfExtents(commandHandle, radius, halfHeight, radius); b3SubmitClientCommand(m_physicsClientHandle, commandHandle); break; } case CMD_REQUEST_ACTUAL_STATE: { if (m_selectedBody >= 0) { b3SharedMemoryCommandHandle commandHandle = b3RequestActualStateCommandInit(m_physicsClientHandle, m_selectedBody); b3SharedMemoryStatusHandle statusHandle = b3SubmitClientCommandAndWaitStatus(m_physicsClientHandle, commandHandle); b3SubmitClientCommand(m_physicsClientHandle, commandHandle); int numJoints = b3GetNumJoints(m_physicsClientHandle, m_selectedBody); for (int i = 0; i < numJoints; ++i) { struct b3JointSensorState sensorState; b3GetJointState(m_physicsClientHandle, statusHandle, i, &sensorState); //b3Printf("Joint %d: %f", i, sensorState.m_jointMotorTorque); } } break; }; case CMD_INIT_POSE: { if (m_selectedBody >= 0) { b3SharedMemoryCommandHandle commandHandle = b3CreatePoseCommandInit(m_physicsClientHandle, m_selectedBody); static int toggle = 0; double pos[3] = {0, 0, 0}; pos[toggle] = 2; toggle++; if (toggle > 2) toggle = 0; btQuaternion orn; orn.setValue(0, 0, 0, 1); switch (toggle) { case 0: orn = btQuaternion(btVector3(1, 0, 0), SIMD_HALF_PI); break; case 1: orn = btQuaternion(btVector3(0, 1, 0), SIMD_HALF_PI); break; case 2: orn = btQuaternion(btVector3(0, 0, 1), SIMD_HALF_PI); break; default: orn.setValue(0, 0, 0, 1); }; b3CreatePoseCommandSetBaseOrientation(commandHandle, orn[0], orn[1], orn[2], orn[3]); b3CreatePoseCommandSetBasePosition(commandHandle, pos[0], pos[1], pos[2]); int numJoints = b3GetNumJoints(m_physicsClientHandle, m_selectedBody); static double jointPos = SIMD_PI / 2.f; for (int i = 0; i < numJoints; i++) { b3JointInfo info; b3GetJointInfo(m_physicsClientHandle, m_selectedBody, i, &info); if ((info.m_jointType == 0) || (info.m_jointType == 1)) //revolute or prismatic { b3CreatePoseCommandSetJointPosition(m_physicsClientHandle, commandHandle, i, jointPos); } } jointPos += SIMD_PI / 8.0; b3SubmitClientCommand(m_physicsClientHandle, commandHandle); } break; } case CMD_STEP_FORWARD_SIMULATION: { b3SharedMemoryCommandHandle commandHandle = b3InitStepSimulationCommand(m_physicsClientHandle); b3SubmitClientCommand(m_physicsClientHandle, commandHandle); break; } case CMD_REQUEST_DEBUG_LINES: { b3SharedMemoryCommandHandle commandHandle = b3InitRequestDebugLinesCommand(m_physicsClientHandle, btIDebugDraw::DBG_DrawWireframe); b3SubmitClientCommand(m_physicsClientHandle, commandHandle); break; } case CMD_SEND_DESIRED_STATE: { if (m_selectedBody >= 0) { // b3SharedMemoryCommandHandle command = b3JointControlCommandInit( m_physicsClientHandle, m_selectedBody, CONTROL_MODE_VELOCITY); b3SharedMemoryCommandHandle command = b3JointControlCommandInit2(m_physicsClientHandle, m_selectedBody, CONTROL_MODE_POSITION_VELOCITY_PD); // b3Printf("prepare control command for body %d", m_selectedBody); prepareControlCommand(command); b3SubmitClientCommand(m_physicsClientHandle, command); } break; } case CMD_RESET_SIMULATION: { b3SharedMemoryCommandHandle commandHandle = b3InitResetSimulationCommand(m_physicsClientHandle); b3SubmitClientCommand(m_physicsClientHandle, commandHandle); break; } case CMD_SEND_BULLET_DATA_STREAM: { #if 0 //this worked, but needs C-API and a streaming options, similar to debug lines command.m_type = buttonId; cl->enqueueCommand(command); #endif break; } case CMD_CUSTOM_SET_GRAVITY: { b3SharedMemoryCommandHandle commandHandle = b3InitPhysicsParamCommand(m_physicsClientHandle); b3PhysicsParamSetGravity(commandHandle, 0.0, 0.0, -9.8); b3SubmitClientCommand(m_physicsClientHandle, commandHandle); break; } case CMD_CUSTOM_SET_REALTIME_SIMULATION: { b3SharedMemoryCommandHandle commandHandle = b3InitPhysicsParamCommand(m_physicsClientHandle); b3PhysicsParamSetRealTimeSimulation(commandHandle, 1); b3SubmitClientCommand(m_physicsClientHandle, commandHandle); break; } case CMD_CALCULATE_INVERSE_DYNAMICS: { if (m_selectedBody >= 0) { btAlignedObjectArray<double> jointPositionsQ; btAlignedObjectArray<double> jointVelocitiesQdot; btAlignedObjectArray<double> jointAccelerations; int numJoints = b3GetNumJoints(m_physicsClientHandle, m_selectedBody); if (numJoints) { b3Printf("Compute inverse dynamics for joint accelerations:"); jointPositionsQ.resize(numJoints); jointVelocitiesQdot.resize(numJoints); jointAccelerations.resize(numJoints); for (int i = 0; i < numJoints; i++) { jointAccelerations[i] = 100; b3Printf("Desired joint acceleration[%d]=%f", i, jointAccelerations[i]); } b3SharedMemoryCommandHandle commandHandle = b3CalculateInverseDynamicsCommandInit(m_physicsClientHandle, m_selectedBody, &jointPositionsQ[0], &jointVelocitiesQdot[0], &jointAccelerations[0]); b3SubmitClientCommand(m_physicsClientHandle, commandHandle); } } break; } case CMD_REQUEST_CONTACT_POINT_INFORMATION: { b3SharedMemoryCommandHandle commandHandle = b3InitRequestContactPointInformation(m_physicsClientHandle); b3SetContactFilterBodyA(commandHandle, 0); b3SetContactFilterBodyB(commandHandle, 1); b3SubmitClientCommand(m_physicsClientHandle, commandHandle); break; } case CMD_SAVE_WORLD: { b3SharedMemoryCommandHandle commandHandle = b3SaveWorldCommandInit(m_physicsClientHandle, "saveWorld.py"); b3SubmitClientCommand(m_physicsClientHandle, commandHandle); break; } case CMD_REQUEST_VISUAL_SHAPE_INFO: { if (m_selectedBody >= 0) { //request visual shape information b3SharedMemoryCommandHandle commandHandle = b3InitRequestVisualShapeInformation(m_physicsClientHandle, m_selectedBody); b3SubmitClientCommand(m_physicsClientHandle, commandHandle); } break; } case CMD_SET_SHADOW: { b3SharedMemoryCommandHandle commandHandle = b3InitRequestCameraImage(m_physicsClientHandle); float viewMatrix[16]; float projectionMatrix[16]; m_guiHelper->getRenderInterface()->getActiveCamera()->getCameraProjectionMatrix(projectionMatrix); m_guiHelper->getRenderInterface()->getActiveCamera()->getCameraViewMatrix(viewMatrix); b3RequestCameraImageSetCameraMatrices(commandHandle, viewMatrix, projectionMatrix); b3RequestCameraImageSetPixelResolution(commandHandle, camVisualizerWidth, camVisualizerHeight); bool hasShadow = true; b3RequestCameraImageSetShadow(commandHandle, hasShadow); b3SubmitClientCommand(m_physicsClientHandle, commandHandle); break; } case CMD_UPDATE_VISUAL_SHAPE: { int objectUniqueId = 0; int linkIndex = -1; int shapeIndex = -1; int textureIndex = -2; double rgbaColor[4] = {0.0, 1.0, 0.0, 1.0}; b3SharedMemoryCommandHandle commandHandle = b3InitUpdateVisualShape2(m_physicsClientHandle, objectUniqueId, linkIndex, shapeIndex); b3UpdateVisualShapeRGBAColor(commandHandle, rgbaColor); b3SubmitClientCommand(m_physicsClientHandle, commandHandle); break; } default: { b3Error("Unknown buttonId"); btAssert(0); } }; }
void PhysicsClientExample::prepareAndSubmitCommand(int commandId) { switch (commandId) { case CMD_LOAD_URDF: { b3SharedMemoryCommandHandle commandHandle = b3LoadUrdfCommandInit(m_physicsClientHandle, "kuka_iiwa/model.urdf"); //setting the initial position, orientation and other arguments are optional double startPosX = 0; static double startPosY = 0; double startPosZ = 0; b3LoadUrdfCommandSetStartPosition(commandHandle, startPosX,startPosY,startPosZ); startPosY += 2.f; // ret = b3LoadUrdfCommandSetUseFixedBase(commandHandle, 1); b3SubmitClientCommand(m_physicsClientHandle, commandHandle); break; } case CMD_REQUEST_CAMERA_IMAGE_DATA: { ///request an image from a simulated camera, using a software renderer. b3SharedMemoryCommandHandle commandHandle = b3InitRequestCameraImage(m_physicsClientHandle); float viewMatrix[16]; float projectionMatrix[16]; this->m_guiHelper->getRenderInterface()->getActiveCamera()->getCameraProjectionMatrix(projectionMatrix); this->m_guiHelper->getRenderInterface()->getActiveCamera()->getCameraViewMatrix(viewMatrix); b3RequestCameraImageSetCameraMatrices(commandHandle, viewMatrix,projectionMatrix); b3SubmitClientCommand(m_physicsClientHandle, commandHandle); break; } case CMD_CREATE_BOX_COLLISION_SHAPE: { b3SharedMemoryCommandHandle commandHandle = b3CreateBoxShapeCommandInit(m_physicsClientHandle); b3CreateBoxCommandSetStartPosition(commandHandle,0,0,-3); b3CreateBoxCommandSetColorRGBA(commandHandle,0,0,1,1); 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); b3CreateBoxCommandSetColorRGBA(commandHandle,1,1,0,1); double radius = 0.2; double halfHeight = 0.5; b3CreateBoxCommandSetHalfExtents(commandHandle,radius,halfHeight,radius); b3SubmitClientCommand(m_physicsClientHandle, commandHandle); break; } case CMD_REQUEST_ACTUAL_STATE: { if (m_selectedBody>=0) { b3SharedMemoryCommandHandle commandHandle = b3RequestActualStateCommandInit(m_physicsClientHandle,m_selectedBody); b3SharedMemoryStatusHandle statusHandle = b3SubmitClientCommandAndWaitStatus(m_physicsClientHandle, commandHandle); b3SubmitClientCommand(m_physicsClientHandle, commandHandle); int numJoints = b3GetNumJoints(m_physicsClientHandle, m_selectedBody); for (int i = 0; i < numJoints; ++i) { struct b3JointSensorState sensorState; b3GetJointState(m_physicsClientHandle, statusHandle, i, &sensorState); b3Printf("Joint %d: %f", i, sensorState.m_jointMotorTorque); } } break; }; case CMD_INIT_POSE: { if (m_selectedBody>=0) { b3SharedMemoryCommandHandle commandHandle = b3CreatePoseCommandInit(m_physicsClientHandle,m_selectedBody); static int toggle = 0; double pos[3] = {0,0,0}; pos[toggle] = 2; toggle++; if (toggle>2) toggle=0; btQuaternion orn; orn.setValue(0,0,0,1); switch (toggle) { case 0: orn = btQuaternion(btVector3(1,0,0),SIMD_HALF_PI); break; case 1: orn = btQuaternion(btVector3(0,1,0),SIMD_HALF_PI); break; case 2: orn = btQuaternion(btVector3(0,0,1),SIMD_HALF_PI); break; default: orn.setValue(0,0,0,1); }; b3CreatePoseCommandSetBaseOrientation(commandHandle,orn[0],orn[1],orn[2],orn[3]); b3CreatePoseCommandSetBasePosition(commandHandle, pos[0],pos[1],pos[2]); int numJoints = b3GetNumJoints(m_physicsClientHandle,m_selectedBody); static double jointPos = SIMD_PI/2.f; for (int i=0;i<numJoints;i++) { b3JointInfo info; b3GetJointInfo(m_physicsClientHandle, m_selectedBody,i, &info); if ((info.m_jointType == 0) || (info.m_jointType == 1)) //revolute or prismatic { b3CreatePoseCommandSetJointPosition(m_physicsClientHandle,commandHandle,i,jointPos); } } jointPos += SIMD_PI/8.0; b3SubmitClientCommand(m_physicsClientHandle, commandHandle); } break; } case CMD_STEP_FORWARD_SIMULATION: { b3SharedMemoryCommandHandle commandHandle = b3InitStepSimulationCommand(m_physicsClientHandle); b3SubmitClientCommand(m_physicsClientHandle, commandHandle); break; } case CMD_REQUEST_DEBUG_LINES: { b3SharedMemoryCommandHandle commandHandle = b3InitRequestDebugLinesCommand(m_physicsClientHandle, btIDebugDraw::DBG_DrawWireframe); b3SubmitClientCommand(m_physicsClientHandle, commandHandle); break; } case CMD_SEND_DESIRED_STATE: { // b3SharedMemoryCommandHandle command = b3JointControlCommandInit( m_physicsClientHandle, CONTROL_MODE_VELOCITY); b3SharedMemoryCommandHandle command = b3JointControlCommandInit( m_physicsClientHandle, CONTROL_MODE_POSITION_VELOCITY_PD); prepareControlCommand(command); b3SubmitClientCommand(m_physicsClientHandle, command); break; } case CMD_RESET_SIMULATION: { b3SharedMemoryCommandHandle commandHandle = b3InitResetSimulationCommand(m_physicsClientHandle); b3SubmitClientCommand(m_physicsClientHandle, commandHandle); break; } case CMD_SEND_BULLET_DATA_STREAM: { #if 0 //this worked, but needs C-API and a streaming options, similar to debug lines command.m_type = buttonId; cl->enqueueCommand(command); #endif break; } case CMD_SEND_PHYSICS_SIMULATION_PARAMETERS: { b3SharedMemoryCommandHandle commandHandle = b3InitPhysicsParamCommand(m_physicsClientHandle); b3PhysicsParamSetGravity(commandHandle, 0.0, 0.0, -9.8); b3SubmitClientCommand(m_physicsClientHandle, commandHandle); break; } default: { b3Error("Unknown buttonId"); btAssert(0); } }; }
int main(int argc, char* argv[]) { int i, dofCount , posVarCount, dofIndex, ret ,numJoints, allowSharedMemoryInitialization=0; int timeout = MAX_TIMEOUT; int sensorJointIndexLeft=-1; int sensorJointIndexRight=-1; const char* urdfFileName = "r2d2.urdf"; double gravx=0, gravy=0, gravz=-9.8; double timeStep = 1./60.; double startPosX, startPosY,startPosZ; int imuLinkIndex = -1; SharedMemoryCommand_t command; SharedMemoryStatus_t status; b3PhysicsClientHandle sm; b3Printf("timeout = %d\n",timeout); printf("hello world\n"); sm = b3ConnectSharedMemory( allowSharedMemoryInitialization); if (b3CanSubmitCommand(sm)) { ret = b3InitPhysicsParamCommand(&command); ret = b3PhysicsParamSetGravity(&command, gravx,gravy, gravz); ret = b3PhysicsParamSetTimeStep(&command, timeStep); ret = b3SubmitClientCommand(sm, &command); timeout = MAX_TIMEOUT; while ((timeout-- > 0) && b3ProcessServerStatus(sm, &status)==0) {} b3Printf("timeout = %d\n",timeout); ret = b3LoadUrdfCommandInit(&command, urdfFileName); //setting the initial position, orientation and other arguments are optional startPosX =2; startPosY =3; startPosZ = 1; ret = b3LoadUrdfCommandSetStartPosition(&command, startPosX,startPosY,startPosZ); ret = b3SubmitClientCommand(sm, &command); timeout = MAX_TIMEOUT; while ((timeout-- > 0) && b3ProcessServerStatus(sm, &status)==0) {} b3Printf("timeout = %d\n",timeout); numJoints = b3GetNumJoints(sm); for (i=0;i<numJoints;i++) { struct b3JointInfo jointInfo; b3GetJointInfo(sm,i,&jointInfo); printf("jointInfo[%d].m_jointName=%s\n",i,jointInfo.m_jointName); //pick the IMU link index based on torso name if (strstr(jointInfo.m_linkName,"base_link")) { imuLinkIndex = i; } //pick the joint index based on joint name if (strstr(jointInfo.m_jointName,"base_to_left_leg")) { sensorJointIndexLeft = i; } if (strstr(jointInfo.m_jointName,"base_to_right_leg")) { sensorJointIndexRight = i; } } if ((sensorJointIndexLeft>=0) || (sensorJointIndexRight>=0)) { ret = b3CreateSensorCommandInit(&command); if (imuLinkIndex>=0) { ret = b3CreateSensorEnableIMUForLink(&command, imuLinkIndex, 1); } if (sensorJointIndexLeft>=0) { ret = b3CreateSensorEnable6DofJointForceTorqueSensor(&command, sensorJointIndexLeft, 1); } if(sensorJointIndexRight>=0) { ret = b3CreateSensorEnable6DofJointForceTorqueSensor(&command, sensorJointIndexRight, 1); } ret = b3SubmitClientCommand(sm, &command); timeout = MAX_TIMEOUT; while ((timeout-- > 0) && b3ProcessServerStatus(sm, &status)==0) {} } ret = b3CreateBoxShapeCommandInit(&command); ret = b3CreateBoxCommandSetStartPosition(&command, 0,0,-1); ret = b3CreateBoxCommandSetStartOrientation(&command,0,0,0,1); ret = b3CreateBoxCommandSetHalfExtents(&command, 10,10,1); ret = b3SubmitClientCommand(sm, &command); timeout = MAX_TIMEOUT; while ((timeout-- > 0) && b3ProcessServerStatus(sm, &status)==0) {} b3RequestActualStateCommandInit(&command); ret = b3SubmitClientCommand(sm, &command); timeout = MAX_TIMEOUT; while ((timeout-- > 0) && b3ProcessServerStatus(sm, &status)==0) {} posVarCount =status.m_sendActualStateArgs.m_numDegreeOfFreedomQ; dofCount =status.m_sendActualStateArgs.m_numDegreeOfFreedomU; b3Printf("posVarCount = %d\n",posVarCount); printf("dofCount = %d\n",dofCount); b3JointControlCommandInit(&command, CONTROL_MODE_VELOCITY); for ( dofIndex=0;dofIndex<dofCount;dofIndex++) { b3JointControlSetDesiredVelocity(&command,dofIndex,1); b3JointControlSetMaximumForce(&command,dofIndex,100); } ret = b3SubmitClientCommand(sm, &command); timeout = MAX_TIMEOUT; while ((timeout-- > 0) && b3ProcessServerStatus(sm, &status)==0) {} ///perform some simulation steps for testing for ( i=0;i<100;i++) { ret = b3InitStepSimulationCommand(&command); ret = b3SubmitClientCommand(sm, &command); timeout = MAX_TIMEOUT; while ((timeout-- > 0) && b3ProcessServerStatus(sm, &status)==0) {} } b3RequestActualStateCommandInit(&command); ret = b3SubmitClientCommand(sm, &command); timeout = MAX_TIMEOUT; while ((timeout-- > 0) && b3ProcessServerStatus(sm, &status)==0) {} if (sensorJointIndexLeft>=0) { b3Printf("Sensor for joint [%d] = %f,%f,%f\n", sensorJointIndexLeft, status.m_sendActualStateArgs.m_jointReactionForces[6*sensorJointIndexLeft+0], status.m_sendActualStateArgs.m_jointReactionForces[6*sensorJointIndexLeft+1], status.m_sendActualStateArgs.m_jointReactionForces[6*sensorJointIndexLeft+2]); } if (sensorJointIndexRight>=0) { b3Printf("Sensor for joint [%d] = %f,%f,%f\n", sensorJointIndexRight, status.m_sendActualStateArgs.m_jointReactionForces[6*sensorJointIndexRight+0], status.m_sendActualStateArgs.m_jointReactionForces[6*sensorJointIndexRight+1], status.m_sendActualStateArgs.m_jointReactionForces[6*sensorJointIndexRight+2]); } ret = b3InitResetSimulationCommand(&command); ret = b3SubmitClientCommand(sm, &command); timeout = MAX_TIMEOUT; while ((timeout-- > 0) && b3ProcessServerStatus(sm, &status)==0) {} } b3DisconnectSharedMemory(sm); }