5 #ifndef __pinocchio_aba_hpp__ 6 #define __pinocchio_aba_hpp__ 8 #include "pinocchio/multibody/model.hpp" 9 #include "pinocchio/multibody/data.hpp" 10 #include "pinocchio/algorithm/check.hpp" 30 template<
typename Scalar,
int Options,
template<
typename,
int>
class JointCollectionTpl,
typename ConfigVectorType,
typename TangentVectorType1,
typename TangentVectorType2>
32 aba(
const ModelTpl<Scalar,Options,JointCollectionTpl> & model,
33 DataTpl<Scalar,Options,JointCollectionTpl> & data,
34 const Eigen::MatrixBase<ConfigVectorType> & q,
35 const Eigen::MatrixBase<TangentVectorType1> & v,
36 const Eigen::MatrixBase<TangentVectorType2> & tau);
56 template<
typename Scalar,
int Options,
template<
typename,
int>
class JointCollectionTpl,
typename ConfigVectorType,
typename TangentVectorType1,
typename TangentVectorType2,
typename ForceDerived>
58 aba(
const ModelTpl<Scalar,Options,JointCollectionTpl> & model,
59 DataTpl<Scalar,Options,JointCollectionTpl> & data,
60 const Eigen::MatrixBase<ConfigVectorType> & q,
61 const Eigen::MatrixBase<TangentVectorType1> & v,
62 const Eigen::MatrixBase<TangentVectorType2> & tau,
63 const container::aligned_vector<ForceDerived> & fext);
77 template<
typename Scalar,
int Options,
template<
typename,
int>
class JointCollectionTpl,
typename ConfigVectorType>
78 inline const typename DataTpl<Scalar,Options,JointCollectionTpl>::RowMatrixXs &
79 computeMinverse(
const ModelTpl<Scalar,Options,JointCollectionTpl> & model,
80 DataTpl<Scalar,Options,JointCollectionTpl> & data,
81 const Eigen::MatrixBase<ConfigVectorType> & q);
84 PINOCCHIO_DEFINE_ALGO_CHECKER(ABA);
89 #include "pinocchio/algorithm/aba.hxx" 91 #endif // ifndef __pinocchio_aba_hpp__ 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)
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). It also handles the notion of co-tangent vector (e.g. torque, etc).
Main pinocchio namespace.