MultiBodyTree.cpp 15 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548
  1. #include "MultiBodyTree.hpp"
  2. #include <cmath>
  3. #include <limits>
  4. #include <vector>
  5. #include "IDMath.hpp"
  6. #include "details/MultiBodyTreeImpl.hpp"
  7. #include "details/MultiBodyTreeInitCache.hpp"
  8. namespace btInverseDynamics
  9. {
  10. MultiBodyTree::MultiBodyTree()
  11. : m_is_finalized(false),
  12. m_mass_parameters_are_valid(true),
  13. m_accept_invalid_mass_parameters(false),
  14. m_impl(0x0),
  15. m_init_cache(0x0)
  16. {
  17. m_init_cache = new InitCache();
  18. }
  19. MultiBodyTree::~MultiBodyTree()
  20. {
  21. delete m_impl;
  22. delete m_init_cache;
  23. }
  24. void MultiBodyTree::setAcceptInvalidMassParameters(bool flag)
  25. {
  26. m_accept_invalid_mass_parameters = flag;
  27. }
  28. bool MultiBodyTree::getAcceptInvalidMassProperties() const
  29. {
  30. return m_accept_invalid_mass_parameters;
  31. }
  32. int MultiBodyTree::getBodyOrigin(const int body_index, vec3 *world_origin) const
  33. {
  34. return m_impl->getBodyOrigin(body_index, world_origin);
  35. }
  36. int MultiBodyTree::getBodyCoM(const int body_index, vec3 *world_com) const
  37. {
  38. return m_impl->getBodyCoM(body_index, world_com);
  39. }
  40. int MultiBodyTree::getBodyTransform(const int body_index, mat33 *world_T_body) const
  41. {
  42. return m_impl->getBodyTransform(body_index, world_T_body);
  43. }
  44. int MultiBodyTree::getBodyAngularVelocity(const int body_index, vec3 *world_omega) const
  45. {
  46. return m_impl->getBodyAngularVelocity(body_index, world_omega);
  47. }
  48. int MultiBodyTree::getBodyLinearVelocity(const int body_index, vec3 *world_velocity) const
  49. {
  50. return m_impl->getBodyLinearVelocity(body_index, world_velocity);
  51. }
  52. int MultiBodyTree::getBodyLinearVelocityCoM(const int body_index, vec3 *world_velocity) const
  53. {
  54. return m_impl->getBodyLinearVelocityCoM(body_index, world_velocity);
  55. }
  56. int MultiBodyTree::getBodyAngularAcceleration(const int body_index, vec3 *world_dot_omega) const
  57. {
  58. return m_impl->getBodyAngularAcceleration(body_index, world_dot_omega);
  59. }
  60. int MultiBodyTree::getBodyLinearAcceleration(const int body_index, vec3 *world_acceleration) const
  61. {
  62. return m_impl->getBodyLinearAcceleration(body_index, world_acceleration);
  63. }
  64. int MultiBodyTree::getParentRParentBodyRef(const int body_index, vec3 *r) const
  65. {
  66. return m_impl->getParentRParentBodyRef(body_index, r);
  67. }
  68. int MultiBodyTree::getBodyTParentRef(const int body_index, mat33 *T) const
  69. {
  70. return m_impl->getBodyTParentRef(body_index, T);
  71. }
  72. int MultiBodyTree::getBodyAxisOfMotion(const int body_index, vec3 *axis) const
  73. {
  74. return m_impl->getBodyAxisOfMotion(body_index, axis);
  75. }
  76. void MultiBodyTree::printTree() { m_impl->printTree(); }
  77. void MultiBodyTree::printTreeData() { m_impl->printTreeData(); }
  78. int MultiBodyTree::numBodies() const { return m_impl->m_num_bodies; }
  79. int MultiBodyTree::numDoFs() const { return m_impl->m_num_dofs; }
  80. int MultiBodyTree::calculateInverseDynamics(const vecx &q, const vecx &u, const vecx &dot_u,
  81. vecx *joint_forces)
  82. {
  83. if (false == m_is_finalized)
  84. {
  85. bt_id_error_message("system has not been initialized\n");
  86. return -1;
  87. }
  88. if (-1 == m_impl->calculateInverseDynamics(q, u, dot_u, joint_forces))
  89. {
  90. bt_id_error_message("error in inverse dynamics calculation\n");
  91. return -1;
  92. }
  93. return 0;
  94. }
  95. int MultiBodyTree::calculateMassMatrix(const vecx &q, const bool update_kinematics,
  96. const bool initialize_matrix,
  97. const bool set_lower_triangular_matrix, matxx *mass_matrix)
  98. {
  99. if (false == m_is_finalized)
  100. {
  101. bt_id_error_message("system has not been initialized\n");
  102. return -1;
  103. }
  104. if (-1 ==
  105. m_impl->calculateMassMatrix(q, update_kinematics, initialize_matrix,
  106. set_lower_triangular_matrix, mass_matrix))
  107. {
  108. bt_id_error_message("error in mass matrix calculation\n");
  109. return -1;
  110. }
  111. return 0;
  112. }
  113. int MultiBodyTree::calculateMassMatrix(const vecx &q, matxx *mass_matrix)
  114. {
  115. return calculateMassMatrix(q, true, true, true, mass_matrix);
  116. }
  117. int MultiBodyTree::calculateKinematics(const vecx &q, const vecx &u, const vecx &dot_u)
  118. {
  119. vec3 world_gravity(m_impl->m_world_gravity);
  120. // temporarily set gravity to zero, to ensure we get the actual accelerations
  121. setZero(m_impl->m_world_gravity);
  122. if (false == m_is_finalized)
  123. {
  124. bt_id_error_message("system has not been initialized\n");
  125. return -1;
  126. }
  127. if (-1 == m_impl->calculateKinematics(q, u, dot_u,
  128. MultiBodyTree::MultiBodyImpl::POSITION_VELOCITY_ACCELERATION))
  129. {
  130. bt_id_error_message("error in kinematics calculation\n");
  131. return -1;
  132. }
  133. m_impl->m_world_gravity = world_gravity;
  134. return 0;
  135. }
  136. int MultiBodyTree::calculatePositionKinematics(const vecx &q)
  137. {
  138. if (false == m_is_finalized)
  139. {
  140. bt_id_error_message("system has not been initialized\n");
  141. return -1;
  142. }
  143. if (-1 == m_impl->calculateKinematics(q, q, q,
  144. MultiBodyTree::MultiBodyImpl::POSITION_VELOCITY))
  145. {
  146. bt_id_error_message("error in kinematics calculation\n");
  147. return -1;
  148. }
  149. return 0;
  150. }
  151. int MultiBodyTree::calculatePositionAndVelocityKinematics(const vecx &q, const vecx &u)
  152. {
  153. if (false == m_is_finalized)
  154. {
  155. bt_id_error_message("system has not been initialized\n");
  156. return -1;
  157. }
  158. if (-1 == m_impl->calculateKinematics(q, u, u,
  159. MultiBodyTree::MultiBodyImpl::POSITION_VELOCITY))
  160. {
  161. bt_id_error_message("error in kinematics calculation\n");
  162. return -1;
  163. }
  164. return 0;
  165. }
  166. #if (defined BT_ID_HAVE_MAT3X) && (defined BT_ID_WITH_JACOBIANS)
  167. int MultiBodyTree::calculateJacobians(const vecx &q, const vecx &u)
  168. {
  169. if (false == m_is_finalized)
  170. {
  171. bt_id_error_message("system has not been initialized\n");
  172. return -1;
  173. }
  174. if (-1 == m_impl->calculateJacobians(q, u,
  175. MultiBodyTree::MultiBodyImpl::POSITION_VELOCITY))
  176. {
  177. bt_id_error_message("error in jacobian calculation\n");
  178. return -1;
  179. }
  180. return 0;
  181. }
  182. int MultiBodyTree::calculateJacobians(const vecx &q)
  183. {
  184. if (false == m_is_finalized)
  185. {
  186. bt_id_error_message("system has not been initialized\n");
  187. return -1;
  188. }
  189. if (-1 == m_impl->calculateJacobians(q, q,
  190. MultiBodyTree::MultiBodyImpl::POSITION_ONLY))
  191. {
  192. bt_id_error_message("error in jacobian calculation\n");
  193. return -1;
  194. }
  195. return 0;
  196. }
  197. int MultiBodyTree::getBodyDotJacobianTransU(const int body_index, vec3 *world_dot_jac_trans_u) const
  198. {
  199. return m_impl->getBodyDotJacobianTransU(body_index, world_dot_jac_trans_u);
  200. }
  201. int MultiBodyTree::getBodyDotJacobianRotU(const int body_index, vec3 *world_dot_jac_rot_u) const
  202. {
  203. return m_impl->getBodyDotJacobianRotU(body_index, world_dot_jac_rot_u);
  204. }
  205. int MultiBodyTree::getBodyJacobianTrans(const int body_index, mat3x *world_jac_trans) const
  206. {
  207. return m_impl->getBodyJacobianTrans(body_index, world_jac_trans);
  208. }
  209. int MultiBodyTree::getBodyJacobianRot(const int body_index, mat3x *world_jac_rot) const
  210. {
  211. return m_impl->getBodyJacobianRot(body_index, world_jac_rot);
  212. }
  213. #endif
  214. int MultiBodyTree::addBody(int body_index, int parent_index, JointType joint_type,
  215. const vec3 &parent_r_parent_body_ref, const mat33 &body_T_parent_ref,
  216. const vec3 &body_axis_of_motion_, idScalar mass,
  217. const vec3 &body_r_body_com, const mat33 &body_I_body,
  218. const int user_int, void *user_ptr)
  219. {
  220. if (body_index < 0)
  221. {
  222. bt_id_error_message("body index must be positive (got %d)\n", body_index);
  223. return -1;
  224. }
  225. vec3 body_axis_of_motion(body_axis_of_motion_);
  226. switch (joint_type)
  227. {
  228. case REVOLUTE:
  229. case PRISMATIC:
  230. // check if axis is unit vector
  231. if (!isUnitVector(body_axis_of_motion))
  232. {
  233. bt_id_warning_message(
  234. "axis of motion not a unit axis ([%f %f %f]), will use normalized vector\n",
  235. body_axis_of_motion(0), body_axis_of_motion(1), body_axis_of_motion(2));
  236. idScalar length = BT_ID_SQRT(BT_ID_POW(body_axis_of_motion(0), 2) +
  237. BT_ID_POW(body_axis_of_motion(1), 2) +
  238. BT_ID_POW(body_axis_of_motion(2), 2));
  239. if (length < BT_ID_SQRT(std::numeric_limits<idScalar>::min()))
  240. {
  241. bt_id_error_message("axis of motion vector too short (%e)\n", length);
  242. return -1;
  243. }
  244. body_axis_of_motion = (1.0 / length) * body_axis_of_motion;
  245. }
  246. break;
  247. case FIXED:
  248. break;
  249. case FLOATING:
  250. break;
  251. case SPHERICAL:
  252. break;
  253. default:
  254. bt_id_error_message("unknown joint type %d\n", joint_type);
  255. return -1;
  256. }
  257. // sanity check for mass properties. Zero mass is OK.
  258. if (mass < 0)
  259. {
  260. m_mass_parameters_are_valid = false;
  261. bt_id_error_message("Body %d has invalid mass %e\n", body_index, mass);
  262. if (!m_accept_invalid_mass_parameters)
  263. {
  264. return -1;
  265. }
  266. }
  267. if (!isValidInertiaMatrix(body_I_body, body_index, FIXED == joint_type))
  268. {
  269. m_mass_parameters_are_valid = false;
  270. // error message printed in function call
  271. if (!m_accept_invalid_mass_parameters)
  272. {
  273. return -1;
  274. }
  275. }
  276. if (!isValidTransformMatrix(body_T_parent_ref))
  277. {
  278. return -1;
  279. }
  280. return m_init_cache->addBody(body_index, parent_index, joint_type, parent_r_parent_body_ref,
  281. body_T_parent_ref, body_axis_of_motion, mass, body_r_body_com,
  282. body_I_body, user_int, user_ptr);
  283. }
  284. int MultiBodyTree::getParentIndex(const int body_index, int *parent_index) const
  285. {
  286. return m_impl->getParentIndex(body_index, parent_index);
  287. }
  288. int MultiBodyTree::getUserInt(const int body_index, int *user_int) const
  289. {
  290. return m_impl->getUserInt(body_index, user_int);
  291. }
  292. int MultiBodyTree::getUserPtr(const int body_index, void **user_ptr) const
  293. {
  294. return m_impl->getUserPtr(body_index, user_ptr);
  295. }
  296. int MultiBodyTree::setUserInt(const int body_index, const int user_int)
  297. {
  298. return m_impl->setUserInt(body_index, user_int);
  299. }
  300. int MultiBodyTree::setUserPtr(const int body_index, void *const user_ptr)
  301. {
  302. return m_impl->setUserPtr(body_index, user_ptr);
  303. }
  304. int MultiBodyTree::finalize()
  305. {
  306. const int &num_bodies = m_init_cache->numBodies();
  307. const int &num_dofs = m_init_cache->numDoFs();
  308. if (num_dofs < 0)
  309. {
  310. bt_id_error_message("Need num_dofs>=1, but num_dofs= %d\n", num_dofs);
  311. //return -1;
  312. }
  313. // 1 allocate internal MultiBody structure
  314. m_impl = new MultiBodyImpl(num_bodies, num_dofs);
  315. // 2 build new index set assuring index(parent) < index(child)
  316. if (-1 == m_init_cache->buildIndexSets())
  317. {
  318. return -1;
  319. }
  320. m_init_cache->getParentIndexArray(&m_impl->m_parent_index);
  321. // 3 setup internal kinematic and dynamic data
  322. for (int index = 0; index < num_bodies; index++)
  323. {
  324. InertiaData inertia;
  325. JointData joint;
  326. if (-1 == m_init_cache->getInertiaData(index, &inertia))
  327. {
  328. return -1;
  329. }
  330. if (-1 == m_init_cache->getJointData(index, &joint))
  331. {
  332. return -1;
  333. }
  334. RigidBody &rigid_body = m_impl->m_body_list[index];
  335. rigid_body.m_mass = inertia.m_mass;
  336. rigid_body.m_body_mass_com = inertia.m_mass * inertia.m_body_pos_body_com;
  337. rigid_body.m_body_I_body = inertia.m_body_I_body;
  338. rigid_body.m_joint_type = joint.m_type;
  339. rigid_body.m_parent_pos_parent_body_ref = joint.m_parent_pos_parent_child_ref;
  340. rigid_body.m_body_T_parent_ref = joint.m_child_T_parent_ref;
  341. rigid_body.m_parent_pos_parent_body_ref = joint.m_parent_pos_parent_child_ref;
  342. rigid_body.m_joint_type = joint.m_type;
  343. int user_int;
  344. if (-1 == m_init_cache->getUserInt(index, &user_int))
  345. {
  346. return -1;
  347. }
  348. if (-1 == m_impl->setUserInt(index, user_int))
  349. {
  350. return -1;
  351. }
  352. void *user_ptr;
  353. if (-1 == m_init_cache->getUserPtr(index, &user_ptr))
  354. {
  355. return -1;
  356. }
  357. if (-1 == m_impl->setUserPtr(index, user_ptr))
  358. {
  359. return -1;
  360. }
  361. // Set joint Jacobians. Note that the dimension is always 3x1 here to avoid variable sized
  362. // matrices.
  363. switch (rigid_body.m_joint_type)
  364. {
  365. case REVOLUTE:
  366. rigid_body.m_Jac_JR(0) = joint.m_child_axis_of_motion(0);
  367. rigid_body.m_Jac_JR(1) = joint.m_child_axis_of_motion(1);
  368. rigid_body.m_Jac_JR(2) = joint.m_child_axis_of_motion(2);
  369. rigid_body.m_Jac_JT(0) = 0.0;
  370. rigid_body.m_Jac_JT(1) = 0.0;
  371. rigid_body.m_Jac_JT(2) = 0.0;
  372. break;
  373. case PRISMATIC:
  374. rigid_body.m_Jac_JR(0) = 0.0;
  375. rigid_body.m_Jac_JR(1) = 0.0;
  376. rigid_body.m_Jac_JR(2) = 0.0;
  377. rigid_body.m_Jac_JT(0) = joint.m_child_axis_of_motion(0);
  378. rigid_body.m_Jac_JT(1) = joint.m_child_axis_of_motion(1);
  379. rigid_body.m_Jac_JT(2) = joint.m_child_axis_of_motion(2);
  380. break;
  381. case FIXED:
  382. // NOTE/TODO: dimension really should be zero ..
  383. rigid_body.m_Jac_JR(0) = 0.0;
  384. rigid_body.m_Jac_JR(1) = 0.0;
  385. rigid_body.m_Jac_JR(2) = 0.0;
  386. rigid_body.m_Jac_JT(0) = 0.0;
  387. rigid_body.m_Jac_JT(1) = 0.0;
  388. rigid_body.m_Jac_JT(2) = 0.0;
  389. break;
  390. case SPHERICAL:
  391. // NOTE/TODO: this is not really correct.
  392. // the Jacobians should be 3x3 matrices here !
  393. rigid_body.m_Jac_JR(0) = 0.0;
  394. rigid_body.m_Jac_JR(1) = 0.0;
  395. rigid_body.m_Jac_JR(2) = 0.0;
  396. rigid_body.m_Jac_JT(0) = 0.0;
  397. rigid_body.m_Jac_JT(1) = 0.0;
  398. rigid_body.m_Jac_JT(2) = 0.0;
  399. break;
  400. case FLOATING:
  401. // NOTE/TODO: this is not really correct.
  402. // the Jacobians should be 3x3 matrices here !
  403. rigid_body.m_Jac_JR(0) = 0.0;
  404. rigid_body.m_Jac_JR(1) = 0.0;
  405. rigid_body.m_Jac_JR(2) = 0.0;
  406. rigid_body.m_Jac_JT(0) = 0.0;
  407. rigid_body.m_Jac_JT(1) = 0.0;
  408. rigid_body.m_Jac_JT(2) = 0.0;
  409. break;
  410. default:
  411. bt_id_error_message("unsupported joint type %d\n", rigid_body.m_joint_type);
  412. return -1;
  413. }
  414. }
  415. // 4 assign degree of freedom indices & build per-joint-type index arrays
  416. if (-1 == m_impl->generateIndexSets())
  417. {
  418. bt_id_error_message("generating index sets\n");
  419. return -1;
  420. }
  421. // 5 do some pre-computations ..
  422. m_impl->calculateStaticData();
  423. // 6. make sure all user forces are set to zero, as this might not happen
  424. // in the vector ctors.
  425. m_impl->clearAllUserForcesAndMoments();
  426. m_is_finalized = true;
  427. return 0;
  428. }
  429. int MultiBodyTree::setGravityInWorldFrame(const vec3 &gravity)
  430. {
  431. return m_impl->setGravityInWorldFrame(gravity);
  432. }
  433. int MultiBodyTree::getJointType(const int body_index, JointType *joint_type) const
  434. {
  435. return m_impl->getJointType(body_index, joint_type);
  436. }
  437. int MultiBodyTree::getJointTypeStr(const int body_index, const char **joint_type) const
  438. {
  439. return m_impl->getJointTypeStr(body_index, joint_type);
  440. }
  441. int MultiBodyTree::getDoFOffset(const int body_index, int *q_offset) const
  442. {
  443. return m_impl->getDoFOffset(body_index, q_offset);
  444. }
  445. int MultiBodyTree::setBodyMass(const int body_index, idScalar mass)
  446. {
  447. return m_impl->setBodyMass(body_index, mass);
  448. }
  449. int MultiBodyTree::setBodyFirstMassMoment(const int body_index, const vec3 &first_mass_moment)
  450. {
  451. return m_impl->setBodyFirstMassMoment(body_index, first_mass_moment);
  452. }
  453. int MultiBodyTree::setBodySecondMassMoment(const int body_index, const mat33 &second_mass_moment)
  454. {
  455. return m_impl->setBodySecondMassMoment(body_index, second_mass_moment);
  456. }
  457. int MultiBodyTree::getBodyMass(const int body_index, idScalar *mass) const
  458. {
  459. return m_impl->getBodyMass(body_index, mass);
  460. }
  461. int MultiBodyTree::getBodyFirstMassMoment(const int body_index, vec3 *first_mass_moment) const
  462. {
  463. return m_impl->getBodyFirstMassMoment(body_index, first_mass_moment);
  464. }
  465. int MultiBodyTree::getBodySecondMassMoment(const int body_index, mat33 *second_mass_moment) const
  466. {
  467. return m_impl->getBodySecondMassMoment(body_index, second_mass_moment);
  468. }
  469. void MultiBodyTree::clearAllUserForcesAndMoments() { m_impl->clearAllUserForcesAndMoments(); }
  470. int MultiBodyTree::addUserForce(const int body_index, const vec3 &body_force)
  471. {
  472. return m_impl->addUserForce(body_index, body_force);
  473. }
  474. int MultiBodyTree::addUserMoment(const int body_index, const vec3 &body_moment)
  475. {
  476. return m_impl->addUserMoment(body_index, body_moment);
  477. }
  478. } // namespace btInverseDynamics