Template Function pinocchio::centerOfMass(const ModelTpl<Scalar, Options, JointCollectionTpl>&, DataTpl<Scalar, Options, JointCollectionTpl>&, const bool)

Function Documentation

template<typename Scalar, int Options, template<typename, int> class JointCollectionTpl>
const DataTpl<Scalar, Options, JointCollectionTpl>::Vector3 &pinocchio::centerOfMass(const ModelTpl<Scalar, Options, JointCollectionTpl> &model, DataTpl<Scalar, Options, JointCollectionTpl> &data, const bool computeSubtreeComs = true)

Computes the center of mass position, velocity and acceleration of a given model according to the current kinematic values contained in data. The result is accessible through data.com[0], data.vcom[0] and data.acom[0] for the full body com position and velocity. And data.com[i] and data.vcom[i] for the subtree supported by joint i (expressed in the joint i frame).

Template Parameters:

JointCollection – Collection of Joint types.

Parameters:
  • model[in] The model structure of the rigid body system.

  • data[in] The data structure of the rigid body system.

  • computeSubtreeComs[in] If true, the algorithm computes also the center of mass of the subtrees, expressed in the local coordinate frame of each joint.