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

A stage in the control problem. More...

#include <aligator/core/stage-model.hpp>

Inheritance diagram for aligator::StageModelTpl< Scalar >:
[legend]

Public Types

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)
 
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
 
virtual bool hasDynModel () 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.
 
virtual void evaluate (const ConstVectorRef &x, const ConstVectorRef &u, const ConstVectorRef &y, Data &data) const
 Evaluate all the functions (cost, dynamics, constraints) at this node.
 
virtual void computeFirstOrderDerivatives (const ConstVectorRef &x, const ConstVectorRef &u, const ConstVectorRef &y, Data &data) const
 Compute the first-order derivatives of the StageModelTpl.
 
virtual void computeSecondOrderDerivatives (const ConstVectorRef &x, const ConstVectorRef &u, Data &data) const
 Compute the second-order derivatives of the StageModelTpl.
 
virtual shared_ptr< DatacreateData () const
 Create a StageData object.
 
template<typename Cstr , typename >
void addConstraint (Cstr &&cstr)
 

Public Attributes

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.
 

Friends

std::ostream & operator<< (std::ostream &oss, const StageModelTpl &stage)
 

Detailed Description

template<typename Scalar>
struct aligator::StageModelTpl< Scalar >

A stage in the control problem.

Each stage containts cost functions, dynamical and constraint models. These objects are hold through smart pointers to leverage dynamic polymorphism.

Definition at line 90 of file fwd.hpp.

Member Typedef Documentation

◆ Scalar

template<typename Scalar >
using aligator::StageModelTpl< Scalar >::Scalar = _Scalar

Definition at line 26 of file stage-model.hpp.

◆ Manifold

template<typename Scalar >
using aligator::StageModelTpl< Scalar >::Manifold = ManifoldAbstractTpl<Scalar>

Definition at line 29 of file stage-model.hpp.

◆ PolyManifold

template<typename Scalar >
using aligator::StageModelTpl< Scalar >::PolyManifold = xyz::polymorphic<Manifold>

Definition at line 30 of file stage-model.hpp.

◆ Dynamics

template<typename Scalar >
using aligator::StageModelTpl< Scalar >::Dynamics = DynamicsModelTpl<Scalar>

Definition at line 31 of file stage-model.hpp.

◆ PolyDynamics

template<typename Scalar >
using aligator::StageModelTpl< Scalar >::PolyDynamics = xyz::polymorphic<Dynamics>

Definition at line 32 of file stage-model.hpp.

◆ PolyFunction

template<typename Scalar >
using aligator::StageModelTpl< Scalar >::PolyFunction = xyz::polymorphic<StageFunctionTpl<Scalar>>

Definition at line 33 of file stage-model.hpp.

◆ PolyConstraintSet

template<typename Scalar >
using aligator::StageModelTpl< Scalar >::PolyConstraintSet = xyz::polymorphic<ConstraintSetTpl<Scalar>>

Definition at line 34 of file stage-model.hpp.

◆ Cost

template<typename Scalar >
using aligator::StageModelTpl< Scalar >::Cost = CostAbstractTpl<Scalar>

Definition at line 35 of file stage-model.hpp.

◆ PolyCost

template<typename Scalar >
using aligator::StageModelTpl< Scalar >::PolyCost = xyz::polymorphic<Cost>

Definition at line 36 of file stage-model.hpp.

◆ StageConstraint

template<typename Scalar >
using aligator::StageModelTpl< Scalar >::StageConstraint = StageConstraintTpl<Scalar>

Definition at line 39 of file stage-model.hpp.

◆ Data

template<typename Scalar >
using aligator::StageModelTpl< Scalar >::Data = StageDataTpl<Scalar>

Definition at line 41 of file stage-model.hpp.

Constructor & Destructor Documentation

◆ StageModelTpl()

template<typename Scalar >
aligator::StageModelTpl< Scalar >::StageModelTpl ( const PolyCost & cost,
const PolyDynamics & dynamics )

Constructor assumes the control space is a Euclidean space of dimension nu.

