Public Member Functions | Protected Member Functions | Protected Attributes | List of all members

Data class for defining optimal control problems. More...

#include <ocp.hpp>

Inheritance diagram for OCP:
Inheritance graph
[legend]

Public Member Functions

returnValue maximizeLagrangeTerm (const Expression &arg)
 
returnValue maximizeMayerTerm (const Expression &arg)
 
returnValue minimizeLagrangeTerm (const Expression &arg)
 
returnValue minimizeMayerTerm (const Expression &arg)
 
returnValue minimizeMayerTerm (const int &multiObjectiveIdx, const Expression &arg)
 
 OCP (const double &tStart_=0.0, const double &tEnd_=1.0, const int &N_=20)
 
 OCP (const double &tStart_, const double &tEnd_, const DVector &_numSteps)
 
 OCP (const double &tStart_, const Parameter &tEnd_, const int &N_=20)
 
 OCP (const Grid &grid_)
 
returnValue subjectTo (const DifferentialEquation &differentialEquation_)
 
returnValue subjectTo (const ConstraintComponent &component)
 
returnValue subjectTo (int index_, const ConstraintComponent &component)
 
returnValue subjectTo (const double lb_, const Expression &arg1, const Expression &arg2, const double ub_)
 
virtual ~OCP ()
 
Least Squares terms.

Adds a Least Square term of the form

\begin{equation*} \frac{1}{2} \sum_i \Vert h(t_i,x(t_i),u(t_i),p(t_i),...) - r \Vert^2_{S_{i}} \end{equation*}

Here the sum is over all grid points of the objective grid. The DMatrix $ S $ is assumed to be symmetric and positive (semi-) definite. The Function $ r $ is called reference and can be specified by the user. The function $ h $ is a standard Function.

See also
Function
Returns
SUCCESSFUL_RETURN
returnValue minimizeLSQ (const DMatrix &S, const Function &h, const DVector &r)
 
returnValue minimizeLSQ (const Function &h, const DVector &r)
 
returnValue minimizeLSQ (const Function &h)
 
returnValue minimizeLSQ (const MatrixVariablesGrid &S, const Function &h, const VariablesGrid &r)
 
returnValue minimizeLSQ (const DMatrix &S, const Function &h, const VariablesGrid &r)
 
returnValue minimizeLSQ (const Function &h, const VariablesGrid &r)
 
returnValue minimizeLSQ (const MatrixVariablesGrid &S, const Function &h, const char *rFilename)
 
returnValue minimizeLSQ (const DMatrix &S, const Function &h, const char *rFilename)
 
returnValue minimizeLSQ (const Function &h, const char *rFilename)
 
returnValue minimizeLSQ (const DMatrix &S, const Function &h)
 
returnValue minimizeLSQ (const BMatrix &S, const Function &h)
 
returnValue minimizeLSQ (const DMatrix &S, const std::string &h)
 
returnValue minimizeLSQ (const BMatrix &S, const std::string &h)
 
Least Squares end terms.

Adds an Least Square term that is only evaluated at the end:

\begin{equation*} \frac{1}{2} \Vert( m(T,x(T),u(T),p(T),...) - r )\Vert^2_S \end{equation*}

where $ S $ is a weighting matrix, $ r $ a reference vector and $ T $ the time at the last objective grid point. The function $ m $ is a standard Function.

Returns
SUCCESSFUL_RETURN
returnValue minimizeLSQEndTerm (const DMatrix &S, const Function &m, const DVector &r)
 
returnValue minimizeLSQEndTerm (const Function &m, const DVector &r)
 
returnValue minimizeLSQEndTerm (const DMatrix &S, const Function &m)
 
returnValue minimizeLSQEndTerm (const DMatrix &S, const std::string &m)
 
returnValue minimizeLSQEndTerm (const BMatrix &S, const Function &m)
 
returnValue minimizeLSQEndTerm (const BMatrix &S, const std::string &m)
 
Set linear terms in the LSQ formulation.
returnValue minimizeLSQLinearTerms (const DVector &Slx, const DVector &Slu)
 
