SharedMemoryCommands.h 13 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506
  1. #ifndef SHARED_MEMORY_COMMANDS_H
  2. #define SHARED_MEMORY_COMMANDS_H
  3. //this is a very experimental draft of commands. We will iterate on this API (commands, arguments etc)
  4. #include "SharedMemoryPublic.h"
  5. #ifdef __GNUC__
  6. #include <stdint.h>
  7. typedef int32_t smInt32_t;
  8. typedef int64_t smInt64_t;
  9. typedef uint32_t smUint32_t;
  10. typedef uint64_t smUint64_t;
  11. #elif defined(_MSC_VER)
  12. typedef __int32 smInt32_t;
  13. typedef __int64 smInt64_t;
  14. typedef unsigned __int32 smUint32_t;
  15. typedef unsigned __int64 smUint64_t;
  16. #else
  17. typedef int smInt32_t;
  18. typedef long long int smInt64_t;
  19. typedef unsigned int smUint32_t;
  20. typedef unsigned long long int smUint64_t;
  21. #endif
  22. #define SHARED_MEMORY_MAX_STREAM_CHUNK_SIZE (256*1024)
  23. #define SHARED_MEMORY_SERVER_TEST_C
  24. #define MAX_DEGREE_OF_FREEDOM 128
  25. #define MAX_NUM_SENSORS 256
  26. #define MAX_URDF_FILENAME_LENGTH 1024
  27. #define MAX_SDF_FILENAME_LENGTH 1024
  28. #define MAX_FILENAME_LENGTH MAX_URDF_FILENAME_LENGTH
  29. #define MAX_NUM_LINKS MAX_DEGREE_OF_FREEDOM
  30. #define MAX_SDF_BODIES 500
  31. struct TmpFloat3
  32. {
  33. float m_x;
  34. float m_y;
  35. float m_z;
  36. };
  37. #ifdef _WIN32
  38. __inline
  39. #else
  40. inline
  41. #endif
  42. TmpFloat3 CreateTmpFloat3(float x, float y, float z)
  43. {
  44. TmpFloat3 tmp;
  45. tmp.m_x = x;
  46. tmp.m_y = y;
  47. tmp.m_z = z;
  48. return tmp;
  49. }
  50. enum EnumSdfArgsUpdateFlags
  51. {
  52. SDF_ARGS_FILE_NAME=1,
  53. };
  54. struct SdfArgs
  55. {
  56. char m_sdfFileName[MAX_URDF_FILENAME_LENGTH];
  57. int m_useMultiBody;
  58. };
  59. enum EnumUrdfArgsUpdateFlags
  60. {
  61. URDF_ARGS_FILE_NAME=1,
  62. URDF_ARGS_INITIAL_POSITION=2,
  63. URDF_ARGS_INITIAL_ORIENTATION=4,
  64. URDF_ARGS_USE_MULTIBODY=8,
  65. URDF_ARGS_USE_FIXED_BASE=16,
  66. };
  67. struct UrdfArgs
  68. {
  69. char m_urdfFileName[MAX_URDF_FILENAME_LENGTH];
  70. double m_initialPosition[3];
  71. double m_initialOrientation[4];
  72. int m_useMultiBody;
  73. int m_useFixedBase;
  74. };
  75. struct BulletDataStreamArgs
  76. {
  77. char m_bulletFileName[MAX_FILENAME_LENGTH];
  78. int m_streamChunkLength;
  79. int m_bodyUniqueId;
  80. };
  81. struct SetJointFeedbackArgs
  82. {
  83. int m_bodyUniqueId;
  84. int m_linkId;
  85. int m_isEnabled;
  86. };
  87. enum EnumInitPoseFlags
  88. {
  89. INIT_POSE_HAS_INITIAL_POSITION=1,
  90. INIT_POSE_HAS_INITIAL_ORIENTATION=2,
  91. INIT_POSE_HAS_JOINT_STATE=4
  92. };
  93. ///InitPoseArgs is mainly to initialize (teleport) the robot in a particular position
  94. ///No motors or controls are needed to initialize the pose. It is similar to
  95. ///moving a robot to a starting place, while it is switched off. It is only called
  96. ///at the start of a robot control session. All velocities and control forces are cleared to zero.
  97. struct InitPoseArgs
  98. {
  99. int m_bodyUniqueId;
  100. int m_hasInitialStateQ[MAX_DEGREE_OF_FREEDOM];
  101. double m_initialStateQ[MAX_DEGREE_OF_FREEDOM];
  102. };
  103. struct RequestDebugLinesArgs
  104. {
  105. int m_debugMode;
  106. int m_startingLineIndex;
  107. };
  108. struct RequestPixelDataArgs
  109. {
  110. float m_viewMatrix[16];
  111. float m_projectionMatrix[16];
  112. int m_startPixelIndex;
  113. int m_pixelWidth;
  114. int m_pixelHeight;
  115. };
  116. enum EnumRequestPixelDataUpdateFlags
  117. {
  118. REQUEST_PIXEL_ARGS_HAS_CAMERA_MATRICES=1,
  119. REQUEST_PIXEL_ARGS_SET_PIXEL_WIDTH_HEIGHT=4,
  120. //don't exceed (1<<15), because this enum is shared with EnumRenderer in SharedMemoryPublic.h
  121. };
  122. struct RequestContactDataArgs
  123. {
  124. int m_startingContactPointIndex;
  125. int m_objectAIndexFilter;
  126. int m_objectBIndexFilter;
  127. };
  128. struct SendDebugLinesArgs
  129. {
  130. int m_startingLineIndex;
  131. int m_numDebugLines;
  132. int m_numRemainingDebugLines;
  133. };
  134. struct SendPixelDataArgs
  135. {
  136. int m_imageWidth;
  137. int m_imageHeight;
  138. int m_startingPixelIndex;
  139. int m_numPixelsCopied;
  140. int m_numRemainingPixels;
  141. };
  142. struct PickBodyArgs
  143. {
  144. double m_rayFromWorld[3];
  145. double m_rayToWorld[3];
  146. };
  147. ///Controlling a robot involves sending the desired state to its joint motor controllers.
  148. ///The control mode determines the state variables used for motor control.
  149. struct SendDesiredStateArgs
  150. {
  151. int m_bodyUniqueId;
  152. int m_controlMode;
  153. //PD parameters in case m_controlMode == CONTROL_MODE_POSITION_VELOCITY_PD
  154. double m_Kp[MAX_DEGREE_OF_FREEDOM];//indexed by degree of freedom, 6 for base, and then the dofs for each link
  155. double m_Kd[MAX_DEGREE_OF_FREEDOM];//indexed by degree of freedom, 6 for base, and then the dofs for each link
  156. int m_hasDesiredStateFlags[MAX_DEGREE_OF_FREEDOM];
  157. //desired state is only written by the client, read-only access by server is expected
  158. //m_desiredStateQ is indexed by position variables,
  159. //starting with 3 base position variables, 4 base orientation variables (quaternion), then link position variables
  160. double m_desiredStateQ[MAX_DEGREE_OF_FREEDOM];
  161. //m_desiredStateQdot is index by velocity degrees of freedom, 3 linear and 3 angular variables for the base and then link velocity variables
  162. double m_desiredStateQdot[MAX_DEGREE_OF_FREEDOM];
  163. //m_desiredStateForceTorque is either the actual applied force/torque (in CONTROL_MODE_TORQUE) or
  164. //or the maximum applied force/torque for the PD/motor/constraint to reach the desired velocity in CONTROL_MODE_VELOCITY and CONTROL_MODE_POSITION_VELOCITY_PD mode
  165. //indexed by degree of freedom, 6 dof base, and then dofs for each link
  166. double m_desiredStateForceTorque[MAX_DEGREE_OF_FREEDOM];
  167. };
  168. enum EnumSimDesiredStateUpdateFlags
  169. {
  170. SIM_DESIRED_STATE_HAS_Q=1,
  171. SIM_DESIRED_STATE_HAS_QDOT=2,
  172. SIM_DESIRED_STATE_HAS_KD=4,
  173. SIM_DESIRED_STATE_HAS_KP=8,
  174. SIM_DESIRED_STATE_HAS_MAX_FORCE=16,
  175. };
  176. enum EnumSimParamUpdateFlags
  177. {
  178. SIM_PARAM_UPDATE_DELTA_TIME=1,
  179. SIM_PARAM_UPDATE_GRAVITY=2,
  180. SIM_PARAM_UPDATE_NUM_SOLVER_ITERATIONS=4,
  181. SIM_PARAM_UPDATE_NUM_SIMULATION_SUB_STEPS=8,
  182. SIM_PARAM_UPDATE_REAL_TIME_SIMULATION = 16,
  183. SIM_PARAM_UPDATE_DEFAULT_CONTACT_ERP=32
  184. };
  185. ///Controlling a robot involves sending the desired state to its joint motor controllers.
  186. ///The control mode determines the state variables used for motor control.
  187. struct SendPhysicsSimulationParameters
  188. {
  189. double m_deltaTime;
  190. double m_gravityAcceleration[3];
  191. int m_numSimulationSubSteps;
  192. int m_numSolverIterations;
  193. bool m_allowRealTimeSimulation;
  194. double m_defaultContactERP;
  195. };
  196. struct RequestActualStateArgs
  197. {
  198. int m_bodyUniqueId;
  199. };
  200. struct SendActualStateArgs
  201. {
  202. int m_bodyUniqueId;
  203. int m_numDegreeOfFreedomQ;
  204. int m_numDegreeOfFreedomU;
  205. double m_rootLocalInertialFrame[7];
  206. //actual state is only written by the server, read-only access by client is expected
  207. double m_actualStateQ[MAX_DEGREE_OF_FREEDOM];
  208. double m_actualStateQdot[MAX_DEGREE_OF_FREEDOM];
  209. //measured 6DOF force/torque sensors: force[x,y,z] and torque[x,y,z]
  210. double m_jointReactionForces[6*MAX_DEGREE_OF_FREEDOM];
  211. double m_jointMotorForce[MAX_DEGREE_OF_FREEDOM];
  212. double m_linkState[7*MAX_NUM_LINKS];
  213. double m_linkLocalInertialFrames[7*MAX_NUM_LINKS];
  214. };
  215. enum EnumSensorTypes
  216. {
  217. SENSOR_FORCE_TORQUE=1,
  218. SENSOR_IMU=2,
  219. };
  220. struct CreateSensorArgs
  221. {
  222. int m_bodyUniqueId;
  223. int m_numJointSensorChanges;
  224. int m_sensorType[MAX_DEGREE_OF_FREEDOM];
  225. ///todo: clean up the duplication, make sure no-one else is using those members directly (use C-API header instead)
  226. int m_jointIndex[MAX_DEGREE_OF_FREEDOM];
  227. int m_enableJointForceSensor[MAX_DEGREE_OF_FREEDOM];
  228. int m_linkIndex[MAX_DEGREE_OF_FREEDOM];
  229. int m_enableSensor[MAX_DEGREE_OF_FREEDOM];
  230. };
  231. typedef struct SharedMemoryCommand SharedMemoryCommand_t;
  232. enum EnumBoxShapeFlags
  233. {
  234. BOX_SHAPE_HAS_INITIAL_POSITION=1,
  235. BOX_SHAPE_HAS_INITIAL_ORIENTATION=2,
  236. BOX_SHAPE_HAS_HALF_EXTENTS=4,
  237. BOX_SHAPE_HAS_MASS=8,
  238. BOX_SHAPE_HAS_COLLISION_SHAPE_TYPE=16,
  239. BOX_SHAPE_HAS_COLOR=32,
  240. };
  241. ///This command will be replaced to allow arbitrary collision shape types
  242. struct CreateBoxShapeArgs
  243. {
  244. double m_halfExtentsX;
  245. double m_halfExtentsY;
  246. double m_halfExtentsZ;
  247. double m_mass;
  248. int m_collisionShapeType;//see SharedMemoryPublic.h
  249. double m_initialPosition[3];
  250. double m_initialOrientation[4];
  251. double m_colorRGBA[4];
  252. };
  253. struct SdfLoadedArgs
  254. {
  255. int m_numBodies;
  256. int m_bodyUniqueIds[MAX_SDF_BODIES];
  257. ///@todo(erwincoumans) load cameras, lights etc
  258. //int m_numCameras;
  259. //int m_numLights;
  260. };
  261. struct SdfRequestInfoArgs
  262. {
  263. int m_bodyUniqueId;
  264. };
  265. ///flags for b3ApplyExternalTorque and b3ApplyExternalForce
  266. enum EnumExternalForcePrivateFlags
  267. {
  268. // EF_LINK_FRAME=1,
  269. // EF_WORLD_FRAME=2,
  270. EF_TORQUE=4,
  271. EF_FORCE=8,
  272. };
  273. struct ExternalForceArgs
  274. {
  275. int m_numForcesAndTorques;
  276. int m_bodyUniqueIds[MAX_SDF_BODIES];
  277. int m_linkIds[MAX_SDF_BODIES];
  278. double m_forcesAndTorques[3*MAX_SDF_BODIES];
  279. double m_positions[3*MAX_SDF_BODIES];
  280. int m_forceFlags[MAX_SDF_BODIES];
  281. };
  282. enum EnumSdfRequestInfoFlags
  283. {
  284. SDF_REQUEST_INFO_BODY=1,
  285. //SDF_REQUEST_INFO_CAMERA=2,
  286. };
  287. struct CalculateInverseDynamicsArgs
  288. {
  289. int m_bodyUniqueId;
  290. double m_jointPositionsQ[MAX_DEGREE_OF_FREEDOM];
  291. double m_jointVelocitiesQdot[MAX_DEGREE_OF_FREEDOM];
  292. double m_jointAccelerations[MAX_DEGREE_OF_FREEDOM];
  293. };
  294. struct CalculateInverseDynamicsResultArgs
  295. {
  296. int m_bodyUniqueId;
  297. int m_dofCount;
  298. double m_jointForces[MAX_DEGREE_OF_FREEDOM];
  299. };
  300. struct CalculateJacobianArgs
  301. {
  302. int m_bodyUniqueId;
  303. int m_linkIndex;
  304. double m_localPosition[3];
  305. double m_jointPositionsQ[MAX_DEGREE_OF_FREEDOM];
  306. double m_jointVelocitiesQdot[MAX_DEGREE_OF_FREEDOM];
  307. double m_jointAccelerations[MAX_DEGREE_OF_FREEDOM];
  308. };
  309. struct CalculateJacobianResultArgs
  310. {
  311. int m_dofCount;
  312. double m_linearJacobian[3*MAX_DEGREE_OF_FREEDOM];
  313. double m_angularJacobian[3*MAX_DEGREE_OF_FREEDOM];
  314. };
  315. enum EnumCalculateInverseKinematicsFlags
  316. {
  317. IK_HAS_TARGET_POSITION=1,
  318. IK_HAS_TARGET_ORIENTATION=2,
  319. IK_HAS_NULL_SPACE_VELOCITY=4,
  320. //IK_HAS_CURRENT_JOINT_POSITIONS=8,//not used yet
  321. };
  322. struct CalculateInverseKinematicsArgs
  323. {
  324. int m_bodyUniqueId;
  325. // double m_jointPositionsQ[MAX_DEGREE_OF_FREEDOM];
  326. double m_targetPosition[3];
  327. double m_targetOrientation[4];//orientation represented as quaternion, x,y,z,w
  328. int m_endEffectorLinkIndex;
  329. double m_lowerLimit[MAX_DEGREE_OF_FREEDOM];
  330. double m_upperLimit[MAX_DEGREE_OF_FREEDOM];
  331. double m_jointRange[MAX_DEGREE_OF_FREEDOM];
  332. double m_restPose[MAX_DEGREE_OF_FREEDOM];
  333. };
  334. struct CalculateInverseKinematicsResultArgs
  335. {
  336. int m_bodyUniqueId;
  337. int m_dofCount;
  338. double m_jointPositions[MAX_DEGREE_OF_FREEDOM];
  339. };
  340. struct CreateJointArgs
  341. {
  342. int m_parentBodyIndex;
  343. int m_parentJointIndex;
  344. int m_childBodyIndex;
  345. int m_childJointIndex;
  346. double m_parentFrame[7];
  347. double m_childFrame[7];
  348. double m_jointAxis[3];
  349. int m_jointType;
  350. };
  351. struct SharedMemoryCommand
  352. {
  353. int m_type;
  354. smUint64_t m_timeStamp;
  355. int m_sequenceNumber;
  356. //m_updateFlags is a bit fields to tell which parameters need updating
  357. //for example m_updateFlags = SIM_PARAM_UPDATE_DELTA_TIME | SIM_PARAM_UPDATE_NUM_SOLVER_ITERATIONS;
  358. int m_updateFlags;
  359. union
  360. {
  361. struct UrdfArgs m_urdfArguments;
  362. struct SdfArgs m_sdfArguments;
  363. struct SdfRequestInfoArgs m_sdfRequestInfoArgs;
  364. struct InitPoseArgs m_initPoseArgs;
  365. struct SendPhysicsSimulationParameters m_physSimParamArgs;
  366. struct BulletDataStreamArgs m_dataStreamArguments;
  367. struct SendDesiredStateArgs m_sendDesiredStateCommandArgument;
  368. struct RequestActualStateArgs m_requestActualStateInformationCommandArgument;
  369. struct CreateSensorArgs m_createSensorArguments;
  370. struct CreateBoxShapeArgs m_createBoxShapeArguments;
  371. struct RequestDebugLinesArgs m_requestDebugLinesArguments;
  372. struct RequestPixelDataArgs m_requestPixelDataArguments;
  373. struct PickBodyArgs m_pickBodyArguments;
  374. struct ExternalForceArgs m_externalForceArguments;
  375. struct CalculateInverseDynamicsArgs m_calculateInverseDynamicsArguments;
  376. struct CalculateJacobianArgs m_calculateJacobianArguments;
  377. struct CreateJointArgs m_createJointArguments;
  378. struct RequestContactDataArgs m_requestContactPointArguments;
  379. struct CalculateInverseKinematicsArgs m_calculateInverseKinematicsArguments;
  380. };
  381. };
  382. struct RigidBodyCreateArgs
  383. {
  384. int m_bodyUniqueId;
  385. };
  386. struct SendContactDataArgs
  387. {
  388. int m_startingContactPointIndex;
  389. int m_numContactPointsCopied;
  390. int m_numRemainingContactPoints;
  391. };
  392. struct SharedMemoryStatus
  393. {
  394. int m_type;
  395. smUint64_t m_timeStamp;
  396. int m_sequenceNumber;
  397. union
  398. {
  399. struct BulletDataStreamArgs m_dataStreamArguments;
  400. struct SdfLoadedArgs m_sdfLoadedArgs;
  401. struct SendActualStateArgs m_sendActualStateArgs;
  402. struct SendDebugLinesArgs m_sendDebugLinesArgs;
  403. struct SendPixelDataArgs m_sendPixelDataArguments;
  404. struct RigidBodyCreateArgs m_rigidBodyCreateArgs;
  405. struct CalculateInverseDynamicsResultArgs m_inverseDynamicsResultArgs;
  406. struct CalculateJacobianResultArgs m_jacobianResultArgs;
  407. struct SendContactDataArgs m_sendContactPointArgs;
  408. struct CalculateInverseKinematicsResultArgs m_inverseKinematicsResultArgs;
  409. };
  410. };
  411. typedef struct SharedMemoryStatus SharedMemoryStatus_t;
  412. #endif //SHARED_MEMORY_COMMANDS_H