|
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename ConfigVectorType , typename TangentVectorType1 , typename TangentVectorType2 , typename ForceDerived > |
const DataTpl< Scalar, Options, JointCollectionTpl >::TangentVectorType & | pinocchio::aba (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 > &tau, const container::aligned_vector< ForceDerived > &fext, const Convention rf=Convention::LOCAL) |
| The Articulated-Body algorithm. It computes the forward dynamics, aka the joint accelerations given the current state and actuation of the model and the external forces. More...
|
|
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename ConfigVectorType , typename TangentVectorType1 , typename TangentVectorType2 > |
const DataTpl< Scalar, Options, JointCollectionTpl >::TangentVectorType & | pinocchio::aba (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 > &tau, const Convention convention=Convention::LOCAL) |
| The Articulated-Body algorithm. It computes the forward dynamics, aka the joint accelerations given the current state and actuation of the model. More...
|
|
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl> |
const DataTpl< Scalar, Options, JointCollectionTpl >::RowMatrixXs & | pinocchio::computeMinverse (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data) |
| Computes the inverse of the joint space inertia matrix using Articulated Body formulation. Compared to the complete signature computeMinverse<Scalar,Options,ConfigVectorType>, this version assumes that ABA has been called first. More...
|
|
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename ConfigVectorType > |
const DataTpl< Scalar, Options, JointCollectionTpl >::RowMatrixXs & | pinocchio::computeMinverse (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q) |
| Computes the inverse of the joint space inertia matrix using Articulated Body formulation. More...
|
|
| pinocchio::PINOCCHIO_DEFINE_ALGO_CHECKER (ABA) |
|