Template Function pinocchio::rnea(const int, ModelPoolTpl<Scalar, Options, JointCollectionTpl>&, const Eigen::MatrixBase<ConfigVectorPool>&, const Eigen::MatrixBase<TangentVectorPool1>&, const Eigen::MatrixBase<TangentVectorPool2>&, const Eigen::MatrixBase<TangentVectorPool3>&)

Function Documentation

template<typename Scalar, int Options, template<typename, int> class JointCollectionTpl, typename ConfigVectorPool, typename TangentVectorPool1, typename TangentVectorPool2, typename TangentVectorPool3>
void pinocchio::rnea(const int num_threads, ModelPoolTpl<Scalar, Options, JointCollectionTpl> &pool, const Eigen::MatrixBase<ConfigVectorPool> &q, const Eigen::MatrixBase<TangentVectorPool1> &v, const Eigen::MatrixBase<TangentVectorPool2> &a, const Eigen::MatrixBase<TangentVectorPool3> &tau)

The Recursive Newton-Euler algorithm. It computes the inverse dynamics, aka the joint torques according to the current state of the system and the desired joint accelerations.

Template Parameters:
  • JointCollection – Collection of Joint types.

  • ConfigVectorPool – Matrix type of the joint configuration vector.

  • TangentVectorPool1 – Matrix type of the joint velocity vector.

  • TangentVectorPool2 – Matrix type of the joint acceleration vector.

  • TangentVectorPool3 – Matrix type of the joint torque vector.

Parameters:
  • pool[in] Pool containing model and data for parallel computations.

  • num_threads[in] Number of threads used for parallel computations.

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

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

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

  • tau[out] The joint torque vector (dim model.nv x batch_size).