◆ ~StageModelTpl()

template<typename Scalar >
virtual aligator::StageModelTpl< Scalar >::~StageModelTpl ( )
virtualdefault

Member Function Documentation

◆ ALIGATOR_DYNAMIC_TYPEDEFS()

template<typename Scalar >
aligator::StageModelTpl< Scalar >::ALIGATOR_DYNAMIC_TYPEDEFS ( Scalar )

◆ getCost() [1/2]

template<typename Scalar >
template<typename U >
U * aligator::StageModelTpl< Scalar >::getCost ( )
inline

Get a pointer to an expected concrete type for the cost function.

Definition at line 57 of file stage-model.hpp.

◆ getCost() [2/2]

template<typename Scalar >
template<typename U >
const U * aligator::StageModelTpl< Scalar >::getCost ( ) const
inline

Definition at line 63 of file stage-model.hpp.

◆ getDynamics() [1/2]

template<typename Scalar >
template<typename U >
U * aligator::StageModelTpl< Scalar >::getDynamics ( )
inline

Get a pointer to an expected concrete type for the dynamics class.

Definition at line 69 of file stage-model.hpp.

◆ getDynamics() [2/2]

template<typename Scalar >
template<typename U >
const U * aligator::StageModelTpl< Scalar >::getDynamics ( ) const
inline

Definition at line 75 of file stage-model.hpp.

◆ xspace()

template<typename Scalar >
const Manifold & aligator::StageModelTpl< Scalar >::xspace ( ) const
inline

Definition at line 85 of file stage-model.hpp.

◆ uspace()

template<typename Scalar >
const Manifold & aligator::StageModelTpl< Scalar >::uspace ( ) const
inline

Definition at line 86 of file stage-model.hpp.

◆ xspace_next()

template<typename Scalar >
const Manifold & aligator::StageModelTpl< Scalar >::xspace_next ( ) const
inline

Definition at line 87 of file stage-model.hpp.

◆ cost()

template<typename Scalar >
const Cost & aligator::StageModelTpl< Scalar >::cost ( ) const
inline

Definition at line 89 of file stage-model.hpp.

◆ hasDynModel()

template<typename Scalar >
virtual bool aligator::StageModelTpl< Scalar >::hasDynModel ( ) const
inlinevirtual

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 in aligator::compat::croc::ActionModelWrapperTpl< Scalar >.

Definition at line 93 of file stage-model.hpp.

◆ nx1()

template<typename Scalar >
int aligator::StageModelTpl< Scalar >::nx1 ( ) const
inline

Definition at line 95 of file stage-model.hpp.

◆ ndx1()

template<typename Scalar >
int aligator::StageModelTpl< Scalar >::ndx1 ( ) const
inline

Definition at line 96 of file stage-model.hpp.

◆ nu()

template<typename Scalar >
int aligator::StageModelTpl< Scalar >::nu ( ) const
inline

Definition at line 97 of file stage-model.hpp.

◆ nx2()

template<typename Scalar >
int aligator::StageModelTpl< Scalar >::nx2 ( ) const
inline

Definition at line 98 of file stage-model.hpp.

◆ ndx2()

template<typename Scalar >
int aligator::StageModelTpl< Scalar >::ndx2 ( ) const
inline

Definition at line 99 of file stage-model.hpp.

◆ nc()

template<typename Scalar >
int aligator::StageModelTpl< Scalar >::nc ( ) const
inline

Total number of constraints.

Definition at line 101 of file stage-model.hpp.

◆ numConstraints()

template<typename Scalar >
std::size_t aligator::StageModelTpl< Scalar >::numConstraints ( ) const
inline

Number of constraint objects.

Definition at line 104 of file stage-model.hpp.

◆ numPrimal()

template<typename Scalar >
int aligator::StageModelTpl< Scalar >::numPrimal ( ) const
inline

Number of primal optimization variables.

Definition at line 107 of file stage-model.hpp.

◆ numDual()

template<typename Scalar >
int aligator::StageModelTpl< Scalar >::numDual ( ) const
inline

