PhysicsClientC_API.cpp 24 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627628629630631632633634635636637638639640641642643644645646647648649650651652653
  1. #include "PhysicsClientC_API.h"
  2. #include "PhysicsClientSharedMemory.h"
  3. #include "Bullet3Common/b3Scalar.h"
  4. #include <string.h>
  5. #include "SharedMemoryCommands.h"
  6. b3SharedMemoryCommandHandle b3LoadUrdfCommandInit(b3PhysicsClientHandle physClient, const char* urdfFileName)
  7. {
  8. PhysicsClient* cl = (PhysicsClient* ) physClient;
  9. b3Assert(cl);
  10. b3Assert(cl->canSubmitCommand());
  11. struct SharedMemoryCommand* command = cl->getAvailableSharedMemoryCommand();
  12. b3Assert(command);
  13. command->m_type = CMD_LOAD_URDF;
  14. int len = strlen(urdfFileName);
  15. if (len<MAX_URDF_FILENAME_LENGTH)
  16. {
  17. strcpy(command->m_urdfArguments.m_urdfFileName,urdfFileName);
  18. } else
  19. {
  20. command->m_urdfArguments.m_urdfFileName[0] = 0;
  21. }
  22. command->m_updateFlags = URDF_ARGS_FILE_NAME;
  23. return (b3SharedMemoryCommandHandle) command;
  24. }
  25. int b3LoadUrdfCommandSetUseFixedBase(b3SharedMemoryCommandHandle commandHandle, int useFixedBase)
  26. {
  27. struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
  28. b3Assert(command);
  29. b3Assert(command->m_type == CMD_LOAD_URDF);
  30. command->m_updateFlags |=URDF_ARGS_USE_FIXED_BASE;
  31. command->m_urdfArguments.m_useFixedBase = useFixedBase;
  32. return 0;
  33. }
  34. int b3LoadUrdfCommandSetStartPosition(b3SharedMemoryCommandHandle commandHandle, double startPosX,double startPosY,double startPosZ)
  35. {
  36. struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
  37. b3Assert(command);
  38. b3Assert(command->m_type == CMD_LOAD_URDF);
  39. command->m_urdfArguments.m_initialPosition[0] = startPosX;
  40. command->m_urdfArguments.m_initialPosition[1] = startPosY;
  41. command->m_urdfArguments.m_initialPosition[2] = startPosZ;
  42. command->m_updateFlags|=URDF_ARGS_INITIAL_POSITION;
  43. return 0;
  44. }
  45. int b3LoadUrdfCommandSetStartOrientation(b3SharedMemoryCommandHandle commandHandle, double startOrnX,double startOrnY,double startOrnZ, double startOrnW)
  46. {
  47. struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
  48. b3Assert(command);
  49. b3Assert(command->m_type == CMD_LOAD_URDF);
  50. command->m_urdfArguments.m_initialOrientation[0] = startOrnX;
  51. command->m_urdfArguments.m_initialOrientation[1] = startOrnY;
  52. command->m_urdfArguments.m_initialOrientation[2] = startOrnZ;
  53. command->m_urdfArguments.m_initialOrientation[3] = startOrnW;
  54. command->m_updateFlags|=URDF_ARGS_INITIAL_ORIENTATION;
  55. return 0;
  56. }
  57. b3SharedMemoryCommandHandle b3InitPhysicsParamCommand(b3PhysicsClientHandle physClient)
  58. {
  59. PhysicsClient* cl = (PhysicsClient* ) physClient;
  60. b3Assert(cl);
  61. b3Assert(cl->canSubmitCommand());
  62. struct SharedMemoryCommand* command = cl->getAvailableSharedMemoryCommand();
  63. b3Assert(command);
  64. command->m_type = CMD_SEND_PHYSICS_SIMULATION_PARAMETERS;
  65. command->m_updateFlags = 0;
  66. return (b3SharedMemoryCommandHandle) command;
  67. }
  68. int b3PhysicsParamSetGravity(b3SharedMemoryCommandHandle commandHandle, double gravx,double gravy, double gravz)
  69. {
  70. struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
  71. b3Assert(command->m_type == CMD_SEND_PHYSICS_SIMULATION_PARAMETERS);
  72. command->m_physSimParamArgs.m_gravityAcceleration[0] = gravx;
  73. command->m_physSimParamArgs.m_gravityAcceleration[1] = gravy;
  74. command->m_physSimParamArgs.m_gravityAcceleration[2] = gravz;
  75. command->m_updateFlags |= SIM_PARAM_UPDATE_GRAVITY;
  76. return 0;
  77. }
  78. int b3PhysicsParamSetTimeStep(b3SharedMemoryCommandHandle commandHandle, double timeStep)
  79. {
  80. struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
  81. b3Assert(command->m_type == CMD_SEND_PHYSICS_SIMULATION_PARAMETERS);
  82. command->m_updateFlags |= SIM_PARAM_UPDATE_DELTA_TIME;
  83. command->m_physSimParamArgs.m_deltaTime = timeStep;
  84. return 0;
  85. }
  86. b3SharedMemoryCommandHandle b3InitStepSimulationCommand(b3PhysicsClientHandle physClient)
  87. {
  88. PhysicsClient* cl = (PhysicsClient* ) physClient;
  89. b3Assert(cl);
  90. b3Assert(cl->canSubmitCommand());
  91. struct SharedMemoryCommand* command = cl->getAvailableSharedMemoryCommand();
  92. b3Assert(command);
  93. command->m_type = CMD_STEP_FORWARD_SIMULATION;
  94. command->m_updateFlags = 0;
  95. return (b3SharedMemoryCommandHandle) command;
  96. }
  97. b3SharedMemoryCommandHandle b3InitResetSimulationCommand(b3PhysicsClientHandle physClient)
  98. {
  99. PhysicsClient* cl = (PhysicsClient* ) physClient;
  100. b3Assert(cl);
  101. b3Assert(cl->canSubmitCommand());
  102. struct SharedMemoryCommand* command = cl->getAvailableSharedMemoryCommand();
  103. b3Assert(command);
  104. command->m_type = CMD_RESET_SIMULATION;
  105. command->m_updateFlags = 0;
  106. return (b3SharedMemoryCommandHandle) command;
  107. }
  108. b3SharedMemoryCommandHandle b3JointControlCommandInit( b3PhysicsClientHandle physClient, int controlMode)
  109. {
  110. PhysicsClient* cl = (PhysicsClient* ) physClient;
  111. b3Assert(cl);
  112. b3Assert(cl->canSubmitCommand());
  113. struct SharedMemoryCommand* command = cl->getAvailableSharedMemoryCommand();
  114. b3Assert(command);
  115. command->m_type = CMD_SEND_DESIRED_STATE;
  116. command->m_sendDesiredStateCommandArgument.m_controlMode = controlMode;
  117. command->m_sendDesiredStateCommandArgument.m_bodyUniqueId = 0;
  118. command->m_updateFlags = 0;
  119. return (b3SharedMemoryCommandHandle) command;
  120. }
  121. int b3JointControlSetDesiredPosition(b3SharedMemoryCommandHandle commandHandle, int qIndex, double value)
  122. {
  123. struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
  124. b3Assert(command);
  125. command->m_sendDesiredStateCommandArgument.m_desiredStateQ[qIndex] = value;
  126. return 0;
  127. }
  128. int b3JointControlSetKp(b3SharedMemoryCommandHandle commandHandle, int dofIndex, double value)
  129. {
  130. struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
  131. b3Assert(command);
  132. command->m_sendDesiredStateCommandArgument.m_Kp[dofIndex] = value;
  133. return 0;
  134. }
  135. int b3JointControlSetKd(b3SharedMemoryCommandHandle commandHandle, int dofIndex, double value)
  136. {
  137. struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
  138. b3Assert(command);
  139. command->m_sendDesiredStateCommandArgument.m_Kd[dofIndex] = value;
  140. return 0;
  141. }
  142. int b3JointControlSetDesiredVelocity(b3SharedMemoryCommandHandle commandHandle, int dofIndex, double value)
  143. {
  144. struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
  145. b3Assert(command);
  146. command->m_sendDesiredStateCommandArgument.m_desiredStateQdot[dofIndex] = value;
  147. return 0;
  148. }
  149. int b3JointControlSetMaximumForce(b3SharedMemoryCommandHandle commandHandle, int dofIndex, double value)
  150. {
  151. struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
  152. b3Assert(command);
  153. command->m_sendDesiredStateCommandArgument.m_desiredStateForceTorque[dofIndex] = value;
  154. return 0;
  155. }
  156. int b3JointControlSetDesiredForceTorque(b3SharedMemoryCommandHandle commandHandle, int dofIndex, double value)
  157. {
  158. struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
  159. b3Assert(command);
  160. command->m_sendDesiredStateCommandArgument.m_desiredStateForceTorque[dofIndex] = value;
  161. return 0;
  162. }
  163. b3SharedMemoryCommandHandle b3RequestActualStateCommandInit(b3PhysicsClientHandle physClient, int bodyUniqueId)
  164. {
  165. PhysicsClient* cl = (PhysicsClient* ) physClient;
  166. b3Assert(cl);
  167. b3Assert(cl->canSubmitCommand());
  168. struct SharedMemoryCommand* command = cl->getAvailableSharedMemoryCommand();
  169. b3Assert(command);
  170. command->m_type =CMD_REQUEST_ACTUAL_STATE;
  171. command->m_requestActualStateInformationCommandArgument.m_bodyUniqueId = bodyUniqueId;
  172. return (b3SharedMemoryCommandHandle) command;
  173. }
  174. void b3GetJointState(b3PhysicsClientHandle physClient, b3SharedMemoryStatusHandle statusHandle, int jointIndex, b3JointSensorState *state)
  175. {
  176. const SharedMemoryStatus* status = (const SharedMemoryStatus* ) statusHandle;
  177. b3Assert(status);
  178. int bodyIndex = status->m_sendActualStateArgs.m_bodyUniqueId;
  179. b3Assert(bodyIndex>=0);
  180. if (bodyIndex>=0)
  181. {
  182. b3JointInfo info;
  183. b3GetJointInfo(physClient, bodyIndex,jointIndex, &info);
  184. state->m_jointPosition = status->m_sendActualStateArgs.m_actualStateQ[info.m_qIndex];
  185. state->m_jointVelocity = status->m_sendActualStateArgs.m_actualStateQdot[info.m_uIndex];
  186. for (int ii(0); ii < 6; ++ii) {
  187. state->m_jointForceTorque[ii] = status->m_sendActualStateArgs.m_jointReactionForces[6 * jointIndex + ii];
  188. }
  189. }
  190. }
  191. b3SharedMemoryCommandHandle b3CreateBoxShapeCommandInit(b3PhysicsClientHandle physClient)
  192. {
  193. PhysicsClient* cl = (PhysicsClient* ) physClient;
  194. b3Assert(cl);
  195. b3Assert(cl->canSubmitCommand());
  196. struct SharedMemoryCommand* command = cl->getAvailableSharedMemoryCommand();
  197. b3Assert(command);
  198. command->m_type = CMD_CREATE_BOX_COLLISION_SHAPE;
  199. command->m_updateFlags =0;
  200. return (b3SharedMemoryCommandHandle) command;
  201. }
  202. int b3CreateBoxCommandSetStartPosition(b3SharedMemoryCommandHandle commandHandle, double startPosX,double startPosY,double startPosZ)
  203. {
  204. struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
  205. b3Assert(command);
  206. b3Assert(command->m_type == CMD_CREATE_BOX_COLLISION_SHAPE);
  207. command->m_updateFlags |=BOX_SHAPE_HAS_INITIAL_POSITION;
  208. command->m_createBoxShapeArguments.m_initialPosition[0] = startPosX;
  209. command->m_createBoxShapeArguments.m_initialPosition[1] = startPosY;
  210. command->m_createBoxShapeArguments.m_initialPosition[2] = startPosZ;
  211. return 0;
  212. }
  213. int b3CreateBoxCommandSetHalfExtents(b3SharedMemoryCommandHandle commandHandle, double halfExtentsX,double halfExtentsY,double halfExtentsZ)
  214. {
  215. struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
  216. b3Assert(command);
  217. b3Assert(command->m_type == CMD_CREATE_BOX_COLLISION_SHAPE);
  218. command->m_updateFlags |=BOX_SHAPE_HAS_HALF_EXTENTS;
  219. command->m_createBoxShapeArguments.m_halfExtentsX = halfExtentsX;
  220. command->m_createBoxShapeArguments.m_halfExtentsY = halfExtentsY;
  221. command->m_createBoxShapeArguments.m_halfExtentsZ = halfExtentsZ;
  222. return 0;
  223. }
  224. int b3CreateBoxCommandSetMass(b3SharedMemoryCommandHandle commandHandle, double mass)
  225. {
  226. struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
  227. b3Assert(command);
  228. b3Assert(command->m_type == CMD_CREATE_BOX_COLLISION_SHAPE);
  229. command->m_updateFlags |=BOX_SHAPE_HAS_MASS;
  230. command->m_createBoxShapeArguments.m_mass = mass;
  231. return 0;
  232. }
  233. int b3CreateBoxCommandSetCollisionShapeType(b3SharedMemoryCommandHandle commandHandle, int collisionShapeType)
  234. {
  235. struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
  236. b3Assert(command);
  237. b3Assert(command->m_type == CMD_CREATE_BOX_COLLISION_SHAPE);
  238. command->m_updateFlags |=BOX_SHAPE_HAS_COLLISION_SHAPE_TYPE;
  239. command->m_createBoxShapeArguments.m_collisionShapeType = collisionShapeType;
  240. return 0;
  241. }
  242. int b3CreateBoxCommandSetColorRGBA(b3SharedMemoryCommandHandle commandHandle, double red,double green,double blue, double alpha)
  243. {
  244. struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
  245. b3Assert(command);
  246. b3Assert(command->m_type == CMD_CREATE_BOX_COLLISION_SHAPE);
  247. command->m_updateFlags |=BOX_SHAPE_HAS_COLOR;
  248. command->m_createBoxShapeArguments.m_colorRGBA[0] = red;
  249. command->m_createBoxShapeArguments.m_colorRGBA[1] = green;
  250. command->m_createBoxShapeArguments.m_colorRGBA[2] = blue;
  251. command->m_createBoxShapeArguments.m_colorRGBA[3] = alpha;
  252. return 0;
  253. }
  254. int b3CreateBoxCommandSetStartOrientation(b3SharedMemoryCommandHandle commandHandle, double startOrnX,double startOrnY,double startOrnZ, double startOrnW)
  255. {
  256. struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
  257. b3Assert(command);
  258. b3Assert(command->m_type == CMD_CREATE_BOX_COLLISION_SHAPE);
  259. command->m_updateFlags |=BOX_SHAPE_HAS_INITIAL_ORIENTATION;
  260. command->m_createBoxShapeArguments.m_initialOrientation[0] = startOrnX;
  261. command->m_createBoxShapeArguments.m_initialOrientation[1] = startOrnY;
  262. command->m_createBoxShapeArguments.m_initialOrientation[2] = startOrnZ;
  263. command->m_createBoxShapeArguments.m_initialOrientation[3] = startOrnW;
  264. return 0;
  265. }
  266. b3SharedMemoryCommandHandle b3CreatePoseCommandInit(b3PhysicsClientHandle physClient, int bodyIndex)
  267. {
  268. PhysicsClient* cl = (PhysicsClient* ) physClient;
  269. b3Assert(cl);
  270. b3Assert(cl->canSubmitCommand());
  271. struct SharedMemoryCommand* command = cl->getAvailableSharedMemoryCommand();
  272. b3Assert(command);
  273. command->m_type = CMD_INIT_POSE;
  274. command->m_updateFlags =0;
  275. command->m_initPoseArgs.m_bodyUniqueId = bodyIndex;
  276. return (b3SharedMemoryCommandHandle) command;
  277. }
  278. int b3CreatePoseCommandSetBasePosition(b3SharedMemoryCommandHandle commandHandle, double startPosX,double startPosY,double startPosZ)
  279. {
  280. struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
  281. b3Assert(command);
  282. b3Assert(command->m_type == CMD_INIT_POSE);
  283. command->m_updateFlags |=INIT_POSE_HAS_INITIAL_POSITION;
  284. command->m_initPoseArgs.m_initialStateQ[0] = startPosX;
  285. command->m_initPoseArgs.m_initialStateQ[1] = startPosY;
  286. command->m_initPoseArgs.m_initialStateQ[2] = startPosZ;
  287. return 0;
  288. }
  289. int b3CreatePoseCommandSetBaseOrientation(b3SharedMemoryCommandHandle commandHandle, double startOrnX,double startOrnY,double startOrnZ, double startOrnW)
  290. {
  291. struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
  292. b3Assert(command);
  293. b3Assert(command->m_type == CMD_INIT_POSE);
  294. command->m_updateFlags |=INIT_POSE_HAS_INITIAL_ORIENTATION;
  295. command->m_initPoseArgs.m_initialStateQ[3] = startOrnX;
  296. command->m_initPoseArgs.m_initialStateQ[4] = startOrnY;
  297. command->m_initPoseArgs.m_initialStateQ[5] = startOrnZ;
  298. command->m_initPoseArgs.m_initialStateQ[6] = startOrnW;
  299. return 0;
  300. }
  301. int b3CreatePoseCommandSetJointPositions(b3SharedMemoryCommandHandle commandHandle, int numJointPositions, const double* jointPositions)
  302. {
  303. struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
  304. b3Assert(command);
  305. b3Assert(command->m_type == CMD_INIT_POSE);
  306. command->m_updateFlags |=INIT_POSE_HAS_JOINT_STATE;
  307. for (int i=0;i<numJointPositions;i++)
  308. {
  309. command->m_initPoseArgs.m_initialStateQ[i+7] = jointPositions[i];
  310. }
  311. return 0;
  312. }
  313. int b3CreatePoseCommandSetJointPosition(b3PhysicsClientHandle physClient, b3SharedMemoryCommandHandle commandHandle, int jointIndex, double jointPosition)
  314. {
  315. struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
  316. b3Assert(command);
  317. b3Assert(command->m_type == CMD_INIT_POSE);
  318. command->m_updateFlags |=INIT_POSE_HAS_JOINT_STATE;
  319. b3JointInfo info;
  320. b3GetJointInfo(physClient, command->m_initPoseArgs.m_bodyUniqueId,jointIndex, &info);
  321. btAssert((info.m_flags & JOINT_HAS_MOTORIZED_POWER) && info.m_qIndex >=0);
  322. if ((info.m_flags & JOINT_HAS_MOTORIZED_POWER) && info.m_qIndex >=0)
  323. {
  324. command->m_initPoseArgs.m_initialStateQ[info.m_qIndex] = jointPosition;
  325. }
  326. return 0;
  327. }
  328. b3SharedMemoryCommandHandle b3CreateSensorCommandInit(b3PhysicsClientHandle physClient)
  329. {
  330. PhysicsClient* cl = (PhysicsClient* ) physClient;
  331. b3Assert(cl);
  332. b3Assert(cl->canSubmitCommand());
  333. struct SharedMemoryCommand* command = cl->getAvailableSharedMemoryCommand();
  334. b3Assert(command);
  335. command->m_type = CMD_CREATE_SENSOR;
  336. command->m_updateFlags = 0;
  337. command->m_createSensorArguments.m_numJointSensorChanges = 0;
  338. command->m_createSensorArguments.m_bodyUniqueId = 0;
  339. return (b3SharedMemoryCommandHandle) command;
  340. }
  341. int b3CreateSensorEnable6DofJointForceTorqueSensor(b3SharedMemoryCommandHandle commandHandle, int jointIndex, int enable)
  342. {
  343. struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
  344. b3Assert(command);
  345. b3Assert(command->m_type == CMD_CREATE_SENSOR);
  346. int curIndex = command->m_createSensorArguments.m_numJointSensorChanges;
  347. command->m_createSensorArguments.m_sensorType[curIndex] = SENSOR_FORCE_TORQUE;
  348. command->m_createSensorArguments.m_jointIndex[curIndex] = jointIndex;
  349. command->m_createSensorArguments.m_enableJointForceSensor[curIndex] = enable;
  350. command->m_createSensorArguments.m_numJointSensorChanges++;
  351. return 0;
  352. }
  353. int b3CreateSensorEnableIMUForLink(b3SharedMemoryCommandHandle commandHandle, int linkIndex, int enable)
  354. {
  355. struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
  356. b3Assert(command);
  357. b3Assert(command->m_type == CMD_CREATE_SENSOR);
  358. int curIndex = command->m_createSensorArguments.m_numJointSensorChanges;
  359. command->m_createSensorArguments.m_sensorType[curIndex] = SENSOR_IMU;
  360. command->m_createSensorArguments.m_linkIndex[curIndex] = linkIndex;
  361. command->m_createSensorArguments.m_enableSensor[curIndex] = enable;
  362. command->m_createSensorArguments.m_numJointSensorChanges++;
  363. return 0;
  364. }
  365. b3PhysicsClientHandle b3ConnectSharedMemory(int key)
  366. {
  367. PhysicsClientSharedMemory* cl = new PhysicsClientSharedMemory();
  368. ///client should never create shared memory, only the server does
  369. cl->setSharedMemoryKey(key);
  370. cl->connect();
  371. return (b3PhysicsClientHandle ) cl;
  372. }
  373. void b3DisconnectSharedMemory(b3PhysicsClientHandle physClient)
  374. {
  375. PhysicsClient* cl = (PhysicsClient* ) physClient;
  376. delete cl;
  377. }
  378. b3SharedMemoryStatusHandle b3ProcessServerStatus(b3PhysicsClientHandle physClient)
  379. {
  380. PhysicsClient* cl = (PhysicsClient* ) physClient;
  381. const SharedMemoryStatus* stat = cl->processServerStatus();
  382. return (b3SharedMemoryStatusHandle) stat;
  383. }
  384. int b3GetStatusType(b3SharedMemoryStatusHandle statusHandle)
  385. {
  386. const SharedMemoryStatus* status = (const SharedMemoryStatus* ) statusHandle;
  387. b3Assert(status);
  388. if (status)
  389. {
  390. return status->m_type;
  391. }
  392. return 0;
  393. }
  394. int b3GetStatusBodyIndex(b3SharedMemoryStatusHandle statusHandle)
  395. {
  396. const SharedMemoryStatus* status = (const SharedMemoryStatus* ) statusHandle;
  397. b3Assert(status);
  398. int bodyId = -1;
  399. if (status)
  400. {
  401. switch (status->m_type)
  402. {
  403. case CMD_URDF_LOADING_COMPLETED:
  404. {
  405. bodyId = status->m_dataStreamArguments.m_bodyUniqueId;
  406. break;
  407. }
  408. case CMD_RIGID_BODY_CREATION_COMPLETED:
  409. {
  410. bodyId = status->m_rigidBodyCreateArgs.m_bodyUniqueId;
  411. break;
  412. }
  413. default:
  414. {
  415. b3Assert(0);
  416. }
  417. };
  418. }
  419. return bodyId;
  420. }
  421. int b3GetStatusActualState(b3SharedMemoryStatusHandle statusHandle,
  422. int* bodyUniqueId,
  423. int* numDegreeOfFreedomQ,
  424. int* numDegreeOfFreedomU,
  425. const double* rootLocalInertialFrame[],
  426. const double* actualStateQ[],
  427. const double* actualStateQdot[],
  428. const double* jointReactionForces[]) {
  429. const SharedMemoryStatus* status = (const SharedMemoryStatus* ) statusHandle;
  430. const SendActualStateArgs &args = status->m_sendActualStateArgs;
  431. if (bodyUniqueId) {
  432. *bodyUniqueId = args.m_bodyUniqueId;
  433. }
  434. if (numDegreeOfFreedomQ) {
  435. *numDegreeOfFreedomQ = args.m_numDegreeOfFreedomQ;
  436. }
  437. if (numDegreeOfFreedomU) {
  438. *numDegreeOfFreedomU = args.m_numDegreeOfFreedomU;
  439. }
  440. if (rootLocalInertialFrame) {
  441. *rootLocalInertialFrame = args.m_rootLocalInertialFrame;
  442. }
  443. if (actualStateQ) {
  444. *actualStateQ = args.m_actualStateQ;
  445. }
  446. if (actualStateQdot) {
  447. *actualStateQdot = args.m_actualStateQdot;
  448. }
  449. if (jointReactionForces) {
  450. *jointReactionForces = args.m_jointReactionForces;
  451. }
  452. return true;
  453. }
  454. int b3CanSubmitCommand(b3PhysicsClientHandle physClient)
  455. {
  456. PhysicsClient* cl = (PhysicsClient* ) physClient;
  457. if (cl)
  458. {
  459. return (int)cl->canSubmitCommand();
  460. }
  461. return false;
  462. }
  463. int b3SubmitClientCommand(b3PhysicsClientHandle physClient, const b3SharedMemoryCommandHandle commandHandle)
  464. {
  465. struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
  466. PhysicsClient* cl = (PhysicsClient* ) physClient;
  467. return (int)cl->submitClientCommand(*command);
  468. }
  469. b3SharedMemoryStatusHandle b3SubmitClientCommandAndWaitStatus(b3PhysicsClientHandle physClient, const b3SharedMemoryCommandHandle commandHandle)
  470. {
  471. int timeout = 1024*1024*1024;
  472. b3SharedMemoryStatusHandle statusHandle=0;
  473. b3SubmitClientCommand(physClient,commandHandle);
  474. while ((statusHandle==0) && (timeout-- > 0))
  475. {
  476. statusHandle =b3ProcessServerStatus(physClient);
  477. }
  478. return (b3SharedMemoryStatusHandle) statusHandle;
  479. }
  480. int b3GetNumJoints(b3PhysicsClientHandle physClient, int bodyId)
  481. {
  482. PhysicsClient* cl = (PhysicsClient* ) physClient;
  483. return cl->getNumJoints(bodyId);
  484. }
  485. void b3GetJointInfo(b3PhysicsClientHandle physClient, int bodyIndex, int linkIndex, struct b3JointInfo* info)
  486. {
  487. PhysicsClient* cl = (PhysicsClient* ) physClient;
  488. cl->getJointInfo(bodyIndex, linkIndex,*info);
  489. }
  490. b3SharedMemoryCommandHandle b3PickBody(b3PhysicsClientHandle physClient, double rayFromWorldX,
  491. double rayFromWorldY, double rayFromWorldZ,
  492. double rayToWorldX, double rayToWorldY, double rayToWorldZ)
  493. {
  494. PhysicsClient *cl = (PhysicsClient *)physClient;
  495. b3Assert(cl);
  496. b3Assert(cl->canSubmitCommand());
  497. struct SharedMemoryCommand *command = cl->getAvailableSharedMemoryCommand();
  498. b3Assert(command);
  499. command->m_type = CMD_PICK_BODY;
  500. command->m_pickBodyArguments.m_rayFromWorld[0] = rayFromWorldX;
  501. command->m_pickBodyArguments.m_rayFromWorld[1] = rayFromWorldY;
  502. command->m_pickBodyArguments.m_rayFromWorld[2] = rayFromWorldZ;
  503. command->m_pickBodyArguments.m_rayToWorld[0] = rayToWorldX;
  504. command->m_pickBodyArguments.m_rayToWorld[1] = rayToWorldY;
  505. command->m_pickBodyArguments.m_rayToWorld[2] = rayToWorldZ;
  506. return (b3SharedMemoryCommandHandle)command;
  507. }
  508. b3SharedMemoryCommandHandle b3MovePickedBody(b3PhysicsClientHandle physClient, double rayFromWorldX,
  509. double rayFromWorldY, double rayFromWorldZ,
  510. double rayToWorldX, double rayToWorldY,
  511. double rayToWorldZ)
  512. {
  513. PhysicsClient *cl = (PhysicsClient *)physClient;
  514. b3Assert(cl);
  515. b3Assert(cl->canSubmitCommand());
  516. struct SharedMemoryCommand *command = cl->getAvailableSharedMemoryCommand();
  517. b3Assert(command);
  518. command->m_type = CMD_MOVE_PICKED_BODY;
  519. command->m_pickBodyArguments.m_rayFromWorld[0] = rayFromWorldX;
  520. command->m_pickBodyArguments.m_rayFromWorld[1] = rayFromWorldY;
  521. command->m_pickBodyArguments.m_rayFromWorld[2] = rayFromWorldZ;
  522. command->m_pickBodyArguments.m_rayToWorld[0] = rayToWorldX;
  523. command->m_pickBodyArguments.m_rayToWorld[1] = rayToWorldY;
  524. command->m_pickBodyArguments.m_rayToWorld[2] = rayToWorldZ;
  525. return (b3SharedMemoryCommandHandle)command;
  526. }
  527. b3SharedMemoryCommandHandle b3RemovePickingConstraint(b3PhysicsClientHandle physClient)
  528. {
  529. PhysicsClient *cl = (PhysicsClient *)physClient;
  530. b3Assert(cl);
  531. b3Assert(cl->canSubmitCommand());
  532. struct SharedMemoryCommand *command = cl->getAvailableSharedMemoryCommand();
  533. b3Assert(command);
  534. command->m_type = CMD_REMOVE_PICKING_CONSTRAINT_BODY;
  535. return (b3SharedMemoryCommandHandle)command;
  536. }
  537. b3SharedMemoryCommandHandle b3InitRequestDebugLinesCommand(b3PhysicsClientHandle physClient, int debugMode)
  538. {
  539. PhysicsClient* cl = (PhysicsClient* ) physClient;
  540. b3Assert(cl);
  541. b3Assert(cl->canSubmitCommand());
  542. struct SharedMemoryCommand* command = cl->getAvailableSharedMemoryCommand();
  543. b3Assert(command);
  544. command->m_type =CMD_REQUEST_DEBUG_LINES;
  545. command->m_requestDebugLinesArguments.m_debugMode = debugMode;
  546. command->m_requestDebugLinesArguments.m_startingLineIndex = 0;
  547. return (b3SharedMemoryCommandHandle) command;
  548. }
  549. void b3GetDebugLines(b3PhysicsClientHandle physClient, struct b3DebugLines* lines)
  550. {
  551. PhysicsClient* cl = (PhysicsClient* ) physClient;
  552. b3Assert(lines);
  553. if (lines)
  554. {
  555. lines->m_numDebugLines = cl->getNumDebugLines();
  556. lines->m_linesFrom = cl->getDebugLinesFrom();
  557. lines->m_linesTo = cl->getDebugLinesTo();
  558. lines->m_linesColor = cl->getDebugLinesColor();
  559. }
  560. }