7#include <proxsuite-nlp/modelling/spaces/vector-space.hpp>
23template <
typename _Scalar>
25 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
28 using Base = ODEAbstractTpl<Scalar>;
31 using Data = CentroidalFwdDataTpl<Scalar>;
32 using Manifold = proxsuite::nlp::VectorSpaceTpl<Scalar>;
49 const Vector3s &gravity,
50 const ContactMap &contact_map,
const int force_size);
52 void forward(
const ConstVectorRef &x,
const ConstVectorRef &u,
54 void dForward(
const ConstVectorRef &x,
const ConstVectorRef &u,
61 using Base = ODEDataTpl<Scalar>;
72#include "aligator/modelling/dynamics/centroidal-fwd.hxx"
Defines a class representing ODEs.
Eigen::Matrix< Scalar, 3, 3 > Matrix3s
CentroidalFwdDataTpl(const CentroidalFwdDynamicsTpl< Scalar > *cont_dyn)
ODEDataTpl< Scalar > Base
Nonlinear centroidal forward dynamics.
ALIGATOR_DYNAMIC_TYPEDEFS(Scalar)
void dForward(const ConstVectorRef &x, const ConstVectorRef &u, BaseData &data) const
Evaluate the vector field Jacobians.
ODEDataTpl< Scalar > BaseData
const Manifold & space() const
CentroidalFwdDynamicsTpl(const ManifoldPtr &state, const double mass, const Vector3s &gravity, const ContactMap &contact_map, const int force_size)
void forward(const ConstVectorRef &x, const ConstVectorRef &u, BaseData &data) const
Evaluate the ODE vector field: this returns the value of .
shared_ptr< ContDataAbstract > createData() const
Create a data holder instance.
proxsuite::nlp::VectorSpaceTpl< Scalar > Manifold
shared_ptr< Manifold > ManifoldPtr
CentroidalFwdDataTpl< Scalar > Data
Eigen::Matrix< Scalar, 3, 3 > Matrix3s
Base class for ODE dynamics .
const int nu_
Control space dimension.