- 3.0.2 optimal control module.
ct::optcon::OptConProblemBase< STATE_DIM, CONTROL_DIM, SYSTEM_T, LINEAR_SYSTEM_T, LINEARIZER_T, SCALAR > Class Template Reference

#include <OptConProblemBase.h>

Public Types

typedef ct::core::StateVector< STATE_DIM, SCALARstate_vector_t
 
typedef std::shared_ptr< SYSTEM_T > DynamicsPtr_t
 
typedef std::shared_ptr< LINEAR_SYSTEM_T > LinearPtr_t
 
typedef std::shared_ptr< optcon::CostFunctionQuadratic< STATE_DIM, CONTROL_DIM, SCALAR > > CostFunctionPtr_t
 
typedef std::shared_ptr< optcon::LinearConstraintContainer< STATE_DIM, CONTROL_DIM, SCALAR > > ConstraintPtr_t
 
typedef SYSTEM_T::time_t time_t
 

Public Member Functions

 OptConProblemBase ()=default
 
 OptConProblemBase (DynamicsPtr_t nonlinDynamics, CostFunctionPtr_t costFunction, LinearPtr_t linearSystem=nullptr)
 Construct a simple unconstrained Optimal Control Problem. More...
 
 OptConProblemBase (const time_t tf, const state_vector_t &x0, DynamicsPtr_t nonlinDynamics, CostFunctionPtr_t costFunction, LinearPtr_t linearSystem=nullptr)
 Construct a simple unconstrained optimal control problem, with initial state and final time as constructor arguments. More...
 
 OptConProblemBase (DynamicsPtr_t nonlinDynamics, CostFunctionPtr_t costFunction, ConstraintPtr_t inputBoxConstraints, ConstraintPtr_t stateBoxConstraints, ConstraintPtr_t generalConstraints, LinearPtr_t linearSystem=nullptr)
 Construct a constrained Optimal Control Problem. More...
 
 OptConProblemBase (const time_t tf, const state_vector_t &x0, DynamicsPtr_t nonlinDynamics, CostFunctionPtr_t costFunction, ConstraintPtr_t inputBoxConstraints, ConstraintPtr_t stateBoxConstraints, ConstraintPtr_t generalConstraints, LinearPtr_t linearSystem=nullptr)
 Construct a constrained Optimal Control Problem. More...
 
void verify () const
 check if all the ingredients for an unconstrained optimal control problem are there More...
 
const DynamicsPtr_t getNonlinearSystem () const
 
const LinearPtr_t getLinearSystem () const
 
const CostFunctionPtr_t getCostFunction () const
 
void setNonlinearSystem (const DynamicsPtr_t dyn)
 
void setLinearSystem (const LinearPtr_t lin)
 
void setCostFunction (const CostFunctionPtr_t cost)
 
void setInputBoxConstraints (const ConstraintPtr_t constraint)
 
void setStateBoxConstraints (const ConstraintPtr_t constraint)
 
void setGeneralConstraints (const ConstraintPtr_t constraint)
 
const ConstraintPtr_t getInputBoxConstraints () const
 Retrieve the input box constraints. More...
 
const ConstraintPtr_t getStateBoxConstraints () const
 Retrieve the state box constraints. More...
 
const ConstraintPtr_t getGeneralConstraints () const
 Retrieves the general constraints. More...
 
const state_vector_t getInitialState () const
 
void setInitialState (const state_vector_t &x0)
 
time_t getTimeHorizon () const
 
void setTimeHorizon (const time_t tf)
 

Static Public Attributes

static EIGEN_MAKE_ALIGNED_OPERATOR_NEW const size_t STATE_D = STATE_DIM
 
static const size_t CONTROL_D = CONTROL_DIM
 

Detailed Description