returnValue minimizeLSQLinearTerms (const BVector &Slx, const BVector &Slu)
 
returnValue subjectTo (const double lb_, const Expression *arguments, const double ub_)
 
Add a custom constraint to the OCP formulation.

Adds a constraint of the form

\begin{equation*} \text{lb} <= h_i(t_i, x(t_i), u(t_i), p, ...) <= \text{ub} \end{equation*}

with constant lower and upper bounds.

returnValue subjectTo (const DVector &_lb, const Expression &_expr, const DVector &_ub)
 
returnValue subjectTo (int _index, const DVector &_lb, const Expression &_expr, const DVector &_ub)
 
Helper functions.
BooleanType hasObjective () const
 
BooleanType hasConstraint () const
 
returnValue getGrid (Grid &grid_) const
 
returnValue getObjective (Objective &objective_) const
 
returnValue getObjective (const int &multiObjectiveIdx, Expression **arg) const
 
returnValue getConstraint (Constraint &constraint_) const
 
returnValue setObjective (const Objective &objective_)
 
returnValue setConstraint (const Constraint &constraint_)
 
returnValue setNumberIntegrationSteps (const uint numSteps)
 
virtual BooleanType hasEquidistantGrid () const
 
double getStartTime () const
 
double getEndTime () const
 
- Public Member Functions inherited from MultiObjectiveFunctionality
int getNumberOfMayerTerms () const
 
returnValue getObjective (const int &multiObjectiveIdx, Expression **arg) const
 
returnValue minimizeMayerTerm (const int &multiObjectiveIdx, const Expression &arg)
 
 MultiObjectiveFunctionality ()
 
 MultiObjectiveFunctionality (const MultiObjectiveFunctionality &rhs)
 
MultiObjectiveFunctionalityoperator= (const MultiObjectiveFunctionality &rhs)
 
 ~MultiObjectiveFunctionality ()
 
- Public Member Functions inherited from ModelContainer
uint addOutput (const OutputFcn &outputEquation_, const DVector &measurements)
 
uint addOutput (const OutputFcn &outputEquation_, const uint numberMeasurements)
 
uint addOutput (const std::string &output, const std::string &diffs_output, const uint dim, const DVector &measurements)
 
uint addOutput (const std::string &output, const std::string &diffs_output, const uint dim, const uint numberMeasurements)
 
uint addOutput (const std::string &output, const std::string &diffs_output, const uint dim, const DVector &measurements, const std::string &colInd, const std::string &rowPtr)
 
uint addOutput (const std::string &output, const std::string &diffs_output, const uint dim, const uint numberMeasurements, const std::string &colInd, const std::string &rowPtr)
 
BooleanType exportRhs () const
 
DVector getDimOutputs () const
 
const std::string getFileNameModel () const
 
returnValue getIntegrationGrid (Grid &_grid) const
 
returnValue getModel (DifferentialEquation &_f) const
 
ModelDatagetModelData ()
 
uint getN () const
 
uint getNDX () const
 
uint getNOD () const
 
uint getNP () const
 
uint getNU () const
 
DVector getNumMeas () const
 
uint getNX () const
 
uint getNXA () const
 
BooleanType hasDifferentialEquation () const
 
BooleanType hasEquidistantControlGrid () const
 
BooleanType hasOutputs () const
 
 ModelContainer ()
 
BooleanType modelDimensionsSet () const
 
returnValue setDimensions (uint _NX1, uint _NX2, uint _NX3, uint _NDX, uint _NDX3, uint _NXA, uint _NXA3, uint _NU, uint _NOD, uint _NP)
 
returnValue setDimensions (uint _NX1, uint _NX2, uint _NX3, uint _NDX, uint _NXA, uint _NU, uint _NOD, uint _NP)
 
returnValue setDimensions (uint _NX, uint _NDX, uint _NXA, uint _NU, uint _NOD, uint _NP)
 
returnValue setDimensions (uint _NX, uint _NU, uint _NOD, uint _NP)
 
returnValue setIntegrationGrid (const Grid &_ocpGrid, const uint _numSteps)
 
returnValue setLinearInput (const DMatrix &A1_, const DMatrix &B1_)
 
