aligator  0.6.1
A primal-dual augmented Lagrangian-type solver for nonlinear trajectory optimization.
Loading...
Searching...
No Matches
aligator::dynamics::ContinuousCentroidalFwdDynamicsTpl< _Scalar > Struct Template Reference

Nonlinear centroidal forward dynamics with smooth control. More...

#include <aligator/modelling/dynamics/continuous-centroidal-fwd.hpp>

Inheritance diagram for aligator::dynamics::ContinuousCentroidalFwdDynamicsTpl< _Scalar >:
[legend]
Collaboration diagram for aligator::dynamics::ContinuousCentroidalFwdDynamicsTpl< _Scalar >:
[legend]

Public Types

using Scalar = _Scalar
 
using Base = ODEAbstractTpl<Scalar>
 
using BaseData = ODEDataTpl<Scalar>
 
using ContDataAbstract = ContinuousDynamicsDataTpl<Scalar>
 
using Data = ContinuousCentroidalFwdDataTpl<Scalar>
 
using Manifold = proxsuite::nlp::VectorSpaceTpl<Scalar>
 
using ManifoldPtr = shared_ptr<Manifold>
 
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 = ODEDataTpl<Scalar>
 
- Public Types inherited from aligator::dynamics::ContinuousDynamicsAbstractTpl< _Scalar >
using Scalar = _Scalar
 
using Manifold = ManifoldAbstractTpl<Scalar>
 
using ManifoldPtr = shared_ptr<Manifold>
 
using Data = ContinuousDynamicsDataTpl<Scalar>
 

Public Member Functions

 ALIGATOR_DYNAMIC_TYPEDEFS (Scalar)
 
