Template Function pinocchio::computeJointTorqueRegressor

Function Documentation

template<typename Scalar, int Options, template<typename, int> class JointCollectionTpl, typename ConfigVectorType, typename TangentVectorType1, typename TangentVectorType2>
inline DataTpl<Scalar, Options, JointCollectionTpl>::MatrixXs &pinocchio::computeJointTorqueRegressor(const ModelTpl<Scalar, Options, JointCollectionTpl> &model, DataTpl<Scalar, Options, JointCollectionTpl> &data, const Eigen::MatrixBase<ConfigVectorType> &q, const Eigen::MatrixBase<TangentVectorType1> &v, const Eigen::MatrixBase<TangentVectorType2> &a)

Computes the joint torque regressor that links the joint torque to the dynamic parameters of each link according to the current the robot motion.

The result is stored in data.jointTorqueRegressor and it corresponds to a matrix \( Y \) such that \( \tau = Y(q,\dot{q},\ddot{q})\pi \) where \( \pi = (\pi_1^T\ \dots\ \pi_n^T)^T \) and \( \pi_i = \text{model.inertias[i].toDynamicParameters()} \)

Warning

This function writes temporary information in data.bodyRegressor. This means if you have valuable data in it it will be overwritten.

Template Parameters:
  • JointCollection – Collection of Joint types.

  • ConfigVectorType – Type of the joint configuration vector.

  • TangentVectorType1 – Type of the joint velocity vector.

  • TangentVectorType2 – Type of the joint acceleration vector.

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

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

  • q[in] The joint configuration vector (dim model.nq).

  • v[in] The joint velocity vector (dim model.nv).

  • a[in] The joint acceleration vector (dim model.nv).

Returns:

The joint torque regressor of the system.