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

Trajectory optimization problem. More...

#include <aligator/core/traj-opt-problem.hpp>

Collaboration diagram for aligator::TrajOptProblemTpl< Scalar >:
[legend]

Public Types

using Scalar = _Scalar
 
using StageModel = StageModelTpl<Scalar>
 
using StageFunction = StageFunctionTpl<Scalar>
 
using UnaryFunction = UnaryFunctionTpl<Scalar>
 
using Data = TrajOptDataTpl<Scalar>
 
using Manifold = ManifoldAbstractTpl<Scalar>
 
using CostAbstract = CostAbstractTpl<Scalar>
 
using ConstraintSet = ConstraintSetTpl<Scalar>
 
using StateErrorResidual = StateErrorResidualTpl<Scalar>
 
using StageConstraint = StageConstraintTpl<Scalar>
 

Public Member Functions

 ALIGATOR_DYNAMIC_TYPEDEFS (Scalar)
 
 TrajOptProblemTpl (xyz::polymorphic< UnaryFunction > init_constraint, const std::vector< xyz::polymorphic< StageModel > > &stages, xyz::polymorphic< CostAbstract > term_cost)
 
 TrajOptProblemTpl (const ConstVectorRef &x0, const std::vector< xyz::polymorphic< StageModel > > &stages, xyz::polymorphic< CostAbstract > term_cost)
 Constructor for an initial value problem.
 
 TrajOptProblemTpl (xyz::polymorphic< UnaryFunction > init_constraint, xyz::polymorphic< CostAbstract > term_cost)
 
 TrajOptProblemTpl (const ConstVectorRef &x0, const int nu, xyz::polymorphic< Manifold > space, xyz::polymorphic< CostAbstract > term_cost)
 Constructor for an initial value problem.
 
bool initCondIsStateError () const
 
void addStage (const xyz::polymorphic< StageModel > &stage)
 Add a stage to the control problem.
 
ConstVectorRef getInitState () const
 Get initial state constraint.
 
void setInitState (const ConstVectorRef &x0)
 Set initial state constraint.
 
ALIGATOR_DEPRECATED void addTerminalConstraint (const StageConstraint &cstr)
 Add a terminal constraint for the model.
 
void addTerminalConstraint (const xyz::polymorphic< StageFunction > &func, const xyz::polymorphic< ConstraintSet > &set)
 
void removeTerminalConstraints ()
 Remove all terminal constraints.
 
std::size_t numSteps () const
 
Scalar evaluate (const std::vector< VectorXs > &xs, const std::vector< VectorXs > &us, Data &prob_data, std::size_t num_threads=1) const
 Rollout the problem costs, constraints, dynamics, stage per stage.
 
void computeDerivatives (const std::vector< VectorXs > &xs, const std::vector< VectorXs > &us, Data &prob_data, std::size_t num_threads=1, bool compute_second_order=true) const
 Rollout the problem derivatives, stage per stage.
 
void replaceStageCircular (const xyz::polymorphic< StageModel > &model)
 Pop out the first StageModel and replace by the supplied one; updates the supplied problem data (TrajOptDataTpl) object.
 
bool checkIntegrity () const
 

Public Attributes

xyz::polymorphic< UnaryFunctioninit_constraint_
 Initial condition.
 
std::vector< xyz::polymorphic< StageModel > > stages_
 Stages of the control problem.
 
xyz::polymorphic< CostAbstractterm_cost_
 Terminal cost.
 
ConstraintStackTpl< Scalarterm_cstrs_
 Terminal constraints.
 
VectorXs unone_
 Dummy, "neutral" control value.
 

Protected Attributes

StateErrorResidualinit_state_error_
 Pointer to underlying state error residual.
 

Detailed Description

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

Trajectory optimization problem.

Template Parameters
Scalarthe scalar type.

The problem can be written as a nonlinear program:

\[ \begin{aligned} \min_{\bmx,\bmu}~& \sum_{i=0}^{N-1} \ell_i(x_i, u_i) + \ell_N(x_N) \\ \subjectto & \varphi(x_i, u_i, x_{i+1}) = 0, \ 0 \leq i < N \\ & g(x_i, u_i) \in \calC_i \end{aligned} \]

Definition at line 104 of file fwd.hpp.

Member Typedef Documentation

◆ Scalar

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

Definition at line 24 of file traj-opt-problem.hpp.

◆ StageModel

template<typename Scalar >
using aligator::TrajOptProblemTpl< Scalar >::StageModel = StageModelTpl<Scalar>

Definition at line 25 of file traj-opt-problem.hpp.

◆ StageFunction

template<typename Scalar >
using aligator::TrajOptProblemTpl< Scalar >::StageFunction = StageFunctionTpl<Scalar>

Definition at line 26 of file traj-opt-problem.hpp.

◆ UnaryFunction

template<typename Scalar >
using aligator::TrajOptProblemTpl< Scalar >::UnaryFunction = UnaryFunctionTpl<Scalar>

Definition at line 27 of file traj-opt-problem.hpp.

◆ Data

template<typename Scalar >
using aligator::TrajOptProblemTpl< Scalar >::Data = TrajOptDataTpl<Scalar>

Definition at line 28 of file traj-opt-problem.hpp.

◆ Manifold

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

Definition at line 29 of file traj-opt-problem.hpp.

◆ CostAbstract

template<typename Scalar >
using aligator::TrajOptProblemTpl< Scalar >::CostAbstract = CostAbstractTpl<Scalar>

