void prepareControlCommand(b3SharedMemoryCommandHandle commandHandle) { for (int i=0;i<m_numMotors;i++) { btScalar targetPos = m_motorTargetPositions[i].m_posTarget; int qIndex = m_motorTargetPositions[i].m_qIndex; int uIndex = m_motorTargetPositions[i].m_uIndex; b3JointControlSetDesiredPosition(commandHandle, qIndex, targetPos); b3JointControlSetKp(commandHandle, uIndex, 0.1); b3JointControlSetMaximumForce(commandHandle,uIndex,1000); } }
void prepareControlCommand(b3SharedMemoryCommandHandle commandHandle) { for (int i = 0; i < m_numMotors; i++) { btScalar targetPos = m_motorTargetPositions[i].m_posTarget; int qIndex = m_motorTargetPositions[i].m_qIndex; int uIndex = m_motorTargetPositions[i].m_uIndex; static int serial = 0; serial++; // b3Printf("# motors = %d, cmd[%d] qIndex = %d, uIndex = %d, targetPos = %f", m_numMotors, serial, qIndex,uIndex,targetPos); b3JointControlSetDesiredPosition(commandHandle, qIndex, targetPos); b3JointControlSetDesiredVelocity(commandHandle, uIndex, 0); b3JointControlSetKp(commandHandle, qIndex, 0.2); b3JointControlSetKd(commandHandle, uIndex, 1.); b3JointControlSetMaximumForce(commandHandle, uIndex, 5000); } }
int main(int argc, char* argv[]) { kPhysClient = b3CreateInProcessPhysicsServerAndConnect(argc, argv); if (!kPhysClient) return -1; // visualizer command = b3InitConfigureOpenGLVisualizer(kPhysClient); b3ConfigureOpenGLVisualizerSetVisualizationFlags(command, COV_ENABLE_GUI, 0); b3SubmitClientCommandAndWaitStatus(kPhysClient, command); b3ConfigureOpenGLVisualizerSetVisualizationFlags(command, COV_ENABLE_SHADOWS, 0); b3SubmitClientCommandAndWaitStatus(kPhysClient, command); b3SetTimeOut(kPhysClient, 10); //syncBodies is only needed when connecting to an existing physics server that has already some bodies command = b3InitSyncBodyInfoCommand(kPhysClient); statusHandle = b3SubmitClientCommandAndWaitStatus(kPhysClient, command); statusType = b3GetStatusType(statusHandle); // set fixed time step command = b3InitPhysicsParamCommand(kPhysClient); ret = b3PhysicsParamSetTimeStep(command, FIXED_TIMESTEP); statusHandle = b3SubmitClientCommandAndWaitStatus(kPhysClient, command); ret = b3PhysicsParamSetRealTimeSimulation(command, false); statusHandle = b3SubmitClientCommandAndWaitStatus(kPhysClient, command); b3Assert(b3GetStatusType(statusHandle) == CMD_CLIENT_COMMAND_COMPLETED); // load test command = b3LoadUrdfCommandInit(kPhysClient, "TwoJointRobot_wo_fixedJoints.urdf"); int flags = URDF_USE_INERTIA_FROM_FILE; b3LoadUrdfCommandSetFlags(command, flags); b3LoadUrdfCommandSetUseFixedBase(command, true); // q.setEulerZYX(0, 0, 0); // b3LoadUrdfCommandSetStartOrientation(command, q[0], q[1], q[2], q[3]); b3LoadUrdfCommandSetUseMultiBody(command, true); statusHandle = b3SubmitClientCommandAndWaitStatus(kPhysClient, command); statusType = b3GetStatusType(statusHandle); b3Assert(statusType == CMD_URDF_LOADING_COMPLETED); if (statusType == CMD_URDF_LOADING_COMPLETED) { twojoint = b3GetStatusBodyIndex(statusHandle); } //disable default linear/angular damping b3SharedMemoryCommandHandle command = b3InitChangeDynamicsInfo(kPhysClient); double linearDamping = 0; double angularDamping = 0; b3ChangeDynamicsInfoSetLinearDamping(command, twojoint, linearDamping); b3ChangeDynamicsInfoSetAngularDamping(command, twojoint, angularDamping); statusHandle = b3SubmitClientCommandAndWaitStatus(kPhysClient, command); int numJoints = b3GetNumJoints(kPhysClient, twojoint); printf("twojoint numjoints = %d\n", numJoints); // Loop through all joints for (int i = 0; i < numJoints; ++i) { b3GetJointInfo(kPhysClient, twojoint, i, &jointInfo); if (jointInfo.m_jointName[0]) { jointNameToId[std::string(jointInfo.m_jointName)] = i; } else { continue; } // Reset before torque control - see #1459 command = b3JointControlCommandInit2(kPhysClient, twojoint, CONTROL_MODE_VELOCITY); b3JointControlSetDesiredVelocity(command, jointInfo.m_uIndex, 0); b3JointControlSetMaximumForce(command, jointInfo.m_uIndex, 0); statusHandle = b3SubmitClientCommandAndWaitStatus(kPhysClient, command); } // loop unsigned long dtus1 = (unsigned long)1000000.0 * FIXED_TIMESTEP; double simTimeS = 0; double q[2], v[2]; while (b3CanSubmitCommand(kPhysClient)) { simTimeS += 0.000001 * dtus1; // apply some torque b3GetJointInfo(kPhysClient, twojoint, jointNameToId["joint_2"], &jointInfo); command = b3JointControlCommandInit2(kPhysClient, twojoint, CONTROL_MODE_TORQUE); b3JointControlSetDesiredForceTorque(command, jointInfo.m_uIndex, 0.5 * sin(10 * simTimeS)); statusHandle = b3SubmitClientCommandAndWaitStatus(kPhysClient, command); // get joint values command = b3RequestActualStateCommandInit(kPhysClient, twojoint); statusHandle = b3SubmitClientCommandAndWaitStatus(kPhysClient, command); b3GetJointState(kPhysClient, statusHandle, jointNameToId["joint_1"], &state); q[0] = state.m_jointPosition; v[0] = state.m_jointVelocity; b3GetJointState(kPhysClient, statusHandle, jointNameToId["joint_2"], &state); q[1] = state.m_jointPosition; v[1] = state.m_jointVelocity; statusHandle = b3SubmitClientCommandAndWaitStatus(kPhysClient, b3InitStepSimulationCommand(kPhysClient)); // debugging output printf("%.3f\t%.3f\t%.3f\t%.3f\t%.3f\n", simTimeS, q[0], q[1], v[0], v[1]); b3Clock::usleep(1000. * 1000. * FIXED_TIMESTEP); } b3DisconnectSharedMemory(kPhysClient); return 0; }
int main(int argc, char* argv[]) { int i, dofCount , posVarCount, dofIndex, ret ,numJoints, allowSharedMemoryInitialization=0; int sensorJointIndexLeft=-1; int sensorJointIndexRight=-1; int statusType = -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; b3PhysicsClientHandle sm=0; int bodyIndex = -1; printf("hello world\n"); #ifdef PHYSICS_LOOP_BACK sm = b3ConnectPhysicsLoopback(SHARED_MEMORY_KEY); #else sm = b3ConnectSharedMemory(SHARED_MEMORY_KEY); #endif if (b3CanSubmitCommand(sm)) { { b3SharedMemoryCommandHandle command = b3InitPhysicsParamCommand(sm); ret = b3PhysicsParamSetGravity(command, gravx,gravy, gravz); ret = b3PhysicsParamSetTimeStep(command, timeStep); b3SubmitClientCommandAndWaitStatus(sm, command); } { b3SharedMemoryStatusHandle statusHandle; b3SharedMemoryCommandHandle command = b3LoadUrdfCommandInit(sm, urdfFileName); //setting the initial position, orientation and other arguments are optional startPosX =2; startPosY =3; startPosZ = 1; ret = b3LoadUrdfCommandSetStartPosition(command, startPosX,startPosY,startPosZ); statusHandle = b3SubmitClientCommandAndWaitStatus(sm, command); bodyIndex = b3GetStatusBodyIndex(statusHandle); } if (bodyIndex>=0) { numJoints = b3GetNumJoints(sm,bodyIndex); for (i=0;i<numJoints;i++) { struct b3JointInfo jointInfo; b3GetJointInfo(sm,bodyIndex, 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)) { b3SharedMemoryCommandHandle command = b3CreateSensorCommandInit(sm); b3SharedMemoryStatusHandle statusHandle; if (imuLinkIndex>=0) { ret = b3CreateSensorEnableIMUForLink(command, imuLinkIndex, 1); } if (sensorJointIndexLeft>=0) { ret = b3CreateSensorEnable6DofJointForceTorqueSensor(command, sensorJointIndexLeft, 1); } if(sensorJointIndexRight>=0) { ret = b3CreateSensorEnable6DofJointForceTorqueSensor(command, sensorJointIndexRight, 1); } statusHandle = b3SubmitClientCommandAndWaitStatus(sm, command); } } { b3SharedMemoryStatusHandle statusHandle; b3SharedMemoryCommandHandle command = b3CreateBoxShapeCommandInit(sm); ret = b3CreateBoxCommandSetStartPosition(command, 0,0,-1); ret = b3CreateBoxCommandSetStartOrientation(command,0,0,0,1); ret = b3CreateBoxCommandSetHalfExtents(command, 10,10,1); statusHandle = b3SubmitClientCommandAndWaitStatus(sm, command); } { int statusType; b3SharedMemoryCommandHandle command = b3RequestActualStateCommandInit(sm,bodyIndex); b3SharedMemoryStatusHandle statusHandle; statusHandle = b3SubmitClientCommandAndWaitStatus(sm, command); statusType = b3GetStatusType(statusHandle); if (statusType == CMD_ACTUAL_STATE_UPDATE_COMPLETED) { b3GetStatusActualState(statusHandle, 0, &posVarCount, &dofCount, 0, 0, 0, 0); b3Printf("posVarCount = %d\n",posVarCount); printf("dofCount = %d\n",dofCount); } } { #if 0 b3SharedMemoryStatusHandle statusHandle; b3SharedMemoryCommandHandle command = b3JointControlCommandInit( sm, CONTROL_MODE_VELOCITY); for ( dofIndex=0;dofIndex<dofCount;dofIndex++) { b3JointControlSetDesiredVelocity(command,dofIndex,1); b3JointControlSetMaximumForce(command,dofIndex,100); } statusHandle = b3SubmitClientCommandAndWaitStatus(sm, command); #endif } ///perform some simulation steps for testing for ( i=0;i<100;i++) { b3SubmitClientCommandAndWaitStatus(sm, b3InitStepSimulationCommand(sm)); } { b3SharedMemoryStatusHandle state = b3SubmitClientCommandAndWaitStatus(sm, b3RequestActualStateCommandInit(sm,bodyIndex)); if (sensorJointIndexLeft>=0) { struct b3JointSensorState sensorState; b3GetJointState(sm,state,sensorJointIndexLeft,&sensorState); b3Printf("Sensor for joint [%d] = %f,%f,%f\n", sensorJointIndexLeft, sensorState.m_jointForceTorque[0], sensorState.m_jointForceTorque[1], sensorState.m_jointForceTorque[2]); } if (sensorJointIndexRight>=0) { struct b3JointSensorState sensorState; b3GetJointState(sm,state,sensorJointIndexRight,&sensorState); b3Printf("Sensor for joint [%d] = %f,%f,%f\n", sensorJointIndexRight, sensorState.m_jointForceTorque[0], sensorState.m_jointForceTorque[1], sensorState.m_jointForceTorque[2]); } } { b3SubmitClientCommandAndWaitStatus(sm, b3InitResetSimulationCommand(sm)); } } b3DisconnectSharedMemory(sm); }
B3_SHARED_API int preTickPluginCallback_vrSyncPlugin(struct b3PluginContext* context) { MyClass* obj = (MyClass*)context->m_userPointer; if (obj && obj->m_controllerId >= 0) { { int i = 0; { for (int n = 0; n < context->m_numVRControllerEvents; n++) { const b3VRControllerEvent& event = context->m_vrControllerEvents[n]; if (event.m_controllerId == obj->m_controllerId) { if (obj->m_constraintId >= 0) { struct b3UserConstraint constraintInfo; if (b3GetUserConstraintInfo(context->m_physClient, obj->m_constraintId, &constraintInfo)) { //this is basically equivalent to doing this in Python/pybullet: //p.changeConstraint(pr2_cid, e[POSITION], e[ORIENTATION], maxForce=...) b3SharedMemoryCommandHandle commandHandle; int userConstraintUniqueId = obj->m_constraintId; commandHandle = b3InitChangeUserConstraintCommand(context->m_physClient, userConstraintUniqueId); double pos[4] = {event.m_pos[0], event.m_pos[1], event.m_pos[2], 1}; b3InitChangeUserConstraintSetPivotInB(commandHandle, pos); double orn[4] = {event.m_orn[0], event.m_orn[1], event.m_orn[2], event.m_orn[3]}; b3InitChangeUserConstraintSetFrameInB(commandHandle, orn); b3InitChangeUserConstraintSetMaxForce(commandHandle, obj->m_maxForce); b3SharedMemoryStatusHandle statusHandle = b3SubmitClientCommandAndWaitStatus(context->m_physClient, commandHandle); } } // apply the analogue button to close the constraint, using a gear constraint with position target if (obj->m_constraintId2 >= 0) { struct b3UserConstraint constraintInfo; if (b3GetUserConstraintInfo(context->m_physClient, obj->m_constraintId2, &constraintInfo)) { //this block is similar to //p.changeConstraint(c,gearRatio=1, erp=..., relativePositionTarget=relPosTarget, maxForce=...) //printf("obj->m_constraintId2=%d\n", obj->m_constraintId2); b3SharedMemoryCommandHandle commandHandle; commandHandle = b3InitChangeUserConstraintCommand(context->m_physClient, obj->m_constraintId2); //0 -> open, 1 = closed double openPos = 1.; double relPosTarget = openPos - (event.m_analogAxis * openPos); b3InitChangeUserConstraintSetRelativePositionTarget(commandHandle, relPosTarget); b3InitChangeUserConstraintSetERP(commandHandle, 1); b3SharedMemoryStatusHandle statusHandle = b3SubmitClientCommandAndWaitStatus(context->m_physClient, commandHandle); } } //printf("event.m_analogAxis=%f\n", event.m_analogAxis); // use the pr2_gripper motors to keep the gripper centered/symmetric around the center axis if (obj->m_gripperId >= 0) { //this block is similar to //b = p.getJointState(pr2_gripper,2)[0] //print("b = " + str(b)) //p.setJointMotorControl2(pr2_gripper, 0, p.POSITION_CONTROL, targetPosition=b, force=3) //printf("obj->m_gripperId=%d\n", obj->m_gripperId); { b3SharedMemoryCommandHandle cmd_handle = b3RequestActualStateCommandInit(context->m_physClient, obj->m_gripperId); b3SharedMemoryStatusHandle status_handle = b3SubmitClientCommandAndWaitStatus(context->m_physClient, cmd_handle); int status_type = b3GetStatusType(status_handle); if (status_type == CMD_ACTUAL_STATE_UPDATE_COMPLETED) { //printf("status_type == CMD_ACTUAL_STATE_UPDATE_COMPLETED\n"); b3JointSensorState sensorState; if (b3GetJointState(context->m_physClient, status_handle, 2, &sensorState)) { b3SharedMemoryCommandHandle commandHandle; double targetPosition = sensorState.m_jointPosition; //printf("targetPosition =%f\n", targetPosition); if (1) { b3JointInfo info; b3GetJointInfo(context->m_physClient, obj->m_gripperId, 0, &info); commandHandle = b3JointControlCommandInit2(context->m_physClient, obj->m_gripperId, CONTROL_MODE_POSITION_VELOCITY_PD); double kp = .1; double targetVelocity = 0; double kd = .6; b3JointControlSetDesiredPosition(commandHandle, info.m_qIndex, targetPosition); b3JointControlSetKp(commandHandle, info.m_uIndex, kp); b3JointControlSetDesiredVelocity(commandHandle, info.m_uIndex, targetVelocity); b3JointControlSetKd(commandHandle, info.m_uIndex, kd); b3JointControlSetMaximumForce(commandHandle, info.m_uIndex, obj->m_maxForce2); b3SubmitClientCommandAndWaitStatus(context->m_physClient, cmd_handle); } } else { //printf("???\n"); } } else { //printf("no\n"); } } } } } } } } return 0; }
void testSharedMemory(b3PhysicsClientHandle sm) { int i, dofCount , posVarCount, ret ,numJoints ; int sensorJointIndexLeft=-1; int sensorJointIndexRight=-1; const char* urdfFileName = "r2d2.urdf"; const char* sdfFileName = "kuka_iiwa/model.sdf"; double gravx=0, gravy=0, gravz=-9.8; double timeStep = 1./60.; double startPosX, startPosY,startPosZ; int imuLinkIndex = -1; int bodyIndex = -1; if (b3CanSubmitCommand(sm)) { { b3SharedMemoryCommandHandle command = b3InitPhysicsParamCommand(sm); b3SharedMemoryStatusHandle statusHandle; ret = b3PhysicsParamSetGravity(command, gravx,gravy, gravz); ret = b3PhysicsParamSetTimeStep(command, timeStep); statusHandle = b3SubmitClientCommandAndWaitStatus(sm, command); ASSERT_EQ(b3GetStatusType(statusHandle), CMD_CLIENT_COMMAND_COMPLETED); } { b3SharedMemoryStatusHandle statusHandle; int statusType; int bodyIndicesOut[10];//MAX_SDF_BODIES = 10 int numJoints, numBodies; int bodyUniqueId; b3SharedMemoryCommandHandle command = b3LoadSdfCommandInit(sm, sdfFileName); statusHandle = b3SubmitClientCommandAndWaitStatus(sm, command); statusType = b3GetStatusType(statusHandle); ASSERT_EQ(statusType, CMD_SDF_LOADING_COMPLETED); numBodies = b3GetStatusBodyIndices(statusHandle, bodyIndicesOut, 10); ASSERT_EQ(numBodies,1); bodyUniqueId = bodyIndicesOut[0]; { { b3SharedMemoryStatusHandle statusHandle; int statusType; b3SharedMemoryCommandHandle command = b3InitRequestVisualShapeInformation(sm, bodyUniqueId); statusHandle = b3SubmitClientCommandAndWaitStatus(sm, command); statusType = b3GetStatusType(statusHandle); if (statusType == CMD_VISUAL_SHAPE_INFO_COMPLETED) { struct b3VisualShapeInformation vi; b3GetVisualShapeInformation(sm, &vi); } } } numJoints = b3GetNumJoints(sm,bodyUniqueId); ASSERT_EQ(numJoints,7); #if 0 b3Printf("numJoints: %d\n", numJoints); for (i=0;i<numJoints;i++) { struct b3JointInfo jointInfo; if (b3GetJointInfo(sm,bodyUniqueId, i,&jointInfo)) { b3Printf("jointInfo[%d].m_jointName=%s\n",i,jointInfo.m_jointName); } } #endif { b3SharedMemoryStatusHandle statusHandle; b3SharedMemoryCommandHandle commandHandle; double jointAngle = 0.f; int jointIndex; commandHandle = b3CreatePoseCommandInit(sm, bodyUniqueId); for (jointIndex=0;jointIndex<numJoints;jointIndex++) { b3CreatePoseCommandSetJointPosition(sm, commandHandle, jointIndex, jointAngle); } statusHandle = b3SubmitClientCommandAndWaitStatus(sm, commandHandle); ASSERT_EQ(b3GetStatusType(statusHandle), CMD_CLIENT_COMMAND_COMPLETED); } } { b3SharedMemoryStatusHandle statusHandle; int statusType; b3SharedMemoryCommandHandle command = b3LoadUrdfCommandInit(sm, urdfFileName); //setting the initial position, orientation and other arguments are optional startPosX =2; startPosY =0; startPosZ = 1; ret = b3LoadUrdfCommandSetStartPosition(command, startPosX,startPosY,startPosZ); statusHandle = b3SubmitClientCommandAndWaitStatus(sm, command); statusType = b3GetStatusType(statusHandle); ASSERT_EQ(statusType, CMD_URDF_LOADING_COMPLETED); bodyIndex = b3GetStatusBodyIndex(statusHandle); } if (bodyIndex>=0) { numJoints = b3GetNumJoints(sm,bodyIndex); for (i=0;i<numJoints;i++) { struct b3JointInfo jointInfo; b3GetJointInfo(sm,bodyIndex, 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)) { b3SharedMemoryCommandHandle command = b3CreateSensorCommandInit(sm, bodyIndex); b3SharedMemoryStatusHandle statusHandle; if (imuLinkIndex>=0) { ret = b3CreateSensorEnableIMUForLink(command, imuLinkIndex, 1); } if (sensorJointIndexLeft>=0) { ret = b3CreateSensorEnable6DofJointForceTorqueSensor(command, sensorJointIndexLeft, 1); } if(sensorJointIndexRight>=0) { ret = b3CreateSensorEnable6DofJointForceTorqueSensor(command, sensorJointIndexRight, 1); } statusHandle = b3SubmitClientCommandAndWaitStatus(sm, command); ASSERT_EQ(b3GetStatusType(statusHandle), CMD_CLIENT_COMMAND_COMPLETED); } } { b3SharedMemoryStatusHandle statusHandle; b3SharedMemoryCommandHandle command = b3CreateBoxShapeCommandInit(sm); ret = b3CreateBoxCommandSetStartPosition(command, 0,0,-1); ret = b3CreateBoxCommandSetStartOrientation(command,0,0,0,1); ret = b3CreateBoxCommandSetHalfExtents(command, 10,10,1); statusHandle = b3SubmitClientCommandAndWaitStatus(sm, command); ASSERT_EQ(b3GetStatusType(statusHandle), CMD_RIGID_BODY_CREATION_COMPLETED); } { int statusType; b3SharedMemoryCommandHandle command = b3RequestActualStateCommandInit(sm,bodyIndex); b3SharedMemoryStatusHandle statusHandle; statusHandle = b3SubmitClientCommandAndWaitStatus(sm, command); statusType = b3GetStatusType(statusHandle); ASSERT_EQ(statusType, CMD_ACTUAL_STATE_UPDATE_COMPLETED); if (statusType == CMD_ACTUAL_STATE_UPDATE_COMPLETED) { b3GetStatusActualState(statusHandle, 0, &posVarCount, &dofCount, 0, 0, 0, 0); ASSERT_EQ(posVarCount,15); ASSERT_EQ(dofCount,14); } } { #if 0 b3SharedMemoryStatusHandle statusHandle; b3SharedMemoryCommandHandle command = b3JointControlCommandInit( sm, CONTROL_MODE_VELOCITY); for ( dofIndex=0;dofIndex<dofCount;dofIndex++) { b3JointControlSetDesiredVelocity(command,dofIndex,1); b3JointControlSetMaximumForce(command,dofIndex,100); } statusHandle = b3SubmitClientCommandAndWaitStatus(sm, command); #endif } ///perform some simulation steps for testing for ( i=0;i<100;i++) { b3SharedMemoryStatusHandle statusHandle; int statusType; if (b3CanSubmitCommand(sm)) { statusHandle = b3SubmitClientCommandAndWaitStatus(sm, b3InitStepSimulationCommand(sm)); statusType = b3GetStatusType(statusHandle); ASSERT_EQ(statusType, CMD_STEP_FORWARD_SIMULATION_COMPLETED); } else { break; } } if (b3CanSubmitCommand(sm)) { b3SharedMemoryStatusHandle state = b3SubmitClientCommandAndWaitStatus(sm, b3RequestActualStateCommandInit(sm,bodyIndex)); if (sensorJointIndexLeft>=0) { struct b3JointSensorState sensorState; b3GetJointState(sm,state,sensorJointIndexLeft,&sensorState); b3Printf("Sensor for joint [%d] = %f,%f,%f\n", sensorJointIndexLeft, sensorState.m_jointForceTorque[0], sensorState.m_jointForceTorque[1], sensorState.m_jointForceTorque[2]); } if (sensorJointIndexRight>=0) { struct b3JointSensorState sensorState; b3GetJointState(sm,state,sensorJointIndexRight,&sensorState); b3Printf("Sensor for joint [%d] = %f,%f,%f\n", sensorJointIndexRight, sensorState.m_jointForceTorque[0], sensorState.m_jointForceTorque[1], sensorState.m_jointForceTorque[2]); } { b3SharedMemoryStatusHandle statusHandle; statusHandle = b3SubmitClientCommandAndWaitStatus(sm, b3InitResetSimulationCommand(sm)); ASSERT_EQ(b3GetStatusType(statusHandle), CMD_RESET_SIMULATION_COMPLETED); } } } b3DisconnectSharedMemory(sm); }
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); }