test.c 10.0 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313
  1. //#include "SharedMemoryCommands.h"
  2. #ifdef PHYSICS_SHARED_MEMORY
  3. #include "SharedMemory/PhysicsClientC_API.h"
  4. #endif //PHYSICS_SHARED_MEMORY
  5. #ifdef PHYSICS_LOOP_BACK
  6. #include "SharedMemory/PhysicsLoopBackC_API.h"
  7. #endif //PHYSICS_LOOP_BACK
  8. #ifdef PHYSICS_SERVER_DIRECT
  9. #include "SharedMemory/PhysicsDirectC_API.h"
  10. #endif //PHYSICS_SERVER_DIRECT
  11. #ifdef PHYSICS_IN_PROCESS_EXAMPLE_BROWSER
  12. #include "SharedMemory/SharedMemoryInProcessPhysicsC_API.h"
  13. #endif//PHYSICS_IN_PROCESS_EXAMPLE_BROWSER
  14. #include "SharedMemory/SharedMemoryPublic.h"
  15. #include "Bullet3Common/b3Logging.h"
  16. #include <string.h>
  17. #include <stdio.h>
  18. #ifndef ENABLE_GTEST
  19. #include <assert.h>
  20. #define ASSERT_EQ(a,b) assert((a)==(b));
  21. #else
  22. #define printf
  23. #endif
  24. void testSharedMemory(b3PhysicsClientHandle sm)
  25. {
  26. int i, dofCount , posVarCount, ret ,numJoints ;
  27. int sensorJointIndexLeft=-1;
  28. int sensorJointIndexRight=-1;
  29. const char* urdfFileName = "r2d2.urdf";
  30. const char* sdfFileName = "kuka_iiwa/model.sdf";
  31. double gravx=0, gravy=0, gravz=-9.8;
  32. double timeStep = 1./60.;
  33. double startPosX, startPosY,startPosZ;
  34. int imuLinkIndex = -1;
  35. int bodyIndex = -1;
  36. if (b3CanSubmitCommand(sm))
  37. {
  38. {
  39. b3SharedMemoryCommandHandle command = b3InitPhysicsParamCommand(sm);
  40. b3SharedMemoryStatusHandle statusHandle;
  41. ret = b3PhysicsParamSetGravity(command, gravx,gravy, gravz);
  42. ret = b3PhysicsParamSetTimeStep(command, timeStep);
  43. statusHandle = b3SubmitClientCommandAndWaitStatus(sm, command);
  44. ASSERT_EQ(b3GetStatusType(statusHandle), CMD_CLIENT_COMMAND_COMPLETED);
  45. }
  46. {
  47. b3SharedMemoryStatusHandle statusHandle;
  48. int statusType;
  49. int bodyIndicesOut[10];//MAX_SDF_BODIES = 10
  50. int numJoints, numBodies;
  51. int bodyUniqueId;
  52. b3SharedMemoryCommandHandle command = b3LoadSdfCommandInit(sm, sdfFileName);
  53. statusHandle = b3SubmitClientCommandAndWaitStatus(sm, command);
  54. statusType = b3GetStatusType(statusHandle);
  55. ASSERT_EQ(statusType, CMD_SDF_LOADING_COMPLETED);
  56. numBodies = b3GetStatusBodyIndices(statusHandle, bodyIndicesOut, 10);
  57. ASSERT_EQ(numBodies,1);
  58. bodyUniqueId = bodyIndicesOut[0];
  59. numJoints = b3GetNumJoints(sm,bodyUniqueId);
  60. ASSERT_EQ(numJoints,7);
  61. #if 0
  62. b3Printf("numJoints: %d\n", numJoints);
  63. for (i=0;i<numJoints;i++)
  64. {
  65. struct b3JointInfo jointInfo;
  66. if (b3GetJointInfo(sm,bodyUniqueId, i,&jointInfo))
  67. {
  68. b3Printf("jointInfo[%d].m_jointName=%s\n",i,jointInfo.m_jointName);
  69. }
  70. }
  71. #endif
  72. {
  73. b3SharedMemoryStatusHandle statusHandle;
  74. b3SharedMemoryCommandHandle commandHandle;
  75. double jointAngle = 0.f;
  76. int jointIndex;
  77. commandHandle = b3CreatePoseCommandInit(sm, bodyUniqueId);
  78. for (jointIndex=0;jointIndex<numJoints;jointIndex++)
  79. {
  80. b3CreatePoseCommandSetJointPosition(sm, commandHandle, jointIndex, jointAngle);
  81. }
  82. statusHandle = b3SubmitClientCommandAndWaitStatus(sm, commandHandle);
  83. ASSERT_EQ(b3GetStatusType(statusHandle), CMD_CLIENT_COMMAND_COMPLETED);
  84. }
  85. }
  86. {
  87. b3SharedMemoryStatusHandle statusHandle;
  88. int statusType;
  89. b3SharedMemoryCommandHandle command = b3LoadUrdfCommandInit(sm, urdfFileName);
  90. //setting the initial position, orientation and other arguments are optional
  91. startPosX =2;
  92. startPosY =0;
  93. startPosZ = 1;
  94. ret = b3LoadUrdfCommandSetStartPosition(command, startPosX,startPosY,startPosZ);
  95. statusHandle = b3SubmitClientCommandAndWaitStatus(sm, command);
  96. statusType = b3GetStatusType(statusHandle);
  97. ASSERT_EQ(statusType, CMD_URDF_LOADING_COMPLETED);
  98. bodyIndex = b3GetStatusBodyIndex(statusHandle);
  99. }
  100. if (bodyIndex>=0)
  101. {
  102. numJoints = b3GetNumJoints(sm,bodyIndex);
  103. for (i=0;i<numJoints;i++)
  104. {
  105. struct b3JointInfo jointInfo;
  106. b3GetJointInfo(sm,bodyIndex, i,&jointInfo);
  107. // printf("jointInfo[%d].m_jointName=%s\n",i,jointInfo.m_jointName);
  108. //pick the IMU link index based on torso name
  109. if (strstr(jointInfo.m_linkName,"base_link"))
  110. {
  111. imuLinkIndex = i;
  112. }
  113. //pick the joint index based on joint name
  114. if (strstr(jointInfo.m_jointName,"base_to_left_leg"))
  115. {
  116. sensorJointIndexLeft = i;
  117. }
  118. if (strstr(jointInfo.m_jointName,"base_to_right_leg"))
  119. {
  120. sensorJointIndexRight = i;
  121. }
  122. }
  123. if ((sensorJointIndexLeft>=0) || (sensorJointIndexRight>=0))
  124. {
  125. b3SharedMemoryCommandHandle command = b3CreateSensorCommandInit(sm, bodyIndex);
  126. b3SharedMemoryStatusHandle statusHandle;
  127. if (imuLinkIndex>=0)
  128. {
  129. ret = b3CreateSensorEnableIMUForLink(command, imuLinkIndex, 1);
  130. }
  131. if (sensorJointIndexLeft>=0)
  132. {
  133. ret = b3CreateSensorEnable6DofJointForceTorqueSensor(command, sensorJointIndexLeft, 1);
  134. }
  135. if(sensorJointIndexRight>=0)
  136. {
  137. ret = b3CreateSensorEnable6DofJointForceTorqueSensor(command, sensorJointIndexRight, 1);
  138. }
  139. statusHandle = b3SubmitClientCommandAndWaitStatus(sm, command);
  140. ASSERT_EQ(b3GetStatusType(statusHandle), CMD_CLIENT_COMMAND_COMPLETED);
  141. }
  142. }
  143. {
  144. b3SharedMemoryStatusHandle statusHandle;
  145. b3SharedMemoryCommandHandle command = b3CreateBoxShapeCommandInit(sm);
  146. ret = b3CreateBoxCommandSetStartPosition(command, 0,0,-1);
  147. ret = b3CreateBoxCommandSetStartOrientation(command,0,0,0,1);
  148. ret = b3CreateBoxCommandSetHalfExtents(command, 10,10,1);
  149. statusHandle = b3SubmitClientCommandAndWaitStatus(sm, command);
  150. ASSERT_EQ(b3GetStatusType(statusHandle), CMD_RIGID_BODY_CREATION_COMPLETED);
  151. }
  152. {
  153. int statusType;
  154. b3SharedMemoryCommandHandle command = b3RequestActualStateCommandInit(sm,bodyIndex);
  155. b3SharedMemoryStatusHandle statusHandle;
  156. statusHandle = b3SubmitClientCommandAndWaitStatus(sm, command);
  157. statusType = b3GetStatusType(statusHandle);
  158. ASSERT_EQ(statusType, CMD_ACTUAL_STATE_UPDATE_COMPLETED);
  159. if (statusType == CMD_ACTUAL_STATE_UPDATE_COMPLETED)
  160. {
  161. b3GetStatusActualState(statusHandle,
  162. 0, &posVarCount, &dofCount,
  163. 0, 0, 0, 0);
  164. ASSERT_EQ(posVarCount,15);
  165. ASSERT_EQ(dofCount,14);
  166. }
  167. }
  168. {
  169. #if 0
  170. b3SharedMemoryStatusHandle statusHandle;
  171. b3SharedMemoryCommandHandle command = b3JointControlCommandInit( sm, CONTROL_MODE_VELOCITY);
  172. for ( dofIndex=0;dofIndex<dofCount;dofIndex++)
  173. {
  174. b3JointControlSetDesiredVelocity(command,dofIndex,1);
  175. b3JointControlSetMaximumForce(command,dofIndex,100);
  176. }
  177. statusHandle = b3SubmitClientCommandAndWaitStatus(sm, command);
  178. #endif
  179. }
  180. ///perform some simulation steps for testing
  181. for ( i=0;i<100;i++)
  182. {
  183. b3SharedMemoryStatusHandle statusHandle;
  184. int statusType;
  185. if (b3CanSubmitCommand(sm))
  186. {
  187. statusHandle = b3SubmitClientCommandAndWaitStatus(sm, b3InitStepSimulationCommand(sm));
  188. statusType = b3GetStatusType(statusHandle);
  189. ASSERT_EQ(statusType, CMD_STEP_FORWARD_SIMULATION_COMPLETED);
  190. } else
  191. {
  192. break;
  193. }
  194. }
  195. if (b3CanSubmitCommand(sm))
  196. {
  197. b3SharedMemoryStatusHandle state = b3SubmitClientCommandAndWaitStatus(sm, b3RequestActualStateCommandInit(sm,bodyIndex));
  198. if (sensorJointIndexLeft>=0)
  199. {
  200. struct b3JointSensorState sensorState;
  201. b3GetJointState(sm,state,sensorJointIndexLeft,&sensorState);
  202. b3Printf("Sensor for joint [%d] = %f,%f,%f\n", sensorJointIndexLeft,
  203. sensorState.m_jointForceTorque[0],
  204. sensorState.m_jointForceTorque[1],
  205. sensorState.m_jointForceTorque[2]);
  206. }
  207. if (sensorJointIndexRight>=0)
  208. {
  209. struct b3JointSensorState sensorState;
  210. b3GetJointState(sm,state,sensorJointIndexRight,&sensorState);
  211. b3Printf("Sensor for joint [%d] = %f,%f,%f\n", sensorJointIndexRight,
  212. sensorState.m_jointForceTorque[0],
  213. sensorState.m_jointForceTorque[1],
  214. sensorState.m_jointForceTorque[2]);
  215. }
  216. {
  217. b3SharedMemoryStatusHandle statusHandle;
  218. statusHandle = b3SubmitClientCommandAndWaitStatus(sm, b3InitResetSimulationCommand(sm));
  219. ASSERT_EQ(b3GetStatusType(statusHandle), CMD_RESET_SIMULATION_COMPLETED);
  220. }
  221. }
  222. }
  223. b3DisconnectSharedMemory(sm);
  224. }
  225. #ifdef ENABLE_GTEST
  226. TEST(BulletPhysicsClientServerTest, DirectConnection) {
  227. b3PhysicsClientHandle sm = b3ConnectPhysicsDirect();
  228. testSharedMemory(sm);
  229. }
  230. TEST(BulletPhysicsClientServerTest, LoopBackSharedMemory) {
  231. b3PhysicsClientHandle sm = b3ConnectPhysicsLoopback(SHARED_MEMORY_KEY);
  232. testSharedMemory(sm);
  233. }
  234. #else
  235. int main(int argc, char* argv[])
  236. {
  237. #ifdef PHYSICS_LOOP_BACK
  238. b3PhysicsClientHandle sm = b3ConnectPhysicsLoopback(SHARED_MEMORY_KEY);
  239. #endif
  240. #ifdef PHYSICS_SERVER_DIRECT
  241. b3PhysicsClientHandle sm = b3ConnectPhysicsDirect();
  242. #endif
  243. #ifdef PHYSICS_IN_PROCESS_EXAMPLE_BROWSER
  244. #ifdef __APPLE__
  245. b3PhysicsClientHandle sm = b3CreateInProcessPhysicsServerAndConnectMainThread(argc,argv);
  246. #else
  247. b3PhysicsClientHandle sm = b3CreateInProcessPhysicsServerAndConnect(argc,argv);
  248. #endif //__APPLE__
  249. #endif
  250. #ifdef PHYSICS_SHARED_MEMORY
  251. b3PhysicsClientHandle sm = b3ConnectSharedMemory(SHARED_MEMORY_KEY);
  252. #endif //PHYSICS_SHARED_MEMORY
  253. testSharedMemory(sm);
  254. }
  255. #endif