template<size_t STATE_DIM, size_t CONTROL_DIM, typename SYSTEM_T, typename LINEAR_SYSTEM_T, typename LINEARIZER_T, typename SCALAR = double>
class ct::optcon::OptConProblemBase< STATE_DIM, CONTROL_DIM, SYSTEM_T, LINEAR_SYSTEM_T, LINEARIZER_T, SCALAR >

Examples:
DMS.cpp, LinearSystemTest.h, NLOC.cpp, NLOC_boxConstrained.cpp, NLOC_generalConstrained.cpp, NLOC_MPC.cpp, NonlinearSystemTest.h, switched_continuous_optcon.cpp, and SymplecticTest.h.

Member Typedef Documentation

◆ state_vector_t

template<size_t STATE_DIM, size_t CONTROL_DIM, typename SYSTEM_T, typename LINEAR_SYSTEM_T, typename LINEARIZER_T, typename SCALAR = double>
typedef ct::core::StateVector<STATE_DIM, SCALAR> ct::optcon::OptConProblemBase< STATE_DIM, CONTROL_DIM, SYSTEM_T, LINEAR_SYSTEM_T, LINEARIZER_T, SCALAR >::state_vector_t

◆ DynamicsPtr_t

template<size_t STATE_DIM, size_t CONTROL_DIM, typename SYSTEM_T, typename LINEAR_SYSTEM_T, typename LINEARIZER_T, typename SCALAR = double>
typedef std::shared_ptr<SYSTEM_T> ct::optcon::OptConProblemBase< STATE_DIM, CONTROL_DIM, SYSTEM_T, LINEAR_SYSTEM_T, LINEARIZER_T, SCALAR >::DynamicsPtr_t

◆ LinearPtr_t

template<size_t STATE_DIM, size_t CONTROL_DIM, typename SYSTEM_T, typename LINEAR_SYSTEM_T, typename LINEARIZER_T, typename SCALAR = double>
typedef std::shared_ptr<LINEAR_SYSTEM_T> ct::optcon::OptConProblemBase< STATE_DIM, CONTROL_DIM, SYSTEM_T, LINEAR_SYSTEM_T, LINEARIZER_T, SCALAR >::LinearPtr_t

◆ CostFunctionPtr_t

template<size_t STATE_DIM, size_t CONTROL_DIM, typename SYSTEM_T, typename LINEAR_SYSTEM_T, typename LINEARIZER_T, typename SCALAR = double>
typedef std::shared_ptr<optcon::CostFunctionQuadratic<STATE_DIM, CONTROL_DIM, SCALAR> > ct::optcon::OptConProblemBase< STATE_DIM, CONTROL_DIM, SYSTEM_T, LINEAR_SYSTEM_T, LINEARIZER_T, SCALAR >::CostFunctionPtr_t

◆ ConstraintPtr_t

template<size_t STATE_DIM, size_t CONTROL_DIM, typename SYSTEM_T, typename LINEAR_SYSTEM_T, typename LINEARIZER_T, typename SCALAR = double>
typedef std::shared_ptr<optcon::LinearConstraintContainer<STATE_DIM, CONTROL_DIM, SCALAR> > ct::optcon::OptConProblemBase< STATE_DIM, CONTROL_DIM, SYSTEM_T, LINEAR_SYSTEM_T, LINEARIZER_T, SCALAR >::ConstraintPtr_t

◆ time_t

template<size_t STATE_DIM, size_t CONTROL_DIM, typename SYSTEM_T, typename LINEAR_SYSTEM_T, typename LINEARIZER_T, typename SCALAR = double>
typedef SYSTEM_T::time_t ct::optcon::OptConProblemBase< STATE_DIM, CONTROL_DIM, SYSTEM_T, LINEAR_SYSTEM_T, LINEARIZER_T, SCALAR >::time_t

Constructor & Destructor Documentation

◆ OptConProblemBase() [1/5]

template<size_t STATE_DIM, size_t CONTROL_DIM, typename SYSTEM_T, typename LINEAR_SYSTEM_T, typename LINEARIZER_T, typename SCALAR = double>
ct::optcon::OptConProblemBase< STATE_DIM, CONTROL_DIM, SYSTEM_T, LINEAR_SYSTEM_T, LINEARIZER_T, SCALAR >::OptConProblemBase ( )
default

