pinocchio  2.7.1
A fast and flexible implementation of Rigid Body Dynamics algorithms and their analytical derivatives
aba.hpp
1 //
2 // Copyright (c) 2016-2018 CNRS
3 //
4 
5 #ifndef __pinocchio_aba_hpp__
6 #define __pinocchio_aba_hpp__
7 
8 #include "pinocchio/multibody/model.hpp"
9 #include "pinocchio/multibody/data.hpp"
10 #include "pinocchio/algorithm/check.hpp"
11 
12 namespace pinocchio
13 {
32  template<typename Scalar, int Options, template<typename,int> class JointCollectionTpl, typename ConfigVectorType, typename TangentVectorType1, typename TangentVectorType2>
34  aba(const ModelTpl<Scalar,Options,JointCollectionTpl> & model,
35  DataTpl<Scalar,Options,JointCollectionTpl> & data,
36  const Eigen::MatrixBase<ConfigVectorType> & q,
37  const Eigen::MatrixBase<TangentVectorType1> & v,
38  const Eigen::MatrixBase<TangentVectorType2> & tau);
39 
60  template<typename Scalar, int Options, template<typename,int> class JointCollectionTpl, typename ConfigVectorType, typename TangentVectorType1, typename TangentVectorType2, typename ForceDerived>
62  aba(const ModelTpl<Scalar,Options,JointCollectionTpl> & model,
63  DataTpl<Scalar,Options,JointCollectionTpl> & data,
64  const Eigen::MatrixBase<ConfigVectorType> & q,
65  const Eigen::MatrixBase<TangentVectorType1> & v,
66  const Eigen::MatrixBase<TangentVectorType2> & tau,
67  const container::aligned_vector<ForceDerived> & fext);
68 
82  template<typename Scalar, int Options, template<typename,int> class JointCollectionTpl, typename ConfigVectorType>
83  inline const typename DataTpl<Scalar,Options,JointCollectionTpl>::RowMatrixXs &
84  computeMinverse(const ModelTpl<Scalar,Options,JointCollectionTpl> & model,
85  DataTpl<Scalar,Options,JointCollectionTpl> & data,
86  const Eigen::MatrixBase<ConfigVectorType> & q);
87 
88 
89  PINOCCHIO_DEFINE_ALGO_CHECKER(ABA);
90 
91 } // namespace pinocchio
92 
93 /* --- Details -------------------------------------------------------------------- */
94 #include "pinocchio/algorithm/aba.hxx"
95 
96 #endif // ifndef __pinocchio_aba_hpp__
pinocchio::computeMinverse
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.
pinocchio::DataTpl::TangentVectorType
VectorXs TangentVectorType
Dense vectorized version of a joint tangent vector (e.g. velocity, acceleration, etc)....
Definition: data.hpp:70
pinocchio::aba
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...
pinocchio
Main pinocchio namespace.
Definition: treeview.dox:11