Definition at line 30 of file traj-opt-problem.hpp.

◆ ConstraintSet

template<typename Scalar >
using aligator::TrajOptProblemTpl< Scalar >::ConstraintSet = ConstraintSetTpl<Scalar>

Definition at line 31 of file traj-opt-problem.hpp.

◆ StateErrorResidual

template<typename Scalar >
using aligator::TrajOptProblemTpl< Scalar >::StateErrorResidual = StateErrorResidualTpl<Scalar>

Definition at line 32 of file traj-opt-problem.hpp.

◆ StageConstraint

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

Definition at line 35 of file traj-opt-problem.hpp.

Member Function Documentation

◆ ALIGATOR_DYNAMIC_TYPEDEFS()

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

◆ initCondIsStateError()

template<typename Scalar >
bool aligator::TrajOptProblemTpl< Scalar >::initCondIsStateError ( ) const
inline

Definition at line 130 of file traj-opt-problem.hpp.

◆ addStage()

template<typename Scalar >
void aligator::TrajOptProblemTpl< Scalar >::addStage ( const xyz::polymorphic< StageModel > & stage)

Add a stage to the control problem.

◆ getInitState()

template<typename Scalar >
ConstVectorRef aligator::TrajOptProblemTpl< Scalar >::getInitState ( ) const
inline

Get initial state constraint.

Definition at line 136 of file traj-opt-problem.hpp.

◆ setInitState()

template<typename Scalar >
void aligator::TrajOptProblemTpl< Scalar >::setInitState ( const ConstVectorRef & x0)
inline

Set initial state constraint.

Definition at line 145 of file traj-opt-problem.hpp.

◆ addTerminalConstraint() [1/2]

template<typename Scalar >
ALIGATOR_DEPRECATED void aligator::TrajOptProblemTpl< Scalar >::addTerminalConstraint ( const StageConstraint & cstr)

Add a terminal constraint for the model.

◆ addTerminalConstraint() [2/2]

template<typename Scalar >
void aligator::TrajOptProblemTpl< Scalar >::addTerminalConstraint ( const xyz::polymorphic< StageFunction > & func,
const xyz::polymorphic< ConstraintSet > & set )
inline

Definition at line 155 of file traj-opt-problem.hpp.

◆ removeTerminalConstraints()

template<typename Scalar >
void aligator::TrajOptProblemTpl< Scalar >::removeTerminalConstraints ( )
inline

Remove all terminal constraints.

Definition at line 160 of file traj-opt-problem.hpp.

◆ numSteps()

template<typename Scalar >
std::size_t aligator::TrajOptProblemTpl< Scalar >::numSteps ( ) const

◆ evaluate()

template<typename Scalar >
Scalar aligator::TrajOptProblemTpl< Scalar >::evaluate ( const std::vector< VectorXs > & xs,
const std::vector< VectorXs > & us,
Data & prob_data,
std::size_t num_threads = 1 ) const

Rollout the problem costs, constraints, dynamics, stage per stage.

◆ computeDerivatives()

template<typename Scalar >
void aligator::TrajOptProblemTpl< Scalar >::computeDerivatives ( const std::vector< VectorXs > & xs,
const std::vector< VectorXs > & us,
Data & prob_data,
std::size_t num_threads = 1,
bool compute_second_order = true ) const

Rollout the problem derivatives, stage per stage.

Parameters
xsState sequence
usControl sequence
prob_dataProblem data
num_threadsNumber of threads to use
compute_second_orderWhether to compute second-order derivatives

◆ replaceStageCircular()

template<typename Scalar >
void aligator::TrajOptProblemTpl< Scalar >::replaceStageCircular ( const xyz::polymorphic< StageModel > & model)

Pop out the first StageModel and replace by the supplied one; updates the supplied problem data (TrajOptDataTpl) object.

◆ checkIntegrity()

template<typename Scalar >
bool aligator::TrajOptProblemTpl< Scalar >::checkIntegrity ( ) const

Member Data Documentation

◆ init_constraint_

template<typename Scalar >
xyz::polymorphic<UnaryFunction> aligator::TrajOptProblemTpl< Scalar >::init_constraint_

Initial condition.

Definition at line 95 of file traj-opt-problem.hpp.

◆ stages_

template<typename Scalar >
std::vector<xyz::polymorphic<StageModel> > aligator::TrajOptProblemTpl< Scalar >::stages_

Stages of the control problem.

Definition at line 97 of file traj-opt-problem.hpp.

◆ term_cost_

template<typename Scalar >
xyz::polymorphic<CostAbstract> aligator::TrajOptProblemTpl< Scalar >::term_cost_

Terminal cost.

Definition at line 99 of file traj-opt-problem.hpp.

◆ term_cstrs_

template<typename Scalar >
ConstraintStackTpl<Scalar> aligator::TrajOptProblemTpl< Scalar >::term_cstrs_

Terminal constraints.

Definition at line 101 of file traj-opt-problem.hpp.

◆ unone_

template<typename Scalar >
VectorXs aligator::TrajOptProblemTpl< Scalar >::unone_

Dummy, "neutral" control value.

Definition at line 103 of file traj-opt-problem.hpp.

◆ init_state_error_

template<typename Scalar >
StateErrorResidual* aligator::TrajOptProblemTpl< Scalar >::init_state_error_
protected

Pointer to underlying state error residual.

Definition at line 191 of file traj-opt-problem.hpp.


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