◆ OptConProblemBase() [2/5]

template<size_t STATE_DIM, size_t CONTROL_DIM, typename SYSTEM_T , typename LINEAR_SYSTEM_T , typename LINEARIZER_T , typename SCALAR >
ct::optcon::OptConProblemBase< STATE_DIM, CONTROL_DIM, SYSTEM_T, LINEAR_SYSTEM_T, LINEARIZER_T, SCALAR >::OptConProblemBase ( DynamicsPtr_t  nonlinDynamics,
CostFunctionPtr_t  costFunction,
LinearPtr_t  linearSystem = nullptr 
)

Construct a simple unconstrained Optimal Control Problem.

Warning
time and initial state to be specified later
Parameters
nonlinDynamicsthe nonlinear system dynamics
costFunctiona quadratic cost function
linearSystem(optional) the linear system holding the dynamics derivatives. If the user does not specify the derivatives, they are generated automatically using numerical differentiation. Warning: this is slow

◆ OptConProblemBase() [3/5]

template<size_t STATE_DIM, size_t CONTROL_DIM, typename SYSTEM_T , typename LINEAR_SYSTEM_T , typename LINEARIZER_T , typename SCALAR >
ct::optcon::OptConProblemBase< STATE_DIM, CONTROL_DIM, SYSTEM_T, LINEAR_SYSTEM_T, LINEARIZER_T, SCALAR >::OptConProblemBase ( const time_t  tf,
const state_vector_t x0,
DynamicsPtr_t  nonlinDynamics,
CostFunctionPtr_t  costFunction,
LinearPtr_t  linearSystem = nullptr 
)

Construct a simple unconstrained optimal control problem, with initial state and final time as constructor arguments.

Parameters
tfThe optimal control problem final time horizon
x0The initial system state
nonlinDynamicsThe nonlinear system dynamics
costFunctionA quadratic cost function
linearSystem(optional) Linearized System Dynamics.

◆ OptConProblemBase() [4/5]

template<size_t STATE_DIM, size_t CONTROL_DIM, typename SYSTEM_T , typename LINEAR_SYSTEM_T , typename LINEARIZER_T , typename SCALAR >
ct::optcon::OptConProblemBase< STATE_DIM, CONTROL_DIM, SYSTEM_T, LINEAR_SYSTEM_T, LINEARIZER_T, SCALAR >::OptConProblemBase ( DynamicsPtr_t  nonlinDynamics,
CostFunctionPtr_t  costFunction,
ConstraintPtr_t  inputBoxConstraints,
ConstraintPtr_t  stateBoxConstraints,
ConstraintPtr_t  generalConstraints,
LinearPtr_t  linearSystem = nullptr 
)

Construct a constrained Optimal Control Problem.

Parameters
nonlinDynamicsthe nonlinear system dynamics
costFunctiona quadratic cost function
inputBoxConstraintsthe input box constraints
stateBoxConstraintsthe state box constraints
generalConstraintsthe general constraints
linearSystem(optional) the linear system holding the dynamics derivatives.
Warning
time and initial state to be specified later
If the user does not specify the derivatives, they are generated automatically using numerical differentiation. This is slow

◆ OptConProblemBase() [5/5]

template<size_t STATE_DIM, size_t CONTROL_DIM, typename SYSTEM_T , typename LINEAR_SYSTEM_T , typename LINEARIZER_T , typename SCALAR >
ct::optcon::OptConProblemBase< STATE_DIM, CONTROL_DIM, SYSTEM_T, LINEAR_SYSTEM_T, LINEARIZER_T, SCALAR >::OptConProblemBase ( const time_t  tf,
const state_vector_t x0,
DynamicsPtr_t  nonlinDynamics,
CostFunctionPtr_t  costFunction,
ConstraintPtr_t  inputBoxConstraints,
ConstraintPtr_t  stateBoxConstraints,
ConstraintPtr_t  generalConstraints,
LinearPtr_t  linearSystem = nullptr 
)