returnValue setLinearInput (const DMatrix &M1_, const DMatrix &A1_, const DMatrix &B1_)
 
returnValue setLinearOutput (const DMatrix &A3_, const OutputFcn &rhs_)
 
returnValue setLinearOutput (const DMatrix &M3_, const DMatrix &A3_, const OutputFcn &rhs_)
 
returnValue setLinearOutput (const DMatrix &A3_, const std::string &_rhs3, const std::string &_diffs_rhs3)
 
returnValue setLinearOutput (const DMatrix &M3_, const DMatrix &A3_, const std::string &_rhs3, const std::string &_diffs_rhs3)
 
returnValue setModel (const DifferentialEquation &_f)
 
returnValue setModel (const std::string &fileName, const std::string &_rhs_ODE, const std::string &_diffs_rhs_ODE)
 
returnValue setModelData (const ModelData &data)
 
returnValue setN (const uint N_)
 
returnValue setNARXmodel (const uint _delay, const DMatrix &_parms)
 
returnValue setNOD (const uint NOD_)
 
returnValue setNonlinearFeedback (const DMatrix &C_, const OutputFcn &feedb_)
 
returnValue setNP (const uint NP_)
 
returnValue setNU (const uint NU_)
 
returnValue setupOutput (const DVector &numberMeasurements)
 

Protected Member Functions

void setupGrid (double tStart, double tEnd, int N)
 
void setupGrid (const DVector &times)
 

Protected Attributes

std::shared_ptr< Constraintconstraint
 
std::shared_ptr< Gridgrid
 
std::shared_ptr< Objectiveobjective
 
- Protected Attributes inherited from MultiObjectiveFunctionality
Expression ** mayerTerms
 
int nMayer
 
- Protected Attributes inherited from ModelContainer
ModelData modelData
 
uint NOD
 
uint NP
 
uint NU
 

Detailed Description

Data class for defining optimal control problems.

The class OCP is a data class for defining optimal control problems. In the most easiest an optimal control problem can consists of an objective only - i.e. in principle we can set up NLP's as well if no dynamic system is specified. However, in general the objective functional is optimized subject to a dynamic equation and different kind of constraints.

Note that the OCP class is only designed for the user and collects data only. In order to solve an OCP this class must be setup and passed to an appropriate OptimizationAlgorithm.

For setting up an optimal control problem (OCP), we should first specify the time horizon on which the OCP is defined. Note that there are several constructors available which allow to construct an OCP directly with the corresponding time interval. Here, the interval can consist of of given bounds, but in another variant a parameter can be passed in order to allow the setup of optimal control problems for which the end time is optimized, too.

Constraints can be specified with the "subjectTo" syntax. Please note that every parameter, state, control etc which is not fixed via a constraint will be regarded as an optimization variable. In particular, initial value or boundary constraints appear in many OCP formulations and of course all these constraints should all be set explicitly. Moreover, the dynamic equations (model) is regarded as a constraint, too.

Please note that the OCP class only collects the formulation of the problem. If initial values for non-linear problems should be specified, this needs to be done on the algorithm dealing with the OCP. (

See also
OptimizationAlgorithm)

For advanced users and developers it might be important to know that the class OCP inherits the MultiObjectiveFunctionality which is needed if more than one objective should be specified.

Please check the tutorial examples as well as the class reference below, to learn about the usage of this class in more detail.

Definition at line 89 of file ocp.hpp.

Constructor & Destructor Documentation

BEGIN_NAMESPACE_ACADO OCP::OCP ( const double &  tStart_ = 0.0,
const double &  tEnd_ = 1.0,
const int &  N_ = 20 
)

Default Constructor which can optionally set the time-horizon of the problem.

Parameters
tStart_start of the time horizon of the OCP
tEnd_end of the time horizon of the OCP
N_number of discretization intervals

Definition at line 45 of file ocp.cpp.

OCP::OCP ( const double &  tStart_,
const double &  tEnd_,
const DVector _numSteps 
)

Constructor which can set a non equidistant time-horizon of the problem.

