void PhysicsClientExample::initPhysics() { if (m_guiHelper && m_guiHelper->getParameterInterface()) { int upAxis = 2; m_guiHelper->setUpAxis(upAxis); createButtons(); } else { MyCallback(CMD_LOAD_URDF, true, this); MyCallback(CMD_STEP_FORWARD_SIMULATION,true,this); MyCallback(CMD_STEP_FORWARD_SIMULATION,true,this); MyCallback(CMD_RESET_SIMULATION,true,this); } m_selectedBody = -1; m_prevSelectedBody = -1; if (m_options == eCLIENTEXAMPLE_SERVER) { m_canvas = m_guiHelper->get2dCanvasInterface(); if (m_canvas) { m_canvasIndex = m_canvas->createCanvas("Synthetic Camera",camVisualizerWidth, camVisualizerHeight); for (int i=0;i<camVisualizerWidth;i++) { for (int j=0;j<camVisualizerHeight;j++) { unsigned char red=255; unsigned char green=255; unsigned char blue=255; unsigned char alpha=255; if (i==j) { red = 0; green=0; blue=0; } m_canvas->setPixel(m_canvasIndex,i,j,red,green,blue,alpha); } } m_canvas->refreshImageData(m_canvasIndex); } m_isOptionalServerConnected = m_physicsServer.connectSharedMemory( m_guiHelper); } m_physicsClientHandle = b3ConnectSharedMemory(m_sharedMemoryKey); //m_physicsClientHandle = b3ConnectPhysicsLoopback(SHARED_MEMORY_KEY); //m_physicsClientHandle = b3ConnectPhysicsDirect(); if (!b3CanSubmitCommand(m_physicsClientHandle)) { b3Warning("Cannot connect to physics client"); } }
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_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); }