MultiBodyTree.cpp 15 KB

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