Parameters
tStart_start of the time horizon of the OCP
tEnd_end of the time horizon of the OCP
_numStepsnumber of integration steps in each discretization interval

Definition at line 56 of file ocp.cpp.

OCP::OCP ( const double &  tStart_,
const Parameter tEnd_,
const int &  N_ = 20 
)

Constructor that takes a parametric version of the time horizon. This contructor should be used if the end time should be optimized, too.

Parameters
tStart_start of the time horizon of the OCP
tEnd_end of the time horizon of the OCP
N_number of discretization intervals

Definition at line 91 of file ocp.cpp.

OCP::OCP ( const Grid grid_)

Constructor that takes the time horizon in form of a Grid.

Parameters
grid_discretization grid

Definition at line 80 of file ocp.cpp.

OCP::~OCP ( )
virtual

Destructor (deletes everything).

Definition at line 101 of file ocp.cpp.

Member Function Documentation

returnValue OCP::getConstraint ( Constraint constraint_) const

Definition at line 331 of file ocp.cpp.

double OCP::getEndTime ( ) const

Definition at line 362 of file ocp.cpp.

returnValue OCP::getGrid ( Grid grid_) const

Definition at line 329 of file ocp.cpp.

returnValue OCP::getObjective ( Objective objective_) const

Definition at line 330 of file ocp.cpp.

returnValue OCP::getObjective ( const int &  multiObjectiveIdx,
Expression **  arg 
) const

Definition at line 355 of file ocp.cpp.

double OCP::getStartTime ( ) const

Definition at line 361 of file ocp.cpp.

BooleanType OCP::hasConstraint ( ) const

Definition at line 322 of file ocp.cpp.

BooleanType OCP::hasEquidistantGrid ( ) const
virtual

Returns whether the ocp grid is equidistant.

Returns
true iff the OCP grid is equidistant, false otherwise.

Definition at line 364 of file ocp.cpp.

BooleanType OCP::hasObjective ( ) const

Definition at line 316 of file ocp.cpp.

returnValue OCP::maximizeLagrangeTerm ( const Expression arg)

Adds an expression as a the Lagrange term to be maximized.

Returns
SUCCESSFUL_RETURN

Definition at line 241 of file ocp.cpp.

returnValue OCP::maximizeMayerTerm ( const Expression arg)

Adds an expression as a the Mayer term to be maximized. Note that this function is introduced for convenience only. A call of the form maximizeMayerTerm( arg ) is equivalent to calling minimizeMayerTerm( -arg ).

Returns
SUCCESSFUL_RETURN

Definition at line 239 of file ocp.cpp.

returnValue OCP::minimizeLagrangeTerm ( const Expression arg)

Adds an expression as a the Lagrange term to be minimized.

Returns
SUCCESSFUL_RETURN

Definition at line 240 of file ocp.cpp.

returnValue OCP::minimizeLSQ ( const DMatrix S,
const Function h,
const DVector r 
)
Parameters
Sa weighting matrix
hthe LSQ-Function
rthe reference

Definition at line 244 of file ocp.cpp.

returnValue OCP::minimizeLSQ ( const Function h,
const DVector r 
)
Parameters
hthe LSQ-Function
rthe reference

Definition at line 252 of file ocp.cpp.

returnValue OCP::minimizeLSQ ( const Function h)
Parameters
hthe LSQ-Function

Definition at line 260 of file ocp.cpp.

returnValue OCP::minimizeLSQ ( const MatrixVariablesGrid S,
const Function h,
const VariablesGrid r 
)
Parameters
Sa weighting matrix
hthe LSQ-Function
rthe reference

Definition at line 272 of file ocp.cpp.

returnValue OCP::minimizeLSQ ( const DMatrix S,
const Function h,
const VariablesGrid r 
)
Parameters
Sa weighting matrix
hthe LSQ-Function
rthe reference

Definition at line 279 of file ocp.cpp.

returnValue OCP::minimizeLSQ ( const Function h,
const VariablesGrid r 
)
Parameters
hthe LSQ-Function
rthe reference

Definition at line 290 of file ocp.cpp.

