5 #ifndef __pinocchio_algorithm_aba_hpp__
6 #define __pinocchio_algorithm_aba_hpp__
8 #include "pinocchio/multibody/model.hpp"
9 #include "pinocchio/multibody/data.hpp"
10 #include "pinocchio/algorithm/check.hpp"
37 template<
typename,
int>
class JointCollectionTpl,
38 typename ConfigVectorType,
39 typename TangentVectorType1,
40 typename TangentVectorType2>
44 const Eigen::MatrixBase<ConfigVectorType> & q,
45 const Eigen::MatrixBase<TangentVectorType1> & v,
46 const Eigen::MatrixBase<TangentVectorType2> & tau,
74 template<
typename,
int>
class JointCollectionTpl,
75 typename ConfigVectorType,
76 typename TangentVectorType1,
77 typename TangentVectorType2,
78 typename ForceDerived>
82 const Eigen::MatrixBase<ConfigVectorType> & q,
83 const Eigen::MatrixBase<TangentVectorType1> & v,
84 const Eigen::MatrixBase<TangentVectorType2> & tau,
85 const container::aligned_vector<ForceDerived> & fext,
104 template<
typename,
int>
class JointCollectionTpl,
105 typename ConfigVectorType>
106 const typename DataTpl<Scalar, Options, JointCollectionTpl>::RowMatrixXs &
computeMinverse(
109 const Eigen::MatrixBase<ConfigVectorType> & q);
124 template<
typename Scalar,
int Options,
template<
typename,
int>
class JointCollectionTpl>
125 const typename DataTpl<Scalar, Options, JointCollectionTpl>::RowMatrixXs &
computeMinverse(
129 PINOCCHIO_DEFINE_ALGO_CHECKER(ABA);
134 #include "pinocchio/algorithm/aba.hxx"
136 #if PINOCCHIO_ENABLE_TEMPLATE_INSTANTIATION
137 #include "pinocchio/algorithm/aba.txx"
Convention
List of convention to call algorithms.
Main pinocchio namespace.
const DataTpl< Scalar, Options, JointCollectionTpl >::TangentVectorType & 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 t...
const DataTpl< Scalar, Options, JointCollectionTpl >::RowMatrixXs & 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.
VectorXs TangentVectorType
Dense vectorized version of a joint tangent vector (e.g. velocity, acceleration, etc)....