5 #ifndef __pinocchio_algorithm_centroidal_derivatives_hpp__ 6 #define __pinocchio_algorithm_centroidal_derivatives_hpp__ 8 #include "pinocchio/multibody/model.hpp" 9 #include "pinocchio/multibody/data.hpp" 10 #include "pinocchio/algorithm/check.hpp" 45 template<
typename Scalar,
int Options,
template<
typename,
int>
class JointCollectionTpl,
46 typename ConfigVectorType,
typename TangentVectorType1,
typename TangentVectorType2,
47 typename Matrix6xLike0,
typename Matrix6xLike1,
typename Matrix6xLike2,
typename Matrix6xLike3>
50 DataTpl<Scalar,Options,JointCollectionTpl> & data,
51 const Eigen::MatrixBase<ConfigVectorType> &
q,
52 const Eigen::MatrixBase<TangentVectorType1> &
v,
53 const Eigen::MatrixBase<TangentVectorType2> & a,
54 const Eigen::MatrixBase<Matrix6xLike0> & dh_dq,
55 const Eigen::MatrixBase<Matrix6xLike1> & dhdot_dq,
56 const Eigen::MatrixBase<Matrix6xLike2> & dhdot_dv,
57 const Eigen::MatrixBase<Matrix6xLike3> & dhdot_da);
79 template<
typename Scalar,
int Options,
template<
typename,
int>
class JointCollectionTpl,
80 typename Matrix6xLike0,
typename Matrix6xLike1,
typename Matrix6xLike2,
typename Matrix6xLike3>
83 DataTpl<Scalar,Options,JointCollectionTpl> & data,
84 const Eigen::MatrixBase<Matrix6xLike1> & dh_dq,
85 const Eigen::MatrixBase<Matrix6xLike1> & dhdot_dq,
86 const Eigen::MatrixBase<Matrix6xLike2> & dhdot_dv,
87 const Eigen::MatrixBase<Matrix6xLike3> & dhdot_da);
93 #include "pinocchio/algorithm/centroidal-derivatives.hxx" 95 #endif // ifndef __pinocchio_algorithm_centroidal_derivatives_hpp__ JointCollectionTpl const Eigen::MatrixBase< ConfigVectorType > const Eigen::MatrixBase< TangentVectorType > & v
void computeCentroidalDynamicsDerivatives(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 > &a, const Eigen::MatrixBase< Matrix6xLike0 > &dh_dq, const Eigen::MatrixBase< Matrix6xLike1 > &dhdot_dq, const Eigen::MatrixBase< Matrix6xLike2 > &dhdot_dv, const Eigen::MatrixBase< Matrix6xLike3 > &dhdot_da)
Computes the analytical derivatives of the centroidal dynamics with respect to the joint configuratio...
JointCollectionTpl const Eigen::MatrixBase< ConfigVectorType > & q
void getCentroidalDynamicsDerivatives(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< Matrix6xLike1 > &dh_dq, const Eigen::MatrixBase< Matrix6xLike1 > &dhdot_dq, const Eigen::MatrixBase< Matrix6xLike2 > &dhdot_dv, const Eigen::MatrixBase< Matrix6xLike3 > &dhdot_da)
Retrive the analytical derivatives of the centroidal dynamics from the RNEA derivatives. pinocchio::computeRNEADerivatives should have been called first.
Main pinocchio namespace.
JointCollectionTpl & model