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

Function Documentation

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

Computes both the jacobian and the the center of mass position of a given model according to the current value stored in data. It assumes that forwardKinematics has been called first. The results are accessible through data.Jcom and data.com[0] and are both expressed in the world frame. In addition, the algorithm also computes the Jacobian of all the joints (.

See also

pinocchio::computeJointJacobians). And data.com[i] gives the center of mass of the subtree supported by joint i (expressed in the world frame).

Template Parameters:
  • JointCollection – Collection of Joint types.

  • ConfigVectorType – Type of the joint configuration vector.

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 also computes the center of mass of the subtrees, expressed in the world coordinate frame.

Returns:

The jacobian of center of mass position of the rigid body system expressed in the world frame (matrix 3 x model.nv).