Number of dual variables, i.e. Lagrange multipliers.

Definition at line 109 of file stage-model.hpp.

◆ addConstraint() [1/3]

template<typename Scalar >
template<typename Cstr , typename = std::enable_if_t<std::is_same_v< std::decay_t<Cstr>, StageConstraint>>>
ALIGATOR_DEPRECATED void aligator::StageModelTpl< Scalar >::addConstraint ( Cstr && cstr)

Add a constraint to the stage.

◆ addConstraint() [2/3]

template<typename Scalar >
void aligator::StageModelTpl< Scalar >::addConstraint ( const PolyFunction & func,
const PolyConstraintSet & cstr_set )

Add a constraint to the stage.

Adds a constraint by allocating a new StageConstraintTpl.

◆ evaluate()

template<typename Scalar >
virtual void aligator::StageModelTpl< Scalar >::evaluate ( const ConstVectorRef & x,
const ConstVectorRef & u,
const ConstVectorRef & y,
Data & data ) const
virtual

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

Reimplemented in aligator::compat::croc::ActionModelWrapperTpl< Scalar >.

◆ computeFirstOrderDerivatives()

template<typename Scalar >
virtual void aligator::StageModelTpl< Scalar >::computeFirstOrderDerivatives ( const ConstVectorRef & x,
const ConstVectorRef & u,
const ConstVectorRef & y,
Data & data ) const
virtual

Compute the first-order derivatives of the StageModelTpl.

Reimplemented in aligator::compat::croc::ActionModelWrapperTpl< Scalar >.

◆ computeSecondOrderDerivatives()

template<typename Scalar >
virtual void aligator::StageModelTpl< Scalar >::computeSecondOrderDerivatives ( const ConstVectorRef & x,
const ConstVectorRef & u,
Data & data ) const
virtual

Compute the second-order derivatives of the StageModelTpl.

Reimplemented in aligator::compat::croc::ActionModelWrapperTpl< Scalar >.

◆ createData()

template<typename Scalar >
virtual shared_ptr< Data > aligator::StageModelTpl< Scalar >::createData ( ) const
virtual

Create a StageData object.

Reimplemented in aligator::compat::croc::ActionModelWrapperTpl< Scalar >.

◆ addConstraint() [3/3]

template<typename Scalar >
template<typename Cstr , typename >
void aligator::StageModelTpl< Scalar >::addConstraint ( Cstr && cstr)

Definition at line 166 of file stage-model.hpp.

Friends And Related Symbol Documentation

◆ operator<<

template<typename Scalar >
std::ostream & operator<< ( std::ostream & oss,
const StageModelTpl< Scalar > & stage )
friend

Definition at line 142 of file stage-model.hpp.

Member Data Documentation

◆ xspace_

template<typename Scalar >
PolyManifold aligator::StageModelTpl< Scalar >::xspace_

State space for the current state \(x_k\).

Definition at line 44 of file stage-model.hpp.

◆ xspace_next_

template<typename Scalar >
PolyManifold aligator::StageModelTpl< Scalar >::xspace_next_

State space for the next state \(x_{k+1}\).

Definition at line 46 of file stage-model.hpp.

◆ uspace_

template<typename Scalar >
PolyManifold aligator::StageModelTpl< Scalar >::uspace_

Control vector space – by default, a simple Euclidean space.

Definition at line 48 of file stage-model.hpp.

◆ constraints_

template<typename Scalar >
ConstraintStackTpl<Scalar> aligator::StageModelTpl< Scalar >::constraints_

Constraint manager.

Definition at line 50 of file stage-model.hpp.

◆ cost_

template<typename Scalar >
PolyCost aligator::StageModelTpl< Scalar >::cost_

Stage cost function.

Definition at line 52 of file stage-model.hpp.

◆ dynamics_

template<typename Scalar >
PolyDynamics aligator::StageModelTpl< Scalar >::dynamics_

Dynamics model.

Definition at line 54 of file stage-model.hpp.


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