Template Function pinocchio::rnea(const ModelTpl<Scalar, Options, JointCollectionTpl>&, DataTpl<Scalar, Options, JointCollectionTpl>&, const Eigen::MatrixBase<ConfigVectorType>&, const Eigen::MatrixBase<TangentVectorType1>&, const Eigen::MatrixBase<TangentVectorType2>&, const container::aligned_vector<ForceDerived>&)
Defined in File rnea.hpp
Function Documentation
-
template<typename Scalar, int Options, template<typename, int> class JointCollectionTpl, typename ConfigVectorType, typename TangentVectorType1, typename TangentVectorType2, typename ForceDerived>
inline const DataTpl<Scalar, Options, JointCollectionTpl>::TangentVectorType &pinocchio::rnea(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, const container::aligned_vector<ForceDerived> &fext) The Recursive Newton-Euler algorithm. It computes the inverse dynamics, aka the joint torques according to the current state of the system, the desired joint accelerations and the external forces.
- 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.
ForceDerived – Type of the external forces.
- 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).
fext – [in] Vector of external forces expressed in the local frame of the joints (dim model.njoints)
- Returns:
The desired joint torques stored in data.tau.