Construct a constrained Optimal Control Problem.

Parameters
tfThe optimal control problem final time horizon
x0The initial system state
nonlinDynamicsthe nonlinear system dynamics
costFunctiona quadratic cost function
inputBoxConstraintsthe input box constraints
stateBoxConstraintsthe state box constraints
generalConstraintsthe general constraints
linearSystem(optional) the linear system holding the dynamics derivatives.
Warning
time and initial state to be specified later
If the user does not specify the derivatives, they are generated automatically using numerical differentiation. This is slow

Member Function Documentation

◆ verify()

template<size_t STATE_DIM, size_t CONTROL_DIM, typename SYSTEM_T , typename LINEAR_SYSTEM_T , typename LINEARIZER_T , typename SCALAR >
void ct::optcon::OptConProblemBase< STATE_DIM, CONTROL_DIM, SYSTEM_T, LINEAR_SYSTEM_T, LINEARIZER_T, SCALAR >::verify ( ) const

check if all the ingredients for an unconstrained optimal control problem are there

◆ getNonlinearSystem()

template<size_t STATE_DIM, size_t CONTROL_DIM, typename SYSTEM_T , typename LINEAR_SYSTEM_T , typename LINEARIZER_T , typename SCALAR >
const OptConProblemBase< STATE_DIM, CONTROL_DIM, SYSTEM_T, LINEAR_SYSTEM_T, LINEARIZER_T, SCALAR >::DynamicsPtr_t ct::optcon::OptConProblemBase< STATE_DIM, CONTROL_DIM, SYSTEM_T, LINEAR_SYSTEM_T, LINEARIZER_T, SCALAR >::getNonlinearSystem ( ) const

◆ getLinearSystem()

template<size_t STATE_DIM, size_t CONTROL_DIM, typename SYSTEM_T , typename LINEAR_SYSTEM_T , typename LINEARIZER_T , typename SCALAR >
const OptConProblemBase< STATE_DIM, CONTROL_DIM, SYSTEM_T, LINEAR_SYSTEM_T, LINEARIZER_T, SCALAR >::LinearPtr_t ct::optcon::OptConProblemBase< STATE_DIM, CONTROL_DIM, SYSTEM_T, LINEAR_SYSTEM_T, LINEARIZER_T, SCALAR >::getLinearSystem ( ) const

◆ getCostFunction()

template<size_t STATE_DIM, size_t CONTROL_DIM, typename SYSTEM_T , typename LINEAR_SYSTEM_T , typename LINEARIZER_T , typename SCALAR >
const OptConProblemBase< STATE_DIM, CONTROL_DIM, SYSTEM_T, LINEAR_SYSTEM_T, LINEARIZER_T, SCALAR >::CostFunctionPtr_t ct::optcon::OptConProblemBase< STATE_DIM, CONTROL_DIM, SYSTEM_T, LINEAR_SYSTEM_T, LINEARIZER_T, SCALAR >::getCostFunction ( ) const

returns a pinter to the cost function

◆ setNonlinearSystem()

template<size_t STATE_DIM, size_t CONTROL_DIM, typename SYSTEM_T , typename LINEAR_SYSTEM_T , typename LINEARIZER_T , typename SCALAR >
void ct::optcon::OptConProblemBase< STATE_DIM, CONTROL_DIM, SYSTEM_T, LINEAR_SYSTEM_T, LINEARIZER_T, SCALAR >::setNonlinearSystem ( const DynamicsPtr_t  dyn)

returns a pointer to the controlled system

◆ setLinearSystem()

