aligator  0.6.1
A primal-dual augmented Lagrangian-type solver for nonlinear trajectory optimization.
Loading...
Searching...
No Matches
aligator::compat::croc::ActionModelWrapperTpl< Scalar > Struct Template Reference

Wraps a crocoddyl::ActionModelAbstract. More...

#include <aligator/compat/crocoddyl/action-model-wrap.hpp>

Inheritance diagram for aligator::compat::croc::ActionModelWrapperTpl< Scalar >:
[legend]
Collaboration diagram for aligator::compat::croc::ActionModelWrapperTpl< Scalar >:
[legend]

Public Types

using Base = StageModelTpl<Scalar>
 
using Data = StageDataTpl<Scalar>
 
using Constraint = StageConstraintTpl<Scalar>
 
using Dynamics = typename Base::Dynamics
 
using CrocActionModel = crocoddyl::ActionModelAbstractTpl<Scalar>
 
using StateWrapper = StateWrapperTpl<Scalar>
 
using ActionDataWrap = ActionDataWrapperTpl<Scalar>
 
using DynDataWrap = DynamicsDataWrapperTpl<Scalar>
 
- Public Types inherited from aligator::StageModelTpl< Scalar >
using Scalar
 
using Manifold
 
using ManifoldPtr
 
using Dynamics
 
using DynamicsPtr
 
using FunctionPtr
 
using ConstraintSetPtr
 
using Constraint
 
using Cost
 
using CostPtr
 
using Data
 

Public Member Functions

 ALIGATOR_DYNAMIC_TYPEDEFS (Scalar)
 
 ActionModelWrapperTpl (boost::shared_ptr< CrocActionModel > action_model)
 
bool has_dyn_model () const override
 
void evaluate (const ConstVectorRef &x, const ConstVectorRef &u, const ConstVectorRef &y, Data &data) const override
 Evaluate all the functions (cost, dynamics, constraints) at this node.
 
void computeFirstOrderDerivatives (const ConstVectorRef &x, const ConstVectorRef &u, const ConstVectorRef &y, Data &data) const override
 Compute the first-order derivatives of the StageModelTpl.
 
void computeSecondOrderDerivatives (const ConstVectorRef &, const ConstVectorRef &, Data &) const override
 Does nothing for this class.
 
shared_ptr< DatacreateData () const override
 Create a StageData object.
 
- Public Member Functions inherited from aligator::StageModelTpl< Scalar >
 ALIGATOR_DYNAMIC_TYPEDEFS (Scalar)
 
 StageModelTpl (CostPtr cost, DynamicsPtr dynamics)
 
virtual ~StageModelTpl ()=default
 
const Manifoldxspace () const
 
const Manifolduspace () const
 
const Manifoldxspace_next () const
 
const Costcost () const
 
virtual ALIGATOR_DEPRECATED const Dynamicsdyn_model () const
 
int nx1 () const
 
int ndx1 () const
 
int nu () const
 
int nx2 () const
 
int ndx2 () const
 
int nc () const
 Total number of constraints.
 
std::size_t numConstraints () const
 Number of constraint objects.
 
int numPrimal () const
 Number of primal optimization variables.
 
int numDual () const
 Number of dual variables, i.e. Lagrange multipliers.
 
void addConstraint (T &&cstr)
 Add a constraint to the stage.
 
void addConstraint (FunctionPtr func, ConstraintSetPtr cstr_set)
 Add a constraint to the stage.
 
- Public Member Functions inherited from aligator::Cloneable< T >
shared_ptr< T > clone () const
 

Public Attributes

boost::shared_ptr< CrocActionModelaction_model_
 
- Public Attributes inherited from aligator::StageModelTpl< Scalar >
ManifoldPtr xspace_
 State space for the current state \(x_k\).
 
ManifoldPtr xspace_next_
 State space for the next state \(x_{k+1}\).
 
ManifoldPtr uspace_
 Control vector space – by default, a simple Euclidean space.
 
ConstraintStackTpl< Scalarconstraints_
 Constraint manager.
 
CostPtr cost_
 Stage cost function.
 
DynamicsPtr dynamics_
 Dynamics model.
 

Additional Inherited Members

- Protected Member Functions inherited from aligator::StageModelTpl< Scalar >
 StageModelTpl (ManifoldPtr space, const int nu)
 
