- 3.0.2 optimal control module.
ct::optcon Namespace Reference

Namespaces

 example
 
 tpl
 

Classes

class  BoxConstraintBase
 Base for box constraint, templated on dimension of the decision vector of the derived class. More...
 
class  CARE
 Continuous-Time Algebraic Riccati Equation. More...
 
class  Cholesky
 Cholesky square root decomposition of a symmetric positive-definite matrix. More...
 
class  ConstraintBase
 Base class for the constraints used in this toolbox. More...
 
class  ConstraintContainerAnalytical
 Contains all the constraints using analytically calculated jacobians. More...
 
class  ConstraintContainerBase
 The ConstraintBase Class is the base class for defining the non-linear optimization constraints. More...
 
class  ConstraintDiscretizer
 The class takes continuous constraints defined with the constraint toolbox and discretizes them over the DMS shots. These discretized constraints can then be used in the NLP module. More...
 
class  ConstraintsContainerDms
 Container class for the constraints used in DMS. More...
 
class  ContinuityConstraint
 Implementation of the DMS continuity constraints. More...
 
class  ControlInputConstraint
 Class for control input box constraint term. More...
 
class  ControllerDms
 DMS controller class. More...
 
class  CostEvaluatorFull
 Performs the full cost integration over the shots. More...
 
class  CostEvaluatorSimple
 Evaluates the cost at the shots and performs some interpolation in between. More...
 
class  CostFunction
 A base function for cost functions. All cost functions should derive from this. More...
 
class  CostFunctionAnalytical
 A cost function which contains only terms that have analytical derivatives. More...
 
class  CostFunctionQuadratic
 Describes a cost function with a quadratic approximation, i.e. one that can compute first and second order derivatives with respect to state and control input. This does NOT mean it has to be a purely quadratic cost function. If you are looking for a purely quadratic cost function, check CostFunctionQuadraticSimple. More...
 
class  CostFunctionQuadraticSimple
 A simple quadratic cost function. More...
 
class  CTSystemModel
 System model adapted to CT. System model encapsulates the integrator, so it is able to propagate the system, but also computes derivatives w.r.t. both state and noise. When propagating the system, CTSystemModel does not use the specified control input, but uses the assigned system controller instead. More...
 
class  DARE
 Discrete-Time Algebraic Riccati Equation. More...
 
class  DisturbedSystem
 Disturbed system augments the nominal system so that all the CT interfaces and dimensions are satisfied. What is done is basically augmenting the state with the assumed disturbance with specified dimensionality. More...
 
class  DisturbedSystemController
 Disturbed controller allows us to augment the controller so that all the CT interfaces and dimensions are satisfied. Augmenting is done in such a way that the nominal controller is wrapped and all the nominal states are controlled in the same way as before augmenting the state. The augmented state (the disturbance part) is assumed constant, thus the computed derivates of that part of the state are set to zero. More...
 
class  DmsDimensions
 Defines basic types used in the DMS algorithm. More...
 
struct  DmsPolicy
 The DMS policy used as a solution container. More...
 
class  DmsProblem
 This class sets up the DMS problem. More...
 
class  DmsSettings
 Defines the DMS settings. More...
 
class  DmsSolver
 Class to solve a specfic DMS problem. More...
 
class  DynamicRiccatiEquation
 Dynamic Riccati Equation. More...
 
class  EstimatorBase
 Estimator base. More...
 
class  ExtendedKalmanFilter
 Extended Kalman Filter implementation. For an algorithmic overview, see also https://en.wikipedia.org/wiki/Extended_Kalman_filter. More...
 
struct  ExtendedKalmanFilterSettings
 Settings for setting up an ExtendedKF. More...
 
class  FHDTLQR
 Finite-Horizon Discrete Time LQR. More...
 
class  GNRiccatiSolver
 
class  InitStateConstraint
 The implementation of the DMS initial state constraint. More...
 
class  InputDisturbedSystem
 Implementation of an input disturbed system where, the dimension of the disturbance is equal to the dimension of the control input, thus DIST_DIM = CONTROL_DIM. This is a special case, however it occurs often and is convenient to have as separate class. More...
 
class  IpoptSettings
 IPOPT settings. Details about the parameters can be found in the IPOPT documentation. More...
 
class  LinearConstraintContainer
 A base function for linear constraint functions which have a first derivative. More...
 
class  LinearMeasurementModel
 Linear Measurement Model is an interface for linear measurement models most commonly used in practice. More...
 
class  LinearSpliner
 The linear spline implementation. More...
 
