aligator  0.10.0
A primal-dual augmented Lagrangian-type solver for nonlinear trajectory optimization.
Loading...
Searching...
No Matches
continuous-centroidal-fwd.hpp
Go to the documentation of this file.
1
2#pragma once
3
6
7#include <proxsuite-nlp/modelling/spaces/vector-space.hpp>
8
9namespace aligator {
10namespace dynamics {
11template <typename Scalar> struct CentroidalFwdDataTpl;
12
24template <typename _Scalar>
25struct ContinuousCentroidalFwdDynamicsTpl : ODEAbstractTpl<_Scalar> {
26 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
27 using Scalar = _Scalar;
33 using Manifold = proxsuite::nlp::VectorSpaceTpl<Scalar>;
34 using Matrix3s = Eigen::Matrix<Scalar, 3, 3>;
36
37 using Base::nu_;
38
40 std::size_t nk_;
41 double mass_;
42 Vector3s gravity_;
45
46 const Manifold &space() const { return *space_; }
47
48 ContinuousCentroidalFwdDynamicsTpl(const Manifold &state, const double mass,
49 const Vector3s &gravity,
50 const ContactMap &contact_map,
51 const int force_size);
52
53 void forward(const ConstVectorRef &x, const ConstVectorRef &u,
54 BaseData &data) const;
55 void dForward(const ConstVectorRef &x, const ConstVectorRef &,
56 BaseData &data) const;
57
58 shared_ptr<ContDataAbstract> createData() const;
59};
60
61template <typename Scalar>
64 using Matrix3s = Eigen::Matrix<Scalar, 3, 3>;
65
67
70};
71
72} // namespace dynamics
73} // namespace aligator
74
75#include "aligator/modelling/dynamics/continuous-centroidal-fwd.hxx"
Main package namespace.
Defines a class representing ODEs.
ContinuousCentroidalFwdDataTpl(const ContinuousCentroidalFwdDynamicsTpl< Scalar > *cont_dyn)
Nonlinear centroidal forward dynamics with smooth control.
Definition fwd.hpp:31
shared_ptr< ContDataAbstract > createData() const
Create a data holder instance.
ContinuousCentroidalFwdDynamicsTpl(const Manifold &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 .
void dForward(const ConstVectorRef &x, const ConstVectorRef &, BaseData &data) const
Evaluate the vector field Jacobians.
Data struct for ContinuousDynamicsAbstractTpl.
Definition fwd.hpp:15
Base class for ODE dynamics .