template<size_t STATE_DIM, size_t CONTROL_DIM, typename SYSTEM_T , typename LINEAR_SYSTEM_T , typename LINEARIZER_T , typename SCALAR >
void ct::optcon::OptConProblemBase< STATE_DIM, CONTROL_DIM, SYSTEM_T, LINEAR_SYSTEM_T, LINEARIZER_T, SCALAR >::setLinearSystem ( const LinearPtr_t  lin)

returns a pointer to the linear system approximation

◆ setCostFunction()

template<size_t STATE_DIM, size_t CONTROL_DIM, typename SYSTEM_T , typename LINEAR_SYSTEM_T , typename LINEARIZER_T , typename SCALAR >
void ct::optcon::OptConProblemBase< STATE_DIM, CONTROL_DIM, SYSTEM_T, LINEAR_SYSTEM_T, LINEARIZER_T, SCALAR >::setCostFunction ( const CostFunctionPtr_t  cost)

returns a pinter to the cost function

◆ setInputBoxConstraints()

template<size_t STATE_DIM, size_t CONTROL_DIM, typename SYSTEM_T , typename LINEAR_SYSTEM_T , typename LINEARIZER_T , typename SCALAR >
void ct::optcon::OptConProblemBase< STATE_DIM, CONTROL_DIM, SYSTEM_T, LINEAR_SYSTEM_T, LINEARIZER_T, SCALAR >::setInputBoxConstraints ( const ConstraintPtr_t  constraint)

set input box constraints

Parameters
constraintpointer to box constraint

Referenced by main().

◆ setStateBoxConstraints()

template<size_t STATE_DIM, size_t CONTROL_DIM, typename SYSTEM_T , typename LINEAR_SYSTEM_T , typename LINEARIZER_T , typename SCALAR >
void ct::optcon::OptConProblemBase< STATE_DIM, CONTROL_DIM, SYSTEM_T, LINEAR_SYSTEM_T, LINEARIZER_T, SCALAR >::setStateBoxConstraints ( const ConstraintPtr_t  constraint)

set state box constraints

Parameters
constraintpointer to box constraint

Referenced by main().

◆ setGeneralConstraints()

template<size_t STATE_DIM, size_t CONTROL_DIM, typename SYSTEM_T , typename LINEAR_SYSTEM_T , typename LINEARIZER_T , typename SCALAR >
void ct::optcon::OptConProblemBase< STATE_DIM, CONTROL_DIM, SYSTEM_T, LINEAR_SYSTEM_T, LINEARIZER_T, SCALAR >::setGeneralConstraints ( const ConstraintPtr_t  constraint)

◆ getInputBoxConstraints()

template<size_t STATE_DIM, size_t CONTROL_DIM, typename SYSTEM_T , typename LINEAR_SYSTEM_T , typename LINEARIZER_T , typename SCALAR >
const OptConProblemBase< STATE_DIM, CONTROL_DIM, SYSTEM_T, LINEAR_SYSTEM_T, LINEARIZER_T, SCALAR >::ConstraintPtr_t ct::optcon::OptConProblemBase< STATE_DIM, CONTROL_DIM, SYSTEM_T, LINEAR_SYSTEM_T, LINEARIZER_T, SCALAR >::getInputBoxConstraints ( ) const

Retrieve the input box constraints.

Returns
The input box constraints.

◆ getStateBoxConstraints()

template<size_t STATE_DIM, size_t CONTROL_DIM, typename SYSTEM_T , typename LINEAR_SYSTEM_T , typename LINEARIZER_T , typename SCALAR >
const OptConProblemBase< STATE_DIM, CONTROL_DIM, SYSTEM_T, LINEAR_SYSTEM_T, LINEARIZER_T, SCALAR >::ConstraintPtr_t ct::optcon::OptConProblemBase< STATE_DIM, CONTROL_DIM, SYSTEM_T, LINEAR_SYSTEM_T, LINEARIZER_T, SCALAR >::getStateBoxConstraints ( ) const

Retrieve the state box constraints.

Returns
The state box constraints.

◆ getGeneralConstraints()