virtual StageModelTplclone_impl () const override
 

Detailed Description

template<typename Scalar>
struct aligator::compat::croc::ActionModelWrapperTpl< Scalar >

Wraps a crocoddyl::ActionModelAbstract.

This data structure rewires an ActionModel into a StageModel object.

Definition at line 22 of file action-model-wrap.hpp.

Member Typedef Documentation

◆ Base

Definition at line 24 of file action-model-wrap.hpp.

◆ Data

Definition at line 25 of file action-model-wrap.hpp.

◆ Constraint

Definition at line 26 of file action-model-wrap.hpp.

◆ Dynamics

template<typename Scalar >
using aligator::compat::croc::ActionModelWrapperTpl< Scalar >::Dynamics = typename Base::Dynamics

Definition at line 27 of file action-model-wrap.hpp.

◆ CrocActionModel

template<typename Scalar >
using aligator::compat::croc::ActionModelWrapperTpl< Scalar >::CrocActionModel = crocoddyl::ActionModelAbstractTpl<Scalar>

Definition at line 28 of file action-model-wrap.hpp.

◆ StateWrapper

template<typename Scalar >
using aligator::compat::croc::ActionModelWrapperTpl< Scalar >::StateWrapper = StateWrapperTpl<Scalar>

Definition at line 29 of file action-model-wrap.hpp.

◆ ActionDataWrap

Definition at line 30 of file action-model-wrap.hpp.

◆ DynDataWrap

Definition at line 31 of file action-model-wrap.hpp.

Constructor & Destructor Documentation

◆ ActionModelWrapperTpl()

template<typename Scalar >
aligator::compat::croc::ActionModelWrapperTpl< Scalar >::ActionModelWrapperTpl ( boost::shared_ptr< CrocActionModel > action_model)
explicit

Member Function Documentation

◆ ALIGATOR_DYNAMIC_TYPEDEFS()

template<typename Scalar >
aligator::compat::croc::ActionModelWrapperTpl< Scalar >::ALIGATOR_DYNAMIC_TYPEDEFS ( Scalar )

◆ has_dyn_model()

template<typename Scalar >
bool aligator::compat::croc::ActionModelWrapperTpl< Scalar >::has_dyn_model ( ) const
inlineoverridevirtual

Whether the stage's dynamics model can be accessed. This boolean allows flexibility in solvers when dealing with different frontends e.g. Crocoddyl's API.

Reimplemented from aligator::StageModelTpl< Scalar >.

Definition at line 38 of file action-model-wrap.hpp.

◆ evaluate()

template<typename Scalar >
void aligator::compat::croc::ActionModelWrapperTpl< Scalar >::evaluate ( const ConstVectorRef & x,
const ConstVectorRef & u,
const ConstVectorRef & y,
Data & data ) const
overridevirtual

Evaluate all the functions (cost, dynamics, constraints) at this node.

Reimplemented from aligator::StageModelTpl< Scalar >.

◆ computeFirstOrderDerivatives()

template<typename Scalar >
void aligator::compat::croc::ActionModelWrapperTpl< Scalar >::computeFirstOrderDerivatives ( const ConstVectorRef & x,
const ConstVectorRef & u,
const ConstVectorRef & y,
Data & data ) const
overridevirtual

Compute the first-order derivatives of the StageModelTpl.

Reimplemented from aligator::StageModelTpl< Scalar >.

◆ computeSecondOrderDerivatives()

template<typename Scalar >
void aligator::compat::croc::ActionModelWrapperTpl< Scalar >::computeSecondOrderDerivatives ( const ConstVectorRef & ,
const ConstVectorRef & ,
Data &  ) const
inlineoverridevirtual

Does nothing for this class.

Reimplemented from aligator::StageModelTpl< Scalar >.

Definition at line 49 of file action-model-wrap.hpp.

◆ createData()

template<typename Scalar >
shared_ptr< Data > aligator::compat::croc::ActionModelWrapperTpl< Scalar >::createData ( ) const
overridevirtual

Create a StageData object.

Reimplemented from aligator::StageModelTpl< Scalar >.

Member Data Documentation

◆ action_model_

template<typename Scalar >
boost::shared_ptr<CrocActionModel> aligator::compat::croc::ActionModelWrapperTpl< Scalar >::action_model_

Definition at line 33 of file action-model-wrap.hpp.


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