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

Constraint multibody forward dynamics, using Pinocchio. More...

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

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

Public Types

using Scalar = _Scalar
 
using Base = ODEAbstractTpl<Scalar>
 
using BaseData = ContinuousDynamicsDataTpl<Scalar>
 
using ContDataAbstract = ContinuousDynamicsDataTpl<Scalar>
 
using Data = MultibodyConstraintFwdDataTpl<Scalar>
 
using RigidConstraintModelVector
 
using RigidConstraintDataVector
 
using ProxSettings = pinocchio::ProximalSettingsTpl<Scalar>
 
using Manifold = proxsuite::nlp::MultibodyPhaseSpace<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 Manifoldspace () const
 
int ntau () const
 
 MultibodyConstraintFwdDynamicsTpl (const Manifold &state, const MatrixXs &actuation, const RigidConstraintModelVector &constraint_models, const ProxSettings &prox_settings)
 
virtual void forward (const ConstVectorRef &x, const ConstVectorRef &u, BaseData &data) const
 Evaluate the ODE vector field: this returns the value of \(\dot{x}\).
 
virtual 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

Manifold space_
 
MatrixXs actuation_matrix_
 
RigidConstraintModelVector constraint_models_
 
ProxSettings prox_settings_
 
- 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::MultibodyConstraintFwdDynamicsTpl< _Scalar >

Constraint multibody forward dynamics, using Pinocchio.

Definition at line 20 of file multibody-constraint-fwd.hpp.

Member Typedef Documentation

◆ Scalar

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

Definition at line 22 of file multibody-constraint-fwd.hpp.

◆ Base

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

Definition at line 24 of file multibody-constraint-fwd.hpp.

◆ BaseData

template<typename _Scalar >
using aligator::dynamics::MultibodyConstraintFwdDynamicsTpl< _Scalar >::BaseData = ContinuousDynamicsDataTpl<Scalar>

Definition at line 25 of file multibody-constraint-fwd.hpp.

◆ ContDataAbstract

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

Definition at line 26 of file multibody-constraint-fwd.hpp.

◆ Data

Definition at line 27 of file multibody-constraint-fwd.hpp.

◆ RigidConstraintModelVector

template<typename _Scalar >
using aligator::dynamics::MultibodyConstraintFwdDynamicsTpl< _Scalar >::RigidConstraintModelVector
Initial value:
PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(
pinocchio::RigidConstraintModelTpl<Scalar>)

Definition at line 30 of file multibody-constraint-fwd.hpp.

◆ RigidConstraintDataVector

template<typename _Scalar >
using aligator::dynamics::MultibodyConstraintFwdDynamicsTpl< _Scalar >::RigidConstraintDataVector
Initial value:
PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(pinocchio::RigidConstraintData)

Definition at line 32 of file multibody-constraint-fwd.hpp.

◆ ProxSettings

template<typename _Scalar >
using aligator::dynamics::MultibodyConstraintFwdDynamicsTpl< _Scalar >::ProxSettings = pinocchio::ProximalSettingsTpl<Scalar>

Definition at line 35 of file multibody-constraint-fwd.hpp.

◆ Manifold

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

Definition at line 36 of file multibody-constraint-fwd.hpp.

Constructor & Destructor Documentation

◆ MultibodyConstraintFwdDynamicsTpl()

template<typename _Scalar >
aligator::dynamics::MultibodyConstraintFwdDynamicsTpl< _Scalar >::MultibodyConstraintFwdDynamicsTpl ( const Manifold & state,
const MatrixXs & actuation,
const RigidConstraintModelVector & constraint_models,
const ProxSettings & prox_settings )

Member Function Documentation

◆ ALIGATOR_DYNAMIC_TYPEDEFS()

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

◆ space()

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

Definition at line 43 of file multibody-constraint-fwd.hpp.

◆ ntau()

template<typename _Scalar >
int aligator::dynamics::MultibodyConstraintFwdDynamicsTpl< _Scalar >::ntau ( ) const
inline

Definition at line 44 of file multibody-constraint-fwd.hpp.

◆ forward()

template<typename _Scalar >
virtual void aligator::dynamics::MultibodyConstraintFwdDynamicsTpl< _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 >
virtual void aligator::dynamics::MultibodyConstraintFwdDynamicsTpl< _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::MultibodyConstraintFwdDynamicsTpl< _Scalar >::createData ( ) const
virtual

Create a data holder instance.

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

Member Data Documentation

◆ space_

template<typename _Scalar >
Manifold aligator::dynamics::MultibodyConstraintFwdDynamicsTpl< _Scalar >::space_

Definition at line 38 of file multibody-constraint-fwd.hpp.

◆ actuation_matrix_

template<typename _Scalar >
MatrixXs aligator::dynamics::MultibodyConstraintFwdDynamicsTpl< _Scalar >::actuation_matrix_

Definition at line 39 of file multibody-constraint-fwd.hpp.

◆ constraint_models_

template<typename _Scalar >
RigidConstraintModelVector aligator::dynamics::MultibodyConstraintFwdDynamicsTpl< _Scalar >::constraint_models_

Definition at line 40 of file multibody-constraint-fwd.hpp.

◆ prox_settings_

template<typename _Scalar >
ProxSettings aligator::dynamics::MultibodyConstraintFwdDynamicsTpl< _Scalar >::prox_settings_

Definition at line 41 of file multibody-constraint-fwd.hpp.


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