MultiBodyTree.hpp 17 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367
  1. #ifndef MULTIBODYTREE_HPP_
  2. #define MULTIBODYTREE_HPP_
  3. #include "IDConfig.hpp"
  4. #include "IDMath.hpp"
  5. namespace btInverseDynamics
  6. {
  7. /// Enumeration of supported joint types
  8. enum JointType
  9. {
  10. /// no degree of freedom, moves with parent
  11. FIXED = 0,
  12. /// one rotational degree of freedom relative to parent
  13. REVOLUTE,
  14. /// one translational degree of freedom relative to parent
  15. PRISMATIC,
  16. /// six degrees of freedom relative to parent
  17. FLOATING,
  18. /// three degrees of freedom, relative to parent
  19. SPHERICAL
  20. };
  21. /// Interface class for calculating inverse dynamics for tree structured
  22. /// multibody systems
  23. ///
  24. /// Note on degrees of freedom
  25. /// The q vector contains the generalized coordinate set defining the tree's configuration.
  26. /// Every joint adds elements that define the corresponding link's frame pose relative to
  27. /// its parent. For the joint types that is:
  28. /// - FIXED: none
  29. /// - REVOLUTE: angle of rotation [rad]
  30. /// - PRISMATIC: displacement [m]
  31. /// - FLOATING: Euler x-y-z angles [rad] and displacement in body-fixed frame of parent [m]
  32. /// (in that order)
  33. /// - SPHERICAL: Euler x-y-z angles [rad]
  34. /// The u vector contains the generalized speeds, which are
  35. /// - FIXED: none
  36. /// - REVOLUTE: time derivative of angle of rotation [rad/s]
  37. /// - PRISMATIC: time derivative of displacement [m/s]
  38. /// - FLOATING: angular velocity [rad/s] (*not* time derivative of rpy angles)
  39. /// and time derivative of displacement in parent frame [m/s]
  40. // - SPHERICAL: angular velocity [rad/s]
  41. ///
  42. /// The q and u vectors are obtained by stacking contributions of all bodies in one
  43. /// vector in the order of body indices.
  44. ///
  45. /// Note on generalized forces: analogous to u, i.e.,
  46. /// - FIXED: none
  47. /// - REVOLUTE: moment [Nm], about joint axis
  48. /// - PRISMATIC: force [N], along joint axis
  49. /// - FLOATING: moment vector [Nm] and force vector [N], both in body-fixed frame
  50. /// (in that order)
  51. /// - SPHERICAL: moment vector [Nm]
  52. /// TODO - force element interface (friction, springs, dampers, etc)
  53. /// - gears and motor inertia
  54. class MultiBodyTree
  55. {
  56. public:
  57. ID_DECLARE_ALIGNED_ALLOCATOR();
  58. /// The contructor.
  59. /// Initialization & allocation is via addBody and buildSystem calls.
  60. MultiBodyTree();
  61. /// the destructor. This also deallocates all memory
  62. ~MultiBodyTree();
  63. /// Add body to the system. this allocates memory and not real-time safe.
  64. /// This only adds the data to an initial cache. After all bodies have been
  65. /// added,
  66. /// the system is setup using the buildSystem call
  67. /// @param body_index index of the body to be added. Must >=0, <number of bodies,
  68. /// and index of parent must be < index of body
  69. /// @param parent_index index of the parent body
  70. /// The root of the tree has index 0 and its parent (the world frame)
  71. /// is assigned index -1
  72. /// the rotation and translation relative to the parent are taken as
  73. /// pose of the root body relative to the world frame. Other parameters
  74. /// are ignored
  75. /// @param JointType type of joint connecting the body to the parent
  76. /// @param mass the mass of the body
  77. /// @param body_r_body_com the center of mass of the body relative to and
  78. /// described in
  79. /// the body fixed frame, which is located in the joint axis connecting
  80. /// the body to its parent
  81. /// @param body_I_body the moment of inertia of the body w.r.t the body-fixed
  82. /// frame
  83. /// (ie, the reference point is the origin of the body-fixed frame and
  84. /// the matrix is written
  85. /// w.r.t. those unit vectors)
  86. /// @param parent_r_parent_body_ref position of joint relative to the parent
  87. /// body's reference frame
  88. /// for q=0, written in the parent bodies reference frame
  89. /// @param body_axis_of_motion translation/rotation axis in body-fixed frame.
  90. /// Ignored for joints that are not revolute or prismatic.
  91. /// must be a unit vector.
  92. /// @param body_T_parent_ref transform matrix from parent to body reference
  93. /// frame for q=0.
  94. /// This is the matrix transforming a vector represented in the
  95. /// parent's reference frame into one represented
  96. /// in this body's reference frame.
  97. /// ie, if parent_vec is a vector in R^3 whose components are w.r.t to
  98. /// the parent's reference frame,
  99. /// then the same vector written w.r.t. this body's frame (for q=0) is
  100. /// given by
  101. /// body_vec = parent_R_body_ref * parent_vec
  102. /// @param user_ptr pointer to user data
  103. /// @param user_int pointer to user integer
  104. /// @return 0 on success, -1 on error
  105. int addBody(int body_index, int parent_index, JointType joint_type,
  106. const vec3& parent_r_parent_body_ref, const mat33& body_T_parent_ref,
  107. const vec3& body_axis_of_motion, idScalar mass, const vec3& body_r_body_com,
  108. const mat33& body_I_body, const int user_int, void* user_ptr);
  109. /// set policy for invalid mass properties
  110. /// @param flag if true, invalid mass properties are accepted,
  111. /// the default is false
  112. void setAcceptInvalidMassParameters(bool flag);
  113. /// @return the mass properties policy flag
  114. bool getAcceptInvalidMassProperties() const;
  115. /// build internal data structures
  116. /// call this after all bodies have been added via addBody
  117. /// @return 0 on success, -1 on error
  118. int finalize();
  119. /// pretty print ascii description of tree to stdout
  120. void printTree();
  121. /// print tree data to stdout
  122. void printTreeData();
  123. /// Calculate joint forces for given generalized state & derivatives.
  124. /// This also updates kinematic terms computed in calculateKinematics.
  125. /// If gravity is not set to zero, acceleration terms will contain
  126. /// gravitational acceleration.
  127. /// @param q generalized coordinates
  128. /// @param u generalized velocities. In the general case, u=T(q)*dot(q) and dim(q)>=dim(u)
  129. /// @param dot_u time derivative of u
  130. /// @param joint_forces this is where the resulting joint forces will be
  131. /// stored. dim(joint_forces) = dim(u)
  132. /// @return 0 on success, -1 on error
  133. int calculateInverseDynamics(const vecx& q, const vecx& u, const vecx& dot_u,
  134. vecx* joint_forces);
  135. /// Calculate joint space mass matrix
  136. /// @param q generalized coordinates
  137. /// @param initialize_matrix if true, initialize mass matrix with zero.
  138. /// If mass_matrix is initialized to zero externally and only used
  139. /// for mass matrix computations for the same system, it is safe to
  140. /// set this to false.
  141. /// @param set_lower_triangular_matrix if true, the lower triangular section of mass_matrix
  142. /// is also populated, otherwise not.
  143. /// @param mass_matrix matrix for storing the output (should be dim(q)xdim(q))
  144. /// @return -1 on error, 0 on success
  145. int calculateMassMatrix(const vecx& q, const bool update_kinematics,
  146. const bool initialize_matrix, const bool set_lower_triangular_matrix,
  147. matxx* mass_matrix);
  148. /// Calculate joint space mass matrix.
  149. /// This version will update kinematics, initialize all mass_matrix elements to zero and
  150. /// populate all mass matrix entries.
  151. /// @param q generalized coordinates
  152. /// @param mass_matrix matrix for storing the output (should be dim(q)xdim(q))
  153. /// @return -1 on error, 0 on success
  154. int calculateMassMatrix(const vecx& q, matxx* mass_matrix);
  155. /// Calculates kinematics also calculated in calculateInverseDynamics,
  156. /// but not dynamics.
  157. /// This function ensures that correct accelerations are computed that do not
  158. /// contain gravitational acceleration terms.
  159. /// Does not calculate Jacobians, but only vector quantities (positions, velocities & accelerations)
  160. int calculateKinematics(const vecx& q, const vecx& u, const vecx& dot_u);
  161. /// Calculate position kinematics
  162. int calculatePositionKinematics(const vecx& q);
  163. /// Calculate position and velocity kinematics
  164. int calculatePositionAndVelocityKinematics(const vecx& q, const vecx& u);
  165. #if (defined BT_ID_HAVE_MAT3X) && (defined BT_ID_WITH_JACOBIANS)
  166. /// Calculate Jacobians (dvel/du), as well as velocity-dependent accelearation components
  167. /// d(Jacobian)/dt*u
  168. /// This function assumes that calculateInverseDynamics was called, or calculateKinematics,
  169. /// or calculatePositionAndVelocityKinematics
  170. int calculateJacobians(const vecx& q, const vecx& u);
  171. /// Calculate Jacobians (dvel/du)
  172. /// This function assumes that calculateInverseDynamics was called, or
  173. /// one of the calculateKineamtics functions
  174. int calculateJacobians(const vecx& q);
  175. #endif // BT_ID_HAVE_MAT3X
  176. /// set gravitational acceleration
  177. /// the default is [0;0;-9.8] in the world frame
  178. /// @param gravity the gravitational acceleration in world frame
  179. /// @return 0 on success, -1 on error
  180. int setGravityInWorldFrame(const vec3& gravity);
  181. /// returns number of bodies in tree
  182. int numBodies() const;
  183. /// returns number of mechanical degrees of freedom (dimension of q-vector)
  184. int numDoFs() const;
  185. /// get origin of a body-fixed frame, represented in world frame
  186. /// @param body_index index for frame/body
  187. /// @param world_origin pointer for return data
  188. /// @return 0 on success, -1 on error
  189. int getBodyOrigin(const int body_index, vec3* world_origin) const;
  190. /// get center of mass of a body, represented in world frame
  191. /// @param body_index index for frame/body
  192. /// @param world_com pointer for return data
  193. /// @return 0 on success, -1 on error
  194. int getBodyCoM(const int body_index, vec3* world_com) const;
  195. /// get transform from of a body-fixed frame to the world frame
  196. /// @param body_index index for frame/body
  197. /// @param world_T_body pointer for return data
  198. /// @return 0 on success, -1 on error
  199. int getBodyTransform(const int body_index, mat33* world_T_body) const;
  200. /// get absolute angular velocity for a body, represented in the world frame
  201. /// @param body_index index for frame/body
  202. /// @param world_omega pointer for return data
  203. /// @return 0 on success, -1 on error
  204. int getBodyAngularVelocity(const int body_index, vec3* world_omega) const;
  205. /// get linear velocity of a body, represented in world frame
  206. /// @param body_index index for frame/body
  207. /// @param world_velocity pointer for return data
  208. /// @return 0 on success, -1 on error
  209. int getBodyLinearVelocity(const int body_index, vec3* world_velocity) const;
  210. /// get linear velocity of a body's CoM, represented in world frame
  211. /// (not required for inverse dynamics, provided for convenience)
  212. /// @param body_index index for frame/body
  213. /// @param world_vel_com pointer for return data
  214. /// @return 0 on success, -1 on error
  215. int getBodyLinearVelocityCoM(const int body_index, vec3* world_velocity) const;
  216. /// get origin of a body-fixed frame, represented in world frame
  217. /// @param body_index index for frame/body
  218. /// @param world_origin pointer for return data
  219. /// @return 0 on success, -1 on error
  220. int getBodyAngularAcceleration(const int body_index, vec3* world_dot_omega) const;
  221. /// get origin of a body-fixed frame, represented in world frame
  222. /// NOTE: this will include the gravitational acceleration, so the actual acceleration is
  223. /// obtainened by setting gravitational acceleration to zero, or subtracting it.
  224. /// @param body_index index for frame/body
  225. /// @param world_origin pointer for return data
  226. /// @return 0 on success, -1 on error
  227. int getBodyLinearAcceleration(const int body_index, vec3* world_acceleration) const;
  228. #if (defined BT_ID_HAVE_MAT3X) && (defined BT_ID_WITH_JACOBIANS)
  229. // get translational jacobian, in world frame (dworld_velocity/du)
  230. int getBodyJacobianTrans(const int body_index, mat3x* world_jac_trans) const;
  231. // get rotational jacobian, in world frame (dworld_omega/du)
  232. int getBodyJacobianRot(const int body_index, mat3x* world_jac_rot) const;
  233. // get product of translational jacobian derivative * generatlized velocities
  234. int getBodyDotJacobianTransU(const int body_index, vec3* world_dot_jac_trans_u) const;
  235. // get product of rotational jacobian derivative * generatlized velocities
  236. int getBodyDotJacobianRotU(const int body_index, vec3* world_dot_jac_rot_u) const;
  237. #endif // BT_ID_HAVE_MAT3X
  238. /// returns the (internal) index of body
  239. /// @param body_index is the index of a body
  240. /// @param parent_index pointer to where parent index will be stored
  241. /// @return 0 on success, -1 on error
  242. int getParentIndex(const int body_index, int* parent_index) const;
  243. /// get joint type
  244. /// @param body_index index of the body
  245. /// @param joint_type the corresponding joint type
  246. /// @return 0 on success, -1 on failure
  247. int getJointType(const int body_index, JointType* joint_type) const;
  248. /// get joint type as string
  249. /// @param body_index index of the body
  250. /// @param joint_type string naming the corresponding joint type
  251. /// @return 0 on success, -1 on failure
  252. int getJointTypeStr(const int body_index, const char** joint_type) const;
  253. /// get offset translation to parent body (see addBody)
  254. /// @param body_index index of the body
  255. /// @param r the offset translation (see above)
  256. /// @return 0 on success, -1 on failure
  257. int getParentRParentBodyRef(const int body_index, vec3* r) const;
  258. /// get offset rotation to parent body (see addBody)
  259. /// @param body_index index of the body
  260. /// @param T the transform (see above)
  261. /// @return 0 on success, -1 on failure
  262. int getBodyTParentRef(const int body_index, mat33* T) const;
  263. /// get axis of motion (see addBody)
  264. /// @param body_index index of the body
  265. /// @param axis the axis (see above)
  266. /// @return 0 on success, -1 on failure
  267. int getBodyAxisOfMotion(const int body_index, vec3* axis) const;
  268. /// get offset for degrees of freedom of this body into the q-vector
  269. /// @param body_index index of the body
  270. /// @param q_offset offset the q vector
  271. /// @return -1 on error, 0 on success
  272. int getDoFOffset(const int body_index, int* q_offset) const;
  273. /// get user integer. not used by the library.
  274. /// @param body_index index of the body
  275. /// @param user_int the user integer
  276. /// @return 0 on success, -1 on error
  277. int getUserInt(const int body_index, int* user_int) const;
  278. /// get user pointer. not used by the library.
  279. /// @param body_index index of the body
  280. /// @param user_ptr the user pointer
  281. /// @return 0 on success, -1 on error
  282. int getUserPtr(const int body_index, void** user_ptr) const;
  283. /// set user integer. not used by the library.
  284. /// @param body_index index of the body
  285. /// @param user_int the user integer
  286. /// @return 0 on success, -1 on error
  287. int setUserInt(const int body_index, const int user_int);
  288. /// set user pointer. not used by the library.
  289. /// @param body_index index of the body
  290. /// @param user_ptr the user pointer
  291. /// @return 0 on success, -1 on error
  292. int setUserPtr(const int body_index, void* const user_ptr);
  293. /// set mass for a body
  294. /// @param body_index index of the body
  295. /// @param mass the mass to set
  296. /// @return 0 on success, -1 on failure
  297. int setBodyMass(const int body_index, const idScalar mass);
  298. /// set first moment of mass for a body
  299. /// (mass * center of mass, in body fixed frame, relative to joint)
  300. /// @param body_index index of the body
  301. /// @param first_mass_moment the vector to set
  302. /// @return 0 on success, -1 on failure
  303. int setBodyFirstMassMoment(const int body_index, const vec3& first_mass_moment);
  304. /// set second moment of mass for a body
  305. /// (moment of inertia, in body fixed frame, relative to joint)
  306. /// @param body_index index of the body
  307. /// @param second_mass_moment the inertia matrix
  308. /// @return 0 on success, -1 on failure
  309. int setBodySecondMassMoment(const int body_index, const mat33& second_mass_moment);
  310. /// get mass for a body
  311. /// @param body_index index of the body
  312. /// @param mass the mass
  313. /// @return 0 on success, -1 on failure
  314. int getBodyMass(const int body_index, idScalar* mass) const;
  315. /// get first moment of mass for a body
  316. /// (mass * center of mass, in body fixed frame, relative to joint)
  317. /// @param body_index index of the body
  318. /// @param first_moment the vector
  319. /// @return 0 on success, -1 on failure
  320. int getBodyFirstMassMoment(const int body_index, vec3* first_mass_moment) const;
  321. /// get second moment of mass for a body
  322. /// (moment of inertia, in body fixed frame, relative to joint)
  323. /// @param body_index index of the body
  324. /// @param second_mass_moment the inertia matrix
  325. /// @return 0 on success, -1 on failure
  326. int getBodySecondMassMoment(const int body_index, mat33* second_mass_moment) const;
  327. /// set all user forces and moments to zero
  328. void clearAllUserForcesAndMoments();
  329. /// Add an external force to a body, acting at the origin of the body-fixed frame.
  330. /// Calls to addUserForce are cumulative. Set the user force and moment to zero
  331. /// via clearAllUserForcesAndMoments()
  332. /// @param body_force the force represented in the body-fixed frame of reference
  333. /// @return 0 on success, -1 on error
  334. int addUserForce(const int body_index, const vec3& body_force);
  335. /// Add an external moment to a body.
  336. /// Calls to addUserMoment are cumulative. Set the user force and moment to zero
  337. /// via clearAllUserForcesAndMoments()
  338. /// @param body_moment the moment represented in the body-fixed frame of reference
  339. /// @return 0 on success, -1 on error
  340. int addUserMoment(const int body_index, const vec3& body_moment);
  341. private:
  342. // flag indicating if system has been initialized
  343. bool m_is_finalized;
  344. // flag indicating if mass properties are physically valid
  345. bool m_mass_parameters_are_valid;
  346. // flag defining if unphysical mass parameters are accepted
  347. bool m_accept_invalid_mass_parameters;
  348. // This struct implements the inverse dynamics calculations
  349. class MultiBodyImpl;
  350. MultiBodyImpl* m_impl;
  351. // cache data structure for initialization
  352. class InitCache;
  353. InitCache* m_init_cache;
  354. };
  355. } // namespace btInverseDynamics
  356. #endif // MULTIBODYTREE_HPP_