struct  LineSearchSettings
 GNMS Line Search Settings. More...
 
class  LQOCProblem
 Defines a Linear-Quadratic Optimal Control Problem, which is optionally constrained. More...
 
class  LQOCSolver
 
struct  LQOCSolverSettings
 LQOC Solver settings. More...
 
class  LQR
 continuous-time infinite-horizon LQR More...
 
class  LTIMeasurementModel
 Linear Time-Invariant measurement model is simply a linear measurement model for which the matrix C is constant in time. More...
 
class  MeasurementModelBase
 
class  MPC
 Main MPC class. More...
 
struct  mpc_settings
 MPC Settings struct. More...
 
class  MultipleShooting
 
class  NLOCAlgorithm
 
class  NLOCBackendBase
 C++ implementation of GNMS. More...
 
class  NLOCBackendMP
 
class  NLOCBackendST
 
class  NLOptConSettings
 Settings for the NLOptCon algorithm. More...
 
class  NLOptConSolver
 
class  NlpSolverSettings
 Contains the NLP solver settings. More...
 
class  ObstacleConstraint
 Class for obstacle constraint. More...
 
class  OptconContinuousSystemInterface
 interface class for optimal control algorithms More...
 
class  OptconDiscreteSystemInterface
 interface class for optimal control algorithms More...
 
class  OptConProblemBase
 
class  OptConSolver
 
class  OptconSystemInterface
 interface base class for optimal control algorithms More...
 
class  OptVectorDms
 This class is a wrapper around the NLP Optvector. It wraps the Vectors from the NLP solvers into state, control and time trajectories. More...
 
class  PolicyHandler
 
class  RKnDerivatives
 This class implements analytical sensitivity generation for the euler and rk4 integration scheme. More...
 
class  SensitivityIntegratorCT
 This class can integrate a controlled system and a costfunction. Furthermore, it provides first order derivatives with respect to initial state and control. More...
 
class  ShotContainer
 This class performs the state and the sensitivity integration on a shot. More...
 
class  SingleShooting
 
class  SnoptSettings
 SnoptSolver settings. Details about the parameters can be found in the SNOPT documentation. More...
 
class  SnoptSolver
 
class  SplinerBase
 Abstract base class for the control input splining between the DMS shots. More...
 
class  StateConstraint
 Class for state box constraint. More...
 
class  StateFeedbackPolicyHandler
 the default policy handler for iLQR More...
 
struct  StateObserverSettings
 Settings for setting up a StateObserver. More...
 
class  SteadyStateKalmanFilter
 Steady State Kalman Filter is a time invariant linear estimator. It starts with the same update rule as the standard Kalman Filter, but instead of propagating the covariance and estimate through time, it assumes convergence reducing the problem to solving an Algebraic Ricatti Equation. More...
 
struct  SteadyStateKalmanFilterSettings
 Settings for setting up a SteadyStateKF. More...
 
class  SwitchedLinearConstraintContainer
 A container for switching linear constraint containers. More...
 
class  SystemModelBase
 System model is an interface that encapsulates the integrator to be able to propagate the system, but is also able to compute derivatives w.r.t. both state and noise. More...
 
class  TermBase
 An interface for a term, supporting both analytical and auto-diff terms. More...
 
class  TerminalConstraint
 Class for terminal constraint. More...
 
class  TermLinear
 A linear term of type $ J = a x + b u + c $. More...
 
class  TermMixed
 A basic quadratic term of type $ J = u^T P x $. More...
 
class  TermQuadMult
 A multiplicative term of type $ J = (x^T Q x) (u^T R u) $. More...
 
class  TermQuadratic
 A basic quadratic term of type $ J = x^T Q x + u^T R u $. More...
 
class  TermQuadTracking
 A quadratic tracking term of type $ J(t) = (x_{ref}(t) - x)^T Q (x_{ref}(t) - x) + (u_{ref}(t) - u)^T R (u_{ref}(t) - u) $. More...
 
class  TermSmoothAbs
 A smooth absolute term of type $ J = a sqrt((x-x_ref)^2 + alpha^2) + b sqrt((u-u_ref)^2 + alpha^2) $ where this calculation is performed component-wise and summed with individual weighting factors a[i], b[i]. More...
 
class  TermStateBarrier
 A state barrier term (could also be considered a soft constraint) Note that this term explicitly excludes controls, as there are better ways to limit control effort in a "soft" way, e.g. through the use of sigmoid functions. More...
 
class  UnscentedKalmanFilter
 Unscented Kalman Filter is a nonlinear estimator best suited for highly nonlinear systems. It combines the principles of EKF and particle filter. The downside is the computation complexity. More...
 
