PhysicsClientExample.cpp 16 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566
  1. #include "PhysicsClientExample.h"
  2. #include "../CommonInterfaces/CommonMultiBodyBase.h"
  3. #include "SharedMemoryCommon.h"
  4. #include "../CommonInterfaces/CommonParameterInterface.h"
  5. #include "PhysicsClientC_API.h"
  6. #include "PhysicsClient.h"
  7. //#include "SharedMemoryCommands.h"
  8. #include "PhysicsLoopBackC_API.h"
  9. #include "PhysicsDirectC_API.h"
  10. #include "PhysicsClientC_API.h"
  11. struct MyMotorInfo2
  12. {
  13. btScalar m_velTarget;
  14. btScalar m_maxForce;
  15. int m_uIndex;
  16. };
  17. #define MAX_NUM_MOTORS 128
  18. class PhysicsClientExample : public SharedMemoryCommon
  19. {
  20. protected:
  21. b3PhysicsClientHandle m_physicsClientHandle;
  22. bool m_wantsTermination;
  23. btAlignedObjectArray<int> m_userCommandRequests;
  24. int m_sharedMemoryKey;
  25. int m_selectedBody;
  26. int m_prevSelectedBody;
  27. void createButton(const char* name, int id, bool isTrigger );
  28. void createButtons();
  29. public:
  30. //@todo, add accessor methods
  31. MyMotorInfo2 m_motorTargetVelocities[MAX_NUM_MOTORS];
  32. int m_numMotors;
  33. PhysicsClientExample(GUIHelperInterface* helper);
  34. virtual ~PhysicsClientExample();
  35. virtual void initPhysics();
  36. void selectComboBox(int comboIndex, const char* name)
  37. {
  38. if (m_guiHelper && m_guiHelper->getParameterInterface())
  39. {
  40. int bodyIndex = comboIndex;
  41. if (m_selectedBody != bodyIndex)
  42. {
  43. m_selectedBody = bodyIndex;
  44. }
  45. }
  46. }
  47. virtual void stepSimulation(float deltaTime);
  48. virtual void resetCamera()
  49. {
  50. float dist = 5;
  51. float pitch = 50;
  52. float yaw = 35;
  53. float targetPos[3]={0,0,0};//-3,2.8,-2.5};
  54. m_guiHelper->resetCamera(dist,pitch,yaw,targetPos[0],targetPos[1],targetPos[2]);
  55. }
  56. virtual bool wantsTermination()
  57. {
  58. return m_wantsTermination;
  59. }
  60. virtual bool isConnected()
  61. {
  62. return (m_physicsClientHandle!=0);
  63. }
  64. void enqueueCommand(int commandId);
  65. void prepareAndSubmitCommand(int commandId);
  66. virtual void exitPhysics(){};
  67. virtual void renderScene()
  68. {
  69. b3DebugLines debugLines;
  70. b3GetDebugLines(m_physicsClientHandle,&debugLines);
  71. int numLines = debugLines.m_numDebugLines;
  72. int lineWidth = 1;
  73. if (1)
  74. {
  75. btAlignedObjectArray<btVector3FloatData> points;
  76. points.resize(numLines*2);
  77. btAlignedObjectArray<unsigned int> indices;
  78. indices.resize(numLines*2);
  79. for (int i=0;i<numLines;i++)
  80. {
  81. points[i*2].m_floats[0] = debugLines.m_linesFrom[i*3+0];
  82. points[i*2].m_floats[1] = debugLines.m_linesFrom[i*3+1];
  83. points[i*2].m_floats[2] = debugLines.m_linesFrom[i*3+2];
  84. points[i*2+1].m_floats[0] = debugLines.m_linesTo[i*3+0];
  85. points[i*2+1].m_floats[1] = debugLines.m_linesTo[i*3+1];
  86. points[i*2+1].m_floats[2] = debugLines.m_linesTo[i*3+2];
  87. indices[i*2] = i*2;
  88. indices[i*2+1] = i*2+1;
  89. }
  90. float color[4] = {0.2,0.2,1,1};
  91. if (points.size() && indices.size())
  92. {
  93. m_guiHelper->getRenderInterface()->drawLines(&points[0].m_floats[0],color,points.size(),sizeof(btVector3FloatData),&indices[0],indices.size(),lineWidth);
  94. }
  95. } else
  96. {
  97. for (int i=0;i<numLines;i++)
  98. {
  99. m_guiHelper->getRenderInterface()->drawLine(debugLines.m_linesFrom,debugLines.m_linesTo,debugLines.m_linesColor,lineWidth);
  100. }
  101. }
  102. }
  103. void prepareControlCommand(b3SharedMemoryCommandHandle commandHandle)
  104. {
  105. for (int i=0;i<m_numMotors;i++)
  106. {
  107. btScalar targetVel = m_motorTargetVelocities[i].m_velTarget;
  108. int uIndex = m_motorTargetVelocities[i].m_uIndex;
  109. b3JointControlSetDesiredVelocity(commandHandle, uIndex,targetVel);
  110. b3JointControlSetMaximumForce(commandHandle,uIndex,1000);
  111. }
  112. }
  113. virtual void physicsDebugDraw(int debugFlags){}
  114. virtual bool mouseMoveCallback(float x,float y){return false;};
  115. virtual bool mouseButtonCallback(int button, int state, float x, float y){return false;}
  116. virtual bool keyboardCallback(int key, int state){return false;}
  117. virtual void setSharedMemoryKey(int key)
  118. {
  119. m_sharedMemoryKey = key;
  120. }
  121. };
  122. void MyComboBoxCallback (int combobox, const char* item, void* userPointer)
  123. {
  124. b3Printf("Item selected %s", item);
  125. PhysicsClientExample* cl = (PhysicsClientExample*) userPointer;
  126. b3Assert(cl);
  127. if (cl)
  128. {
  129. cl->selectComboBox(combobox,item);
  130. }
  131. }
  132. void MyCallback(int buttonId, bool buttonState, void* userPtr)
  133. {
  134. PhysicsClientExample* cl = (PhysicsClientExample*) userPtr;
  135. b3Assert(cl);
  136. if (cl && buttonState)
  137. {
  138. cl->enqueueCommand(buttonId);
  139. }
  140. }
  141. void PhysicsClientExample::enqueueCommand(int commandId)
  142. {
  143. m_userCommandRequests.push_back(commandId);
  144. }
  145. void PhysicsClientExample::prepareAndSubmitCommand(int commandId)
  146. {
  147. switch (commandId)
  148. {
  149. case CMD_LOAD_URDF:
  150. {
  151. b3SharedMemoryCommandHandle commandHandle = b3LoadUrdfCommandInit(m_physicsClientHandle, "kuka_lwr/kuka.urdf");
  152. //setting the initial position, orientation and other arguments are optional
  153. double startPosX = 0;
  154. static double startPosY = 0;
  155. double startPosZ = 0;
  156. b3LoadUrdfCommandSetStartPosition(commandHandle, startPosX,startPosY,startPosZ);
  157. startPosY += 2.f;
  158. // ret = b3LoadUrdfCommandSetUseFixedBase(commandHandle, 1);
  159. b3SubmitClientCommand(m_physicsClientHandle, commandHandle);
  160. break;
  161. }
  162. case CMD_CREATE_BOX_COLLISION_SHAPE:
  163. {
  164. b3SharedMemoryCommandHandle commandHandle = b3CreateBoxShapeCommandInit(m_physicsClientHandle);
  165. b3CreateBoxCommandSetStartPosition(commandHandle,0,0,-3);
  166. b3CreateBoxCommandSetColorRGBA(commandHandle,0,0,1,1);
  167. b3SubmitClientCommand(m_physicsClientHandle, commandHandle);
  168. break;
  169. }
  170. case CMD_CREATE_RIGID_BODY:
  171. {
  172. b3SharedMemoryCommandHandle commandHandle = b3CreateBoxShapeCommandInit(m_physicsClientHandle);
  173. b3CreateBoxCommandSetStartPosition(commandHandle,0,0,0);
  174. b3CreateBoxCommandSetMass(commandHandle,1);
  175. b3CreateBoxCommandSetCollisionShapeType(commandHandle,COLLISION_SHAPE_TYPE_CYLINDER_Y);
  176. b3CreateBoxCommandSetColorRGBA(commandHandle,1,1,0,1);
  177. double radius = 0.2;
  178. double halfHeight = 0.5;
  179. b3CreateBoxCommandSetHalfExtents(commandHandle,radius,halfHeight,radius);
  180. b3SubmitClientCommand(m_physicsClientHandle, commandHandle);
  181. break;
  182. }
  183. case CMD_REQUEST_ACTUAL_STATE:
  184. {
  185. if (m_selectedBody>=0)
  186. {
  187. b3SharedMemoryCommandHandle commandHandle = b3RequestActualStateCommandInit(m_physicsClientHandle,m_selectedBody);
  188. b3SubmitClientCommand(m_physicsClientHandle, commandHandle);
  189. }
  190. break;
  191. };
  192. case CMD_INIT_POSE:
  193. {
  194. if (m_selectedBody>=0)
  195. {
  196. b3SharedMemoryCommandHandle commandHandle = b3CreatePoseCommandInit(m_physicsClientHandle,m_selectedBody);
  197. static int toggle = 0;
  198. double pos[3] = {0,0,0};
  199. pos[toggle] = 2;
  200. toggle++;
  201. if (toggle>2)
  202. toggle=0;
  203. btQuaternion orn;
  204. orn.setValue(0,0,0,1);
  205. switch (toggle)
  206. {
  207. case 0:
  208. orn = btQuaternion(btVector3(1,0,0),SIMD_HALF_PI);
  209. break;
  210. case 1:
  211. orn = btQuaternion(btVector3(0,1,0),SIMD_HALF_PI);
  212. break;
  213. case 2:
  214. orn = btQuaternion(btVector3(0,0,1),SIMD_HALF_PI);
  215. break;
  216. default:
  217. orn.setValue(0,0,0,1);
  218. };
  219. b3CreatePoseCommandSetBaseOrientation(commandHandle,orn[0],orn[1],orn[2],orn[3]);
  220. b3CreatePoseCommandSetBasePosition(commandHandle, pos[0],pos[1],pos[2]);
  221. int numJoints = b3GetNumJoints(m_physicsClientHandle,m_selectedBody);
  222. static double jointPos = SIMD_PI/2.f;
  223. for (int i=0;i<numJoints;i++)
  224. {
  225. b3JointInfo info;
  226. b3GetJointInfo(m_physicsClientHandle, m_selectedBody,i, &info);
  227. if ((info.m_jointType == 0) || (info.m_jointType == 1)) //revolute or prismatic
  228. {
  229. b3CreatePoseCommandSetJointPosition(m_physicsClientHandle,commandHandle,i,jointPos);
  230. }
  231. }
  232. jointPos += SIMD_PI/8.0;
  233. b3SubmitClientCommand(m_physicsClientHandle, commandHandle);
  234. }
  235. break;
  236. }
  237. case CMD_STEP_FORWARD_SIMULATION:
  238. {
  239. b3SharedMemoryCommandHandle commandHandle = b3InitStepSimulationCommand(m_physicsClientHandle);
  240. b3SubmitClientCommand(m_physicsClientHandle, commandHandle);
  241. break;
  242. }
  243. case CMD_REQUEST_DEBUG_LINES:
  244. {
  245. b3SharedMemoryCommandHandle commandHandle = b3InitRequestDebugLinesCommand(m_physicsClientHandle, btIDebugDraw::DBG_DrawWireframe);
  246. b3SubmitClientCommand(m_physicsClientHandle, commandHandle);
  247. break;
  248. }
  249. case CMD_SEND_DESIRED_STATE:
  250. {
  251. b3SharedMemoryCommandHandle command = b3JointControlCommandInit( m_physicsClientHandle, CONTROL_MODE_VELOCITY);
  252. prepareControlCommand(command);
  253. b3SubmitClientCommand(m_physicsClientHandle, command);
  254. break;
  255. }
  256. case CMD_RESET_SIMULATION:
  257. {
  258. b3SharedMemoryCommandHandle commandHandle = b3InitResetSimulationCommand(m_physicsClientHandle);
  259. b3SubmitClientCommand(m_physicsClientHandle, commandHandle);
  260. break;
  261. }
  262. case CMD_SEND_BULLET_DATA_STREAM:
  263. {
  264. #if 0
  265. //this worked, but needs C-API and a streaming options, similar to debug lines
  266. command.m_type = buttonId;
  267. cl->enqueueCommand(command);
  268. #endif
  269. break;
  270. }
  271. default:
  272. {
  273. b3Error("Unknown buttonId");
  274. btAssert(0);
  275. }
  276. };
  277. }
  278. PhysicsClientExample::PhysicsClientExample(GUIHelperInterface* helper)
  279. :SharedMemoryCommon(helper),
  280. m_physicsClientHandle(0),
  281. m_wantsTermination(false),
  282. m_sharedMemoryKey(SHARED_MEMORY_KEY),
  283. m_selectedBody(-1),
  284. m_prevSelectedBody(-1),
  285. m_numMotors(0)
  286. {
  287. b3Printf("Started PhysicsClientExample\n");
  288. }
  289. PhysicsClientExample::~PhysicsClientExample()
  290. {
  291. if (m_physicsClientHandle)
  292. {
  293. b3ProcessServerStatus(m_physicsClientHandle);
  294. b3DisconnectSharedMemory(m_physicsClientHandle);
  295. }
  296. b3Printf("~PhysicsClientExample\n");
  297. }
  298. void PhysicsClientExample::createButton(const char* name, int buttonId, bool isTrigger )
  299. {
  300. ButtonParams button(name,buttonId, isTrigger);
  301. button.m_callback = MyCallback;
  302. button.m_userPointer = this;
  303. m_guiHelper->getParameterInterface()->registerButtonParameter(button);
  304. }
  305. void PhysicsClientExample::createButtons()
  306. {
  307. bool isTrigger = false;
  308. if (m_guiHelper && m_guiHelper->getParameterInterface())
  309. {
  310. m_guiHelper->getParameterInterface()->removeAllParameters();
  311. createButton("Load URDF",CMD_LOAD_URDF, isTrigger);
  312. createButton("Step Sim",CMD_STEP_FORWARD_SIMULATION, isTrigger);
  313. createButton("Send Bullet Stream",CMD_SEND_BULLET_DATA_STREAM, isTrigger);
  314. createButton("Get State",CMD_REQUEST_ACTUAL_STATE, isTrigger);
  315. createButton("Send Desired State",CMD_SEND_DESIRED_STATE, isTrigger);
  316. createButton("Create Box Collider",CMD_CREATE_BOX_COLLISION_SHAPE,isTrigger);
  317. createButton("Create Cylinder Body",CMD_CREATE_RIGID_BODY,isTrigger);
  318. createButton("Reset Simulation",CMD_RESET_SIMULATION,isTrigger);
  319. createButton("Initialize Pose",CMD_INIT_POSE, isTrigger);
  320. if (m_physicsClientHandle && m_selectedBody>=0)
  321. {
  322. int numJoints = b3GetNumJoints(m_physicsClientHandle,m_selectedBody);
  323. for (int i=0;i<numJoints;i++)
  324. {
  325. b3JointInfo info;
  326. b3GetJointInfo(m_physicsClientHandle,m_selectedBody,i,&info);
  327. b3Printf("Joint %s at q-index %d and u-index %d\n",info.m_jointName,info.m_qIndex,info.m_uIndex);
  328. if (info.m_flags & JOINT_HAS_MOTORIZED_POWER)
  329. {
  330. if (m_numMotors<MAX_NUM_MOTORS)
  331. {
  332. char motorName[1024];
  333. sprintf(motorName,"%s q'", info.m_jointName);
  334. MyMotorInfo2* motorInfo = &m_motorTargetVelocities[m_numMotors];
  335. motorInfo->m_velTarget = 0.f;
  336. motorInfo->m_uIndex = info.m_uIndex;
  337. SliderParams slider(motorName,&motorInfo->m_velTarget);
  338. slider.m_minVal=-4;
  339. slider.m_maxVal=4;
  340. if (m_guiHelper && m_guiHelper->getParameterInterface())
  341. {
  342. m_guiHelper->getParameterInterface()->registerSliderFloatParameter(slider);
  343. }
  344. m_numMotors++;
  345. }
  346. }
  347. }
  348. }
  349. }
  350. }
  351. void PhysicsClientExample::initPhysics()
  352. {
  353. if (m_guiHelper && m_guiHelper->getParameterInterface())
  354. {
  355. int upAxis = 2;
  356. m_guiHelper->setUpAxis(upAxis);
  357. createButtons();
  358. } else
  359. {
  360. MyCallback(CMD_LOAD_URDF, true, this);
  361. MyCallback(CMD_STEP_FORWARD_SIMULATION,true,this);
  362. MyCallback(CMD_STEP_FORWARD_SIMULATION,true,this);
  363. MyCallback(CMD_RESET_SIMULATION,true,this);
  364. }
  365. m_selectedBody = -1;
  366. m_prevSelectedBody = -1;
  367. //m_physicsClientHandle = b3ConnectSharedMemory(m_sharedMemoryKey);
  368. m_physicsClientHandle = b3ConnectPhysicsLoopback(SHARED_MEMORY_KEY);
  369. //m_physicsClientHandle = b3ConnectPhysicsDirect();
  370. if (!b3CanSubmitCommand(m_physicsClientHandle))
  371. {
  372. b3Warning("Cannot connect to physics client");
  373. }
  374. }
  375. void PhysicsClientExample::stepSimulation(float deltaTime)
  376. {
  377. if (m_prevSelectedBody != m_selectedBody)
  378. {
  379. createButtons();
  380. m_prevSelectedBody = m_selectedBody;
  381. }
  382. //while (!b3CanSubmitCommand(m_physicsClientHandle))
  383. {
  384. b3SharedMemoryStatusHandle status = b3ProcessServerStatus(m_physicsClientHandle);
  385. bool hasStatus = (status != 0);
  386. if (hasStatus)
  387. {
  388. int statusType = b3GetStatusType(status);
  389. if (statusType == CMD_ACTUAL_STATE_UPDATE_COMPLETED)
  390. {
  391. //b3Printf("bla\n");
  392. }
  393. if (statusType == CMD_URDF_LOADING_COMPLETED)
  394. {
  395. int bodyIndex = b3GetStatusBodyIndex(status);
  396. if (bodyIndex>=0)
  397. {
  398. int numJoints = b3GetNumJoints(m_physicsClientHandle,bodyIndex);
  399. for (int i=0;i<numJoints;i++)
  400. {
  401. b3JointInfo info;
  402. b3GetJointInfo(m_physicsClientHandle,bodyIndex,i,&info);
  403. b3Printf("Joint %s at q-index %d and u-index %d\n",info.m_jointName,info.m_qIndex,info.m_uIndex);
  404. }
  405. ComboBoxParams comboParams;
  406. comboParams.m_comboboxId = bodyIndex;
  407. comboParams.m_numItems = 1;
  408. comboParams.m_startItem = 0;
  409. comboParams.m_callback = MyComboBoxCallback;
  410. comboParams.m_userPointer = this;
  411. const char* bla = "bla";
  412. const char* blarray[1];
  413. blarray[0] = bla;
  414. comboParams.m_items=blarray;//{&bla};
  415. m_guiHelper->getParameterInterface()->registerComboBox(comboParams);
  416. }
  417. }
  418. }
  419. }
  420. if (b3CanSubmitCommand(m_physicsClientHandle))
  421. {
  422. if (m_userCommandRequests.size())
  423. {
  424. //b3Printf("Outstanding user command requests: %d\n", m_userCommandRequests.size());
  425. int commandId = m_userCommandRequests[0];
  426. //a manual 'pop_front', we don't use 'remove' because it will re-order the commands
  427. for (int i=1;i<m_userCommandRequests.size();i++)
  428. {
  429. m_userCommandRequests[i-1] = m_userCommandRequests[i];
  430. }
  431. m_userCommandRequests.pop_back();
  432. //for the CMD_RESET_SIMULATION we need to do something special: clear the GUI sliders
  433. if (commandId ==CMD_RESET_SIMULATION)
  434. {
  435. m_selectedBody = -1;
  436. m_numMotors=0;
  437. createButtons();
  438. }
  439. prepareAndSubmitCommand(commandId);
  440. } else
  441. {
  442. if (m_numMotors)
  443. {
  444. enqueueCommand(CMD_SEND_DESIRED_STATE);
  445. enqueueCommand(CMD_STEP_FORWARD_SIMULATION);
  446. enqueueCommand(CMD_REQUEST_DEBUG_LINES);
  447. //enqueueCommand(CMD_REQUEST_ACTUAL_STATE);
  448. }
  449. }
  450. }
  451. }
  452. extern int gSharedMemoryKey;
  453. class CommonExampleInterface* PhysicsClientCreateFunc(struct CommonExampleOptions& options)
  454. {
  455. PhysicsClientExample* example = new PhysicsClientExample(options.m_guiHelper);
  456. if (gSharedMemoryKey>=0)
  457. {
  458. example->setSharedMemoryKey(gSharedMemoryKey);
  459. }
  460. return example;
  461. }