2
0

btMultiBodyTreeCreator.cpp 11 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306
  1. #include "btMultiBodyTreeCreator.hpp"
  2. namespace btInverseDynamics
  3. {
  4. btMultiBodyTreeCreator::btMultiBodyTreeCreator() : m_initialized(false) {}
  5. int btMultiBodyTreeCreator::createFromBtMultiBody(const btMultiBody *btmb, const bool verbose)
  6. {
  7. if (0x0 == btmb)
  8. {
  9. bt_id_error_message("cannot create MultiBodyTree from null pointer\n");
  10. return -1;
  11. }
  12. // in case this is a second call, discard old data
  13. m_data.clear();
  14. m_initialized = false;
  15. // btMultiBody treats base link separately
  16. m_data.resize(1 + btmb->getNumLinks());
  17. // add base link data
  18. {
  19. LinkData &link = m_data[0];
  20. link.parent_index = -1;
  21. if (btmb->hasFixedBase())
  22. {
  23. link.joint_type = FIXED;
  24. }
  25. else
  26. {
  27. link.joint_type = FLOATING;
  28. }
  29. btTransform transform = (btmb->getBaseWorldTransform());
  30. //compute inverse dynamics in body-fixed frame
  31. transform.setIdentity();
  32. link.parent_r_parent_body_ref(0) = transform.getOrigin()[0];
  33. link.parent_r_parent_body_ref(1) = transform.getOrigin()[1];
  34. link.parent_r_parent_body_ref(2) = transform.getOrigin()[2];
  35. link.body_T_parent_ref(0, 0) = transform.getBasis()[0][0];
  36. link.body_T_parent_ref(0, 1) = transform.getBasis()[0][1];
  37. link.body_T_parent_ref(0, 2) = transform.getBasis()[0][2];
  38. link.body_T_parent_ref(1, 0) = transform.getBasis()[1][0];
  39. link.body_T_parent_ref(1, 1) = transform.getBasis()[1][1];
  40. link.body_T_parent_ref(1, 2) = transform.getBasis()[1][2];
  41. link.body_T_parent_ref(2, 0) = transform.getBasis()[2][0];
  42. link.body_T_parent_ref(2, 1) = transform.getBasis()[2][1];
  43. link.body_T_parent_ref(2, 2) = transform.getBasis()[2][2];
  44. // random unit vector. value not used for fixed or floating joints.
  45. link.body_axis_of_motion(0) = 0;
  46. link.body_axis_of_motion(1) = 0;
  47. link.body_axis_of_motion(2) = 1;
  48. link.mass = btmb->getBaseMass();
  49. // link frame in the center of mass
  50. link.body_r_body_com(0) = 0;
  51. link.body_r_body_com(1) = 0;
  52. link.body_r_body_com(2) = 0;
  53. // BulletDynamics uses body-fixed frame in the cog, aligned with principal axes
  54. link.body_I_body(0, 0) = btmb->getBaseInertia()[0];
  55. link.body_I_body(0, 1) = 0.0;
  56. link.body_I_body(0, 2) = 0.0;
  57. link.body_I_body(1, 0) = 0.0;
  58. link.body_I_body(1, 1) = btmb->getBaseInertia()[1];
  59. link.body_I_body(1, 2) = 0.0;
  60. link.body_I_body(2, 0) = 0.0;
  61. link.body_I_body(2, 1) = 0.0;
  62. link.body_I_body(2, 2) = btmb->getBaseInertia()[2];
  63. // shift reference point to link origin (in joint axis)
  64. mat33 tilde_r_com = tildeOperator(link.body_r_body_com);
  65. link.body_I_body = link.body_I_body - link.mass * tilde_r_com * tilde_r_com;
  66. if (verbose)
  67. {
  68. id_printf(
  69. "base: mass= %f, bt_inertia= [%f %f %f]\n"
  70. "Io= [%f %f %f;\n"
  71. " %f %f %f;\n"
  72. " %f %f %f]\n",
  73. link.mass, btmb->getBaseInertia()[0], btmb->getBaseInertia()[1],
  74. btmb->getBaseInertia()[2], link.body_I_body(0, 0), link.body_I_body(0, 1),
  75. link.body_I_body(0, 2), link.body_I_body(1, 0), link.body_I_body(1, 1),
  76. link.body_I_body(1, 2), link.body_I_body(2, 0), link.body_I_body(2, 1),
  77. link.body_I_body(2, 2));
  78. }
  79. }
  80. for (int bt_index = 0; bt_index < btmb->getNumLinks(); bt_index++)
  81. {
  82. if (verbose)
  83. {
  84. id_printf("bt->id: converting link %d\n", bt_index);
  85. }
  86. const btMultibodyLink &bt_link = btmb->getLink(bt_index);
  87. LinkData &link = m_data[bt_index + 1];
  88. link.parent_index = bt_link.m_parent + 1;
  89. link.mass = bt_link.m_mass;
  90. if (verbose)
  91. {
  92. id_printf("mass= %f\n", link.mass);
  93. }
  94. // from this body's pivot to this body's com in this body's frame
  95. link.body_r_body_com[0] = bt_link.m_dVector[0];
  96. link.body_r_body_com[1] = bt_link.m_dVector[1];
  97. link.body_r_body_com[2] = bt_link.m_dVector[2];
  98. if (verbose)
  99. {
  100. id_printf("com= %f %f %f\n", link.body_r_body_com[0], link.body_r_body_com[1],
  101. link.body_r_body_com[2]);
  102. }
  103. // BulletDynamics uses a body-fixed frame in the CoM, aligned with principal axes
  104. link.body_I_body(0, 0) = bt_link.m_inertiaLocal[0];
  105. link.body_I_body(0, 1) = 0.0;
  106. link.body_I_body(0, 2) = 0.0;
  107. link.body_I_body(1, 0) = 0.0;
  108. link.body_I_body(1, 1) = bt_link.m_inertiaLocal[1];
  109. link.body_I_body(1, 2) = 0.0;
  110. link.body_I_body(2, 0) = 0.0;
  111. link.body_I_body(2, 1) = 0.0;
  112. link.body_I_body(2, 2) = bt_link.m_inertiaLocal[2];
  113. // shift reference point to link origin (in joint axis)
  114. mat33 tilde_r_com = tildeOperator(link.body_r_body_com);
  115. link.body_I_body = link.body_I_body - link.mass * tilde_r_com * tilde_r_com;
  116. if (verbose)
  117. {
  118. id_printf(
  119. "link %d: mass= %f, bt_inertia= [%f %f %f]\n"
  120. "Io= [%f %f %f;\n"
  121. " %f %f %f;\n"
  122. " %f %f %f]\n",
  123. bt_index, link.mass, bt_link.m_inertiaLocal[0], bt_link.m_inertiaLocal[1],
  124. bt_link.m_inertiaLocal[2], link.body_I_body(0, 0), link.body_I_body(0, 1),
  125. link.body_I_body(0, 2), link.body_I_body(1, 0), link.body_I_body(1, 1),
  126. link.body_I_body(1, 2), link.body_I_body(2, 0), link.body_I_body(2, 1),
  127. link.body_I_body(2, 2));
  128. }
  129. // transform for vectors written in parent frame to this link's body-fixed frame
  130. btMatrix3x3 basis = btTransform(bt_link.m_zeroRotParentToThis).getBasis();
  131. link.body_T_parent_ref(0, 0) = basis[0][0];
  132. link.body_T_parent_ref(0, 1) = basis[0][1];
  133. link.body_T_parent_ref(0, 2) = basis[0][2];
  134. link.body_T_parent_ref(1, 0) = basis[1][0];
  135. link.body_T_parent_ref(1, 1) = basis[1][1];
  136. link.body_T_parent_ref(1, 2) = basis[1][2];
  137. link.body_T_parent_ref(2, 0) = basis[2][0];
  138. link.body_T_parent_ref(2, 1) = basis[2][1];
  139. link.body_T_parent_ref(2, 2) = basis[2][2];
  140. if (verbose)
  141. {
  142. id_printf(
  143. "body_T_parent_ref= %f %f %f\n"
  144. " %f %f %f\n"
  145. " %f %f %f\n",
  146. basis[0][0], basis[0][1], basis[0][2], basis[1][0], basis[1][1], basis[1][2],
  147. basis[2][0], basis[2][1], basis[2][2]);
  148. }
  149. switch (bt_link.m_jointType)
  150. {
  151. case btMultibodyLink::eRevolute:
  152. link.joint_type = REVOLUTE;
  153. if (verbose)
  154. {
  155. id_printf("type= revolute\n");
  156. }
  157. link.body_axis_of_motion(0) = bt_link.m_axes[0].m_topVec[0];
  158. link.body_axis_of_motion(1) = bt_link.m_axes[0].m_topVec[1];
  159. link.body_axis_of_motion(2) = bt_link.m_axes[0].m_topVec[2];
  160. // for revolute joints, m_eVector = parentComToThisPivotOffset
  161. // m_dVector = thisPivotToThisComOffset
  162. // from parent com to pivot, in parent frame
  163. link.parent_r_parent_body_ref(0) = bt_link.m_eVector[0];
  164. link.parent_r_parent_body_ref(1) = bt_link.m_eVector[1];
  165. link.parent_r_parent_body_ref(2) = bt_link.m_eVector[2];
  166. break;
  167. case btMultibodyLink::ePrismatic:
  168. link.joint_type = PRISMATIC;
  169. if (verbose)
  170. {
  171. id_printf("type= prismatic\n");
  172. }
  173. link.body_axis_of_motion(0) = bt_link.m_axes[0].m_bottomVec[0];
  174. link.body_axis_of_motion(1) = bt_link.m_axes[0].m_bottomVec[1];
  175. link.body_axis_of_motion(2) = bt_link.m_axes[0].m_bottomVec[2];
  176. // for prismatic joints, eVector
  177. // according to documentation :
  178. // parentComToThisComOffset
  179. // but seems to be: from parent's com to parent's
  180. // pivot ??
  181. // m_dVector = thisPivotToThisComOffset
  182. link.parent_r_parent_body_ref(0) = bt_link.m_eVector[0];
  183. link.parent_r_parent_body_ref(1) = bt_link.m_eVector[1];
  184. link.parent_r_parent_body_ref(2) = bt_link.m_eVector[2];
  185. break;
  186. case btMultibodyLink::eSpherical:
  187. link.joint_type = SPHERICAL;
  188. link.parent_r_parent_body_ref(0) = bt_link.m_eVector[0];
  189. link.parent_r_parent_body_ref(1) = bt_link.m_eVector[1];
  190. link.parent_r_parent_body_ref(2) = bt_link.m_eVector[2];
  191. // random unit vector
  192. link.body_axis_of_motion(0) = 0;
  193. link.body_axis_of_motion(1) = 1;
  194. link.body_axis_of_motion(2) = 0;
  195. break;
  196. case btMultibodyLink::ePlanar:
  197. bt_id_error_message("planar joints not implemented\n");
  198. return -1;
  199. case btMultibodyLink::eFixed:
  200. link.joint_type = FIXED;
  201. // random unit vector
  202. link.body_axis_of_motion(0) = 0;
  203. link.body_axis_of_motion(1) = 0;
  204. link.body_axis_of_motion(2) = 1;
  205. // for fixed joints, m_dVector = thisPivotToThisComOffset;
  206. // m_eVector = parentComToThisPivotOffset;
  207. link.parent_r_parent_body_ref(0) = bt_link.m_eVector[0];
  208. link.parent_r_parent_body_ref(1) = bt_link.m_eVector[1];
  209. link.parent_r_parent_body_ref(2) = bt_link.m_eVector[2];
  210. break;
  211. default:
  212. bt_id_error_message("unknown btMultiBody::eFeatherstoneJointType %d\n",
  213. bt_link.m_jointType);
  214. return -1;
  215. }
  216. if (link.parent_index > 0)
  217. { // parent body isn't the root
  218. const btMultibodyLink &bt_parent_link = btmb->getLink(link.parent_index - 1);
  219. // from parent pivot to parent com, in parent frame
  220. link.parent_r_parent_body_ref(0) += bt_parent_link.m_dVector[0];
  221. link.parent_r_parent_body_ref(1) += bt_parent_link.m_dVector[1];
  222. link.parent_r_parent_body_ref(2) += bt_parent_link.m_dVector[2];
  223. }
  224. else
  225. {
  226. // parent is root body. btMultiBody only knows 6-DoF or 0-DoF root bodies,
  227. // whose link frame is in the CoM (ie, no notion of a pivot point)
  228. }
  229. if (verbose)
  230. {
  231. id_printf("parent_r_parent_body_ref= %f %f %f\n", link.parent_r_parent_body_ref[0],
  232. link.parent_r_parent_body_ref[1], link.parent_r_parent_body_ref[2]);
  233. }
  234. }
  235. m_initialized = true;
  236. return 0;
  237. }
  238. int btMultiBodyTreeCreator::getNumBodies(int *num_bodies) const
  239. {
  240. if (false == m_initialized)
  241. {
  242. bt_id_error_message("btMultiBody not converted yet\n");
  243. return -1;
  244. }
  245. *num_bodies = static_cast<int>(m_data.size());
  246. return 0;
  247. }
  248. int btMultiBodyTreeCreator::getBody(const int body_index, int *parent_index, JointType *joint_type,
  249. vec3 *parent_r_parent_body_ref, mat33 *body_T_parent_ref,
  250. vec3 *body_axis_of_motion, idScalar *mass,
  251. vec3 *body_r_body_com, mat33 *body_I_body, int *user_int,
  252. void **user_ptr) const
  253. {
  254. if (false == m_initialized)
  255. {
  256. bt_id_error_message("MultiBodyTree not created yet\n");
  257. return -1;
  258. }
  259. if (body_index < 0 || body_index >= static_cast<int>(m_data.size()))
  260. {
  261. bt_id_error_message("index out of range (got %d but only %zu bodies)\n", body_index,
  262. m_data.size());
  263. return -1;
  264. }
  265. *parent_index = m_data[body_index].parent_index;
  266. *joint_type = m_data[body_index].joint_type;
  267. *parent_r_parent_body_ref = m_data[body_index].parent_r_parent_body_ref;
  268. *body_T_parent_ref = m_data[body_index].body_T_parent_ref;
  269. *body_axis_of_motion = m_data[body_index].body_axis_of_motion;
  270. *mass = m_data[body_index].mass;
  271. *body_r_body_com = m_data[body_index].body_r_body_com;
  272. *body_I_body = m_data[body_index].body_I_body;
  273. *user_int = -1;
  274. *user_ptr = 0x0;
  275. return 0;
  276. }
  277. } // namespace btInverseDynamics