PhysicsClientC_API.cpp 56 KB

12345678910111213141516171819202122232425262728293031323334353637383940414243444546474849505152535455565758596061626364656667686970717273747576777879808182838485868788899091929394959697989910010110210310410510610710810911011111211311411511611711811912012112212312412512612712812913013113213313413513613713813914014114214314414514614714814915015115215315415515615715815916016116216316416516616716816917017117217317417517617717817918018118218318418518618718818919019119219319419519619719819920020120220320420520620720820921021121221321421521621721821922022122222322422522622722822923023123223323423523623723823924024124224324424524624724824925025125225325425525625725825926026126226326426526626726826927027127227327427527627727827928028128228328428528628728828929029129229329429529629729829930030130230330430530630730830931031131231331431531631731831932032132232332432532632732832933033133233333433533633733833934034134234334434534634734834935035135235335435535635735835936036136236336436536636736836937037137237337437537637737837938038138238338438538638738838939039139239339439539639739839940040140240340440540640740840941041141241341441541641741841942042142242342442542642742842943043143243343443543643743843944044144244344444544644744844945045145245345445545645745845946046146246346446546646746846947047147247347447547647747847948048148248348448548648748848949049149249349449549649749849950050150250350450550650750850951051151251351451551651751851952052152252352452552652752852953053153253353453553653753853954054154254354454554654754854955055155255355455555655755855956056156256356456556656756856957057157257357457557657757857958058158258358458558658758858959059159259359459559659759859960060160260360460560660760860961061161261361461561661761861962062162262362462562662762862963063163263363463563663763863964064164264364464564664764864965065165265365465565665765865966066166266366466566666766866967067167267367467567667767867968068168268368468568668768868969069169269369469569669769869970070170270370470570670770870971071171271371471571671771871972072172272372472572672772872973073173273373473573673773873974074174274374474574674774874975075175275375475575675775875976076176276376476576676776876977077177277377477577677777877978078178278378478578678778878979079179279379479579679779879980080180280380480580680780880981081181281381481581681781881982082182282382482582682782882983083183283383483583683783883984084184284384484584684784884985085185285385485585685785885986086186286386486586686786886987087187287387487587687787887988088188288388488588688788888989089189289389489589689789889990090190290390490590690790890991091191291391491591691791891992092192292392492592692792892993093193293393493593693793893994094194294394494594694794894995095195295395495595695795895996096196296396496596696796896997097197297397497597697797897998098198298398498598698798898999099199299399499599699799899910001001100210031004100510061007100810091010101110121013101410151016101710181019102010211022102310241025102610271028102910301031103210331034103510361037103810391040104110421043104410451046104710481049105010511052105310541055105610571058105910601061106210631064106510661067106810691070107110721073107410751076107710781079108010811082108310841085108610871088108910901091109210931094109510961097109810991100110111021103110411051106110711081109111011111112111311141115111611171118111911201121112211231124112511261127112811291130113111321133113411351136113711381139114011411142114311441145114611471148114911501151115211531154115511561157115811591160116111621163116411651166116711681169117011711172117311741175117611771178117911801181118211831184118511861187118811891190119111921193119411951196119711981199120012011202120312041205120612071208120912101211121212131214121512161217121812191220122112221223122412251226122712281229123012311232123312341235123612371238123912401241124212431244124512461247124812491250125112521253125412551256125712581259126012611262126312641265126612671268126912701271127212731274127512761277127812791280128112821283128412851286128712881289129012911292129312941295129612971298129913001301130213031304130513061307130813091310131113121313131413151316131713181319132013211322132313241325132613271328132913301331133213331334133513361337133813391340134113421343134413451346134713481349135013511352135313541355135613571358135913601361136213631364136513661367136813691370137113721373137413751376137713781379138013811382138313841385138613871388138913901391139213931394139513961397139813991400140114021403140414051406140714081409141014111412141314141415141614171418141914201421142214231424142514261427142814291430143114321433143414351436143714381439144014411442144314441445144614471448144914501451145214531454145514561457145814591460146114621463146414651466146714681469147014711472147314741475147614771478147914801481148214831484148514861487148814891490149114921493149414951496149714981499
  1. #include "PhysicsClientC_API.h"
  2. #include "PhysicsClientSharedMemory.h"
  3. #include "Bullet3Common/b3Scalar.h"
  4. #include "Bullet3Common/b3Vector3.h"
  5. #include "Bullet3Common/b3Matrix3x3.h"
  6. #include <string.h>
  7. #include "SharedMemoryCommands.h"
  8. b3SharedMemoryCommandHandle b3LoadSdfCommandInit(b3PhysicsClientHandle physClient, const char* sdfFileName)
  9. {
  10. PhysicsClient* cl = (PhysicsClient* ) physClient;
  11. b3Assert(cl);
  12. b3Assert(cl->canSubmitCommand());
  13. struct SharedMemoryCommand* command = cl->getAvailableSharedMemoryCommand();
  14. b3Assert(command);
  15. command->m_type = CMD_LOAD_SDF;
  16. int len = strlen(sdfFileName);
  17. if (len<MAX_SDF_FILENAME_LENGTH)
  18. {
  19. strcpy(command->m_sdfArguments.m_sdfFileName,sdfFileName);
  20. } else
  21. {
  22. command->m_sdfArguments.m_sdfFileName[0] = 0;
  23. }
  24. command->m_updateFlags = SDF_ARGS_FILE_NAME;
  25. return (b3SharedMemoryCommandHandle) command;
  26. }
  27. b3SharedMemoryCommandHandle b3SaveWorldCommandInit(b3PhysicsClientHandle physClient, const char* sdfFileName)
  28. {
  29. PhysicsClient* cl = (PhysicsClient* ) physClient;
  30. b3Assert(cl);
  31. b3Assert(cl->canSubmitCommand());
  32. struct SharedMemoryCommand* command = cl->getAvailableSharedMemoryCommand();
  33. b3Assert(command);
  34. command->m_type = CMD_SAVE_WORLD;
  35. int len = strlen(sdfFileName);
  36. if (len<MAX_SDF_FILENAME_LENGTH)
  37. {
  38. strcpy(command->m_sdfArguments.m_sdfFileName,sdfFileName);
  39. } else
  40. {
  41. command->m_sdfArguments.m_sdfFileName[0] = 0;
  42. }
  43. command->m_updateFlags = SDF_ARGS_FILE_NAME;
  44. return (b3SharedMemoryCommandHandle) command;
  45. }
  46. b3SharedMemoryCommandHandle b3LoadUrdfCommandInit(b3PhysicsClientHandle physClient, const char* urdfFileName)
  47. {
  48. PhysicsClient* cl = (PhysicsClient* ) physClient;
  49. b3Assert(cl);
  50. b3Assert(cl->canSubmitCommand());
  51. struct SharedMemoryCommand* command = cl->getAvailableSharedMemoryCommand();
  52. b3Assert(command);
  53. command->m_type = CMD_LOAD_URDF;
  54. int len = strlen(urdfFileName);
  55. if (len<MAX_URDF_FILENAME_LENGTH)
  56. {
  57. strcpy(command->m_urdfArguments.m_urdfFileName,urdfFileName);
  58. } else
  59. {
  60. command->m_urdfArguments.m_urdfFileName[0] = 0;
  61. }
  62. command->m_updateFlags = URDF_ARGS_FILE_NAME;
  63. return (b3SharedMemoryCommandHandle) command;
  64. }
  65. int b3LoadUrdfCommandSetUseMultiBody(b3SharedMemoryCommandHandle commandHandle, int useMultiBody)
  66. {
  67. struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
  68. b3Assert(command);
  69. b3Assert(command->m_type == CMD_LOAD_URDF);
  70. command->m_updateFlags |=URDF_ARGS_USE_MULTIBODY;
  71. command->m_urdfArguments.m_useMultiBody = useMultiBody;
  72. return 0;
  73. }
  74. int b3LoadSdfCommandSetUseMultiBody(b3SharedMemoryCommandHandle commandHandle, int useMultiBody)
  75. {
  76. struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
  77. b3Assert(command);
  78. b3Assert(command->m_type == CMD_LOAD_SDF);
  79. command->m_updateFlags |=URDF_ARGS_USE_MULTIBODY;
  80. command->m_sdfArguments.m_useMultiBody = useMultiBody;
  81. return 0;
  82. }
  83. int b3LoadUrdfCommandSetUseFixedBase(b3SharedMemoryCommandHandle commandHandle, int useFixedBase)
  84. {
  85. struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
  86. b3Assert(command);
  87. b3Assert(command->m_type == CMD_LOAD_URDF);
  88. command->m_updateFlags |=URDF_ARGS_USE_FIXED_BASE;
  89. command->m_urdfArguments.m_useFixedBase = useFixedBase;
  90. return 0;
  91. }
  92. int b3LoadUrdfCommandSetStartPosition(b3SharedMemoryCommandHandle commandHandle, double startPosX,double startPosY,double startPosZ)
  93. {
  94. struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
  95. b3Assert(command);
  96. b3Assert(command->m_type == CMD_LOAD_URDF);
  97. command->m_urdfArguments.m_initialPosition[0] = startPosX;
  98. command->m_urdfArguments.m_initialPosition[1] = startPosY;
  99. command->m_urdfArguments.m_initialPosition[2] = startPosZ;
  100. command->m_updateFlags|=URDF_ARGS_INITIAL_POSITION;
  101. return 0;
  102. }
  103. int b3LoadUrdfCommandSetStartOrientation(b3SharedMemoryCommandHandle commandHandle, double startOrnX,double startOrnY,double startOrnZ, double startOrnW)
  104. {
  105. struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
  106. b3Assert(command);
  107. b3Assert(command->m_type == CMD_LOAD_URDF);
  108. command->m_urdfArguments.m_initialOrientation[0] = startOrnX;
  109. command->m_urdfArguments.m_initialOrientation[1] = startOrnY;
  110. command->m_urdfArguments.m_initialOrientation[2] = startOrnZ;
  111. command->m_urdfArguments.m_initialOrientation[3] = startOrnW;
  112. command->m_updateFlags|=URDF_ARGS_INITIAL_ORIENTATION;
  113. return 0;
  114. }
  115. b3SharedMemoryCommandHandle b3InitPhysicsParamCommand(b3PhysicsClientHandle physClient)
  116. {
  117. PhysicsClient* cl = (PhysicsClient* ) physClient;
  118. b3Assert(cl);
  119. b3Assert(cl->canSubmitCommand());
  120. struct SharedMemoryCommand* command = cl->getAvailableSharedMemoryCommand();
  121. b3Assert(command);
  122. command->m_type = CMD_SEND_PHYSICS_SIMULATION_PARAMETERS;
  123. command->m_updateFlags = 0;
  124. return (b3SharedMemoryCommandHandle) command;
  125. }
  126. int b3PhysicsParamSetGravity(b3SharedMemoryCommandHandle commandHandle, double gravx,double gravy, double gravz)
  127. {
  128. struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
  129. b3Assert(command->m_type == CMD_SEND_PHYSICS_SIMULATION_PARAMETERS);
  130. command->m_physSimParamArgs.m_gravityAcceleration[0] = gravx;
  131. command->m_physSimParamArgs.m_gravityAcceleration[1] = gravy;
  132. command->m_physSimParamArgs.m_gravityAcceleration[2] = gravz;
  133. command->m_updateFlags |= SIM_PARAM_UPDATE_GRAVITY;
  134. return 0;
  135. }
  136. int b3PhysicsParamSetRealTimeSimulation(b3SharedMemoryCommandHandle commandHandle, int enableRealTimeSimulation)
  137. {
  138. struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
  139. b3Assert(command->m_type == CMD_SEND_PHYSICS_SIMULATION_PARAMETERS);
  140. command->m_physSimParamArgs.m_allowRealTimeSimulation = enableRealTimeSimulation;
  141. command->m_updateFlags |= SIM_PARAM_UPDATE_REAL_TIME_SIMULATION;
  142. return 0;
  143. }
  144. int b3PhysicsParamSetNumSolverIterations(b3SharedMemoryCommandHandle commandHandle, int numSolverIterations)
  145. {
  146. struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
  147. b3Assert(command->m_type == CMD_SEND_PHYSICS_SIMULATION_PARAMETERS);
  148. command->m_physSimParamArgs.m_numSolverIterations = numSolverIterations;
  149. command->m_updateFlags |= SIM_PARAM_UPDATE_NUM_SOLVER_ITERATIONS;
  150. return 0;
  151. }
  152. int b3PhysicsParamSetTimeStep(b3SharedMemoryCommandHandle commandHandle, double timeStep)
  153. {
  154. struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
  155. b3Assert(command->m_type == CMD_SEND_PHYSICS_SIMULATION_PARAMETERS);
  156. command->m_updateFlags |= SIM_PARAM_UPDATE_DELTA_TIME;
  157. command->m_physSimParamArgs.m_deltaTime = timeStep;
  158. return 0;
  159. }
  160. int b3PhysicsParamSetNumSubSteps(b3SharedMemoryCommandHandle commandHandle, int numSubSteps)
  161. {
  162. struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
  163. b3Assert(command->m_type == CMD_SEND_PHYSICS_SIMULATION_PARAMETERS);
  164. command->m_updateFlags |= SIM_PARAM_UPDATE_NUM_SIMULATION_SUB_STEPS;
  165. command->m_physSimParamArgs.m_numSimulationSubSteps = numSubSteps;
  166. return 0;
  167. }
  168. int b3PhysicsParamSetDefaultContactERP(b3SharedMemoryCommandHandle commandHandle, double defaultContactERP)
  169. {
  170. struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
  171. b3Assert(command->m_type == CMD_SEND_PHYSICS_SIMULATION_PARAMETERS);
  172. command->m_updateFlags |= SIM_PARAM_UPDATE_DEFAULT_CONTACT_ERP;
  173. command->m_physSimParamArgs.m_defaultContactERP = defaultContactERP;
  174. return 0;
  175. }
  176. int b3PhysicsParamSetDefaultContactERP(b3SharedMemoryCommandHandle commandHandle, double defaultContactERP);
  177. b3SharedMemoryCommandHandle b3InitStepSimulationCommand(b3PhysicsClientHandle physClient)
  178. {
  179. PhysicsClient* cl = (PhysicsClient* ) physClient;
  180. b3Assert(cl);
  181. b3Assert(cl->canSubmitCommand());
  182. struct SharedMemoryCommand* command = cl->getAvailableSharedMemoryCommand();
  183. b3Assert(command);
  184. command->m_type = CMD_STEP_FORWARD_SIMULATION;
  185. command->m_updateFlags = 0;
  186. return (b3SharedMemoryCommandHandle) command;
  187. }
  188. b3SharedMemoryCommandHandle b3InitResetSimulationCommand(b3PhysicsClientHandle physClient)
  189. {
  190. PhysicsClient* cl = (PhysicsClient* ) physClient;
  191. b3Assert(cl);
  192. b3Assert(cl->canSubmitCommand());
  193. struct SharedMemoryCommand* command = cl->getAvailableSharedMemoryCommand();
  194. b3Assert(command);
  195. command->m_type = CMD_RESET_SIMULATION;
  196. command->m_updateFlags = 0;
  197. return (b3SharedMemoryCommandHandle) command;
  198. }
  199. b3SharedMemoryCommandHandle b3JointControlCommandInit(b3PhysicsClientHandle physClient, int controlMode)
  200. {
  201. return b3JointControlCommandInit2(physClient,0,controlMode);
  202. }
  203. b3SharedMemoryCommandHandle b3JointControlCommandInit2( b3PhysicsClientHandle physClient, int bodyUniqueId, int controlMode)
  204. {
  205. PhysicsClient* cl = (PhysicsClient* ) physClient;
  206. b3Assert(cl);
  207. b3Assert(cl->canSubmitCommand());
  208. struct SharedMemoryCommand* command = cl->getAvailableSharedMemoryCommand();
  209. b3Assert(command);
  210. command->m_type = CMD_SEND_DESIRED_STATE;
  211. command->m_sendDesiredStateCommandArgument.m_controlMode = controlMode;
  212. command->m_sendDesiredStateCommandArgument.m_bodyUniqueId = bodyUniqueId;
  213. command->m_updateFlags = 0;
  214. for (int i=0;i<MAX_DEGREE_OF_FREEDOM;i++)
  215. {
  216. command->m_sendDesiredStateCommandArgument.m_hasDesiredStateFlags[i] = 0;
  217. }
  218. return (b3SharedMemoryCommandHandle) command;
  219. }
  220. int b3JointControlSetDesiredPosition(b3SharedMemoryCommandHandle commandHandle, int qIndex, double value)
  221. {
  222. struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
  223. b3Assert(command);
  224. command->m_sendDesiredStateCommandArgument.m_desiredStateQ[qIndex] = value;
  225. command->m_updateFlags |= SIM_DESIRED_STATE_HAS_Q;
  226. command->m_sendDesiredStateCommandArgument.m_hasDesiredStateFlags[qIndex] |= SIM_DESIRED_STATE_HAS_Q;
  227. return 0;
  228. }
  229. int b3JointControlSetKp(b3SharedMemoryCommandHandle commandHandle, int dofIndex, double value)
  230. {
  231. struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
  232. b3Assert(command);
  233. command->m_sendDesiredStateCommandArgument.m_Kp[dofIndex] = value;
  234. command->m_updateFlags |= SIM_DESIRED_STATE_HAS_KP;
  235. command->m_sendDesiredStateCommandArgument.m_hasDesiredStateFlags[dofIndex] |= SIM_DESIRED_STATE_HAS_KP;
  236. return 0;
  237. }
  238. int b3JointControlSetKd(b3SharedMemoryCommandHandle commandHandle, int dofIndex, double value)
  239. {
  240. struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
  241. b3Assert(command);
  242. command->m_sendDesiredStateCommandArgument.m_Kd[dofIndex] = value;
  243. command->m_updateFlags |= SIM_DESIRED_STATE_HAS_KD;
  244. command->m_sendDesiredStateCommandArgument.m_hasDesiredStateFlags[dofIndex] |= SIM_DESIRED_STATE_HAS_KD;
  245. return 0;
  246. }
  247. int b3JointControlSetDesiredVelocity(b3SharedMemoryCommandHandle commandHandle, int dofIndex, double value)
  248. {
  249. struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
  250. b3Assert(command);
  251. command->m_sendDesiredStateCommandArgument.m_desiredStateQdot[dofIndex] = value;
  252. command->m_updateFlags |= SIM_DESIRED_STATE_HAS_QDOT;
  253. command->m_sendDesiredStateCommandArgument.m_hasDesiredStateFlags[dofIndex] |= SIM_DESIRED_STATE_HAS_QDOT;
  254. return 0;
  255. }
  256. int b3JointControlSetMaximumForce(b3SharedMemoryCommandHandle commandHandle, int dofIndex, double value)
  257. {
  258. struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
  259. b3Assert(command);
  260. command->m_sendDesiredStateCommandArgument.m_desiredStateForceTorque[dofIndex] = value;
  261. command->m_updateFlags |= SIM_DESIRED_STATE_HAS_MAX_FORCE;
  262. command->m_sendDesiredStateCommandArgument.m_hasDesiredStateFlags[dofIndex] |= SIM_DESIRED_STATE_HAS_MAX_FORCE;
  263. return 0;
  264. }
  265. int b3JointControlSetDesiredForceTorque(b3SharedMemoryCommandHandle commandHandle, int dofIndex, double value)
  266. {
  267. struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
  268. b3Assert(command);
  269. command->m_sendDesiredStateCommandArgument.m_desiredStateForceTorque[dofIndex] = value;
  270. command->m_updateFlags |= SIM_DESIRED_STATE_HAS_MAX_FORCE;
  271. command->m_sendDesiredStateCommandArgument.m_hasDesiredStateFlags[dofIndex] |= SIM_DESIRED_STATE_HAS_MAX_FORCE;
  272. return 0;
  273. }
  274. b3SharedMemoryCommandHandle b3RequestActualStateCommandInit(b3PhysicsClientHandle physClient, int bodyUniqueId)
  275. {
  276. PhysicsClient* cl = (PhysicsClient* ) physClient;
  277. b3Assert(cl);
  278. b3Assert(cl->canSubmitCommand());
  279. struct SharedMemoryCommand* command = cl->getAvailableSharedMemoryCommand();
  280. b3Assert(command);
  281. command->m_type =CMD_REQUEST_ACTUAL_STATE;
  282. command->m_requestActualStateInformationCommandArgument.m_bodyUniqueId = bodyUniqueId;
  283. return (b3SharedMemoryCommandHandle) command;
  284. }
  285. void b3GetJointState(b3PhysicsClientHandle physClient, b3SharedMemoryStatusHandle statusHandle, int jointIndex, b3JointSensorState *state)
  286. {
  287. const SharedMemoryStatus* status = (const SharedMemoryStatus* ) statusHandle;
  288. b3Assert(status);
  289. int bodyIndex = status->m_sendActualStateArgs.m_bodyUniqueId;
  290. b3Assert(bodyIndex>=0);
  291. if (bodyIndex>=0)
  292. {
  293. b3JointInfo info;
  294. b3GetJointInfo(physClient, bodyIndex,jointIndex, &info);
  295. state->m_jointPosition = status->m_sendActualStateArgs.m_actualStateQ[info.m_qIndex];
  296. state->m_jointVelocity = status->m_sendActualStateArgs.m_actualStateQdot[info.m_uIndex];
  297. for (int ii(0); ii < 6; ++ii) {
  298. state->m_jointForceTorque[ii] = status->m_sendActualStateArgs.m_jointReactionForces[6 * jointIndex + ii];
  299. }
  300. state->m_jointMotorTorque = status->m_sendActualStateArgs.m_jointMotorForce[jointIndex];
  301. }
  302. }
  303. void b3GetLinkState(b3PhysicsClientHandle physClient, b3SharedMemoryStatusHandle statusHandle, int linkIndex, b3LinkState *state)
  304. {
  305. const SharedMemoryStatus* status = (const SharedMemoryStatus* ) statusHandle;
  306. b3Assert(status);
  307. int bodyIndex = status->m_sendActualStateArgs.m_bodyUniqueId;
  308. b3Assert(bodyIndex>=0);
  309. if (bodyIndex>=0)
  310. {
  311. for (int i = 0; i < 3; ++i)
  312. {
  313. state->m_worldPosition[i] = status->m_sendActualStateArgs.m_linkState[7 * linkIndex + i];
  314. state->m_localInertialPosition[i] = status->m_sendActualStateArgs.m_linkLocalInertialFrames[7 * linkIndex + i];
  315. }
  316. for (int i = 0; i < 4; ++i)
  317. {
  318. state->m_worldOrientation[i] = status->m_sendActualStateArgs.m_linkState[7 * linkIndex + 3 + i];
  319. state->m_localInertialOrientation[i] = status->m_sendActualStateArgs.m_linkLocalInertialFrames[7 * linkIndex + 3 + i];
  320. }
  321. }
  322. }
  323. b3SharedMemoryCommandHandle b3CreateBoxShapeCommandInit(b3PhysicsClientHandle physClient)
  324. {
  325. PhysicsClient* cl = (PhysicsClient* ) physClient;
  326. b3Assert(cl);
  327. b3Assert(cl->canSubmitCommand());
  328. struct SharedMemoryCommand* command = cl->getAvailableSharedMemoryCommand();
  329. b3Assert(command);
  330. command->m_type = CMD_CREATE_BOX_COLLISION_SHAPE;
  331. command->m_updateFlags =0;
  332. return (b3SharedMemoryCommandHandle) command;
  333. }
  334. int b3CreateBoxCommandSetStartPosition(b3SharedMemoryCommandHandle commandHandle, double startPosX,double startPosY,double startPosZ)
  335. {
  336. struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
  337. b3Assert(command);
  338. b3Assert(command->m_type == CMD_CREATE_BOX_COLLISION_SHAPE);
  339. command->m_updateFlags |=BOX_SHAPE_HAS_INITIAL_POSITION;
  340. command->m_createBoxShapeArguments.m_initialPosition[0] = startPosX;
  341. command->m_createBoxShapeArguments.m_initialPosition[1] = startPosY;
  342. command->m_createBoxShapeArguments.m_initialPosition[2] = startPosZ;
  343. return 0;
  344. }
  345. int b3CreateBoxCommandSetHalfExtents(b3SharedMemoryCommandHandle commandHandle, double halfExtentsX,double halfExtentsY,double halfExtentsZ)
  346. {
  347. struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
  348. b3Assert(command);
  349. b3Assert(command->m_type == CMD_CREATE_BOX_COLLISION_SHAPE);
  350. command->m_updateFlags |=BOX_SHAPE_HAS_HALF_EXTENTS;
  351. command->m_createBoxShapeArguments.m_halfExtentsX = halfExtentsX;
  352. command->m_createBoxShapeArguments.m_halfExtentsY = halfExtentsY;
  353. command->m_createBoxShapeArguments.m_halfExtentsZ = halfExtentsZ;
  354. return 0;
  355. }
  356. int b3CreateBoxCommandSetMass(b3SharedMemoryCommandHandle commandHandle, double mass)
  357. {
  358. struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
  359. b3Assert(command);
  360. b3Assert(command->m_type == CMD_CREATE_BOX_COLLISION_SHAPE);
  361. command->m_updateFlags |=BOX_SHAPE_HAS_MASS;
  362. command->m_createBoxShapeArguments.m_mass = mass;
  363. return 0;
  364. }
  365. int b3CreateBoxCommandSetCollisionShapeType(b3SharedMemoryCommandHandle commandHandle, int collisionShapeType)
  366. {
  367. struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
  368. b3Assert(command);
  369. b3Assert(command->m_type == CMD_CREATE_BOX_COLLISION_SHAPE);
  370. command->m_updateFlags |=BOX_SHAPE_HAS_COLLISION_SHAPE_TYPE;
  371. command->m_createBoxShapeArguments.m_collisionShapeType = collisionShapeType;
  372. return 0;
  373. }
  374. int b3CreateBoxCommandSetColorRGBA(b3SharedMemoryCommandHandle commandHandle, double red,double green,double blue, double alpha)
  375. {
  376. struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
  377. b3Assert(command);
  378. b3Assert(command->m_type == CMD_CREATE_BOX_COLLISION_SHAPE);
  379. command->m_updateFlags |=BOX_SHAPE_HAS_COLOR;
  380. command->m_createBoxShapeArguments.m_colorRGBA[0] = red;
  381. command->m_createBoxShapeArguments.m_colorRGBA[1] = green;
  382. command->m_createBoxShapeArguments.m_colorRGBA[2] = blue;
  383. command->m_createBoxShapeArguments.m_colorRGBA[3] = alpha;
  384. return 0;
  385. }
  386. int b3CreateBoxCommandSetStartOrientation(b3SharedMemoryCommandHandle commandHandle, double startOrnX,double startOrnY,double startOrnZ, double startOrnW)
  387. {
  388. struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
  389. b3Assert(command);
  390. b3Assert(command->m_type == CMD_CREATE_BOX_COLLISION_SHAPE);
  391. command->m_updateFlags |=BOX_SHAPE_HAS_INITIAL_ORIENTATION;
  392. command->m_createBoxShapeArguments.m_initialOrientation[0] = startOrnX;
  393. command->m_createBoxShapeArguments.m_initialOrientation[1] = startOrnY;
  394. command->m_createBoxShapeArguments.m_initialOrientation[2] = startOrnZ;
  395. command->m_createBoxShapeArguments.m_initialOrientation[3] = startOrnW;
  396. return 0;
  397. }
  398. b3SharedMemoryCommandHandle b3CreatePoseCommandInit(b3PhysicsClientHandle physClient, int bodyIndex)
  399. {
  400. PhysicsClient* cl = (PhysicsClient* ) physClient;
  401. b3Assert(cl);
  402. b3Assert(cl->canSubmitCommand());
  403. struct SharedMemoryCommand* command = cl->getAvailableSharedMemoryCommand();
  404. b3Assert(command);
  405. command->m_type = CMD_INIT_POSE;
  406. command->m_updateFlags =0;
  407. command->m_initPoseArgs.m_bodyUniqueId = bodyIndex;
  408. //a bit slow, initialing the full range to zero...
  409. for (int i=0;i<MAX_DEGREE_OF_FREEDOM;i++)
  410. {
  411. command->m_initPoseArgs.m_hasInitialStateQ[i] = 0;
  412. }
  413. return (b3SharedMemoryCommandHandle) command;
  414. }
  415. int b3CreatePoseCommandSetBasePosition(b3SharedMemoryCommandHandle commandHandle, double startPosX,double startPosY,double startPosZ)
  416. {
  417. struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
  418. b3Assert(command);
  419. b3Assert(command->m_type == CMD_INIT_POSE);
  420. command->m_updateFlags |=INIT_POSE_HAS_INITIAL_POSITION;
  421. command->m_initPoseArgs.m_initialStateQ[0] = startPosX;
  422. command->m_initPoseArgs.m_initialStateQ[1] = startPosY;
  423. command->m_initPoseArgs.m_initialStateQ[2] = startPosZ;
  424. command->m_initPoseArgs.m_hasInitialStateQ[0] = 1;
  425. command->m_initPoseArgs.m_hasInitialStateQ[1] = 1;
  426. command->m_initPoseArgs.m_hasInitialStateQ[2] = 1;
  427. return 0;
  428. }
  429. int b3CreatePoseCommandSetBaseOrientation(b3SharedMemoryCommandHandle commandHandle, double startOrnX,double startOrnY,double startOrnZ, double startOrnW)
  430. {
  431. struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
  432. b3Assert(command);
  433. b3Assert(command->m_type == CMD_INIT_POSE);
  434. command->m_updateFlags |=INIT_POSE_HAS_INITIAL_ORIENTATION;
  435. command->m_initPoseArgs.m_initialStateQ[3] = startOrnX;
  436. command->m_initPoseArgs.m_initialStateQ[4] = startOrnY;
  437. command->m_initPoseArgs.m_initialStateQ[5] = startOrnZ;
  438. command->m_initPoseArgs.m_initialStateQ[6] = startOrnW;
  439. command->m_initPoseArgs.m_hasInitialStateQ[3] = 1;
  440. command->m_initPoseArgs.m_hasInitialStateQ[4] = 1;
  441. command->m_initPoseArgs.m_hasInitialStateQ[5] = 1;
  442. command->m_initPoseArgs.m_hasInitialStateQ[6] = 1;
  443. return 0;
  444. }
  445. int b3CreatePoseCommandSetJointPositions(b3SharedMemoryCommandHandle commandHandle, int numJointPositions, const double* jointPositions)
  446. {
  447. struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
  448. b3Assert(command);
  449. b3Assert(command->m_type == CMD_INIT_POSE);
  450. command->m_updateFlags |=INIT_POSE_HAS_JOINT_STATE;
  451. for (int i=0;i<numJointPositions;i++)
  452. {
  453. command->m_initPoseArgs.m_initialStateQ[i+7] = jointPositions[i];
  454. command->m_initPoseArgs.m_hasInitialStateQ[i+7] = 1;
  455. }
  456. return 0;
  457. }
  458. int b3CreatePoseCommandSetJointPosition(b3PhysicsClientHandle physClient, b3SharedMemoryCommandHandle commandHandle, int jointIndex, double jointPosition)
  459. {
  460. struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
  461. b3Assert(command);
  462. b3Assert(command->m_type == CMD_INIT_POSE);
  463. command->m_updateFlags |=INIT_POSE_HAS_JOINT_STATE;
  464. b3JointInfo info;
  465. b3GetJointInfo(physClient, command->m_initPoseArgs.m_bodyUniqueId,jointIndex, &info);
  466. btAssert((info.m_flags & JOINT_HAS_MOTORIZED_POWER) && info.m_qIndex >=0);
  467. if ((info.m_flags & JOINT_HAS_MOTORIZED_POWER) && info.m_qIndex >=0)
  468. {
  469. command->m_initPoseArgs.m_initialStateQ[info.m_qIndex] = jointPosition;
  470. command->m_initPoseArgs.m_hasInitialStateQ[info.m_qIndex] = 1;
  471. }
  472. return 0;
  473. }
  474. b3SharedMemoryCommandHandle b3CreateSensorCommandInit(b3PhysicsClientHandle physClient, int bodyUniqueId)
  475. {
  476. PhysicsClient* cl = (PhysicsClient* ) physClient;
  477. b3Assert(cl);
  478. b3Assert(cl->canSubmitCommand());
  479. struct SharedMemoryCommand* command = cl->getAvailableSharedMemoryCommand();
  480. b3Assert(command);
  481. command->m_type = CMD_CREATE_SENSOR;
  482. command->m_updateFlags = 0;
  483. command->m_createSensorArguments.m_numJointSensorChanges = 0;
  484. command->m_createSensorArguments.m_bodyUniqueId = bodyUniqueId;
  485. return (b3SharedMemoryCommandHandle) command;
  486. }
  487. int b3CreateSensorEnable6DofJointForceTorqueSensor(b3SharedMemoryCommandHandle commandHandle, int jointIndex, int enable)
  488. {
  489. struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
  490. b3Assert(command);
  491. b3Assert(command->m_type == CMD_CREATE_SENSOR);
  492. int curIndex = command->m_createSensorArguments.m_numJointSensorChanges;
  493. command->m_createSensorArguments.m_sensorType[curIndex] = SENSOR_FORCE_TORQUE;
  494. command->m_createSensorArguments.m_jointIndex[curIndex] = jointIndex;
  495. command->m_createSensorArguments.m_enableJointForceSensor[curIndex] = enable;
  496. command->m_createSensorArguments.m_numJointSensorChanges++;
  497. return 0;
  498. }
  499. int b3CreateSensorEnableIMUForLink(b3SharedMemoryCommandHandle commandHandle, int linkIndex, int enable)
  500. {
  501. struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
  502. b3Assert(command);
  503. b3Assert(command->m_type == CMD_CREATE_SENSOR);
  504. int curIndex = command->m_createSensorArguments.m_numJointSensorChanges;
  505. command->m_createSensorArguments.m_sensorType[curIndex] = SENSOR_IMU;
  506. command->m_createSensorArguments.m_linkIndex[curIndex] = linkIndex;
  507. command->m_createSensorArguments.m_enableSensor[curIndex] = enable;
  508. command->m_createSensorArguments.m_numJointSensorChanges++;
  509. return 0;
  510. }
  511. b3PhysicsClientHandle b3ConnectSharedMemory(int key)
  512. {
  513. PhysicsClientSharedMemory* cl = new PhysicsClientSharedMemory();
  514. ///client should never create shared memory, only the server does
  515. cl->setSharedMemoryKey(key);
  516. cl->connect();
  517. return (b3PhysicsClientHandle ) cl;
  518. }
  519. void b3DisconnectSharedMemory(b3PhysicsClientHandle physClient)
  520. {
  521. PhysicsClient* cl = (PhysicsClient* ) physClient;
  522. delete cl;
  523. }
  524. b3SharedMemoryStatusHandle b3ProcessServerStatus(b3PhysicsClientHandle physClient)
  525. {
  526. PhysicsClient* cl = (PhysicsClient* ) physClient;
  527. if (cl && cl->isConnected())
  528. {
  529. const SharedMemoryStatus* stat = cl->processServerStatus();
  530. return (b3SharedMemoryStatusHandle) stat;
  531. }
  532. return 0;
  533. }
  534. int b3GetStatusType(b3SharedMemoryStatusHandle statusHandle)
  535. {
  536. const SharedMemoryStatus* status = (const SharedMemoryStatus* ) statusHandle;
  537. b3Assert(status);
  538. if (status)
  539. {
  540. return status->m_type;
  541. }
  542. return CMD_INVALID_STATUS;
  543. }
  544. int b3GetStatusBodyIndices(b3SharedMemoryStatusHandle statusHandle, int* bodyIndicesOut, int bodyIndicesCapacity)
  545. {
  546. int numBodies = 0;
  547. const SharedMemoryStatus* status = (const SharedMemoryStatus* ) statusHandle;
  548. b3Assert(status);
  549. if (status)
  550. {
  551. switch (status->m_type)
  552. {
  553. case CMD_SDF_LOADING_COMPLETED:
  554. {
  555. int i,maxBodies;
  556. numBodies = status->m_sdfLoadedArgs.m_numBodies;
  557. maxBodies = btMin(bodyIndicesCapacity, numBodies);
  558. for (i=0;i<maxBodies;i++)
  559. {
  560. bodyIndicesOut[i] = status->m_sdfLoadedArgs.m_bodyUniqueIds[i];
  561. }
  562. break;
  563. }
  564. }
  565. }
  566. return numBodies;
  567. }
  568. int b3GetStatusBodyIndex(b3SharedMemoryStatusHandle statusHandle)
  569. {
  570. const SharedMemoryStatus* status = (const SharedMemoryStatus* ) statusHandle;
  571. b3Assert(status);
  572. int bodyId = -1;
  573. if (status)
  574. {
  575. switch (status->m_type)
  576. {
  577. case CMD_URDF_LOADING_COMPLETED:
  578. {
  579. bodyId = status->m_dataStreamArguments.m_bodyUniqueId;
  580. break;
  581. }
  582. case CMD_RIGID_BODY_CREATION_COMPLETED:
  583. {
  584. bodyId = status->m_rigidBodyCreateArgs.m_bodyUniqueId;
  585. break;
  586. }
  587. default:
  588. {
  589. b3Assert(0);
  590. }
  591. };
  592. }
  593. return bodyId;
  594. }
  595. int b3GetStatusActualState(b3SharedMemoryStatusHandle statusHandle,
  596. int* bodyUniqueId,
  597. int* numDegreeOfFreedomQ,
  598. int* numDegreeOfFreedomU,
  599. const double* rootLocalInertialFrame[],
  600. const double* actualStateQ[],
  601. const double* actualStateQdot[],
  602. const double* jointReactionForces[]) {
  603. const SharedMemoryStatus* status = (const SharedMemoryStatus* ) statusHandle;
  604. const SendActualStateArgs &args = status->m_sendActualStateArgs;
  605. btAssert(status->m_type == CMD_ACTUAL_STATE_UPDATE_COMPLETED);
  606. if (status->m_type != CMD_ACTUAL_STATE_UPDATE_COMPLETED)
  607. return false;
  608. if (bodyUniqueId) {
  609. *bodyUniqueId = args.m_bodyUniqueId;
  610. }
  611. if (numDegreeOfFreedomQ) {
  612. *numDegreeOfFreedomQ = args.m_numDegreeOfFreedomQ;
  613. }
  614. if (numDegreeOfFreedomU) {
  615. *numDegreeOfFreedomU = args.m_numDegreeOfFreedomU;
  616. }
  617. if (rootLocalInertialFrame) {
  618. *rootLocalInertialFrame = args.m_rootLocalInertialFrame;
  619. }
  620. if (actualStateQ) {
  621. *actualStateQ = args.m_actualStateQ;
  622. }
  623. if (actualStateQdot) {
  624. *actualStateQdot = args.m_actualStateQdot;
  625. }
  626. if (jointReactionForces) {
  627. *jointReactionForces = args.m_jointReactionForces;
  628. }
  629. return true;
  630. }
  631. int b3CanSubmitCommand(b3PhysicsClientHandle physClient)
  632. {
  633. PhysicsClient* cl = (PhysicsClient* ) physClient;
  634. if (cl)
  635. {
  636. return (int)cl->canSubmitCommand();
  637. }
  638. return false;
  639. }
  640. int b3SubmitClientCommand(b3PhysicsClientHandle physClient, const b3SharedMemoryCommandHandle commandHandle)
  641. {
  642. struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
  643. PhysicsClient* cl = (PhysicsClient* ) physClient;
  644. return (int)cl->submitClientCommand(*command);
  645. }
  646. b3SharedMemoryStatusHandle b3SubmitClientCommandAndWaitStatus(b3PhysicsClientHandle physClient, const b3SharedMemoryCommandHandle commandHandle)
  647. {
  648. int timeout = 1024*1024*1024;
  649. b3SharedMemoryStatusHandle statusHandle=0;
  650. b3SubmitClientCommand(physClient,commandHandle);
  651. while ((statusHandle==0) && (timeout-- > 0))
  652. {
  653. statusHandle =b3ProcessServerStatus(physClient);
  654. }
  655. return (b3SharedMemoryStatusHandle) statusHandle;
  656. }
  657. ///return the total number of bodies in the simulation
  658. int b3GetNumBodies(b3PhysicsClientHandle physClient)
  659. {
  660. PhysicsClient* cl = (PhysicsClient* ) physClient;
  661. return cl->getNumBodies();
  662. }
  663. /// return the body unique id, given the index in range [0 , b3GetNumBodies() )
  664. int b3GetBodyUniqueId(b3PhysicsClientHandle physClient, int serialIndex)
  665. {
  666. PhysicsClient* cl = (PhysicsClient* ) physClient;
  667. return cl->getBodyUniqueId(serialIndex);
  668. }
  669. ///given a body unique id, return the body information. See b3BodyInfo in SharedMemoryPublic.h
  670. int b3GetBodyInfo(b3PhysicsClientHandle physClient, int bodyUniqueId, struct b3BodyInfo* info)
  671. {
  672. PhysicsClient* cl = (PhysicsClient* ) physClient;
  673. return cl->getBodyInfo(bodyUniqueId,*info);
  674. }
  675. int b3GetNumJoints(b3PhysicsClientHandle physClient, int bodyId)
  676. {
  677. PhysicsClient* cl = (PhysicsClient* ) physClient;
  678. return cl->getNumJoints(bodyId);
  679. }
  680. int b3GetJointInfo(b3PhysicsClientHandle physClient, int bodyIndex, int jointIndex, struct b3JointInfo* info)
  681. {
  682. PhysicsClient* cl = (PhysicsClient* ) physClient;
  683. return cl->getJointInfo(bodyIndex, jointIndex, *info);
  684. }
  685. b3SharedMemoryCommandHandle b3CreateJoint(b3PhysicsClientHandle physClient, int parentBodyIndex, int parentJointIndex, int childBodyIndex, int childJointIndex, struct b3JointInfo* info)
  686. {
  687. PhysicsClient* cl = (PhysicsClient* ) physClient;
  688. b3Assert(cl);
  689. b3Assert(cl->canSubmitCommand());
  690. struct SharedMemoryCommand* command = cl->getAvailableSharedMemoryCommand();
  691. b3Assert(command);
  692. command->m_type = CMD_CREATE_JOINT;
  693. command->m_createJointArguments.m_parentBodyIndex = parentBodyIndex;
  694. command->m_createJointArguments.m_parentJointIndex = parentJointIndex;
  695. command->m_createJointArguments.m_childBodyIndex = childBodyIndex;
  696. command->m_createJointArguments.m_childJointIndex = childJointIndex;
  697. for (int i = 0; i < 7; ++i) {
  698. command->m_createJointArguments.m_parentFrame[i] = info->m_parentFrame[i];
  699. command->m_createJointArguments.m_childFrame[i] = info->m_childFrame[i];
  700. }
  701. for (int i = 0; i < 3; ++i) {
  702. command->m_createJointArguments.m_jointAxis[i] = info->m_jointAxis[i];
  703. }
  704. command->m_createJointArguments.m_jointType = info->m_jointType;
  705. return (b3SharedMemoryCommandHandle)command;
  706. }
  707. b3SharedMemoryCommandHandle b3PickBody(b3PhysicsClientHandle physClient, double rayFromWorldX,
  708. double rayFromWorldY, double rayFromWorldZ,
  709. double rayToWorldX, double rayToWorldY, double rayToWorldZ)
  710. {
  711. PhysicsClient *cl = (PhysicsClient *)physClient;
  712. b3Assert(cl);
  713. b3Assert(cl->canSubmitCommand());
  714. struct SharedMemoryCommand *command = cl->getAvailableSharedMemoryCommand();
  715. b3Assert(command);
  716. command->m_type = CMD_PICK_BODY;
  717. command->m_pickBodyArguments.m_rayFromWorld[0] = rayFromWorldX;
  718. command->m_pickBodyArguments.m_rayFromWorld[1] = rayFromWorldY;
  719. command->m_pickBodyArguments.m_rayFromWorld[2] = rayFromWorldZ;
  720. command->m_pickBodyArguments.m_rayToWorld[0] = rayToWorldX;
  721. command->m_pickBodyArguments.m_rayToWorld[1] = rayToWorldY;
  722. command->m_pickBodyArguments.m_rayToWorld[2] = rayToWorldZ;
  723. return (b3SharedMemoryCommandHandle)command;
  724. }
  725. b3SharedMemoryCommandHandle b3MovePickedBody(b3PhysicsClientHandle physClient, double rayFromWorldX,
  726. double rayFromWorldY, double rayFromWorldZ,
  727. double rayToWorldX, double rayToWorldY,
  728. double rayToWorldZ)
  729. {
  730. PhysicsClient *cl = (PhysicsClient *)physClient;
  731. b3Assert(cl);
  732. b3Assert(cl->canSubmitCommand());
  733. struct SharedMemoryCommand *command = cl->getAvailableSharedMemoryCommand();
  734. b3Assert(command);
  735. command->m_type = CMD_MOVE_PICKED_BODY;
  736. command->m_pickBodyArguments.m_rayFromWorld[0] = rayFromWorldX;
  737. command->m_pickBodyArguments.m_rayFromWorld[1] = rayFromWorldY;
  738. command->m_pickBodyArguments.m_rayFromWorld[2] = rayFromWorldZ;
  739. command->m_pickBodyArguments.m_rayToWorld[0] = rayToWorldX;
  740. command->m_pickBodyArguments.m_rayToWorld[1] = rayToWorldY;
  741. command->m_pickBodyArguments.m_rayToWorld[2] = rayToWorldZ;
  742. return (b3SharedMemoryCommandHandle)command;
  743. }
  744. b3SharedMemoryCommandHandle b3RemovePickingConstraint(b3PhysicsClientHandle physClient)
  745. {
  746. PhysicsClient *cl = (PhysicsClient *)physClient;
  747. b3Assert(cl);
  748. b3Assert(cl->canSubmitCommand());
  749. struct SharedMemoryCommand *command = cl->getAvailableSharedMemoryCommand();
  750. b3Assert(command);
  751. command->m_type = CMD_REMOVE_PICKING_CONSTRAINT_BODY;
  752. return (b3SharedMemoryCommandHandle)command;
  753. }
  754. b3SharedMemoryCommandHandle b3InitRequestDebugLinesCommand(b3PhysicsClientHandle physClient, int debugMode)
  755. {
  756. PhysicsClient* cl = (PhysicsClient* ) physClient;
  757. b3Assert(cl);
  758. b3Assert(cl->canSubmitCommand());
  759. struct SharedMemoryCommand* command = cl->getAvailableSharedMemoryCommand();
  760. b3Assert(command);
  761. command->m_type =CMD_REQUEST_DEBUG_LINES;
  762. command->m_requestDebugLinesArguments.m_debugMode = debugMode;
  763. command->m_requestDebugLinesArguments.m_startingLineIndex = 0;
  764. return (b3SharedMemoryCommandHandle) command;
  765. }
  766. void b3GetDebugLines(b3PhysicsClientHandle physClient, struct b3DebugLines* lines)
  767. {
  768. PhysicsClient* cl = (PhysicsClient* ) physClient;
  769. b3Assert(lines);
  770. if (lines)
  771. {
  772. lines->m_numDebugLines = cl->getNumDebugLines();
  773. lines->m_linesFrom = cl->getDebugLinesFrom();
  774. lines->m_linesTo = cl->getDebugLinesTo();
  775. lines->m_linesColor = cl->getDebugLinesColor();
  776. }
  777. }
  778. ///request an image from a simulated camera, using a software renderer.
  779. b3SharedMemoryCommandHandle b3InitRequestCameraImage(b3PhysicsClientHandle physClient)
  780. {
  781. PhysicsClient* cl = (PhysicsClient* ) physClient;
  782. b3Assert(cl);
  783. b3Assert(cl->canSubmitCommand());
  784. struct SharedMemoryCommand* command = cl->getAvailableSharedMemoryCommand();
  785. b3Assert(command);
  786. command->m_type =CMD_REQUEST_CAMERA_IMAGE_DATA;
  787. command->m_requestPixelDataArguments.m_startPixelIndex = 0;
  788. command->m_updateFlags = 0;//REQUEST_PIXEL_ARGS_USE_HARDWARE_OPENGL;
  789. return (b3SharedMemoryCommandHandle) command;
  790. }
  791. void b3RequestCameraImageSelectRenderer(b3SharedMemoryCommandHandle commandHandle, int renderer)
  792. {
  793. struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
  794. b3Assert(command);
  795. b3Assert(command->m_type == CMD_REQUEST_CAMERA_IMAGE_DATA);
  796. b3Assert(renderer>(1<<15));
  797. command->m_updateFlags |= renderer;
  798. }
  799. void b3RequestCameraImageSetCameraMatrices(b3SharedMemoryCommandHandle commandHandle, float viewMatrix[16], float projectionMatrix[16])
  800. {
  801. struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
  802. b3Assert(command);
  803. b3Assert(command->m_type == CMD_REQUEST_CAMERA_IMAGE_DATA);
  804. for (int i=0;i<16;i++)
  805. {
  806. command->m_requestPixelDataArguments.m_projectionMatrix[i] = projectionMatrix[i];
  807. command->m_requestPixelDataArguments.m_viewMatrix[i] = viewMatrix[i];
  808. }
  809. command->m_updateFlags |= REQUEST_PIXEL_ARGS_HAS_CAMERA_MATRICES;
  810. }
  811. void b3RequestCameraImageSetViewMatrix2(b3SharedMemoryCommandHandle commandHandle, const float cameraTargetPosition[3], float distance, float yaw, float pitch, float roll, int upAxis)
  812. {
  813. struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
  814. b3Assert(command);
  815. b3Assert(command->m_type == CMD_REQUEST_CAMERA_IMAGE_DATA);
  816. b3Vector3 camUpVector;
  817. b3Vector3 camForward;
  818. b3Vector3 camPos;
  819. b3Vector3 camTargetPos = b3MakeVector3(cameraTargetPosition[0],cameraTargetPosition[1],cameraTargetPosition[2]);
  820. b3Vector3 eyePos = b3MakeVector3(0,0,0);
  821. int forwardAxis(-1);
  822. {
  823. switch (upAxis)
  824. {
  825. case 1:
  826. {
  827. forwardAxis = 0;
  828. eyePos[forwardAxis] = -distance;
  829. camForward = b3MakeVector3(eyePos[0],eyePos[1],eyePos[2]);
  830. if (camForward.length2() < B3_EPSILON)
  831. {
  832. camForward.setValue(1.f,0.f,0.f);
  833. } else
  834. {
  835. camForward.normalize();
  836. }
  837. b3Scalar rollRad = roll * b3Scalar(0.01745329251994329547);
  838. b3Quaternion rollRot(camForward,rollRad);
  839. camUpVector = b3QuatRotate(rollRot,b3MakeVector3(0,1,0));
  840. //gLightPos = b3MakeVector3(-50.f,100,30);
  841. break;
  842. }
  843. case 2:
  844. {
  845. forwardAxis = 1;
  846. eyePos[forwardAxis] = -distance;
  847. camForward = b3MakeVector3(eyePos[0],eyePos[1],eyePos[2]);
  848. if (camForward.length2() < B3_EPSILON)
  849. {
  850. camForward.setValue(1.f,0.f,0.f);
  851. } else
  852. {
  853. camForward.normalize();
  854. }
  855. b3Scalar rollRad = roll * b3Scalar(0.01745329251994329547);
  856. b3Quaternion rollRot(camForward,rollRad);
  857. camUpVector = b3QuatRotate(rollRot,b3MakeVector3(0,0,1));
  858. //gLightPos = b3MakeVector3(-50.f,30,100);
  859. break;
  860. }
  861. default:
  862. {
  863. //b3Assert(0);
  864. return;
  865. }
  866. };
  867. }
  868. b3Scalar yawRad = yaw * b3Scalar(0.01745329251994329547);// rads per deg
  869. b3Scalar pitchRad = pitch * b3Scalar(0.01745329251994329547);// rads per deg
  870. b3Quaternion pitchRot(camUpVector,pitchRad);
  871. b3Vector3 right = camUpVector.cross(camForward);
  872. b3Quaternion yawRot(right,-yawRad);
  873. eyePos = b3Matrix3x3(pitchRot) * b3Matrix3x3(yawRot) * eyePos;
  874. camPos = eyePos;
  875. camPos += camTargetPos;
  876. float camPosf[4] = {camPos[0],camPos[1],camPos[2],0};
  877. float camPosTargetf[4] = {camTargetPos[0],camTargetPos[1],camTargetPos[2],0};
  878. float camUpf[4] = {camUpVector[0],camUpVector[1],camUpVector[2],0};
  879. b3RequestCameraImageSetViewMatrix(commandHandle,camPosf,camPosTargetf,camUpf);
  880. }
  881. void b3RequestCameraImageSetViewMatrix(b3SharedMemoryCommandHandle commandHandle, const float cameraPosition[3], const float cameraTargetPosition[3], const float cameraUp[3])
  882. {
  883. b3Vector3 eye = b3MakeVector3(cameraPosition[0], cameraPosition[1], cameraPosition[2]);
  884. b3Vector3 center = b3MakeVector3(cameraTargetPosition[0], cameraTargetPosition[1], cameraTargetPosition[2]);
  885. b3Vector3 up = b3MakeVector3(cameraUp[0], cameraUp[1], cameraUp[2]);
  886. b3Vector3 f = (center - eye).normalized();
  887. b3Vector3 u = up.normalized();
  888. b3Vector3 s = (f.cross(u)).normalized();
  889. u = s.cross(f);
  890. float viewMatrix[16];
  891. viewMatrix[0*4+0] = s.x;
  892. viewMatrix[1*4+0] = s.y;
  893. viewMatrix[2*4+0] = s.z;
  894. viewMatrix[0*4+1] = u.x;
  895. viewMatrix[1*4+1] = u.y;
  896. viewMatrix[2*4+1] = u.z;
  897. viewMatrix[0*4+2] =-f.x;
  898. viewMatrix[1*4+2] =-f.y;
  899. viewMatrix[2*4+2] =-f.z;
  900. viewMatrix[0*4+3] = 0.f;
  901. viewMatrix[1*4+3] = 0.f;
  902. viewMatrix[2*4+3] = 0.f;
  903. viewMatrix[3*4+0] = -s.dot(eye);
  904. viewMatrix[3*4+1] = -u.dot(eye);
  905. viewMatrix[3*4+2] = f.dot(eye);
  906. viewMatrix[3*4+3] = 1.f;
  907. struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
  908. b3Assert(command);
  909. b3Assert(command->m_type == CMD_REQUEST_CAMERA_IMAGE_DATA);
  910. for (int i=0;i<16;i++)
  911. {
  912. command->m_requestPixelDataArguments.m_viewMatrix[i] = viewMatrix[i];
  913. }
  914. command->m_updateFlags |= REQUEST_PIXEL_ARGS_HAS_CAMERA_MATRICES;
  915. }
  916. void b3RequestCameraImageSetProjectionMatrix(b3SharedMemoryCommandHandle commandHandle, float left, float right, float bottom, float top, float nearVal, float farVal)
  917. {
  918. float frustum[16];
  919. frustum[0*4+0] = (float(2) * nearVal) / (right - left);
  920. frustum[0*4+1] = float(0);
  921. frustum[0*4+2] = float(0);
  922. frustum[0*4+3] = float(0);
  923. frustum[1*4+0] = float(0);
  924. frustum[1*4+1] = (float(2) * nearVal) / (top - bottom);
  925. frustum[1*4+2] = float(0);
  926. frustum[1*4+3] = float(0);
  927. frustum[2*4+0] = (right + left) / (right - left);
  928. frustum[2*4+1] = (top + bottom) / (top - bottom);
  929. frustum[2*4+2] = -(farVal + nearVal) / (farVal - nearVal);
  930. frustum[2*4+3] = float(-1);
  931. frustum[3*4+0] = float(0);
  932. frustum[3*4+1] = float(0);
  933. frustum[3*4+2] = -(float(2) * farVal * nearVal) / (farVal - nearVal);
  934. frustum[3*4+3] = float(0);
  935. struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
  936. b3Assert(command);
  937. b3Assert(command->m_type == CMD_REQUEST_CAMERA_IMAGE_DATA);
  938. for (int i=0;i<16;i++)
  939. {
  940. command->m_requestPixelDataArguments.m_projectionMatrix[i] = frustum[i];
  941. }
  942. command->m_updateFlags |= REQUEST_PIXEL_ARGS_HAS_CAMERA_MATRICES;
  943. }
  944. void b3RequestCameraImageSetFOVProjectionMatrix(b3SharedMemoryCommandHandle commandHandle, float fov, float aspect, float nearVal, float farVal)
  945. {
  946. float yScale = 1.0 / tan((3.141592538 / 180.0) * fov / 2);
  947. float xScale = yScale / aspect;
  948. float frustum[16];
  949. frustum[0*4+0] = xScale;
  950. frustum[0*4+1] = float(0);
  951. frustum[0*4+2] = float(0);
  952. frustum[0*4+3] = float(0);
  953. frustum[1*4+0] = float(0);
  954. frustum[1*4+1] = yScale;
  955. frustum[1*4+2] = float(0);
  956. frustum[1*4+3] = float(0);
  957. frustum[2*4+0] = 0;
  958. frustum[2*4+1] = 0;
  959. frustum[2*4+2] = (nearVal + farVal) / (nearVal - farVal);
  960. frustum[2*4+3] = float(-1);
  961. frustum[3*4+0] = float(0);
  962. frustum[3*4+1] = float(0);
  963. frustum[3*4+2] = (float(2) * farVal * nearVal) / (nearVal - farVal);
  964. frustum[3*4+3] = float(0);
  965. struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
  966. b3Assert(command);
  967. b3Assert(command->m_type == CMD_REQUEST_CAMERA_IMAGE_DATA);
  968. for (int i=0;i<16;i++)
  969. {
  970. command->m_requestPixelDataArguments.m_projectionMatrix[i] = frustum[i];
  971. }
  972. command->m_updateFlags |= REQUEST_PIXEL_ARGS_HAS_CAMERA_MATRICES;
  973. }
  974. void b3RequestCameraImageSetPixelResolution(b3SharedMemoryCommandHandle commandHandle, int width, int height )
  975. {
  976. struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
  977. b3Assert(command);
  978. b3Assert(command->m_type == CMD_REQUEST_CAMERA_IMAGE_DATA);
  979. command->m_requestPixelDataArguments.m_pixelWidth = width;
  980. command->m_requestPixelDataArguments.m_pixelHeight = height;
  981. command->m_updateFlags |= REQUEST_PIXEL_ARGS_SET_PIXEL_WIDTH_HEIGHT;
  982. }
  983. void b3GetCameraImageData(b3PhysicsClientHandle physClient, struct b3CameraImageData* imageData)
  984. {
  985. PhysicsClient* cl = (PhysicsClient* ) physClient;
  986. if (cl)
  987. {
  988. cl->getCachedCameraImage(imageData);
  989. }
  990. }
  991. ///request an contact point information
  992. b3SharedMemoryCommandHandle b3InitRequestContactPointInformation(b3PhysicsClientHandle physClient)
  993. {
  994. PhysicsClient* cl = (PhysicsClient* ) physClient;
  995. b3Assert(cl);
  996. b3Assert(cl->canSubmitCommand());
  997. struct SharedMemoryCommand* command = cl->getAvailableSharedMemoryCommand();
  998. b3Assert(command);
  999. command->m_type =CMD_REQUEST_CONTACT_POINT_INFORMATION;
  1000. command->m_requestContactPointArguments.m_startingContactPointIndex = 0;
  1001. command->m_requestContactPointArguments.m_objectAIndexFilter = -1;
  1002. command->m_requestContactPointArguments.m_objectBIndexFilter = -1;
  1003. command->m_updateFlags = 0;
  1004. return (b3SharedMemoryCommandHandle) command;
  1005. }
  1006. void b3SetContactFilterBodyA(b3SharedMemoryCommandHandle commandHandle, int bodyUniqueIdA)
  1007. {
  1008. struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
  1009. b3Assert(command);
  1010. b3Assert(command->m_type == CMD_REQUEST_CONTACT_POINT_INFORMATION);
  1011. command->m_requestContactPointArguments.m_objectAIndexFilter = bodyUniqueIdA;
  1012. }
  1013. void b3SetContactFilterBodyB(b3SharedMemoryCommandHandle commandHandle, int bodyUniqueIdB)
  1014. {
  1015. struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
  1016. b3Assert(command);
  1017. b3Assert(command->m_type == CMD_REQUEST_CONTACT_POINT_INFORMATION);
  1018. command->m_requestContactPointArguments.m_objectBIndexFilter = bodyUniqueIdB;
  1019. }
  1020. void b3SetContactFilterBodyB(b3SharedMemoryCommandHandle commandHandle, int bodyUniqueIdB);
  1021. void b3GetContactPointInformation(b3PhysicsClientHandle physClient, struct b3ContactInformation* contactPointData)
  1022. {
  1023. PhysicsClient* cl = (PhysicsClient* ) physClient;
  1024. if (cl)
  1025. {
  1026. cl->getCachedContactPointInformation(contactPointData);
  1027. }
  1028. }
  1029. b3SharedMemoryCommandHandle b3ApplyExternalForceCommandInit(b3PhysicsClientHandle physClient)
  1030. {
  1031. PhysicsClient* cl = (PhysicsClient* ) physClient;
  1032. b3Assert(cl);
  1033. b3Assert(cl->canSubmitCommand());
  1034. struct SharedMemoryCommand* command = cl->getAvailableSharedMemoryCommand();
  1035. b3Assert(command);
  1036. command->m_type = CMD_APPLY_EXTERNAL_FORCE;
  1037. command->m_updateFlags = 0;
  1038. command->m_externalForceArguments.m_numForcesAndTorques = 0;
  1039. return (b3SharedMemoryCommandHandle) command;
  1040. }
  1041. void b3ApplyExternalForce(b3SharedMemoryCommandHandle commandHandle, int bodyUniqueId, int linkId, const double force[3], const double position[3], int flag)
  1042. {
  1043. struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
  1044. b3Assert(command);
  1045. b3Assert(command->m_type == CMD_APPLY_EXTERNAL_FORCE);
  1046. int index = command->m_externalForceArguments.m_numForcesAndTorques;
  1047. command->m_externalForceArguments.m_bodyUniqueIds[index] = bodyUniqueId;
  1048. command->m_externalForceArguments.m_linkIds[index] = linkId;
  1049. command->m_externalForceArguments.m_forceFlags[index] = EF_FORCE+flag;
  1050. for (int i = 0; i < 3; ++i) {
  1051. command->m_externalForceArguments.m_forcesAndTorques[index+i] = force[i];
  1052. command->m_externalForceArguments.m_positions[index+i] = position[i];
  1053. }
  1054. command->m_externalForceArguments.m_numForcesAndTorques++;
  1055. }
  1056. void b3ApplyExternalTorque(b3SharedMemoryCommandHandle commandHandle, int bodyUniqueId, int linkId, const double torque[3], int flag)
  1057. {
  1058. struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
  1059. b3Assert(command);
  1060. b3Assert(command->m_type == CMD_APPLY_EXTERNAL_FORCE);
  1061. int index = command->m_externalForceArguments.m_numForcesAndTorques;
  1062. command->m_externalForceArguments.m_bodyUniqueIds[index] = bodyUniqueId;
  1063. command->m_externalForceArguments.m_linkIds[index] = linkId;
  1064. command->m_externalForceArguments.m_forceFlags[index] = EF_TORQUE+flag;
  1065. for (int i = 0; i < 3; ++i) {
  1066. command->m_externalForceArguments.m_forcesAndTorques[index+i] = torque[i];
  1067. }
  1068. command->m_externalForceArguments.m_numForcesAndTorques++;
  1069. }
  1070. ///compute the forces to achieve an acceleration, given a state q and qdot using inverse dynamics
  1071. b3SharedMemoryCommandHandle b3CalculateInverseDynamicsCommandInit(b3PhysicsClientHandle physClient, int bodyIndex,
  1072. const double* jointPositionsQ, const double* jointVelocitiesQdot, const double* jointAccelerations)
  1073. {
  1074. PhysicsClient* cl = (PhysicsClient*)physClient;
  1075. b3Assert(cl);
  1076. b3Assert(cl->canSubmitCommand());
  1077. struct SharedMemoryCommand* command = cl->getAvailableSharedMemoryCommand();
  1078. b3Assert(command);
  1079. command->m_type = CMD_CALCULATE_INVERSE_DYNAMICS;
  1080. command->m_updateFlags = 0;
  1081. command->m_calculateInverseDynamicsArguments.m_bodyUniqueId = bodyIndex;
  1082. int numJoints = cl->getNumJoints(bodyIndex);
  1083. for (int i = 0; i < numJoints;i++)
  1084. {
  1085. command->m_calculateInverseDynamicsArguments.m_jointPositionsQ[i] = jointPositionsQ[i];
  1086. command->m_calculateInverseDynamicsArguments.m_jointVelocitiesQdot[i] = jointVelocitiesQdot[i];
  1087. command->m_calculateInverseDynamicsArguments.m_jointAccelerations[i] = jointAccelerations[i];
  1088. }
  1089. return (b3SharedMemoryCommandHandle)command;
  1090. }
  1091. int b3GetStatusInverseDynamicsJointForces(b3SharedMemoryStatusHandle statusHandle,
  1092. int* bodyUniqueId,
  1093. int* dofCount,
  1094. double* jointForces)
  1095. {
  1096. const SharedMemoryStatus* status = (const SharedMemoryStatus*)statusHandle;
  1097. btAssert(status->m_type == CMD_CALCULATED_INVERSE_DYNAMICS_COMPLETED);
  1098. if (status->m_type != CMD_CALCULATED_INVERSE_DYNAMICS_COMPLETED)
  1099. return false;
  1100. if (dofCount)
  1101. {
  1102. *dofCount = status->m_inverseDynamicsResultArgs.m_dofCount;
  1103. }
  1104. if (bodyUniqueId)
  1105. {
  1106. *bodyUniqueId = status->m_inverseDynamicsResultArgs.m_bodyUniqueId;
  1107. }
  1108. if (jointForces)
  1109. {
  1110. for (int i = 0; i < status->m_inverseDynamicsResultArgs.m_dofCount; i++)
  1111. {
  1112. jointForces[i] = status->m_inverseDynamicsResultArgs.m_jointForces[i];
  1113. }
  1114. }
  1115. return true;
  1116. }
  1117. b3SharedMemoryCommandHandle b3CalculateJacobianCommandInit(b3PhysicsClientHandle physClient, int bodyIndex, int linkIndex, const double* localPosition, const double* jointPositionsQ, const double* jointVelocitiesQdot, const double* jointAccelerations)
  1118. {
  1119. PhysicsClient* cl = (PhysicsClient*)physClient;
  1120. b3Assert(cl);
  1121. b3Assert(cl->canSubmitCommand());
  1122. struct SharedMemoryCommand* command = cl->getAvailableSharedMemoryCommand();
  1123. b3Assert(command);
  1124. command->m_type = CMD_CALCULATE_JACOBIAN;
  1125. command->m_updateFlags = 0;
  1126. command->m_calculateJacobianArguments.m_bodyUniqueId = bodyIndex;
  1127. command->m_calculateJacobianArguments.m_linkIndex = linkIndex;
  1128. command->m_calculateJacobianArguments.m_localPosition[0] = localPosition[0];
  1129. command->m_calculateJacobianArguments.m_localPosition[1] = localPosition[1];
  1130. command->m_calculateJacobianArguments.m_localPosition[2] = localPosition[2];
  1131. int numJoints = cl->getNumJoints(bodyIndex);
  1132. for (int i = 0; i < numJoints;i++)
  1133. {
  1134. command->m_calculateJacobianArguments.m_jointPositionsQ[i] = jointPositionsQ[i];
  1135. command->m_calculateJacobianArguments.m_jointVelocitiesQdot[i] = jointVelocitiesQdot[i];
  1136. command->m_calculateJacobianArguments.m_jointAccelerations[i] = jointAccelerations[i];
  1137. }
  1138. return (b3SharedMemoryCommandHandle)command;
  1139. }
  1140. int b3GetStatusJacobian(b3SharedMemoryStatusHandle statusHandle, double* linearJacobian, double* angularJacobian)
  1141. {
  1142. const SharedMemoryStatus* status = (const SharedMemoryStatus*)statusHandle;
  1143. btAssert(status->m_type == CMD_CALCULATED_JACOBIAN_COMPLETED);
  1144. if (status->m_type != CMD_CALCULATED_JACOBIAN_COMPLETED)
  1145. return false;
  1146. if (linearJacobian)
  1147. {
  1148. for (int i = 0; i < status->m_jacobianResultArgs.m_dofCount*3; i++)
  1149. {
  1150. linearJacobian[i] = status->m_jacobianResultArgs.m_linearJacobian[i];
  1151. }
  1152. }
  1153. if (angularJacobian)
  1154. {
  1155. for (int i = 0; i < status->m_jacobianResultArgs.m_dofCount*3; i++)
  1156. {
  1157. angularJacobian[i] = status->m_jacobianResultArgs.m_angularJacobian[i];
  1158. }
  1159. }
  1160. return true;
  1161. }
  1162. ///compute the joint positions to move the end effector to a desired target using inverse kinematics
  1163. b3SharedMemoryCommandHandle b3CalculateInverseKinematicsCommandInit(b3PhysicsClientHandle physClient, int bodyIndex)
  1164. {
  1165. PhysicsClient* cl = (PhysicsClient*)physClient;
  1166. b3Assert(cl);
  1167. b3Assert(cl->canSubmitCommand());
  1168. struct SharedMemoryCommand* command = cl->getAvailableSharedMemoryCommand();
  1169. b3Assert(command);
  1170. command->m_type = CMD_CALCULATE_INVERSE_KINEMATICS;
  1171. command->m_updateFlags = 0;
  1172. command->m_calculateInverseKinematicsArguments.m_bodyUniqueId = bodyIndex;
  1173. return (b3SharedMemoryCommandHandle)command;
  1174. }
  1175. void b3CalculateInverseKinematicsAddTargetPurePosition(b3SharedMemoryCommandHandle commandHandle, int endEffectorLinkIndex, const double targetPosition[3])
  1176. {
  1177. struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
  1178. b3Assert(command);
  1179. b3Assert(command->m_type == CMD_CALCULATE_INVERSE_KINEMATICS);
  1180. command->m_updateFlags |= IK_HAS_TARGET_POSITION;
  1181. command->m_calculateInverseKinematicsArguments.m_endEffectorLinkIndex = endEffectorLinkIndex;
  1182. command->m_calculateInverseKinematicsArguments.m_targetPosition[0] = targetPosition[0];
  1183. command->m_calculateInverseKinematicsArguments.m_targetPosition[1] = targetPosition[1];
  1184. command->m_calculateInverseKinematicsArguments.m_targetPosition[2] = targetPosition[2];
  1185. }
  1186. void b3CalculateInverseKinematicsAddTargetPositionWithOrientation(b3SharedMemoryCommandHandle commandHandle, int endEffectorLinkIndex, const double targetPosition[3], const double targetOrientation[4])
  1187. {
  1188. struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
  1189. b3Assert(command);
  1190. b3Assert(command->m_type == CMD_CALCULATE_INVERSE_KINEMATICS);
  1191. command->m_updateFlags |= IK_HAS_TARGET_POSITION+IK_HAS_TARGET_ORIENTATION;
  1192. command->m_calculateInverseKinematicsArguments.m_endEffectorLinkIndex = endEffectorLinkIndex;
  1193. command->m_calculateInverseKinematicsArguments.m_targetPosition[0] = targetPosition[0];
  1194. command->m_calculateInverseKinematicsArguments.m_targetPosition[1] = targetPosition[1];
  1195. command->m_calculateInverseKinematicsArguments.m_targetPosition[2] = targetPosition[2];
  1196. command->m_calculateInverseKinematicsArguments.m_targetOrientation[0] = targetOrientation[0];
  1197. command->m_calculateInverseKinematicsArguments.m_targetOrientation[1] = targetOrientation[1];
  1198. command->m_calculateInverseKinematicsArguments.m_targetOrientation[2] = targetOrientation[2];
  1199. command->m_calculateInverseKinematicsArguments.m_targetOrientation[3] = targetOrientation[3];
  1200. }
  1201. void b3CalculateInverseKinematicsPosWithNullSpaceVel(b3SharedMemoryCommandHandle commandHandle, int numDof, int endEffectorLinkIndex, const double targetPosition[3], const double* lowerLimit, const double* upperLimit, const double* jointRange, const double* restPose)
  1202. {
  1203. struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
  1204. b3Assert(command);
  1205. b3Assert(command->m_type == CMD_CALCULATE_INVERSE_KINEMATICS);
  1206. command->m_updateFlags |= IK_HAS_TARGET_POSITION+IK_HAS_NULL_SPACE_VELOCITY;
  1207. command->m_calculateInverseKinematicsArguments.m_endEffectorLinkIndex = endEffectorLinkIndex;
  1208. command->m_calculateInverseKinematicsArguments.m_targetPosition[0] = targetPosition[0];
  1209. command->m_calculateInverseKinematicsArguments.m_targetPosition[1] = targetPosition[1];
  1210. command->m_calculateInverseKinematicsArguments.m_targetPosition[2] = targetPosition[2];
  1211. for (int i = 0; i < numDof; ++i)
  1212. {
  1213. command->m_calculateInverseKinematicsArguments.m_lowerLimit[i] = lowerLimit[i];
  1214. command->m_calculateInverseKinematicsArguments.m_upperLimit[i] = upperLimit[i];
  1215. command->m_calculateInverseKinematicsArguments.m_jointRange[i] = jointRange[i];
  1216. command->m_calculateInverseKinematicsArguments.m_restPose[i] = restPose[i];
  1217. }
  1218. }
  1219. void b3CalculateInverseKinematicsPosOrnWithNullSpaceVel(b3SharedMemoryCommandHandle commandHandle, int numDof, int endEffectorLinkIndex, const double targetPosition[3], const double targetOrientation[4], const double* lowerLimit, const double* upperLimit, const double* jointRange, const double* restPose)
  1220. {
  1221. struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
  1222. b3Assert(command);
  1223. b3Assert(command->m_type == CMD_CALCULATE_INVERSE_KINEMATICS);
  1224. command->m_updateFlags |= IK_HAS_TARGET_POSITION+IK_HAS_TARGET_ORIENTATION+IK_HAS_NULL_SPACE_VELOCITY;
  1225. command->m_calculateInverseKinematicsArguments.m_endEffectorLinkIndex = endEffectorLinkIndex;
  1226. command->m_calculateInverseKinematicsArguments.m_targetPosition[0] = targetPosition[0];
  1227. command->m_calculateInverseKinematicsArguments.m_targetPosition[1] = targetPosition[1];
  1228. command->m_calculateInverseKinematicsArguments.m_targetPosition[2] = targetPosition[2];
  1229. command->m_calculateInverseKinematicsArguments.m_targetOrientation[0] = targetOrientation[0];
  1230. command->m_calculateInverseKinematicsArguments.m_targetOrientation[1] = targetOrientation[1];
  1231. command->m_calculateInverseKinematicsArguments.m_targetOrientation[2] = targetOrientation[2];
  1232. command->m_calculateInverseKinematicsArguments.m_targetOrientation[3] = targetOrientation[3];
  1233. for (int i = 0; i < numDof; ++i)
  1234. {
  1235. command->m_calculateInverseKinematicsArguments.m_lowerLimit[i] = lowerLimit[i];
  1236. command->m_calculateInverseKinematicsArguments.m_upperLimit[i] = upperLimit[i];
  1237. command->m_calculateInverseKinematicsArguments.m_jointRange[i] = jointRange[i];
  1238. command->m_calculateInverseKinematicsArguments.m_restPose[i] = restPose[i];
  1239. }
  1240. }
  1241. int b3GetStatusInverseKinematicsJointPositions(b3SharedMemoryStatusHandle statusHandle,
  1242. int* bodyUniqueId,
  1243. int* dofCount,
  1244. double* jointPositions)
  1245. {
  1246. const SharedMemoryStatus* status = (const SharedMemoryStatus*)statusHandle;
  1247. btAssert(status->m_type == CMD_CALCULATE_INVERSE_KINEMATICS_COMPLETED);
  1248. if (status->m_type != CMD_CALCULATE_INVERSE_KINEMATICS_COMPLETED)
  1249. return false;
  1250. if (dofCount)
  1251. {
  1252. *dofCount = status->m_inverseKinematicsResultArgs.m_dofCount;
  1253. }
  1254. if (bodyUniqueId)
  1255. {
  1256. *bodyUniqueId = status->m_inverseKinematicsResultArgs.m_bodyUniqueId;
  1257. }
  1258. if (jointPositions)
  1259. {
  1260. for (int i = 0; i < status->m_inverseKinematicsResultArgs.m_dofCount; i++)
  1261. {
  1262. jointPositions[i] = status->m_inverseKinematicsResultArgs.m_jointPositions[i];
  1263. }
  1264. }
  1265. return true;
  1266. }