const Manifoldspace () const
 
 ContinuousCentroidalFwdDynamicsTpl (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 \(\dot{x}\).
 
void dForward (const ConstVectorRef &x, const ConstVectorRef &, BaseData &data) const
 Evaluate the vector field Jacobians.
 
shared_ptr< ContDataAbstractcreateData () 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 Manifoldspace () 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

ManifoldPtr 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.
 

Detailed Description

template<typename _Scalar>
struct aligator::dynamics::ContinuousCentroidalFwdDynamicsTpl< _Scalar >

Nonlinear centroidal forward dynamics with smooth control.

This is described in state-space \(\mathcal{X} = T\mathcal{Q}\) (the phase space \(x = (c,h,L,u)\) with c CoM position, h linear momentum, L angular momentum and u forces) 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. Control parameter is set to be the derivative of u to ensure force smoothness.

Definition at line 25 of file continuous-centroidal-fwd.hpp.

Member Typedef Documentation

◆ Scalar

template<typename _Scalar >
using aligator::dynamics::ContinuousCentroidalFwdDynamicsTpl< _Scalar >::Scalar = _Scalar

Definition at line 27 of file continuous-centroidal-fwd.hpp.

◆ Base

template<typename _Scalar >
using aligator::dynamics::ContinuousCentroidalFwdDynamicsTpl< _Scalar >::Base = ODEAbstractTpl<Scalar>

Definition at line 29 of file continuous-centroidal-fwd.hpp.

◆ BaseData

template<typename _Scalar >
using aligator::dynamics::ContinuousCentroidalFwdDynamicsTpl< _Scalar >::BaseData = ODEDataTpl<Scalar>

Definition at line 30 of file continuous-centroidal-fwd.hpp.

◆ ContDataAbstract

template<typename _Scalar >
using aligator::dynamics::ContinuousCentroidalFwdDynamicsTpl< _Scalar >::ContDataAbstract = ContinuousDynamicsDataTpl<Scalar>

Definition at line 31 of file continuous-centroidal-fwd.hpp.

◆ Data

Definition at line 32 of file continuous-centroidal-fwd.hpp.

◆ Manifold

template<typename _Scalar >
using aligator::dynamics::ContinuousCentroidalFwdDynamicsTpl< _Scalar >::Manifold = proxsuite::nlp::VectorSpaceTpl<Scalar>

Definition at line 33 of file continuous-centroidal-fwd.hpp.

◆ ManifoldPtr

template<typename _Scalar >
using aligator::dynamics::ContinuousCentroidalFwdDynamicsTpl< _Scalar >::ManifoldPtr = shared_ptr<Manifold>

Definition at line 34 of file continuous-centroidal-fwd.hpp.

◆ Matrix3s

template<typename _Scalar >
using aligator::dynamics::ContinuousCentroidalFwdDynamicsTpl< _Scalar >::Matrix3s = Eigen::Matrix<Scalar, 3, 3>

Definition at line 35 of file continuous-centroidal-fwd.hpp.

◆ ContactMap

template<typename _Scalar >
using aligator::dynamics::ContinuousCentroidalFwdDynamicsTpl< _Scalar >::ContactMap = ContactMapTpl<Scalar>

Definition at line 36 of file continuous-centroidal-fwd.hpp.

Constructor & Destructor Documentation

◆ ContinuousCentroidalFwdDynamicsTpl()

template<typename _Scalar >
aligator::dynamics::ContinuousCentroidalFwdDynamicsTpl< _Scalar >::ContinuousCentroidalFwdDynamicsTpl ( const ManifoldPtr & state,
const double mass,
const Vector3s & gravity,
const ContactMap & contact_map,
const int force_size )

Member Function Documentation

◆ ALIGATOR_DYNAMIC_TYPEDEFS()

template<typename _Scalar >
aligator::dynamics::ContinuousCentroidalFwdDynamicsTpl< _Scalar >::ALIGATOR_DYNAMIC_TYPEDEFS ( Scalar )

◆ space()

template<typename _Scalar >
const Manifold & aligator::dynamics::ContinuousCentroidalFwdDynamicsTpl< _Scalar >::space ( ) const
inline

Definition at line 47 of file continuous-centroidal-fwd.hpp.

◆ forward()

template<typename _Scalar >
void aligator::dynamics::ContinuousCentroidalFwdDynamicsTpl< _Scalar >::forward ( const ConstVectorRef & x,
const ConstVectorRef & u,
BaseData & data ) const
virtual

Evaluate the ODE vector field: this returns the value of \(\dot{x}\).

Implements aligator::dynamics::ODEAbstractTpl< _Scalar >.

◆ dForward()

template<typename _Scalar >
void aligator::dynamics::ContinuousCentroidalFwdDynamicsTpl< _Scalar >::dForward ( const ConstVectorRef & x,
const ConstVectorRef & u,
BaseData & data ) const
virtual

Evaluate the vector field Jacobians.

Implements aligator::dynamics::ODEAbstractTpl< _Scalar >.

◆ createData()

template<typename _Scalar >
shared_ptr< ContDataAbstract > aligator::dynamics::ContinuousCentroidalFwdDynamicsTpl< _Scalar >::createData ( ) const
virtual

Create a data holder instance.

Reimplemented from aligator::dynamics::ContinuousDynamicsAbstractTpl< _Scalar >.

Member Data Documentation

◆ space_

template<typename _Scalar >
ManifoldPtr aligator::dynamics::ContinuousCentroidalFwdDynamicsTpl< _Scalar >::space_

Definition at line 40 of file continuous-centroidal-fwd.hpp.

◆ nk_

template<typename _Scalar >
std::size_t aligator::dynamics::ContinuousCentroidalFwdDynamicsTpl< _Scalar >::nk_

Definition at line 41 of file continuous-centroidal-fwd.hpp.

◆ mass_

template<typename _Scalar >
double aligator::dynamics::ContinuousCentroidalFwdDynamicsTpl< _Scalar >::mass_

Definition at line 42 of file continuous-centroidal-fwd.hpp.

◆ gravity_

template<typename _Scalar >
Vector3s aligator::dynamics::ContinuousCentroidalFwdDynamicsTpl< _Scalar >::gravity_

Definition at line 43 of file continuous-centroidal-fwd.hpp.

◆ contact_map_

template<typename _Scalar >
ContactMap aligator::dynamics::ContinuousCentroidalFwdDynamicsTpl< _Scalar >::contact_map_

Definition at line 44 of file continuous-centroidal-fwd.hpp.

◆ force_size_

template<typename _Scalar >
int aligator::dynamics::ContinuousCentroidalFwdDynamicsTpl< _Scalar >::force_size_

Definition at line 45 of file continuous-centroidal-fwd.hpp.


The documentation for this struct was generated from the following file: