aligator
0.10.0
A primal-dual augmented Lagrangian-type solver for nonlinear trajectory optimization.
|
Nonlinear centroidal forward dynamics. More...
#include <aligator/modelling/dynamics/centroidal-fwd.hpp>
Public Types | |
using | Scalar = _Scalar |
using | Base = ODEAbstractTpl<Scalar> |
using | BaseData = ContinuousDynamicsDataTpl<Scalar> |
using | ContDataAbstract = ContinuousDynamicsDataTpl<Scalar> |
using | Data = CentroidalFwdDataTpl<Scalar> |
using | Manifold = proxsuite::nlp::VectorSpaceTpl<Scalar> |
using | Matrix3s = Eigen::Matrix<Scalar, 3, 3> |
using | ContactMap = ContactMapTpl<Scalar> |
Public Types inherited from aligator::dynamics::ODEAbstractTpl< _Scalar > | |
using | Scalar = _Scalar |
using | Base = ContinuousDynamicsAbstractTpl<Scalar> |
using | Data = ContinuousDynamicsDataTpl<Scalar> |
Public Types inherited from aligator::dynamics::ContinuousDynamicsAbstractTpl< _Scalar > | |
using | Scalar |
using | Manifold |
using | ManifoldPtr |
using | Data |
Public Member Functions | |
ALIGATOR_DYNAMIC_TYPEDEFS (Scalar) | |
const Manifold & | space () const |
CentroidalFwdDynamicsTpl (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 \(\dot{x}\). | |
void | dForward (const ConstVectorRef &x, const ConstVectorRef &u, BaseData &data) const |
Evaluate the vector field Jacobians. | |
shared_ptr< ContDataAbstract > | createData () const |
Create a data holder instance. | |
Public Member Functions inherited from aligator::dynamics::ODEAbstractTpl< _Scalar > | |
ALIGATOR_DYNAMIC_TYPEDEFS (Scalar) | |
virtual | ~ODEAbstractTpl ()=default |
void | evaluate (const ConstVectorRef &x, const ConstVectorRef &u, const ConstVectorRef &xdot, Data &data) const override |
void | computeJacobians (const ConstVectorRef &x, const ConstVectorRef &u, const ConstVectorRef &xdot, Data &data) const override |
Public Member Functions inherited from aligator::dynamics::ContinuousDynamicsAbstractTpl< _Scalar > | |
ALIGATOR_DYNAMIC_TYPEDEFS (_Scalar) | |
int | ndx () const |
int | nu () const |
const Manifold & | space () const |
Return a reference to the state space. | |
ContinuousDynamicsAbstractTpl (ManifoldPtr space, const int nu) | |
virtual | ~ContinuousDynamicsAbstractTpl ()=default |
virtual void | evaluate (const ConstVectorRef &x, const ConstVectorRef &u, const ConstVectorRef &xdot, Data &data) const=0 |
Evaluate the vector field at a point \((x, u)\). | |
virtual void | computeJacobians (const ConstVectorRef &x, const ConstVectorRef &u, const ConstVectorRef &xdot, Data &data) const=0 |
Differentiate the vector field. | |
Public Attributes | |
Manifold | space_ |
std::size_t | nk_ |
double | mass_ |
Vector3s | gravity_ |
ContactMap | contact_map_ |
int | force_size_ |
Public Attributes inherited from aligator::dynamics::ODEAbstractTpl< _Scalar > | |
const int | nu_ |
Control space dimension. | |
ManifoldPtr | space_ |
State space. | |
Public Attributes inherited from aligator::dynamics::ContinuousDynamicsAbstractTpl< _Scalar > | |
ManifoldPtr | space_ |
State space. | |
const int | nu_ |
Control space dimension. | |
Nonlinear centroidal forward dynamics.
This is described in state-space \(\mathcal{X} = T\mathcal{Q}\) (the phase space \(x = (c,h,L)\) with c CoM position, h linear momentum) and L angular momentum) using the differential equation
\[ \dot{x} = f(x, u) = F_x * x + F_u(x) * u \]
as described by the Newton-Euler law of momentum.
using aligator::dynamics::CentroidalFwdDynamicsTpl< Scalar >::Scalar = _Scalar |
Definition at line 26 of file centroidal-fwd.hpp.
using aligator::dynamics::CentroidalFwdDynamicsTpl< Scalar >::Base = ODEAbstractTpl<Scalar> |
Definition at line 28 of file centroidal-fwd.hpp.
using aligator::dynamics::CentroidalFwdDynamicsTpl< Scalar >::BaseData = ContinuousDynamicsDataTpl<Scalar> |
Definition at line 29 of file centroidal-fwd.hpp.
using aligator::dynamics::CentroidalFwdDynamicsTpl< Scalar >::ContDataAbstract = ContinuousDynamicsDataTpl<Scalar> |
Definition at line 30 of file centroidal-fwd.hpp.
using aligator::dynamics::CentroidalFwdDynamicsTpl< Scalar >::Data = CentroidalFwdDataTpl<Scalar> |
Definition at line 31 of file centroidal-fwd.hpp.
using aligator::dynamics::CentroidalFwdDynamicsTpl< Scalar >::Manifold = proxsuite::nlp::VectorSpaceTpl<Scalar> |
Definition at line 32 of file centroidal-fwd.hpp.
using aligator::dynamics::CentroidalFwdDynamicsTpl< Scalar >::Matrix3s = Eigen::Matrix<Scalar, 3, 3> |
Definition at line 33 of file centroidal-fwd.hpp.
using aligator::dynamics::CentroidalFwdDynamicsTpl< Scalar >::ContactMap = ContactMapTpl<Scalar> |
Definition at line 34 of file centroidal-fwd.hpp.
aligator::dynamics::CentroidalFwdDynamicsTpl< Scalar >::CentroidalFwdDynamicsTpl | ( | const Manifold & | state, |
const double | mass, | ||
const Vector3s & | gravity, | ||
const ContactMap & | contact_map, | ||
const int | force_size ) |
aligator::dynamics::CentroidalFwdDynamicsTpl< Scalar >::ALIGATOR_DYNAMIC_TYPEDEFS | ( | Scalar | ) |
|
inline |
Definition at line 45 of file centroidal-fwd.hpp.
|
virtual |
Evaluate the ODE vector field: this returns the value of \(\dot{x}\).
Implements aligator::dynamics::ODEAbstractTpl< _Scalar >.
|
virtual |
Evaluate the vector field Jacobians.
Implements aligator::dynamics::ODEAbstractTpl< _Scalar >.
|
virtual |
Create a data holder instance.
Reimplemented from aligator::dynamics::ContinuousDynamicsAbstractTpl< _Scalar >.
Manifold aligator::dynamics::CentroidalFwdDynamicsTpl< Scalar >::space_ |
Definition at line 38 of file centroidal-fwd.hpp.
std::size_t aligator::dynamics::CentroidalFwdDynamicsTpl< Scalar >::nk_ |
Definition at line 39 of file centroidal-fwd.hpp.
double aligator::dynamics::CentroidalFwdDynamicsTpl< Scalar >::mass_ |
Definition at line 40 of file centroidal-fwd.hpp.
Vector3s aligator::dynamics::CentroidalFwdDynamicsTpl< Scalar >::gravity_ |
Definition at line 41 of file centroidal-fwd.hpp.
ContactMap aligator::dynamics::CentroidalFwdDynamicsTpl< Scalar >::contact_map_ |
Definition at line 42 of file centroidal-fwd.hpp.
int aligator::dynamics::CentroidalFwdDynamicsTpl< Scalar >::force_size_ |
Definition at line 43 of file centroidal-fwd.hpp.