7#include <proxsuite-nlp/modelling/spaces/vector-space.hpp>
11template <
typename Scalar>
struct CentroidalFwdDataTpl;
24template <
typename _Scalar>
25struct ContinuousCentroidalFwdDynamicsTpl : ODEAbstractTpl<_Scalar> {
26 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
33 using Manifold = proxsuite::nlp::VectorSpaceTpl<Scalar>;
49 const Vector3s &gravity,
51 const int force_size);
53 void forward(
const ConstVectorRef &x,
const ConstVectorRef &u,
55 void dForward(
const ConstVectorRef &x,
const ConstVectorRef &,
61template <
typename Scalar>
75#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)
Nonlinear centroidal forward dynamics with smooth control.
shared_ptr< ContDataAbstract > createData() const
Create a data holder instance.
Eigen::Matrix< Scalar, 3, 3 > Matrix3s
ContinuousCentroidalFwdDynamicsTpl(const Manifold &state, const double mass, const Vector3s &gravity, const ContactMap &contact_map, const int force_size)
const Manifold & space() const
void forward(const ConstVectorRef &x, const ConstVectorRef &u, BaseData &data) const
Evaluate the ODE vector field: this returns the value of .
void dForward(const ConstVectorRef &x, const ConstVectorRef &, BaseData &data) const
Evaluate the vector field Jacobians.
proxsuite::nlp::VectorSpaceTpl< Scalar > Manifold
ALIGATOR_DYNAMIC_TYPEDEFS(Scalar)
Data struct for ContinuousDynamicsAbstractTpl.
Base class for ODE dynamics .
const int nu_
Control space dimension.