aligator  0.6.1
A primal-dual augmented Lagrangian-type solver for nonlinear trajectory optimization.
Loading...
Searching...
No Matches
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
23template <typename _Scalar>
25 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
26 using Scalar = _Scalar;
28 using Base = ODEAbstractTpl<Scalar>;
29 using BaseData = ODEDataTpl<Scalar>;
30 using ContDataAbstract = ContinuousDynamicsDataTpl<Scalar>;
31 using Data = CentroidalFwdDataTpl<Scalar>;
32 using Manifold = proxsuite::nlp::VectorSpaceTpl<Scalar>;
33 using ManifoldPtr = shared_ptr<Manifold>;
34 using Matrix3s = Eigen::Matrix<Scalar, 3, 3>;
35 using ContactMap = ContactMapTpl<Scalar>;
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 CentroidalFwdDynamicsTpl(const ManifoldPtr &state, const double mass,
49 const Vector3s &gravity,
50 const ContactMap &contact_map, const int force_size);
51
52 void forward(const ConstVectorRef &x, const ConstVectorRef &u,
53 BaseData &data) const;
54 void dForward(const ConstVectorRef &x, const ConstVectorRef &u,
55 BaseData &data) const;
56
57 shared_ptr<ContDataAbstract> createData() const;
58};
59
60template <typename Scalar> struct CentroidalFwdDataTpl : ODEDataTpl<Scalar> {
61 using Base = ODEDataTpl<Scalar>;
62 using Matrix3s = Eigen::Matrix<Scalar, 3, 3>;
63
65
66 CentroidalFwdDataTpl(const CentroidalFwdDynamicsTpl<Scalar> *cont_dyn);
67};
68
69} // namespace dynamics
70} // namespace aligator
71
72#include "aligator/modelling/dynamics/centroidal-fwd.hxx"
Main package namespace.
Defines a class representing ODEs.
Eigen::Matrix< Scalar, 3, 3 > Matrix3s
CentroidalFwdDataTpl(const CentroidalFwdDynamicsTpl< Scalar > *cont_dyn)
Nonlinear centroidal forward dynamics.
void dForward(const ConstVectorRef &x, const ConstVectorRef &u, BaseData &data) const
Evaluate the vector field Jacobians.
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
Base class for ODE dynamics .