struct  UnscentedKalmanFilterSettings
 Settings for setting up an UnscentedKF. More...
 
class  ZeroOrderHoldSpliner
 The spline implementation for the zero order hold spliner. More...
 

Typedefs

typedef tpl::TimeGrid< double > TimeGrid
 
template<size_t OUTPUT_DIM, size_t STATE_DIM, typename SCALAR = double>
using DisturbanceObserverSettings = StateObserverSettings< OUTPUT_DIM, STATE_DIM, SCALAR >
 Settings for setting up a DisturbanceObserver. More...
 
typedef tpl::MpcTimeKeeper< double > MpcTimeKeeper
 
typedef tpl::MpcTimeHorizon< double > MpcTimeHorizon
 
using DiscreteConstraintBase = tpl::DiscreteConstraintBase< double >
 
using DiscreteConstraintContainerBase = tpl::DiscreteConstraintContainerBase< double >
 
using DiscreteCostEvaluatorBase = tpl::DiscreteCostEvaluatorBase< double >
 
using Nlp = tpl::Nlp< double >
 
using OptVector = tpl::OptVector< double >
 
using IpoptSolver = tpl::IpoptSolver< double >
 
using NlpSolver = tpl::NlpSolver< double >
 
template<size_t STATE_DIM, size_t CONTROL_DIM, typename SCALAR = double>
using ContinuousOptConProblem = OptConProblemBase< STATE_DIM, CONTROL_DIM, core::ControlledSystem< STATE_DIM, CONTROL_DIM, SCALAR >, core::LinearSystem< STATE_DIM, CONTROL_DIM, SCALAR >, core::SystemLinearizer< STATE_DIM, CONTROL_DIM, SCALAR >, SCALAR >
 
template<size_t STATE_DIM, size_t CONTROL_DIM, typename SCALAR = double>
using DiscreteOptConProblem = OptConProblemBase< STATE_DIM, CONTROL_DIM, core::DiscreteControlledSystem< STATE_DIM, CONTROL_DIM, SCALAR >, core::DiscreteLinearSystem< STATE_DIM, CONTROL_DIM, SCALAR >, core::DiscreteSystemLinearizer< STATE_DIM, CONTROL_DIM, SCALAR >, SCALAR >
 

Enumerations

enum  MPC_MODE { FIXED_FINAL_TIME = 0, CONSTANT_RECEDING_HORIZON, FIXED_FINAL_TIME_WITH_MIN_TIME_HORIZON, RECEDING_HORIZON_WITH_FIXED_FINAL_TIME }
 select a mode in which MPC is supposed to run More...
 
enum  NlpSolverType : uint8_t { NlpSolverType::IPOPT = 0, NlpSolverType::SNOPT = 1, NlpSolverType::num_types_solver }
 The available types of NLP solvers. More...
 

Functions

template<typename SCALAR >
void loadScalarCF (const std::string &filename, const std::string &scalarName, SCALAR &scalar, const std::string &termName="")
 
template<typename SCALAR >
void loadScalarOptionalCF (const std::string &filename, const std::string &scalarName, SCALAR &scalar, const std::string &termName, const SCALAR &defaultValue)
 
template<typename SCALAR , int ROW, int COL>
void loadMatrixCF (const std::string &filename, const std::string &matrixName, Eigen::Matrix< SCALAR, ROW, COL > &matrix, const std::string &termName="")
 
template<typename TERM_PTR , typename costFuncType >
void addTerm (const std::string &filename, std::string &currentTerm, int currentTermType, TERM_PTR term, costFuncType *costFunc, bool verbose=false)
 
template<typename TERM_PTR , typename costFuncType >
void addADTerm (const std::string &filename, std::string &currentTerm, int currentTermType, TERM_PTR term, costFuncType *costFunc, bool verbose=false)
 
void loadMpcSettings (const std::string &filename, mpc_settings &settings)
 load the mpc settings from file More...
 

Typedef Documentation

◆ TimeGrid

◆ DisturbanceObserverSettings

template<size_t OUTPUT_DIM, size_t STATE_DIM, typename SCALAR = double>
using ct::optcon::DisturbanceObserverSettings = typedef StateObserverSettings<OUTPUT_DIM, STATE_DIM, SCALAR>

Settings for setting up a DisturbanceObserver.

The DisturbanceObserver settings are designed to make the initialization smoother and possible through a file configuration.

◆ MpcTimeKeeper

◆ MpcTimeHorizon

