PhysicsClientExample.cpp 35 KB

12345678910111213141516171819202122232425262728293031323334353637383940414243444546474849505152535455565758596061626364656667686970717273747576777879808182838485868788899091929394959697989910010110210310410510610710810911011111211311411511611711811912012112212312412512612712812913013113213313413513613713813914014114214314414514614714814915015115215315415515615715815916016116216316416516616716816917017117217317417517617717817918018118218318418518618718818919019119219319419519619719819920020120220320420520620720820921021121221321421521621721821922022122222322422522622722822923023123223323423523623723823924024124224324424524624724824925025125225325425525625725825926026126226326426526626726826927027127227327427527627727827928028128228328428528628728828929029129229329429529629729829930030130230330430530630730830931031131231331431531631731831932032132232332432532632732832933033133233333433533633733833934034134234334434534634734834935035135235335435535635735835936036136236336436536636736836937037137237337437537637737837938038138238338438538638738838939039139239339439539639739839940040140240340440540640740840941041141241341441541641741841942042142242342442542642742842943043143243343443543643743843944044144244344444544644744844945045145245345445545645745845946046146246346446546646746846947047147247347447547647747847948048148248348448548648748848949049149249349449549649749849950050150250350450550650750850951051151251351451551651751851952052152252352452552652752852953053153253353453553653753853954054154254354454554654754854955055155255355455555655755855956056156256356456556656756856957057157257357457557657757857958058158258358458558658758858959059159259359459559659759859960060160260360460560660760860961061161261361461561661761861962062162262362462562662762862963063163263363463563663763863964064164264364464564664764864965065165265365465565665765865966066166266366466566666766866967067167267367467567667767867968068168268368468568668768868969069169269369469569669769869970070170270370470570670770870971071171271371471571671771871972072172272372472572672772872973073173273373473573673773873974074174274374474574674774874975075175275375475575675775875976076176276376476576676776876977077177277377477577677777877978078178278378478578678778878979079179279379479579679779879980080180280380480580680780880981081181281381481581681781881982082182282382482582682782882983083183283383483583683783883984084184284384484584684784884985085185285385485585685785885986086186286386486586686786886987087187287387487587687787887988088188288388488588688788888989089189289389489589689789889990090190290390490590690790890991091191291391491591691791891992092192292392492592692792892993093193293393493593693793893994094194294394494594694794894995095195295395495595695795895996096196296396496596696796896997097197297397497597697797897998098198298398498598698798898999099199299399499599699799899910001001100210031004100510061007100810091010101110121013101410151016101710181019102010211022102310241025102610271028102910301031103210331034103510361037103810391040104110421043104410451046104710481049105010511052105310541055
  1. #include "PhysicsClientExample.h"
  2. #include "../CommonInterfaces/CommonMultiBodyBase.h"
  3. #include "../CommonInterfaces/Common2dCanvasInterface.h"
  4. #include "SharedMemoryCommon.h"
  5. #include "../CommonInterfaces/CommonParameterInterface.h"
  6. #include "PhysicsClientC_API.h"
  7. #include "PhysicsClient.h"
  8. //#include "SharedMemoryCommands.h"
  9. #include "PhysicsLoopBackC_API.h"
  10. #include "PhysicsDirectC_API.h"
  11. #include "PhysicsClientC_API.h"
  12. #include "PhysicsServerSharedMemory.h"
  13. struct MyMotorInfo2
  14. {
  15. btScalar m_velTarget;
  16. btScalar m_maxForce;
  17. btScalar m_posTarget;
  18. int m_uIndex;
  19. int m_qIndex;
  20. };
  21. int camVisualizerWidth = 320;//1024/3;
  22. int camVisualizerHeight = 240;//768/3;
  23. #define MAX_NUM_MOTORS 128
  24. class PhysicsClientExample : public SharedMemoryCommon
  25. {
  26. protected:
  27. b3PhysicsClientHandle m_physicsClientHandle;
  28. //this m_physicsServer is only used when option eCLIENTEXAMPLE_SERVER is enabled
  29. PhysicsServerSharedMemory m_physicsServer;
  30. bool m_wantsTermination;
  31. btAlignedObjectArray<int> m_userCommandRequests;
  32. btAlignedObjectArray<int> m_bodyUniqueIds;
  33. int m_sharedMemoryKey;
  34. int m_selectedBody;
  35. int m_prevSelectedBody;
  36. struct Common2dCanvasInterface* m_canvas;
  37. int m_canvasRGBIndex;
  38. int m_canvasDepthIndex;
  39. int m_canvasSegMaskIndex;
  40. void createButton(const char* name, int id, bool isTrigger );
  41. void createButtons();
  42. //@todo, add accessor methods
  43. // MyMotorInfo2 m_motorTargetVelocities[MAX_NUM_MOTORS];
  44. MyMotorInfo2 m_motorTargetPositions[MAX_NUM_MOTORS];
  45. int m_numMotors;
  46. int m_options;
  47. bool m_isOptionalServerConnected;
  48. public:
  49. PhysicsClientExample(GUIHelperInterface* helper, int options);
  50. virtual ~PhysicsClientExample();
  51. virtual void initPhysics();
  52. void selectComboBox(int comboIndex, const char* name)
  53. {
  54. if (m_guiHelper && m_guiHelper->getParameterInterface())
  55. {
  56. int itemIndex = int(atoi(name));
  57. int bodyIndex = m_bodyUniqueIds[itemIndex];
  58. if (m_selectedBody != bodyIndex)
  59. {
  60. m_selectedBody = bodyIndex;
  61. }
  62. }
  63. }
  64. virtual void stepSimulation(float deltaTime);
  65. virtual void resetCamera()
  66. {
  67. float dist = 4;
  68. float pitch = 193;
  69. float yaw = 25;
  70. float targetPos[3]={0,0,0.5};//-3,2.8,-2.5};
  71. m_guiHelper->resetCamera(dist,pitch,yaw,targetPos[0],targetPos[1],targetPos[2]);
  72. }
  73. virtual bool wantsTermination()
  74. {
  75. return m_wantsTermination;
  76. }
  77. virtual bool isConnected()
  78. {
  79. return (m_physicsClientHandle!=0);
  80. }
  81. void enqueueCommand(int commandId);
  82. void prepareAndSubmitCommand(int commandId);
  83. virtual void exitPhysics(){};
  84. virtual void renderScene()
  85. {
  86. if (m_options == eCLIENTEXAMPLE_SERVER)
  87. {
  88. m_physicsServer.renderScene();
  89. }
  90. b3DebugLines debugLines;
  91. b3GetDebugLines(m_physicsClientHandle,&debugLines);
  92. int numLines = debugLines.m_numDebugLines;
  93. int lineWidth = 1;
  94. if (1)
  95. {
  96. btAlignedObjectArray<btVector3FloatData> points;
  97. points.resize(numLines*2);
  98. btAlignedObjectArray<unsigned int> indices;
  99. indices.resize(numLines*2);
  100. for (int i=0;i<numLines;i++)
  101. {
  102. points[i*2].m_floats[0] = debugLines.m_linesFrom[i*3+0];
  103. points[i*2].m_floats[1] = debugLines.m_linesFrom[i*3+1];
  104. points[i*2].m_floats[2] = debugLines.m_linesFrom[i*3+2];
  105. points[i*2+1].m_floats[0] = debugLines.m_linesTo[i*3+0];
  106. points[i*2+1].m_floats[1] = debugLines.m_linesTo[i*3+1];
  107. points[i*2+1].m_floats[2] = debugLines.m_linesTo[i*3+2];
  108. indices[i*2] = i*2;
  109. indices[i*2+1] = i*2+1;
  110. }
  111. float color[4] = {0.2,0.2,1,1};
  112. if (points.size() && indices.size())
  113. {
  114. m_guiHelper->getRenderInterface()->drawLines(&points[0].m_floats[0],color,points.size(),sizeof(btVector3FloatData),&indices[0],indices.size(),lineWidth);
  115. }
  116. } else
  117. {
  118. for (int i=0;i<numLines;i++)
  119. {
  120. m_guiHelper->getRenderInterface()->drawLine(debugLines.m_linesFrom,debugLines.m_linesTo,debugLines.m_linesColor,lineWidth);
  121. }
  122. }
  123. }
  124. void prepareControlCommand(b3SharedMemoryCommandHandle commandHandle)
  125. {
  126. for (int i=0;i<m_numMotors;i++)
  127. {
  128. btScalar targetPos = m_motorTargetPositions[i].m_posTarget;
  129. int qIndex = m_motorTargetPositions[i].m_qIndex;
  130. int uIndex = m_motorTargetPositions[i].m_uIndex;
  131. static int serial=0;
  132. serial++;
  133. // b3Printf("# motors = %d, cmd[%d] qIndex = %d, uIndex = %d, targetPos = %f", m_numMotors, serial, qIndex,uIndex,targetPos);
  134. b3JointControlSetDesiredPosition(commandHandle, qIndex, targetPos);
  135. b3JointControlSetDesiredVelocity(commandHandle,uIndex,0);
  136. b3JointControlSetKp(commandHandle, qIndex, 0.2);
  137. b3JointControlSetKd(commandHandle, uIndex, 1.);
  138. b3JointControlSetMaximumForce(commandHandle,uIndex,5000);
  139. }
  140. }
  141. virtual void physicsDebugDraw(int debugFlags)
  142. {
  143. if (m_options==eCLIENTEXAMPLE_SERVER)
  144. {
  145. m_physicsServer.physicsDebugDraw(debugFlags);
  146. }
  147. }
  148. virtual bool mouseMoveCallback(float x,float y){return false;};
  149. virtual bool mouseButtonCallback(int button, int state, float x, float y){return false;}
  150. virtual bool keyboardCallback(int key, int state){return false;}
  151. virtual void setSharedMemoryKey(int key)
  152. {
  153. m_sharedMemoryKey = key;
  154. }
  155. };
  156. void MyComboBoxCallback (int combobox, const char* item, void* userPointer)
  157. {
  158. //b3Printf("Item selected %s", item);
  159. PhysicsClientExample* cl = (PhysicsClientExample*) userPointer;
  160. b3Assert(cl);
  161. if (cl)
  162. {
  163. cl->selectComboBox(combobox,item);
  164. }
  165. }
  166. void MyCallback(int buttonId, bool buttonState, void* userPtr)
  167. {
  168. PhysicsClientExample* cl = (PhysicsClientExample*) userPtr;
  169. b3Assert(cl);
  170. if (cl && buttonState)
  171. {
  172. cl->enqueueCommand(buttonId);
  173. }
  174. }
  175. void PhysicsClientExample::enqueueCommand(int commandId)
  176. {
  177. m_userCommandRequests.push_back(commandId);
  178. }
  179. void PhysicsClientExample::prepareAndSubmitCommand(int commandId)
  180. {
  181. switch (commandId)
  182. {
  183. case CMD_LOAD_URDF:
  184. {
  185. b3SharedMemoryCommandHandle commandHandle = b3LoadUrdfCommandInit(m_physicsClientHandle, "kuka_iiwa/model.urdf");
  186. //setting the initial position, orientation and other arguments are optional
  187. double startPosX = 0;
  188. static double startPosY = 0;
  189. double startPosZ = 0;
  190. b3LoadUrdfCommandSetStartPosition(commandHandle, startPosX,startPosY,startPosZ);
  191. startPosY += 2.f;
  192. // ret = b3LoadUrdfCommandSetUseFixedBase(commandHandle, 1);
  193. b3SubmitClientCommand(m_physicsClientHandle, commandHandle);
  194. break;
  195. }
  196. case CMD_LOAD_SDF:
  197. {
  198. b3SharedMemoryCommandHandle commandHandle = b3LoadSdfCommandInit(m_physicsClientHandle, "two_cubes.sdf");//kuka_iiwa/model.sdf");
  199. b3SubmitClientCommand(m_physicsClientHandle, commandHandle);
  200. break;
  201. }
  202. case CMD_REQUEST_CAMERA_IMAGE_DATA:
  203. {
  204. ///request an image from a simulated camera, using a software renderer.
  205. b3SharedMemoryCommandHandle commandHandle = b3InitRequestCameraImage(m_physicsClientHandle);
  206. //b3RequestCameraImageSelectRenderer(commandHandle,ER_BULLET_HARDWARE_OPENGL);
  207. float viewMatrix[16];
  208. float projectionMatrix[16];
  209. m_guiHelper->getRenderInterface()->getActiveCamera()->getCameraProjectionMatrix(projectionMatrix);
  210. m_guiHelper->getRenderInterface()->getActiveCamera()->getCameraViewMatrix(viewMatrix);
  211. b3RequestCameraImageSetCameraMatrices(commandHandle, viewMatrix,projectionMatrix);
  212. b3RequestCameraImageSetPixelResolution(commandHandle, camVisualizerWidth,camVisualizerHeight);
  213. b3SubmitClientCommand(m_physicsClientHandle, commandHandle);
  214. break;
  215. }
  216. case CMD_CREATE_BOX_COLLISION_SHAPE:
  217. {
  218. b3SharedMemoryCommandHandle commandHandle = b3CreateBoxShapeCommandInit(m_physicsClientHandle);
  219. b3CreateBoxCommandSetStartPosition(commandHandle,0,0,-1.5);
  220. b3CreateBoxCommandSetColorRGBA(commandHandle,0,0,1,1);
  221. b3SubmitClientCommand(m_physicsClientHandle, commandHandle);
  222. break;
  223. }
  224. case CMD_CREATE_RIGID_BODY:
  225. {
  226. b3SharedMemoryCommandHandle commandHandle = b3CreateBoxShapeCommandInit(m_physicsClientHandle);
  227. b3CreateBoxCommandSetStartPosition(commandHandle,0,0,0);
  228. b3CreateBoxCommandSetMass(commandHandle,1);
  229. b3CreateBoxCommandSetCollisionShapeType(commandHandle,COLLISION_SHAPE_TYPE_CYLINDER_Y);
  230. b3CreateBoxCommandSetColorRGBA(commandHandle,1,1,0,1);
  231. double radius = 0.2;
  232. double halfHeight = 0.5;
  233. b3CreateBoxCommandSetHalfExtents(commandHandle,radius,halfHeight,radius);
  234. b3SubmitClientCommand(m_physicsClientHandle, commandHandle);
  235. break;
  236. }
  237. case CMD_REQUEST_ACTUAL_STATE:
  238. {
  239. if (m_selectedBody>=0)
  240. {
  241. b3SharedMemoryCommandHandle commandHandle = b3RequestActualStateCommandInit(m_physicsClientHandle,m_selectedBody);
  242. b3SharedMemoryStatusHandle statusHandle = b3SubmitClientCommandAndWaitStatus(m_physicsClientHandle, commandHandle);
  243. b3SubmitClientCommand(m_physicsClientHandle, commandHandle);
  244. int numJoints = b3GetNumJoints(m_physicsClientHandle, m_selectedBody);
  245. for (int i = 0; i < numJoints; ++i) {
  246. struct b3JointSensorState sensorState;
  247. b3GetJointState(m_physicsClientHandle, statusHandle, i, &sensorState);
  248. b3Printf("Joint %d: %f", i, sensorState.m_jointMotorTorque);
  249. }
  250. }
  251. break;
  252. };
  253. case CMD_INIT_POSE:
  254. {
  255. if (m_selectedBody>=0)
  256. {
  257. b3SharedMemoryCommandHandle commandHandle = b3CreatePoseCommandInit(m_physicsClientHandle,m_selectedBody);
  258. static int toggle = 0;
  259. double pos[3] = {0,0,0};
  260. pos[toggle] = 2;
  261. toggle++;
  262. if (toggle>2)
  263. toggle=0;
  264. btQuaternion orn;
  265. orn.setValue(0,0,0,1);
  266. switch (toggle)
  267. {
  268. case 0:
  269. orn = btQuaternion(btVector3(1,0,0),SIMD_HALF_PI);
  270. break;
  271. case 1:
  272. orn = btQuaternion(btVector3(0,1,0),SIMD_HALF_PI);
  273. break;
  274. case 2:
  275. orn = btQuaternion(btVector3(0,0,1),SIMD_HALF_PI);
  276. break;
  277. default:
  278. orn.setValue(0,0,0,1);
  279. };
  280. b3CreatePoseCommandSetBaseOrientation(commandHandle,orn[0],orn[1],orn[2],orn[3]);
  281. b3CreatePoseCommandSetBasePosition(commandHandle, pos[0],pos[1],pos[2]);
  282. int numJoints = b3GetNumJoints(m_physicsClientHandle,m_selectedBody);
  283. static double jointPos = SIMD_PI/2.f;
  284. for (int i=0;i<numJoints;i++)
  285. {
  286. b3JointInfo info;
  287. b3GetJointInfo(m_physicsClientHandle, m_selectedBody,i, &info);
  288. if ((info.m_jointType == 0) || (info.m_jointType == 1)) //revolute or prismatic
  289. {
  290. b3CreatePoseCommandSetJointPosition(m_physicsClientHandle,commandHandle,i,jointPos);
  291. }
  292. }
  293. jointPos += SIMD_PI/8.0;
  294. b3SubmitClientCommand(m_physicsClientHandle, commandHandle);
  295. }
  296. break;
  297. }
  298. case CMD_STEP_FORWARD_SIMULATION:
  299. {
  300. b3SharedMemoryCommandHandle commandHandle = b3InitStepSimulationCommand(m_physicsClientHandle);
  301. b3SubmitClientCommand(m_physicsClientHandle, commandHandle);
  302. break;
  303. }
  304. case CMD_REQUEST_DEBUG_LINES:
  305. {
  306. b3SharedMemoryCommandHandle commandHandle = b3InitRequestDebugLinesCommand(m_physicsClientHandle, btIDebugDraw::DBG_DrawWireframe);
  307. b3SubmitClientCommand(m_physicsClientHandle, commandHandle);
  308. break;
  309. }
  310. case CMD_SEND_DESIRED_STATE:
  311. {
  312. if (m_selectedBody>=0)
  313. {
  314. // b3SharedMemoryCommandHandle command = b3JointControlCommandInit( m_physicsClientHandle, m_selectedBody, CONTROL_MODE_VELOCITY);
  315. b3SharedMemoryCommandHandle command = b3JointControlCommandInit2( m_physicsClientHandle, m_selectedBody, CONTROL_MODE_POSITION_VELOCITY_PD);
  316. // b3Printf("prepare control command for body %d", m_selectedBody);
  317. prepareControlCommand(command);
  318. b3SubmitClientCommand(m_physicsClientHandle, command);
  319. }
  320. break;
  321. }
  322. case CMD_RESET_SIMULATION:
  323. {
  324. b3SharedMemoryCommandHandle commandHandle = b3InitResetSimulationCommand(m_physicsClientHandle);
  325. b3SubmitClientCommand(m_physicsClientHandle, commandHandle);
  326. break;
  327. }
  328. case CMD_SEND_BULLET_DATA_STREAM:
  329. {
  330. #if 0
  331. //this worked, but needs C-API and a streaming options, similar to debug lines
  332. command.m_type = buttonId;
  333. cl->enqueueCommand(command);
  334. #endif
  335. break;
  336. }
  337. case CMD_SEND_PHYSICS_SIMULATION_PARAMETERS: {
  338. b3SharedMemoryCommandHandle commandHandle = b3InitPhysicsParamCommand(m_physicsClientHandle);
  339. b3PhysicsParamSetGravity(commandHandle, 0.0, 0.0, -9.8);
  340. b3SubmitClientCommand(m_physicsClientHandle, commandHandle);
  341. break;
  342. }
  343. case CMD_CALCULATE_INVERSE_DYNAMICS:
  344. {
  345. if (m_selectedBody >= 0)
  346. {
  347. btAlignedObjectArray<double> jointPositionsQ;
  348. btAlignedObjectArray<double> jointVelocitiesQdot;
  349. btAlignedObjectArray<double> jointAccelerations;
  350. int numJoints = b3GetNumJoints(m_physicsClientHandle, m_selectedBody);
  351. if (numJoints)
  352. {
  353. b3Printf("Compute inverse dynamics for joint accelerations:");
  354. jointPositionsQ.resize(numJoints);
  355. jointVelocitiesQdot.resize(numJoints);
  356. jointAccelerations.resize(numJoints);
  357. for (int i = 0; i < numJoints; i++)
  358. {
  359. jointAccelerations[i] = 100;
  360. b3Printf("Desired joint acceleration[%d]=%f", i, jointAccelerations[i]);
  361. }
  362. b3SharedMemoryCommandHandle commandHandle = b3CalculateInverseDynamicsCommandInit(m_physicsClientHandle,
  363. m_selectedBody, &jointPositionsQ[0], &jointVelocitiesQdot[0], &jointAccelerations[0]);
  364. b3SubmitClientCommand(m_physicsClientHandle, commandHandle);
  365. }
  366. }
  367. break;
  368. }
  369. case CMD_REQUEST_CONTACT_POINT_INFORMATION:
  370. {
  371. b3SharedMemoryCommandHandle commandHandle = b3InitRequestContactPointInformation(m_physicsClientHandle);
  372. b3SetContactFilterBodyA(commandHandle,0);
  373. b3SetContactFilterBodyB(commandHandle,1);
  374. b3SubmitClientCommand(m_physicsClientHandle, commandHandle);
  375. break;
  376. }
  377. case CMD_SAVE_WORLD:
  378. {
  379. b3SharedMemoryCommandHandle commandHandle = b3SaveWorldCommandInit(m_physicsClientHandle, "saveWorld.py");
  380. b3SubmitClientCommand(m_physicsClientHandle, commandHandle);
  381. break;
  382. }
  383. default:
  384. {
  385. b3Error("Unknown buttonId");
  386. btAssert(0);
  387. }
  388. };
  389. }
  390. PhysicsClientExample::PhysicsClientExample(GUIHelperInterface* helper, int options)
  391. :SharedMemoryCommon(helper),
  392. m_physicsClientHandle(0),
  393. m_wantsTermination(false),
  394. m_sharedMemoryKey(SHARED_MEMORY_KEY),
  395. m_selectedBody(-1),
  396. m_prevSelectedBody(-1),
  397. m_numMotors(0),
  398. m_options(options),
  399. m_isOptionalServerConnected(false),
  400. m_canvas(0),
  401. m_canvasRGBIndex(-1),
  402. m_canvasDepthIndex(-1),
  403. m_canvasSegMaskIndex(-1)
  404. {
  405. b3Printf("Started PhysicsClientExample\n");
  406. }
  407. PhysicsClientExample::~PhysicsClientExample()
  408. {
  409. if (m_physicsClientHandle)
  410. {
  411. b3ProcessServerStatus(m_physicsClientHandle);
  412. b3DisconnectSharedMemory(m_physicsClientHandle);
  413. }
  414. if (m_options == eCLIENTEXAMPLE_SERVER)
  415. {
  416. bool deInitializeSharedMemory = true;
  417. m_physicsServer.disconnectSharedMemory(deInitializeSharedMemory);
  418. }
  419. if (m_canvas)
  420. {
  421. if (m_canvasRGBIndex>=0)
  422. m_canvas->destroyCanvas(m_canvasRGBIndex);
  423. if (m_canvasDepthIndex>=0)
  424. m_canvas->destroyCanvas(m_canvasDepthIndex);
  425. if (m_canvasSegMaskIndex>=0)
  426. m_canvas->destroyCanvas(m_canvasSegMaskIndex);
  427. }
  428. b3Printf("~PhysicsClientExample\n");
  429. }
  430. void PhysicsClientExample::createButton(const char* name, int buttonId, bool isTrigger )
  431. {
  432. ButtonParams button(name,buttonId, isTrigger);
  433. button.m_callback = MyCallback;
  434. button.m_userPointer = this;
  435. m_guiHelper->getParameterInterface()->registerButtonParameter(button);
  436. }
  437. void PhysicsClientExample::createButtons()
  438. {
  439. bool isTrigger = false;
  440. if (m_guiHelper && m_guiHelper->getParameterInterface())
  441. {
  442. m_guiHelper->getParameterInterface()->removeAllParameters();
  443. createButton("Load URDF",CMD_LOAD_URDF, isTrigger);
  444. createButton("Load SDF",CMD_LOAD_SDF, isTrigger);
  445. createButton("Save World",CMD_SAVE_WORLD, isTrigger);
  446. createButton("Get Camera Image",CMD_REQUEST_CAMERA_IMAGE_DATA,isTrigger);
  447. createButton("Step Sim",CMD_STEP_FORWARD_SIMULATION, isTrigger);
  448. createButton("Send Bullet Stream",CMD_SEND_BULLET_DATA_STREAM, isTrigger);
  449. if (m_options!=eCLIENTEXAMPLE_SERVER)
  450. {
  451. createButton("Get State",CMD_REQUEST_ACTUAL_STATE, isTrigger);
  452. }
  453. createButton("Send Desired State",CMD_SEND_DESIRED_STATE, isTrigger);
  454. createButton("Create Box Collider",CMD_CREATE_BOX_COLLISION_SHAPE,isTrigger);
  455. createButton("Create Cylinder Body",CMD_CREATE_RIGID_BODY,isTrigger);
  456. createButton("Reset Simulation",CMD_RESET_SIMULATION,isTrigger);
  457. createButton("Initialize Pose",CMD_INIT_POSE, isTrigger);
  458. createButton("Set gravity", CMD_SEND_PHYSICS_SIMULATION_PARAMETERS, isTrigger);
  459. createButton("Compute Inverse Dynamics", CMD_CALCULATE_INVERSE_DYNAMICS, isTrigger);
  460. createButton("Get Contact Point Info", CMD_REQUEST_CONTACT_POINT_INFORMATION, isTrigger);
  461. if (m_bodyUniqueIds.size())
  462. {
  463. if (m_selectedBody<0)
  464. m_selectedBody = 0;
  465. ComboBoxParams comboParams;
  466. comboParams.m_comboboxId = 0;
  467. comboParams.m_numItems = m_bodyUniqueIds.size();
  468. comboParams.m_startItem = m_selectedBody;
  469. comboParams.m_callback = MyComboBoxCallback;
  470. comboParams.m_userPointer = this;
  471. //todo: get the real object name
  472. const char** blarray = new const char*[m_bodyUniqueIds.size()];
  473. for (int i=0;i<m_bodyUniqueIds.size();i++)
  474. {
  475. char* bla = new char[16];
  476. sprintf(bla,"%d", i);
  477. blarray[i] = bla;
  478. comboParams.m_items=blarray;//{&bla};
  479. }
  480. m_guiHelper->getParameterInterface()->registerComboBox(comboParams);
  481. }
  482. if (m_physicsClientHandle && m_selectedBody>=0)
  483. {
  484. m_numMotors = 0;
  485. int numJoints = b3GetNumJoints(m_physicsClientHandle,m_selectedBody);
  486. for (int i=0;i<numJoints;i++)
  487. {
  488. b3JointInfo info;
  489. b3GetJointInfo(m_physicsClientHandle,m_selectedBody,i,&info);
  490. b3Printf("Joint %s at q-index %d and u-index %d\n",info.m_jointName,info.m_qIndex,info.m_uIndex);
  491. if (info.m_flags & JOINT_HAS_MOTORIZED_POWER)
  492. {
  493. if (m_numMotors<MAX_NUM_MOTORS)
  494. {
  495. char motorName[1024];
  496. sprintf(motorName,"%s q", info.m_jointName);
  497. // MyMotorInfo2* motorInfo = &m_motorTargetVelocities[m_numMotors];
  498. MyMotorInfo2* motorInfo = &m_motorTargetPositions[m_numMotors];
  499. motorInfo->m_velTarget = 0.f;
  500. motorInfo->m_posTarget = 0.f;
  501. motorInfo->m_uIndex = info.m_uIndex;
  502. motorInfo->m_qIndex = info.m_qIndex;
  503. // SliderParams slider(motorName,&motorInfo->m_velTarget);
  504. // slider.m_minVal=-4;
  505. // slider.m_maxVal=4;
  506. SliderParams slider(motorName,&motorInfo->m_posTarget);
  507. slider.m_minVal=-4;
  508. slider.m_maxVal=4;
  509. if (m_guiHelper && m_guiHelper->getParameterInterface())
  510. {
  511. m_guiHelper->getParameterInterface()->registerSliderFloatParameter(slider);
  512. }
  513. m_numMotors++;
  514. }
  515. }
  516. }
  517. }
  518. }
  519. }
  520. void PhysicsClientExample::initPhysics()
  521. {
  522. if (m_guiHelper && m_guiHelper->getParameterInterface())
  523. {
  524. int upAxis = 2;
  525. m_guiHelper->setUpAxis(upAxis);
  526. createButtons();
  527. } else
  528. {
  529. MyCallback(CMD_LOAD_URDF, true, this);
  530. MyCallback(CMD_STEP_FORWARD_SIMULATION,true,this);
  531. MyCallback(CMD_RESET_SIMULATION,true,this);
  532. }
  533. m_selectedBody = -1;
  534. m_prevSelectedBody = -1;
  535. {
  536. m_canvas = m_guiHelper->get2dCanvasInterface();
  537. if (m_canvas)
  538. {
  539. m_canvasRGBIndex = m_canvas->createCanvas("Synthetic Camera RGB data",camVisualizerWidth, camVisualizerHeight);
  540. m_canvasDepthIndex = m_canvas->createCanvas("Synthetic Camera Depth data",camVisualizerWidth, camVisualizerHeight);
  541. m_canvasSegMaskIndex = m_canvas->createCanvas("Synthetic Camera Segmentation Mask",camVisualizerWidth, camVisualizerHeight);
  542. for (int i=0;i<camVisualizerWidth;i++)
  543. {
  544. for (int j=0;j<camVisualizerHeight;j++)
  545. {
  546. unsigned char red=255;
  547. unsigned char green=255;
  548. unsigned char blue=255;
  549. unsigned char alpha=255;
  550. if (i==j)
  551. {
  552. red = 0;
  553. green=0;
  554. blue=0;
  555. }
  556. m_canvas->setPixel(m_canvasRGBIndex,i,j,red,green,blue,alpha);
  557. m_canvas->setPixel(m_canvasDepthIndex,i,j,red,green,blue,alpha);
  558. m_canvas->setPixel(m_canvasSegMaskIndex,i,j,red,green,blue,alpha);
  559. }
  560. }
  561. m_canvas->refreshImageData(m_canvasRGBIndex);
  562. m_canvas->refreshImageData(m_canvasDepthIndex);
  563. m_canvas->refreshImageData(m_canvasSegMaskIndex);
  564. }
  565. }
  566. if (m_options == eCLIENTEXAMPLE_SERVER)
  567. {
  568. m_isOptionalServerConnected = m_physicsServer.connectSharedMemory( m_guiHelper);
  569. }
  570. if (m_options == eCLIENTEXAMPLE_DIRECT)
  571. {
  572. m_physicsClientHandle = b3ConnectPhysicsDirect();
  573. } else
  574. {
  575. m_physicsClientHandle = b3ConnectSharedMemory(m_sharedMemoryKey);
  576. //m_physicsClientHandle = b3ConnectPhysicsLoopback(SHARED_MEMORY_KEY);
  577. }
  578. if (!b3CanSubmitCommand(m_physicsClientHandle))
  579. {
  580. b3Warning("Cannot connect to physics client");
  581. }
  582. }
  583. void PhysicsClientExample::stepSimulation(float deltaTime)
  584. {
  585. if (m_options == eCLIENTEXAMPLE_SERVER)
  586. {
  587. for (int i=0;i<100;i++)
  588. {
  589. m_physicsServer.processClientCommands();
  590. }
  591. }
  592. if (m_prevSelectedBody != m_selectedBody)
  593. {
  594. createButtons();
  595. m_prevSelectedBody = m_selectedBody;
  596. }
  597. //while (!b3CanSubmitCommand(m_physicsClientHandle))
  598. {
  599. b3SharedMemoryStatusHandle status = b3ProcessServerStatus(m_physicsClientHandle);
  600. bool hasStatus = (status != 0);
  601. if (hasStatus)
  602. {
  603. int statusType = b3GetStatusType(status);
  604. if (statusType == CMD_ACTUAL_STATE_UPDATE_COMPLETED)
  605. {
  606. //b3Printf("bla\n");
  607. }
  608. if (statusType ==CMD_CAMERA_IMAGE_COMPLETED)
  609. {
  610. // static int counter=0;
  611. // char msg[1024];
  612. // sprintf(msg,"Camera image %d OK\n",counter++);
  613. b3CameraImageData imageData;
  614. b3GetCameraImageData(m_physicsClientHandle,&imageData);
  615. if (m_canvas)
  616. {
  617. //compute depth image range
  618. float minDepthValue = 1e20f;
  619. float maxDepthValue = -1e20f;
  620. for (int i=0;i<camVisualizerWidth;i++)
  621. {
  622. for (int j=0;j<camVisualizerHeight;j++)
  623. {
  624. int xIndex = int(float(i)*(float(imageData.m_pixelWidth)/float(camVisualizerWidth)));
  625. int yIndex = int(float(j)*(float(imageData.m_pixelHeight)/float(camVisualizerHeight)));
  626. btClamp(yIndex,0,imageData.m_pixelHeight);
  627. btClamp(xIndex,0,imageData.m_pixelWidth);
  628. if (m_canvasDepthIndex >=0)
  629. {
  630. int depthPixelIndex = (xIndex+yIndex*imageData.m_pixelWidth);
  631. float depthValue = imageData.m_depthValues[depthPixelIndex];
  632. //todo: rescale the depthValue to [0..255]
  633. if (depthValue>-1e20)
  634. {
  635. maxDepthValue = btMax(maxDepthValue,depthValue);
  636. minDepthValue = btMin(minDepthValue,depthValue);
  637. }
  638. }
  639. }
  640. }
  641. for (int i=0;i<camVisualizerWidth;i++)
  642. {
  643. for (int j=0;j<camVisualizerHeight;j++)
  644. {
  645. int xIndex = int(float(i)*(float(imageData.m_pixelWidth)/float(camVisualizerWidth)));
  646. int yIndex = int(float(j)*(float(imageData.m_pixelHeight)/float(camVisualizerHeight)));
  647. btClamp(yIndex,0,imageData.m_pixelHeight);
  648. btClamp(xIndex,0,imageData.m_pixelWidth);
  649. int bytesPerPixel = 4; //RGBA
  650. if (m_canvasRGBIndex >=0)
  651. {
  652. int rgbPixelIndex = (xIndex+yIndex*imageData.m_pixelWidth)*bytesPerPixel;
  653. m_canvas->setPixel(m_canvasRGBIndex,i,j,
  654. imageData.m_rgbColorData[rgbPixelIndex],
  655. imageData.m_rgbColorData[rgbPixelIndex+1],
  656. imageData.m_rgbColorData[rgbPixelIndex+2],
  657. 255); //alpha set to 255
  658. }
  659. if (m_canvasDepthIndex >=0)
  660. {
  661. int depthPixelIndex = (xIndex+yIndex*imageData.m_pixelWidth);
  662. float depthValue = imageData.m_depthValues[depthPixelIndex];
  663. //todo: rescale the depthValue to [0..255]
  664. if (depthValue>-1e20)
  665. {
  666. int rgb = (depthValue-minDepthValue)*(255. / (btFabs(maxDepthValue-minDepthValue)));
  667. if (rgb<0 || rgb>255)
  668. {
  669. printf("rgb=%d\n",rgb);
  670. }
  671. m_canvas->setPixel(m_canvasDepthIndex,i,j,
  672. rgb,
  673. rgb,
  674. 255, 255); //alpha set to 255
  675. } else
  676. {
  677. m_canvas->setPixel(m_canvasDepthIndex,i,j,
  678. 0,
  679. 0,
  680. 0, 255); //alpha set to 255
  681. }
  682. }
  683. if (m_canvasSegMaskIndex>=0 && (0!=imageData.m_segmentationMaskValues))
  684. {
  685. int segmentationMaskPixelIndex = (xIndex+yIndex*imageData.m_pixelWidth);
  686. int segmentationMask = imageData.m_segmentationMaskValues[segmentationMaskPixelIndex];
  687. btVector4 palette[4] = {btVector4(32,255,32,255),
  688. btVector4(32,32,255,255),
  689. btVector4(255,255,32,255),
  690. btVector4(32,255,255,255)};
  691. if (segmentationMask>=0)
  692. {
  693. btVector4 rgb = palette[segmentationMask&3];
  694. m_canvas->setPixel(m_canvasSegMaskIndex,i,j,
  695. rgb.x(),
  696. rgb.y(),
  697. rgb.z(), 255); //alpha set to 255
  698. } else
  699. {
  700. m_canvas->setPixel(m_canvasSegMaskIndex,i,j,
  701. 0,
  702. 0,
  703. 0, 255); //alpha set to 255
  704. }
  705. }
  706. }
  707. }
  708. if (m_canvasRGBIndex >=0)
  709. m_canvas->refreshImageData(m_canvasRGBIndex);
  710. if (m_canvasDepthIndex >=0)
  711. m_canvas->refreshImageData(m_canvasDepthIndex);
  712. if (m_canvasSegMaskIndex >=0)
  713. m_canvas->refreshImageData(m_canvasSegMaskIndex);
  714. }
  715. // b3Printf(msg);
  716. }
  717. if (statusType == CMD_CALCULATED_INVERSE_DYNAMICS_COMPLETED)
  718. {
  719. int bodyUniqueId;
  720. int dofCount;
  721. b3GetStatusInverseDynamicsJointForces(status,
  722. &bodyUniqueId,
  723. &dofCount,
  724. 0);
  725. btAlignedObjectArray<double> jointForces;
  726. if (dofCount)
  727. {
  728. jointForces.resize(dofCount);
  729. b3GetStatusInverseDynamicsJointForces(status,
  730. 0,
  731. 0,
  732. &jointForces[0]);
  733. for (int i = 0; i < dofCount; i++)
  734. {
  735. b3Printf("jointForces[%d]=%f", i, jointForces[i]);
  736. }
  737. }
  738. }
  739. if (statusType == CMD_CALCULATED_INVERSE_DYNAMICS_FAILED)
  740. {
  741. b3Warning("Inverse Dynamics computations failed");
  742. }
  743. if (statusType == CMD_CAMERA_IMAGE_FAILED)
  744. {
  745. b3Warning("Camera image FAILED\n");
  746. }
  747. if (statusType == CMD_SDF_LOADING_COMPLETED)
  748. {
  749. int bodyIndicesOut[1024];
  750. int bodyCapacity = 1024;
  751. int numBodies = b3GetStatusBodyIndices(status, bodyIndicesOut, bodyCapacity);
  752. if (numBodies > bodyCapacity)
  753. {
  754. b3Warning("loadSDF number of bodies (%d) exceeds the internal body capacity (%d)",numBodies, bodyCapacity);
  755. } else
  756. {
  757. for (int i=0;i<numBodies;i++)
  758. {
  759. int bodyUniqueId = bodyIndicesOut[i];
  760. m_bodyUniqueIds.push_back(bodyUniqueId);
  761. int numJoints = b3GetNumJoints(m_physicsClientHandle,bodyUniqueId);
  762. if (numJoints>0)
  763. {
  764. m_selectedBody = bodyUniqueId;
  765. }
  766. /* int numJoints = b3GetNumJoints(m_physicsClientHandle,bodyUniqueId);
  767. b3Printf("numJoints = %d", numJoints);
  768. for (int i=0;i<numJoints;i++)
  769. {
  770. b3JointInfo info;
  771. b3GetJointInfo(m_physicsClientHandle,bodyUniqueId,i,&info);
  772. b3Printf("Joint %s at q-index %d and u-index %d\n",info.m_jointName,info.m_qIndex,info.m_uIndex);
  773. }
  774. */
  775. }
  776. }
  777. //int numJoints = b3GetNumJoints(m_physicsClientHandle,bodyIndex);
  778. //int bodyIndex = b3GetStatusBodyIndex(status);
  779. /*if (bodyIndex>=0)
  780. {
  781. int numJoints = b3GetNumJoints(m_physicsClientHandle,bodyIndex);
  782. for (int i=0;i<numJoints;i++)
  783. {
  784. b3JointInfo info;
  785. b3GetJointInfo(m_physicsClientHandle,bodyIndex,i,&info);
  786. b3Printf("Joint %s at q-index %d and u-index %d\n",info.m_jointName,info.m_qIndex,info.m_uIndex);
  787. }
  788. ComboBoxParams comboParams;
  789. comboParams.m_comboboxId = bodyIndex;
  790. comboParams.m_numItems = 1;
  791. comboParams.m_startItem = 0;
  792. comboParams.m_callback = MyComboBoxCallback;
  793. comboParams.m_userPointer = this;
  794. const char* bla = "bla";
  795. const char* blarray[1];
  796. blarray[0] = bla;
  797. comboParams.m_items=blarray;//{&bla};
  798. m_guiHelper->getParameterInterface()->registerComboBox(comboParams);
  799. }
  800. */
  801. }
  802. if (statusType == CMD_URDF_LOADING_COMPLETED)
  803. {
  804. int bodyIndex = b3GetStatusBodyIndex(status);
  805. if (bodyIndex>=0)
  806. {
  807. m_bodyUniqueIds.push_back(bodyIndex);
  808. m_selectedBody = bodyIndex;
  809. int numJoints = b3GetNumJoints(m_physicsClientHandle,bodyIndex);
  810. for (int i=0;i<numJoints;i++)
  811. {
  812. b3JointInfo info;
  813. b3GetJointInfo(m_physicsClientHandle,bodyIndex,i,&info);
  814. b3Printf("Joint %s at q-index %d and u-index %d\n",info.m_jointName,info.m_qIndex,info.m_uIndex);
  815. }
  816. }
  817. }
  818. if (statusType == CMD_CONTACT_POINT_INFORMATION_FAILED)
  819. {
  820. b3Warning("Cannot get contact information");
  821. }
  822. if (statusType == CMD_CONTACT_POINT_INFORMATION_COMPLETED)
  823. {
  824. b3ContactInformation contactPointData;
  825. b3GetContactPointInformation(m_physicsClientHandle, &contactPointData);
  826. b3Printf("Num Contacts: %d\n", contactPointData.m_numContactPoints);
  827. }
  828. }
  829. }
  830. if (b3CanSubmitCommand(m_physicsClientHandle))
  831. {
  832. if (m_userCommandRequests.size())
  833. {
  834. //b3Printf("Outstanding user command requests: %d\n", m_userCommandRequests.size());
  835. int commandId = m_userCommandRequests[0];
  836. //a manual 'pop_front', we don't use 'remove' because it will re-order the commands
  837. for (int i=1;i<m_userCommandRequests.size();i++)
  838. {
  839. m_userCommandRequests[i-1] = m_userCommandRequests[i];
  840. }
  841. m_userCommandRequests.pop_back();
  842. //for the CMD_RESET_SIMULATION we need to do something special: clear the GUI sliders
  843. if (commandId ==CMD_RESET_SIMULATION)
  844. {
  845. m_selectedBody = -1;
  846. m_numMotors=0;
  847. m_bodyUniqueIds.clear();
  848. createButtons();
  849. b3SharedMemoryCommandHandle commandHandle = b3InitResetSimulationCommand(m_physicsClientHandle);
  850. if (m_options == eCLIENTEXAMPLE_SERVER)
  851. {
  852. b3SubmitClientCommand(m_physicsClientHandle, commandHandle);
  853. while (!b3CanSubmitCommand(m_physicsClientHandle))
  854. {
  855. m_physicsServer.processClientCommands();
  856. b3SharedMemoryStatusHandle status = b3ProcessServerStatus(m_physicsClientHandle);
  857. bool hasStatus = (status != 0);
  858. if (hasStatus)
  859. {
  860. //int statusType = b3GetStatusType(status);
  861. //b3Printf("Status after reset: %d",statusType);
  862. }
  863. }
  864. } else
  865. {
  866. prepareAndSubmitCommand(commandId);
  867. }
  868. } else
  869. {
  870. prepareAndSubmitCommand(commandId);
  871. }
  872. } else
  873. {
  874. if (m_numMotors)
  875. {
  876. enqueueCommand(CMD_SEND_DESIRED_STATE);
  877. }
  878. enqueueCommand(CMD_STEP_FORWARD_SIMULATION);
  879. if (m_options != eCLIENTEXAMPLE_SERVER)
  880. {
  881. //enqueueCommand(CMD_REQUEST_DEBUG_LINES);
  882. }
  883. }
  884. }
  885. }
  886. extern int gSharedMemoryKey;
  887. class CommonExampleInterface* PhysicsClientCreateFunc(struct CommonExampleOptions& options)
  888. {
  889. PhysicsClientExample* example = new PhysicsClientExample(options.m_guiHelper, options.m_option);
  890. if (gSharedMemoryKey>=0)
  891. {
  892. example->setSharedMemoryKey(gSharedMemoryKey);
  893. }
  894. return example;
  895. }