template<size_t STATE_DIM, size_t CONTROL_DIM, typename SYSTEM_T , typename LINEAR_SYSTEM_T , typename LINEARIZER_T , typename SCALAR >
const OptConProblemBase< STATE_DIM, CONTROL_DIM, SYSTEM_T, LINEAR_SYSTEM_T, LINEARIZER_T, SCALAR >::ConstraintPtr_t ct::optcon::OptConProblemBase< STATE_DIM, CONTROL_DIM, SYSTEM_T, LINEAR_SYSTEM_T, LINEARIZER_T, SCALAR >::getGeneralConstraints ( ) const

Retrieves the general constraints.

Returns
The the general constraints

◆ getInitialState()

template<size_t STATE_DIM, size_t CONTROL_DIM, typename SYSTEM_T , typename LINEAR_SYSTEM_T , typename LINEARIZER_T , typename SCALAR >
const OptConProblemBase< STATE_DIM, CONTROL_DIM, SYSTEM_T, LINEAR_SYSTEM_T, LINEARIZER_T, SCALAR >::state_vector_t ct::optcon::OptConProblemBase< STATE_DIM, CONTROL_DIM, SYSTEM_T, LINEAR_SYSTEM_T, LINEARIZER_T, SCALAR >::getInitialState ( ) const

get initial state (called by solvers)

◆ setInitialState()

template<size_t STATE_DIM, size_t CONTROL_DIM, typename SYSTEM_T , typename LINEAR_SYSTEM_T , typename LINEARIZER_T , typename SCALAR >
void ct::optcon::OptConProblemBase< STATE_DIM, CONTROL_DIM, SYSTEM_T, LINEAR_SYSTEM_T, LINEARIZER_T, SCALAR >::setInitialState ( const state_vector_t x0)

◆ getTimeHorizon()

template<size_t STATE_DIM, size_t CONTROL_DIM, typename SYSTEM_T , typename LINEAR_SYSTEM_T , typename LINEARIZER_T , typename SCALAR >
OptConProblemBase< STATE_DIM, CONTROL_DIM, SYSTEM_T, LINEAR_SYSTEM_T, LINEARIZER_T, SCALAR >::time_t ct::optcon::OptConProblemBase< STATE_DIM, CONTROL_DIM, SYSTEM_T, LINEAR_SYSTEM_T, LINEARIZER_T, SCALAR >::getTimeHorizon ( ) const

get the current time horizon

Returns
Time Horizon

◆ setTimeHorizon()

template<size_t STATE_DIM, size_t CONTROL_DIM, typename SYSTEM_T , typename LINEAR_SYSTEM_T , typename LINEARIZER_T , typename SCALAR >
void ct::optcon::OptConProblemBase< STATE_DIM, CONTROL_DIM, SYSTEM_T, LINEAR_SYSTEM_T, LINEARIZER_T, SCALAR >::setTimeHorizon ( const time_t  tf)

Member Data Documentation

◆ STATE_D

template<size_t STATE_DIM, size_t CONTROL_DIM, typename SYSTEM_T, typename LINEAR_SYSTEM_T, typename LINEARIZER_T, typename SCALAR = double>
EIGEN_MAKE_ALIGNED_OPERATOR_NEW const size_t ct::optcon::OptConProblemBase< STATE_DIM, CONTROL_DIM, SYSTEM_T, LINEAR_SYSTEM_T, LINEARIZER_T, SCALAR >::STATE_D = STATE_DIM
static

◆ CONTROL_D

template<size_t STATE_DIM, size_t CONTROL_DIM, typename SYSTEM_T, typename LINEAR_SYSTEM_T, typename LINEARIZER_T, typename SCALAR = double>
const size_t ct::optcon::OptConProblemBase< STATE_DIM, CONTROL_DIM, SYSTEM_T, LINEAR_SYSTEM_T, LINEARIZER_T, SCALAR >::CONTROL_D = CONTROL_DIM
static

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