returnValue OCP::minimizeLSQ ( const MatrixVariablesGrid S,
const Function h,
const char *  rFilename 
)
Parameters
Sa weighting matrix
hthe LSQ-Function
rFilenamefilename where the reference is stored

Definition at line 110 of file ocp.cpp.

returnValue OCP::minimizeLSQ ( const DMatrix S,
const Function h,
const char *  rFilename 
)
Parameters
Sa weighting matrix
hthe LSQ-Function
rFilenamefilename where the reference is stored

Definition at line 125 of file ocp.cpp.

returnValue OCP::minimizeLSQ ( const Function h,
const char *  rFilename 
)
Parameters
hthe LSQ-Function
rFilenamefilename where the reference is stored

Definition at line 139 of file ocp.cpp.

returnValue OCP::minimizeLSQ ( const DMatrix S,
const Function h 
)
Note
Applicable only for automatic code generation.
Parameters
Sa weighting matrix
hthe LSQ-Function

Definition at line 371 of file ocp.cpp.

returnValue OCP::minimizeLSQ ( const BMatrix S,
const Function h 
)

Pass the sparsity pattern of the weighting matrix to the code generator.

Note
Applicable only for automatic code generation.
Parameters
Sa weighting matrix
hthe LSQ-Function

Definition at line 381 of file ocp.cpp.

returnValue OCP::minimizeLSQ ( const DMatrix S,
const std::string &  h 
)
Note
Applicable only for automatic code generation.
Parameters
Sa weighting matrix
hthe externally defined LSQ-Function

Definition at line 391 of file ocp.cpp.

returnValue OCP::minimizeLSQ ( const BMatrix S,
const std::string &  h 
)

Pass the sparsity pattern of the weighting matrix to the code generator.

Note
Applicable only for automatic code generation.
Parameters
Sa weighting matrix
hthe externally defined LSQ-Function

Definition at line 401 of file ocp.cpp.

returnValue OCP::minimizeLSQEndTerm ( const DMatrix S,
const Function m,
const DVector r 
)
Parameters
Sa weighting matrix
mthe LSQ-Function
rthe reference

Definition at line 297 of file ocp.cpp.

returnValue OCP::minimizeLSQEndTerm ( const Function m,
const DVector r 
)
Parameters
mthe LSQ-Function
rthe reference

Definition at line 307 of file ocp.cpp.

returnValue OCP::minimizeLSQEndTerm ( const DMatrix S,
const Function m 
)
Note
Applicable only for automatic code generation.
Parameters
Sa weighting matrix
mthe LSQ-Function

Definition at line 376 of file ocp.cpp.

returnValue OCP::minimizeLSQEndTerm ( const DMatrix S,
const std::string &  m 
)
Note
Applicable only for automatic code generation.
Parameters
Sa weighting matrix
mthe externally defined LSQ-Function

Definition at line 396 of file ocp.cpp.

returnValue OCP::minimizeLSQEndTerm ( const BMatrix S,
const Function m 
)

Pass the sparsity pattern of the weighting matrix to the code generator.

Note
Applicable only for automatic code generation.
Parameters
Sa weighting matrix
mthe LSQ-Function

Definition at line 386 of file ocp.cpp.

returnValue OCP::minimizeLSQEndTerm ( const BMatrix S,
const std::string &  m 
)

Pass the sparsity pattern of the weighting matrix to the code generator.

Note
Applicable only for automatic code generation.
Parameters
Sa weighting matrix
mthe externally defined LSQ-Function

Definition at line 406 of file ocp.cpp.

returnValue OCP::minimizeLSQLinearTerms ( const DVector Slx,
const DVector Slu 
)

Applicable only for automatic code generation.

Note
Experimental.
Parameters
Slxa weighting vector for differential states.
Slua weighting vector for controls.

Definition at line 411 of file ocp.cpp.

returnValue OCP::minimizeLSQLinearTerms ( const BVector Slx,
const BVector Slu 
)

Applicable only for automatic code generation.

Note
Experimental.
Parameters
Slxa weighting vector for differential states.
Slua weighting vector for controls.

Definition at line 416 of file ocp.cpp.

