7#include <proxsuite-nlp/modelling/spaces/vector-space.hpp>
11template <
typename Scalar>
struct CentroidalFwdDataTpl;
24template <
typename _Scalar>
26 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
29 using Base = ODEAbstractTpl<Scalar>;
32 using Data = ContinuousCentroidalFwdDataTpl<Scalar>;
33 using Manifold = proxsuite::nlp::VectorSpaceTpl<Scalar>;
50 const double mass,
const Vector3s &gravity,
52 const int force_size);
54 void forward(
const ConstVectorRef &x,
const ConstVectorRef &u,
56 void dForward(
const ConstVectorRef &x,
const ConstVectorRef &,
62template <
typename Scalar>
64 using Base = ODEDataTpl<Scalar>;
70 const ContinuousCentroidalFwdDynamicsTpl<Scalar> *cont_dyn);
76#include "aligator/modelling/dynamics/continuous-centroidal-fwd.hxx"
Defines a class representing ODEs.
Eigen::Matrix< Scalar, 3, 3 > Matrix3s
ContinuousCentroidalFwdDataTpl(const ContinuousCentroidalFwdDynamicsTpl< Scalar > *cont_dyn)
ODEDataTpl< Scalar > Base
Nonlinear centroidal forward dynamics with smooth control.
ALIGATOR_DYNAMIC_TYPEDEFS(Scalar)
ContinuousCentroidalFwdDataTpl< Scalar > Data
proxsuite::nlp::VectorSpaceTpl< Scalar > Manifold
void forward(const ConstVectorRef &x, const ConstVectorRef &u, BaseData &data) const
Evaluate the ODE vector field: this returns the value of .
ContinuousCentroidalFwdDynamicsTpl(const ManifoldPtr &state, const double mass, const Vector3s &gravity, const ContactMap &contact_map, const int force_size)
void dForward(const ConstVectorRef &x, const ConstVectorRef &, BaseData &data) const
Evaluate the vector field Jacobians.
shared_ptr< ContDataAbstract > createData() const
Create a data holder instance.
const Manifold & space() const
ODEDataTpl< Scalar > BaseData
Eigen::Matrix< Scalar, 3, 3 > Matrix3s
shared_ptr< Manifold > ManifoldPtr
Base class for ODE dynamics .
const int nu_
Control space dimension.