5 #ifndef __pinocchio_crba_hpp__ 6 #define __pinocchio_crba_hpp__ 8 #include "pinocchio/multibody/model.hpp" 9 #include "pinocchio/multibody/data.hpp" 10 #include "pinocchio/algorithm/check.hpp" 32 template<
typename Scalar,
int Options,
template<
typename,
int>
class JointCollectionTpl,
typename ConfigVectorType>
34 crba(
const ModelTpl<Scalar,Options,JointCollectionTpl> &
model,
35 DataTpl<Scalar,Options,JointCollectionTpl> &
data,
36 const Eigen::MatrixBase<ConfigVectorType> &
q);
59 template<
typename Scalar,
int Options,
template<
typename,
int>
class JointCollectionTpl,
typename ConfigVectorType>
62 DataTpl<Scalar,Options,JointCollectionTpl> &
data,
63 const Eigen::MatrixBase<ConfigVectorType> &
q);
70 #include "pinocchio/algorithm/crba.hxx" 72 #endif // ifndef __pinocchio_crba_hpp__ const DataTpl< Scalar, Options, JointCollectionTpl >::MatrixXs & crba(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q)
Computes the upper triangular part of the joint space inertia matrix M by using the Composite Rigid B...
JointCollectionTpl const Eigen::MatrixBase< ConfigVectorType > & q
PINOCCHIO_DEFINE_ALGO_CHECKER(ABA)
const DataTpl< Scalar, Options, JointCollectionTpl >::MatrixXs & crbaMinimal(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q)
Computes the upper triangular part of the joint space inertia matrix M by using the Composite Rigid B...
Eigen::Matrix< Scalar, Eigen::Dynamic, Eigen::Dynamic, Options > MatrixXs
Main pinocchio namespace.
JointCollectionTpl & model