btMultiBodyTreeCreator.cpp 12 KB

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