returnValue OCP::minimizeMayerTerm ( const Expression arg)

Adds an expression as a the Mayer term to be minimized.

Returns
SUCCESSFUL_RETURN

Definition at line 238 of file ocp.cpp.

returnValue OCP::minimizeMayerTerm ( const int &  multiObjectiveIdx,
const Expression arg 
)

Adds an expression as a the Mayer term to be minimized. In this version the number of the objective can be specified as well. This functionality is needed for multi-objective optimal control problems.

Returns
SUCCESSFUL_RETURN

Definition at line 104 of file ocp.cpp.

returnValue OCP::setConstraint ( const Constraint constraint_)

Definition at line 339 of file ocp.cpp.

returnValue OCP::setNumberIntegrationSteps ( const uint  numSteps)

Definition at line 346 of file ocp.cpp.

returnValue OCP::setObjective ( const Objective objective_)

Definition at line 334 of file ocp.cpp.

void OCP::setupGrid ( double  tStart,
double  tEnd,
int  N 
)
protected

Definition at line 423 of file ocp.cpp.

void OCP::setupGrid ( const DVector times)
protected

Definition at line 432 of file ocp.cpp.

returnValue OCP::subjectTo ( const DifferentialEquation differentialEquation_)

Adds an differential equation (as a continuous equality constraint).

Parameters
differentialEquation_the differential equation to be added
n_the number of control intervals

Returns
SUCCESSFUL_RETURN

Definition at line 153 of file ocp.cpp.

returnValue OCP::subjectTo ( const ConstraintComponent component)

Adds a (continuous) constraint.

Returns
SUCCESSFUL_RETURN
RET_INFEASIBLE_CONSTRAINT
Adds a discrete, point, constraint.
SUCCESSFUL_RETURN
RET_INFEASIBLE_CONSTRAINT

Definition at line 161 of file ocp.cpp.

returnValue OCP::subjectTo ( int  index_,
const ConstraintComponent component 
)

Definition at line 170 of file ocp.cpp.

returnValue OCP::subjectTo ( const double  lb_,
const Expression arg1,
const Expression arg2,
const double  ub_ 
)

Add a coupled boundary constraint.

Coupled boundary constraints of general form

\begin{equation*} \text{lb} \leq h_1( t_0,x(t_0),u(t_0),p,... ) + h_2( t_e,x(t_e),u(t_e),p,... ) \leq \text{ub} \end{equation*}

where $ t_0 $ is the first and $ t_e $ the last time point in the grid. Adds a constraint of the form

lb <= arg1(0) + arg2(T) <= ub 

with constant lower and upper bounds.

Returns
SUCCESSFUL_RETURN
RET_INFEASIBLE_CONSTRAINT

Definition at line 194 of file ocp.cpp.

returnValue OCP::subjectTo ( const double  lb_,
const Expression arguments,
const double  ub_ 
)

Add a custom constraint.

Adds a constraint of the form

\begin{equation*} \text{lb} <= \sum_i h_i(t_i, x(t_i), u(t_i), p, ...) <= \text{ub} \end{equation*}

with constant lower and upper bounds.

Returns
SUCCESSFUL_RETURN
RET_INFEASIBLE_CONSTRAINT

Definition at line 201 of file ocp.cpp.

returnValue OCP::subjectTo ( const DVector _lb,
const Expression _expr,
const DVector _ub 
)

Definition at line 206 of file ocp.cpp.

returnValue OCP::subjectTo ( int  _index,
const DVector _lb,
const Expression _expr,
const DVector _ub 
)

Definition at line 214 of file ocp.cpp.

Member Data Documentation

std::shared_ptr<Constraint> OCP::constraint
protected

The Constraints.

Definition at line 400 of file ocp.hpp.

std::shared_ptr<Grid> OCP::grid
protected

Common discretization grid.

Definition at line 396 of file ocp.hpp.

std::shared_ptr<Objective> OCP::objective
protected

The Objective.

Definition at line 398 of file ocp.hpp.


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


acado
Author(s): Milan Vukov, Rien Quirynen
autogenerated on Mon Jun 10 2019 12:35:25