6#ifdef PROXSUITE_NLP_WITH_PINOCCHIO
9#include <proxsuite-nlp/modelling/spaces/multibody.hpp>
10#include <pinocchio/multibody/model.hpp>
14template <
typename Scalar>
struct KinodynamicsFwdDataTpl;
30template <
typename _Scalar>
31struct KinodynamicsFwdDynamicsTpl : ODEAbstractTpl<_Scalar> {
32 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
33 using Scalar = _Scalar;
35 using Base = ODEAbstractTpl<Scalar>;
36 using BaseData = ContinuousDynamicsDataTpl<Scalar>;
37 using ContDataAbstract = ContinuousDynamicsDataTpl<Scalar>;
38 using Data = KinodynamicsFwdDataTpl<Scalar>;
39 using Manifold = proxsuite::nlp::MultibodyPhaseSpace<Scalar>;
40 using Model = pinocchio::ModelTpl<Scalar>;
41 using Matrix3s = Eigen::Matrix<Scalar, 3, 3>;
51 std::vector<bool> contact_states_;
52 std::vector<pinocchio::FrameIndex> contact_ids_;
54 const Manifold &space()
const {
return space_; }
56 KinodynamicsFwdDynamicsTpl(
57 const Manifold &state,
const Model &model,
const Vector3s &gravity,
58 const std::vector<bool> &contact_states,
59 const std::vector<pinocchio::FrameIndex> &contact_ids,
60 const int force_size);
62 void forward(
const ConstVectorRef &x,
const ConstVectorRef &u,
63 BaseData &data)
const;
64 void dForward(
const ConstVectorRef &x,
const ConstVectorRef &u,
65 BaseData &data)
const;
67 shared_ptr<ContDataAbstract> createData()
const;
70template <
typename Scalar>
71struct KinodynamicsFwdDataTpl : ContinuousDynamicsDataTpl<Scalar> {
72 using Base = ContinuousDynamicsDataTpl<Scalar>;
73 using PinData = pinocchio::DataTpl<Scalar>;
74 using VectorXs =
typename math_types<Scalar>::VectorXs;
75 using Matrix6Xs =
typename math_types<Scalar>::Matrix6Xs;
76 using Matrix3Xs =
typename math_types<Scalar>::Matrix3Xs;
77 using Matrix3s = Eigen::Matrix<Scalar, 3, 3>;
78 using Matrix6s = Eigen::Matrix<Scalar, 6, 6>;
79 using Vector6s = Eigen::Matrix<Scalar, 6, 1>;
95 Eigen::PartialPivLU<Eigen::Matrix<Scalar, 6, 6>> PivLU_;
97 KinodynamicsFwdDataTpl(
const KinodynamicsFwdDynamicsTpl<Scalar> *model);
103#include "aligator/modelling/dynamics/kinodynamics-fwd.hxx"
#define ALIGATOR_DYNAMIC_TYPEDEFS(Scalar)
pinocchio::DataTpl< Scalar, Options > PinData
typename math_types< Scalar >::Vector3s Vector3s
Defines a class representing ODEs.