◆ DiscreteConstraintBase

◆ DiscreteConstraintContainerBase

◆ DiscreteCostEvaluatorBase

◆ Nlp

using ct::optcon::Nlp = typedef tpl::Nlp<double>

◆ OptVector

using ct::optcon::OptVector = typedef tpl::OptVector<double>

◆ IpoptSolver

using ct::optcon::IpoptSolver = typedef tpl::IpoptSolver<double>

◆ NlpSolver

using ct::optcon::NlpSolver = typedef tpl::NlpSolver<double>

◆ ContinuousOptConProblem

template<size_t STATE_DIM, size_t CONTROL_DIM, typename SCALAR = double>
using ct::optcon::ContinuousOptConProblem = typedef OptConProblemBase<STATE_DIM, CONTROL_DIM, core::ControlledSystem<STATE_DIM, CONTROL_DIM, SCALAR>, core::LinearSystem<STATE_DIM, CONTROL_DIM, SCALAR>, core::SystemLinearizer<STATE_DIM, CONTROL_DIM, SCALAR>, SCALAR>

◆ DiscreteOptConProblem

template<size_t STATE_DIM, size_t CONTROL_DIM, typename SCALAR = double>
using ct::optcon::DiscreteOptConProblem = typedef OptConProblemBase<STATE_DIM, CONTROL_DIM, core::DiscreteControlledSystem<STATE_DIM, CONTROL_DIM, SCALAR>, core::DiscreteLinearSystem<STATE_DIM, CONTROL_DIM, SCALAR>, core::DiscreteSystemLinearizer<STATE_DIM, CONTROL_DIM, SCALAR>, SCALAR>

Enumeration Type Documentation

◆ MPC_MODE

select a mode in which MPC is supposed to run

There are four default implementations for time horizon strategies in MPC, which can be selected using the following "MPC_MODE" enum.

  • FIXED_FINAL_TIME plan until a fixed final time T is reached. Time Horizon will continuously shrink and eventually be zero.
  • FIXED_FINAL_TIME_WITH_MIN_TIME_HORIZON this option continuously shrinks the time horizon from the initil time horizon until some minimum time is reached. This minimum time can be specified in the mpc_settings struct as "minimumTimeHorizonMpc_"
  • CONSTANT_RECEDING_HORIZON Time Horizon remains constant for all times and is equal to the initial time horizon specified in the optimal control problem.
  • RECEDING_HORIZON_WITH_FIXED_FINAL_TIME Time Horizon remains constant until a fixed final time is near. It shrinks and eventually becomes zero. The overall time horizon gets set trough the initial problem time horizon. The smaller, receding time horizon can be specified in the mpc_settings struct as "minimumTimeHorizonMpc_"
Enumerator
FIXED_FINAL_TIME 

FIXED_FINAL_TIME.

CONSTANT_RECEDING_HORIZON 

CONSTANT_RECEDING_HORIZON.

FIXED_FINAL_TIME_WITH_MIN_TIME_HORIZON 

FIXED_FINAL_TIME_WITH_MIN_TIME_HORIZON.

RECEDING_HORIZON_WITH_FIXED_FINAL_TIME 

RECEDING_HORIZON_WITH_FIXED_FINAL_TIME.

◆ NlpSolverType

enum ct::optcon::NlpSolverType : uint8_t
strong

The available types of NLP solvers.

Enumerator
IPOPT 
SNOPT 
num_types_solver 

Function Documentation

◆ loadScalarCF()

template<typename SCALAR >
void ct::optcon::loadScalarCF ( const std::string &  filename,
const std::string &  scalarName,
SCALAR scalar,
const std::string &  termName = "" 
)

◆ loadScalarOptionalCF()

template<typename SCALAR >
void ct::optcon::loadScalarOptionalCF ( const std::string &  filename,
const std::string &  scalarName,
SCALAR scalar,
const std::string &  termName,
const SCALAR defaultValue 
)

◆ loadMatrixCF()

◆ addTerm()

template<typename TERM_PTR , typename costFuncType >
void ct::optcon::addTerm ( const std::string &  filename,
std::string &  currentTerm,
int  currentTermType,
TERM_PTR  term,
costFuncType *  costFunc,
bool  verbose = false 
)

◆ addADTerm()

template<typename TERM_PTR , typename costFuncType >
void ct::optcon::addADTerm ( const std::string &  filename,
std::string &  currentTerm,
int  currentTermType,
TERM_PTR  term,
costFuncType *  costFunc,
bool  verbose = false 
)

◆ loadMpcSettings()