aligator  0.10.0
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 CostAbstract = CostAbstractTpl<Scalar>
 
using CrocActionModel = crocoddyl::ActionModelAbstractTpl<Scalar>
 
using StateWrapper = StateWrapperTpl<Scalar>
 
using ActionDataWrap = ActionDataWrapperTpl<Scalar>
 
using DynDataWrap = DynamicsDataWrapperTpl<Scalar>
 
using Manifold = ManifoldAbstractTpl<Scalar>
 
- Public Types inherited from aligator::StageModelTpl< Scalar >
using Scalar = _Scalar
 
using Manifold = ManifoldAbstractTpl<Scalar>
 
using PolyManifold = xyz::polymorphic<Manifold>
 
using Dynamics = DynamicsModelTpl<Scalar>
 
using PolyDynamics = xyz::polymorphic<Dynamics>
 
using PolyFunction = xyz::polymorphic<StageFunctionTpl<Scalar>>
 
using PolyConstraintSet = xyz::polymorphic<ConstraintSetTpl<Scalar>>
 
using Cost = CostAbstractTpl<Scalar>
 
using PolyCost = xyz::polymorphic<Cost>
 
using StageConstraint = StageConstraintTpl<Scalar>
 
using Data = StageDataTpl<Scalar>
 

Public Member Functions

 ALIGATOR_DYNAMIC_TYPEDEFS (Scalar)
 
 ActionModelWrapperTpl (boost::shared_ptr< CrocActionModel > action_model)
 
bool hasDynModel () 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)
 
template<typename U >
U * getCost ()
 Get a pointer to an expected concrete type for the cost function.
 
template<typename U >
const U * getCost () const
 
template<typename U >
U * getDynamics ()
 Get a pointer to an expected concrete type for the dynamics class.
 
template<typename U >
const U * getDynamics () const
 
 StageModelTpl (const PolyCost &cost, const PolyDynamics &dynamics)
 
virtual ~StageModelTpl ()=default
 
const Manifoldxspace () const
 
const Manifolduspace () const
 
const Manifoldxspace_next () const
 
const Costcost () 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.
 
template<typename Cstr , typename = std::enable_if_t<std::is_same_v< std::decay_t<Cstr>, StageConstraint>>>
ALIGATOR_DEPRECATED void addConstraint (Cstr &&cstr)
 Add a constraint to the stage.
 
void addConstraint (const PolyFunction &func, const PolyConstraintSet &cstr_set)
 Add a constraint to the stage.
 
template<typename Cstr , typename >
void addConstraint (Cstr &&cstr)
 

Public Attributes

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

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 19 of file fwd.hpp.

Member Typedef Documentation

◆ Base

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

◆ Data

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

◆ CostAbstract

template<typename Scalar >
using aligator::compat::croc::ActionModelWrapperTpl< Scalar >::CostAbstract = CostAbstractTpl<Scalar>

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

◆ CrocActionModel

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

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

◆ StateWrapper

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

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

◆ ActionDataWrap

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

◆ DynDataWrap

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

◆ Manifold

template<typename Scalar >
using aligator::compat::croc::ActionModelWrapperTpl< Scalar >::Manifold = ManifoldAbstractTpl<Scalar>

Definition at line 48 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 )

◆ hasDynModel()

template<typename Scalar >
bool aligator::compat::croc::ActionModelWrapperTpl< Scalar >::hasDynModel ( ) 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 55 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 66 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 50 of file action-model-wrap.hpp.


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