#include <OptConProblemBase.h>
|
| 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 EIGEN_MAKE_ALIGNED_OPERATOR_NEW const size_t | STATE_D = STATE_DIM |
|
static const size_t | CONTROL_D = CONTROL_DIM |
|
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.
◆ 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>
◆ DynamicsPtr_t
template<size_t STATE_DIM, size_t CONTROL_DIM, typename SYSTEM_T, typename LINEAR_SYSTEM_T, typename LINEARIZER_T, typename SCALAR = double>
◆ LinearPtr_t
template<size_t STATE_DIM, size_t CONTROL_DIM, typename SYSTEM_T, typename LINEAR_SYSTEM_T, typename LINEARIZER_T, typename SCALAR = double>
◆ CostFunctionPtr_t
template<size_t STATE_DIM, size_t CONTROL_DIM, typename SYSTEM_T, typename LINEAR_SYSTEM_T, typename LINEARIZER_T, typename SCALAR = double>
◆ ConstraintPtr_t
template<size_t STATE_DIM, size_t CONTROL_DIM, typename SYSTEM_T, typename LINEAR_SYSTEM_T, typename LINEARIZER_T, typename SCALAR = double>
◆ time_t
template<size_t STATE_DIM, size_t CONTROL_DIM, typename SYSTEM_T, typename LINEAR_SYSTEM_T, typename LINEARIZER_T, typename SCALAR = double>
◆ 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>
◆ OptConProblemBase() [2/5]
template<size_t STATE_DIM, size_t CONTROL_DIM, typename SYSTEM_T , typename LINEAR_SYSTEM_T , typename LINEARIZER_T , typename SCALAR >
Construct a simple unconstrained Optimal Control Problem.
- Warning
- time and initial state to be specified later
- Parameters
-
nonlinDynamics | the nonlinear system dynamics |
costFunction | a 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 >
Construct a simple unconstrained optimal control problem, with initial state and final time as constructor arguments.
- Parameters
-
tf | The optimal control problem final time horizon |
x0 | The initial system state |
nonlinDynamics | The nonlinear system dynamics |
costFunction | A 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
-
nonlinDynamics | the nonlinear system dynamics |
costFunction | a quadratic cost function |
inputBoxConstraints | the input box constraints |
stateBoxConstraints | the state box constraints |
generalConstraints | the 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
-
tf | The optimal control problem final time horizon |
x0 | The initial system state |
nonlinDynamics | the nonlinear system dynamics |
costFunction | a quadratic cost function |
inputBoxConstraints | the input box constraints |
stateBoxConstraints | the state box constraints |
generalConstraints | the 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
◆ verify()
template<size_t STATE_DIM, size_t CONTROL_DIM, typename SYSTEM_T , typename LINEAR_SYSTEM_T , typename LINEARIZER_T , typename SCALAR >
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 >
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 >
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 >
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 >
set input box constraints
- Parameters
-
constraint | pointer 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 >
set state box constraints
- Parameters
-
constraint | pointer 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 >
◆ 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 >
◆ 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 >
◆ STATE_D
template<size_t STATE_DIM, size_t CONTROL_DIM, typename SYSTEM_T, typename LINEAR_SYSTEM_T, typename LINEARIZER_T, typename SCALAR = double>
◆ CONTROL_D
template<size_t STATE_DIM, size_t CONTROL_DIM, typename SYSTEM_T, typename LINEAR_SYSTEM_T, typename LINEARIZER_T, typename SCALAR = double>
The documentation for this class was generated from the following files: