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

Nonlinear centroidal and full kinematics forward dynamics. More...

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

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

Public Types

using Scalar = _Scalar
 
using Base = ODEAbstractTpl<Scalar>
 
using BaseData = ODEDataTpl<Scalar>
 
using ContDataAbstract = ContinuousDynamicsDataTpl<Scalar>
 
using Data = KinodynamicsFwdDataTpl<Scalar>
 
using Manifold = proxsuite::nlp::MultibodyPhaseSpace<Scalar>
 
using ManifoldPtr = shared_ptr<Manifold>
 
using Model = pinocchio::ModelTpl<Scalar>
 
using Matrix3s = Eigen::Matrix<Scalar, 3, 3>
 
- 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
 
 KinodynamicsFwdDynamicsTpl (const ManifoldPtr &state, const Model &model, const Vector3s &gravity, const std::vector< bool > &contact_states, const std::vector< pinocchio::FrameIndex > &contact_ids, 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< 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_
 
Model pin_model_
 
double mass_
 
Vector3s gravity_
 
int force_size_
 
std::vector< bool > contact_states_
 
std::vector< pinocchio::FrameIndex > contact_ids_
 
- 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::KinodynamicsFwdDynamicsTpl< _Scalar >

Nonlinear centroidal and full kinematics forward dynamics.

This is described in state-space \(\mathcal{X} = T\mathcal{Q}\) (the phase space \(x = (q,v)\) with q kinematics pose and v joint velocity) using the differential equation \( \dot{q} = v \) and \( \dot{v} = \begin{bmatrix} a_u \\ a_j \end{bmatrix} \), with \(a_u\) base acceleration computed from centroidal Newton-Euler law of momentum ( \( \dot{H} = \dot{A}\dot{q} + A\ddot{q} = \begin{bmatrix} \sum_i=1^{n_k} f_i + mg \\ \sum_i=1^{n_k} (p_i - c) \times f_i \end{bmatrix} \) ) and \(a_j\) commanded joints acceleration.

Definition at line 29 of file kinodynamics-fwd.hpp.

Member Typedef Documentation

◆ Scalar

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

Definition at line 31 of file kinodynamics-fwd.hpp.

◆ Base

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

Definition at line 33 of file kinodynamics-fwd.hpp.

◆ BaseData

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

Definition at line 34 of file kinodynamics-fwd.hpp.

◆ ContDataAbstract

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

Definition at line 35 of file kinodynamics-fwd.hpp.

◆ Data

template<typename _Scalar >
using aligator::dynamics::KinodynamicsFwdDynamicsTpl< _Scalar >::Data = KinodynamicsFwdDataTpl<Scalar>

Definition at line 36 of file kinodynamics-fwd.hpp.

◆ Manifold

template<typename _Scalar >
using aligator::dynamics::KinodynamicsFwdDynamicsTpl< _Scalar >::Manifold = proxsuite::nlp::MultibodyPhaseSpace<Scalar>

Definition at line 37 of file kinodynamics-fwd.hpp.

◆ ManifoldPtr

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

Definition at line 38 of file kinodynamics-fwd.hpp.

◆ Model

template<typename _Scalar >
using aligator::dynamics::KinodynamicsFwdDynamicsTpl< _Scalar >::Model = pinocchio::ModelTpl<Scalar>

Definition at line 39 of file kinodynamics-fwd.hpp.

◆ Matrix3s

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

Definition at line 40 of file kinodynamics-fwd.hpp.

Constructor & Destructor Documentation

◆ KinodynamicsFwdDynamicsTpl()

template<typename _Scalar >
aligator::dynamics::KinodynamicsFwdDynamicsTpl< _Scalar >::KinodynamicsFwdDynamicsTpl ( const ManifoldPtr & state,
const Model & model,
const Vector3s & gravity,
const std::vector< bool > & contact_states,
const std::vector< pinocchio::FrameIndex > & contact_ids,
const int force_size )

Member Function Documentation

◆ ALIGATOR_DYNAMIC_TYPEDEFS()

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

◆ space()

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

Definition at line 53 of file kinodynamics-fwd.hpp.

◆ forward()

template<typename _Scalar >
void aligator::dynamics::KinodynamicsFwdDynamicsTpl< _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::KinodynamicsFwdDynamicsTpl< _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::KinodynamicsFwdDynamicsTpl< _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::KinodynamicsFwdDynamicsTpl< _Scalar >::space_

Definition at line 44 of file kinodynamics-fwd.hpp.

◆ pin_model_

template<typename _Scalar >
Model aligator::dynamics::KinodynamicsFwdDynamicsTpl< _Scalar >::pin_model_

Definition at line 45 of file kinodynamics-fwd.hpp.

◆ mass_

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

Definition at line 46 of file kinodynamics-fwd.hpp.

◆ gravity_

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

Definition at line 47 of file kinodynamics-fwd.hpp.

◆ force_size_

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

Definition at line 48 of file kinodynamics-fwd.hpp.

◆ contact_states_

template<typename _Scalar >
std::vector<bool> aligator::dynamics::KinodynamicsFwdDynamicsTpl< _Scalar >::contact_states_

Definition at line 50 of file kinodynamics-fwd.hpp.

◆ contact_ids_

template<typename _Scalar >
std::vector<pinocchio::FrameIndex> aligator::dynamics::KinodynamicsFwdDynamicsTpl< _Scalar >::contact_ids_

Definition at line 51 of file kinodynamics-fwd.hpp.


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