B3_SHARED_API int executePluginCommand_vrSyncPlugin(struct b3PluginContext* context, const struct b3PluginArguments* arguments) { MyClass* obj = (MyClass*)context->m_userPointer; if (arguments->m_numInts >= 4 && arguments->m_numFloats >= 2) { obj->m_constraintId = arguments->m_ints[1]; obj->m_constraintId2 = arguments->m_ints[2]; obj->m_gripperId = arguments->m_ints[3]; printf("obj->m_constraintId=%d\n", obj->m_constraintId); obj->m_maxForce = arguments->m_floats[0]; obj->m_maxForce2 = arguments->m_floats[1]; printf("obj->m_maxForce = %f\n", obj->m_maxForce); obj->m_controllerId = arguments->m_ints[0]; printf("obj->m_controllerId=%d\n", obj->m_controllerId); b3SharedMemoryCommandHandle command = b3InitSyncBodyInfoCommand(context->m_physClient); b3SharedMemoryStatusHandle statusHandle = b3SubmitClientCommandAndWaitStatus(context->m_physClient, command); int statusType = b3GetStatusType(statusHandle); if (statusType != CMD_SYNC_BODY_INFO_COMPLETED) { } } return 0; }
static PyObject * pybullet_loadURDF(PyObject* self, PyObject* args) { int size= PySequence_Size(args); int bodyIndex = -1; const char* urdfFileName=""; float startPosX =0; float startPosY =0; float startPosZ = 1; float startOrnX = 0; float startOrnY = 0; float startOrnZ = 0; float startOrnW = 1; //printf("size=%d\n", size); if (0==sm) { PyErr_SetString(SpamError, "Not connected to physics server."); return NULL; } if (size==1) { if (!PyArg_ParseTuple(args, "s", &urdfFileName)) return NULL; } if (size == 4) { if (!PyArg_ParseTuple(args, "sfff", &urdfFileName, &startPosX,&startPosY,&startPosZ)) return NULL; } if (size==8) { if (!PyArg_ParseTuple(args, "sfffffff", &urdfFileName, &startPosX,&startPosY,&startPosZ, &startOrnX,&startOrnY,&startOrnZ, &startOrnW)) return NULL; } { b3SharedMemoryStatusHandle statusHandle; int statusType; b3SharedMemoryCommandHandle command = b3LoadUrdfCommandInit(sm, urdfFileName); //printf("urdf filename = %s\n", urdfFileName); //setting the initial position, orientation and other arguments are optional b3LoadUrdfCommandSetStartPosition(command, startPosX,startPosY,startPosZ); statusHandle = b3SubmitClientCommandAndWaitStatus(sm, command); statusType = b3GetStatusType(statusHandle); if (statusType!=CMD_URDF_LOADING_COMPLETED) { PyErr_SetString(SpamError, "Cannot load URDF file."); return NULL; } bodyIndex = b3GetStatusBodyIndex(statusHandle); } return PyLong_FromLong(bodyIndex); }
static void pybullet_internalGetBasePositionAndOrientation(int bodyIndex, double basePosition[3],double baseOrientation[3]) { basePosition[0] = 0.; basePosition[1] = 0.; basePosition[2] = 0.; baseOrientation[0] = 0.; baseOrientation[1] = 0.; baseOrientation[2] = 0.; baseOrientation[3] = 1.; { { b3SharedMemoryCommandHandle cmd_handle = b3RequestActualStateCommandInit(sm, bodyIndex); b3SharedMemoryStatusHandle status_handle = b3SubmitClientCommandAndWaitStatus(sm, cmd_handle); const int status_type = b3GetStatusType(status_handle); const double* actualStateQ; b3GetStatusActualState(status_handle, 0/* body_unique_id */, 0/* num_degree_of_freedom_q */, 0/* num_degree_of_freedom_u */, 0 /*root_local_inertial_frame*/, &actualStateQ , 0 /* actual_state_q_dot */, 0 /* joint_reaction_forces */); //now, position x,y,z = actualStateQ[0],actualStateQ[1],actualStateQ[2] //and orientation x,y,z,w = actualStateQ[3],actualStateQ[4],actualStateQ[5],actualStateQ[6] basePosition[0] = actualStateQ[0]; basePosition[1] = actualStateQ[1]; basePosition[2] = actualStateQ[2]; baseOrientation[0] = actualStateQ[3]; baseOrientation[1] = actualStateQ[4]; baseOrientation[2] = actualStateQ[5]; baseOrientation[3] = actualStateQ[6]; } } }
static PyObject * pybullet_stepSimulation(PyObject *self, PyObject *args) { if (0==sm) { PyErr_SetString(SpamError, "Not connected to physics server."); return NULL; } { b3SharedMemoryStatusHandle statusHandle; int statusType; if (b3CanSubmitCommand(sm)) { statusHandle = b3SubmitClientCommandAndWaitStatus(sm, b3InitStepSimulationCommand(sm)); statusType = b3GetStatusType(statusHandle); } } Py_INCREF(Py_None); return Py_None; }
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; }
static PyObject* pybullet_renderImage(PyObject* self, PyObject* args) { if (0==sm) { PyErr_SetString(SpamError, "Not connected to physics server."); return NULL; } ///request an image from a simulated camera, using a software renderer. struct b3CameraImageData imageData; PyObject* objViewMat,* objProjMat; int width, height; if (PyArg_ParseTuple(args, "iiOO", &width, &height, &objViewMat, &objProjMat)) { PyObject* seq; int i, len; PyObject* item; float viewMatrix[16]; float projectionMatrix[16]; int valid = 1; { seq = PySequence_Fast(objViewMat, "expected a sequence"); len = PySequence_Size(objViewMat); //printf("objViewMat size = %d\n", len); if (len==16) { if (PyList_Check(seq)) { for (i = 0; i < len; i++) { item = PyList_GET_ITEM(seq, i); viewMatrix[i] = PyFloat_AsDouble(item); float v = viewMatrix[i]; //printf("view %d to %f\n", i,v); } } else { for (i = 0; i < len; i++) { item = PyTuple_GET_ITEM(seq,i); viewMatrix[i] = PyFloat_AsDouble(item); } } } else { valid = 0; } } { seq = PySequence_Fast(objProjMat, "expected a sequence"); len = PySequence_Size(objProjMat); //printf("projMat len = %d\n", len); if (len==16) { if (PyList_Check(seq)) { for (i = 0; i < len; i++) { item = PyList_GET_ITEM(seq, i); projectionMatrix[i] = PyFloat_AsDouble(item); } } else { for (i = 0; i < len; i++) { item = PyTuple_GET_ITEM(seq,i); projectionMatrix[i] = PyFloat_AsDouble(item); } } } else { valid = 0; } } Py_DECREF(seq); { b3SharedMemoryCommandHandle command; command = b3InitRequestCameraImage(sm); if (valid) { //printf("set b3RequestCameraImageSetCameraMatrices\n"); b3RequestCameraImageSetCameraMatrices(command, viewMatrix, projectionMatrix); } b3RequestCameraImageSetPixelResolution(command,width,height); if (b3CanSubmitCommand(sm)) { b3SharedMemoryStatusHandle statusHandle; int statusType; statusHandle = b3SubmitClientCommandAndWaitStatus(sm, command); statusType = b3GetStatusType(statusHandle); if (statusType==CMD_CAMERA_IMAGE_COMPLETED) { PyObject *item2; PyObject* pyResultList;//store 4 elements in this result: width, height, rgbData, depth b3GetCameraImageData(sm, &imageData); //todo: error handling if image size is 0 pyResultList = PyTuple_New(4); PyTuple_SetItem(pyResultList, 0, PyInt_FromLong(imageData.m_pixelWidth)); PyTuple_SetItem(pyResultList, 1, PyInt_FromLong(imageData.m_pixelHeight)); PyObject *pylistPos; PyObject* pylistDep; int i,j,p; //printf("image width = %d, height = %d\n", imageData.m_pixelWidth, imageData.m_pixelHeight); { PyObject *item; int bytesPerPixel = 4;//Red, Green, Blue, each 8 bit values int num=bytesPerPixel*imageData.m_pixelWidth*imageData.m_pixelHeight; pylistPos = PyTuple_New(num); pylistDep = PyTuple_New(imageData.m_pixelWidth*imageData.m_pixelHeight); for (i=0;i<imageData.m_pixelWidth;i++) { for (j=0;j<imageData.m_pixelHeight;j++) { int depIndex = i+j*imageData.m_pixelWidth; item = PyFloat_FromDouble(imageData.m_depthValues[depIndex]); PyTuple_SetItem(pylistDep, depIndex, item); for (p=0;p<bytesPerPixel;p++) { int pixelIndex = bytesPerPixel*(i+j*imageData.m_pixelWidth)+p; item = PyInt_FromLong(imageData.m_rgbColorData[pixelIndex]); PyTuple_SetItem(pylistPos, pixelIndex, item); } } } } PyTuple_SetItem(pyResultList, 2,pylistPos); PyTuple_SetItem(pyResultList, 3,pylistDep); return pyResultList; } } } } Py_INCREF(Py_None); return Py_None; }
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); }
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::stepSimulation(float deltaTime) { 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_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(); } prepareAndSubmitCommand(commandId); } else { if (m_numMotors) { enqueueCommand(CMD_SEND_DESIRED_STATE); enqueueCommand(CMD_STEP_FORWARD_SIMULATION); enqueueCommand(CMD_REQUEST_DEBUG_LINES); //enqueueCommand(CMD_REQUEST_ACTUAL_STATE); } } } }
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) { //compute depth image range float minDepthValue = 1e20f; float maxDepthValue = -1e20f; for (int i = 0; i < camVisualizerWidth; i++) { for (int j = 0; j < camVisualizerHeight; j++) { int xIndex = int(float(i) * (float(imageData.m_pixelWidth) / float(camVisualizerWidth))); int yIndex = int(float(j) * (float(imageData.m_pixelHeight) / float(camVisualizerHeight))); btClamp(xIndex, 0, imageData.m_pixelWidth); btClamp(yIndex, 0, imageData.m_pixelHeight); if (m_canvasDepthIndex >= 0) { int depthPixelIndex = (xIndex + yIndex * imageData.m_pixelWidth); float depthValue = imageData.m_depthValues[depthPixelIndex]; //todo: rescale the depthValue to [0..255] if (depthValue > -1e20) { maxDepthValue = btMax(maxDepthValue, depthValue); minDepthValue = btMin(minDepthValue, depthValue); } } } } for (int i = 0; i < camVisualizerWidth; i++) { for (int j = 0; j < camVisualizerHeight; j++) { int xIndex = int(float(i) * (float(imageData.m_pixelWidth) / float(camVisualizerWidth))); int yIndex = int(float(j) * (float(imageData.m_pixelHeight) / float(camVisualizerHeight))); btClamp(yIndex, 0, imageData.m_pixelHeight); btClamp(xIndex, 0, imageData.m_pixelWidth); int bytesPerPixel = 4; //RGBA if (m_canvasRGBIndex >= 0) { int rgbPixelIndex = (xIndex + yIndex * imageData.m_pixelWidth) * bytesPerPixel; m_canvas->setPixel(m_canvasRGBIndex, i, j, imageData.m_rgbColorData[rgbPixelIndex], imageData.m_rgbColorData[rgbPixelIndex + 1], imageData.m_rgbColorData[rgbPixelIndex + 2], 255); //alpha set to 255 } if (m_canvasDepthIndex >= 0) { int depthPixelIndex = (xIndex + yIndex * imageData.m_pixelWidth); float depthValue = imageData.m_depthValues[depthPixelIndex]; //todo: rescale the depthValue to [0..255] if (depthValue > -1e20) { int rgb = 0; if (maxDepthValue != minDepthValue) { rgb = (depthValue - minDepthValue) * (255. / (btFabs(maxDepthValue - minDepthValue))); if (rgb < 0 || rgb > 255) { //printf("rgb=%d\n",rgb); } } m_canvas->setPixel(m_canvasDepthIndex, i, j, rgb, rgb, 255, 255); //alpha set to 255 } else { m_canvas->setPixel(m_canvasDepthIndex, i, j, 0, 0, 0, 255); //alpha set to 255 } } if (m_canvasSegMaskIndex >= 0 && (0 != imageData.m_segmentationMaskValues)) { int segmentationMaskPixelIndex = (xIndex + yIndex * imageData.m_pixelWidth); int segmentationMask = imageData.m_segmentationMaskValues[segmentationMaskPixelIndex]; btVector4 palette[4] = {btVector4(32, 255, 32, 255), btVector4(32, 32, 255, 255), btVector4(255, 255, 32, 255), btVector4(32, 255, 255, 255)}; if (segmentationMask >= 0) { int obIndex = segmentationMask & ((1 << 24) - 1); int linkIndex = (segmentationMask >> 24) - 1; btVector4 rgb = palette[(obIndex + linkIndex) & 3]; m_canvas->setPixel(m_canvasSegMaskIndex, i, j, rgb.x(), rgb.y(), rgb.z(), 255); //alpha set to 255 } else { m_canvas->setPixel(m_canvasSegMaskIndex, i, j, 0, 0, 0, 255); //alpha set to 255 } } } } if (m_canvasRGBIndex >= 0) m_canvas->refreshImageData(m_canvasRGBIndex); if (m_canvasDepthIndex >= 0) m_canvas->refreshImageData(m_canvasDepthIndex); if (m_canvasSegMaskIndex >= 0) m_canvas->refreshImageData(m_canvasSegMaskIndex); }