aligator  0.6.1
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>
26 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
27 using Scalar = _Scalar;
29 using Base = ODEAbstractTpl<Scalar>;
30 using BaseData = ODEDataTpl<Scalar>;
31 using ContDataAbstract = ContinuousDynamicsDataTpl<Scalar>;
32 using Data = ContinuousCentroidalFwdDataTpl<Scalar>;
33 using Manifold = proxsuite::nlp::VectorSpaceTpl<Scalar>;
34 using ManifoldPtr = shared_ptr<Manifold>;
35 using Matrix3s = Eigen::Matrix<Scalar, 3, 3>;
36 using ContactMap = ContactMapTpl<Scalar>;
37
38 using Base::nu_;
39
41 std::size_t nk_;
42 double mass_;
43 Vector3s gravity_;
46
47 const Manifold &space() const { return *space_; }
48
50 const double mass, const Vector3s &gravity,
51 const ContactMap &contact_map,
52 const int force_size);
53
54 void forward(const ConstVectorRef &x, const ConstVectorRef &u,
55 BaseData &data) const;
56 void dForward(const ConstVectorRef &x, const ConstVectorRef &,
57 BaseData &data) const;
58
59 shared_ptr<ContDataAbstract> createData() const;
60};
61
62template <typename Scalar>
63struct ContinuousCentroidalFwdDataTpl : ODEDataTpl<Scalar> {
64 using Base = ODEDataTpl<Scalar>;
65 using Matrix3s = Eigen::Matrix<Scalar, 3, 3>;
66
68
70 const ContinuousCentroidalFwdDynamicsTpl<Scalar> *cont_dyn);
71};
72
73} // namespace dynamics
74} // namespace aligator
75
76#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.
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.
Base class for ODE dynamics .