PhysicsClientExample.cpp 36 KB

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