Public Member Functions | Protected Attributes | List of all members

Stores and evaluates the objective function of optimal control problems. More...

#include <objective.hpp>

Inheritance diagram for Objective:
Inheritance graph
[legend]

Public Member Functions

returnValue addLSQ (const MatrixVariablesGrid *S_, const Function &h, const VariablesGrid *r_)
 
returnValue addLSQ (const DMatrix &S, const Function &h)
 
returnValue addLSQ (const DMatrix &S, const std::string &h)
 
returnValue addLSQ (const BMatrix &S, const Function &h)
 
returnValue addLSQ (const BMatrix &S, const std::string &h)
 
returnValue addLSQEndTerm (const DMatrix &S, const Function &m, const DVector &r)
 
returnValue addLSQEndTerm (const DMatrix &S, const Function &h)
 
returnValue addLSQEndTerm (const DMatrix &S, const std::string &h)
 
returnValue addLSQEndTerm (const BMatrix &S, const Function &h)
 
returnValue addLSQEndTerm (const BMatrix &S, const std::string &h)
 
returnValue addLSQLinearTerms (const DVector &Slx, const DVector &Slu)
 
returnValue addLSQLinearTerms (const BVector &Slx, const BVector &Slu)
 
returnValue addMayerTerm (const Expression &arg)
 
returnValue addMayerTerm (const Function &arg)
 
returnValue evaluate (const OCPiterate &x)
 
returnValue evaluateSensitivities ()
 
returnValue evaluateSensitivities (BlockMatrix &hessian)
 
returnValue evaluateSensitivitiesGN (BlockMatrix &hessian)
 
virtual returnValue getBackwardSensitivities (BlockMatrix &D, int order)
 
virtual returnValue getForwardSensitivities (BlockMatrix &D, int order)
 
returnValue getLagrangeTerm (uint index, Function &lagrangeTerm) const
 
returnValue getMayerTerm (uint index, Function &mayerTerm) const
 
int getNP () const
 
int getNU () const
 
uint getNumLagrangeTerms () const
 
uint getNumMayerTerms () const
 
int getNW () const
 
int getNX () const
 
int getNXA () const
 
virtual returnValue getObjectiveValue (double &objectiveValue)
 
BooleanType hasLSQform ()
 
returnValue init (const Grid &grid_)
 
returnValue init (const int nStages, const int nTransitions, DifferentialEquation **fcn, Transition *transitions, Constraint *constraint_)
 
BooleanType isAffine ()
 
BooleanType isConvex ()
 
BooleanType isEmpty () const
 
BooleanType isQuadratic ()
 
 Objective ()
 
 Objective (const Grid &grid_)
 
 Objective (const Objective &rhs)
 
Objectiveoperator= (const Objective &rhs)
 
virtual returnValue setBackwardSeed (BlockMatrix *seed, int order)
 
virtual returnValue setForwardSeed (BlockMatrix *xSeed_, BlockMatrix *xaSeed_, BlockMatrix *pSeed_, BlockMatrix *uSeed_, BlockMatrix *wSeed_, int order)
 
returnValue setReference (const VariablesGrid &ref)
 
virtual returnValue setUnitBackwardSeed ()
 
virtual ~Objective ()
 
Code generation related functions.
returnValue getLSQTerms (LsqElements &_elements) const
 
returnValue getLSQEndTerms (LsqElements &_elements) const
 
returnValue getLSQTerms (LsqExternElements &_elements) const
 
returnValue getLSQEndTerms (LsqExternElements &_elements) const
 
returnValue getLSQLinearTerms (LsqLinearElements &_elements) const
 
- Public Member Functions inherited from LagrangeTerm
returnValue addLagrangeTerm (const Expression &arg)
 
returnValue addLagrangeTerm (const Expression &arg, const int &stageNumber)
 
const GridgetGrid () const
 
returnValue init (const Grid &grid_)
 
 LagrangeTerm ()
 
 LagrangeTerm (const LagrangeTerm &rhs)
 
LagrangeTermoperator= (const LagrangeTerm &rhs)
 
virtual ~LagrangeTerm ()
 

Protected Attributes

LsqExternElements cgExternLsqElements
 
LsqExternElements cgExternLsqEndTermElements
 
LsqElements cgLsqElements
 
LsqElements cgLsqEndTermElements
 
LsqLinearElements cgLsqLinearElements
 
LSQEndTerm ** lsqEndTerm
 
LSQTerm ** lsqTerm
 
MayerTerm ** mayerTerm
 
uint nEndLSQ
 
uint nLSQ
 
uint nMayer
 
- Protected Attributes inherited from LagrangeTerm
Grid grid
 
Expression ** lagrangeFcn
 
int nLagrangeTerms
 

Detailed Description

Stores and evaluates the objective function of optimal control problems.

The class Objective is class is designed to formulate objecive functionals that can be part of an optimal control problem (OCP). Mainly, an objective can have additive terms with different structures that can be added by using various routines that are implemented in this class

Note that a this class is derived from the class LagrangeTerm while it has Mayer and LSQ-Terms as a member. The reason for this assymmetry is that a Lagrange - term will be reformulated as a Mayer term as soon as the function init( ... ) is called. (I.e. the class LagrangeTerm is only used a kind of temporary memory to store Expressions that are added by the user.)

\author Boris Houska, Hans Joachim Ferreau, Milan Vukov

Definition at line 123 of file objective.hpp.

Constructor & Destructor Documentation

BEGIN_NAMESPACE_ACADO Objective::Objective ( )

Default constructor.

Definition at line 49 of file objective.cpp.

Objective::Objective ( const Grid grid_)

Default constructor.

Definition at line 62 of file objective.cpp.

Objective::Objective ( const Objective rhs)

Copy constructor (deep copy).

Definition at line 84 of file objective.cpp.

Objective::~Objective ( )
virtual

Destructor.

Definition at line 124 of file objective.cpp.

Member Function Documentation

returnValue Objective::addLSQ ( const MatrixVariablesGrid S_,
const Function h,
const VariablesGrid r_ 
)

Adds an Least Square term of the general form

0.5* sum_i || h(t_i,x(t_i),u(t_i),p(t_i),...) - r_i ||^2_S_i

Here, the matrices S_i and the reference vectors r_i should be given
in MatrixVariablesGrid and VariablesGrid format respectively. If S_ is
a NULL-pointer the matrices S_i will be unit matrices. If r_ is a
a NULL-pointer the reference will be equal to zero by default.

Returns
SUCCESSFUL_RETURN
Parameters
S_the weighting matrix
hthe LSQ function
r_the reference vectors

Definition at line 155 of file objective.cpp.

returnValue Objective::addLSQ ( const DMatrix S,
const Function h 
)

Definition at line 644 of file objective.cpp.

returnValue Objective::addLSQ ( const DMatrix S,
const std::string &  h 
)

Definition at line 658 of file objective.cpp.

returnValue Objective::addLSQ ( const BMatrix S,
const Function h 
)

Definition at line 672 of file objective.cpp.

returnValue Objective::addLSQ ( const BMatrix S,
const std::string &  h 
)

Definition at line 686 of file objective.cpp.

returnValue Objective::addLSQEndTerm ( const DMatrix S,
const Function m,
const DVector r 
)

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

0.5* || m(T,x(T),p,...) - r ||^2_S

where S is a weighting matrix, r a reference vector and T the time
at the last objective grid point.

Returns
SUCCESSFUL_RETURN
Parameters
Sa weighting matrix
mthe LSQ-Function
rthe reference

Definition at line 175 of file objective.cpp.

returnValue Objective::addLSQEndTerm ( const DMatrix S,
const Function h 
)

Definition at line 651 of file objective.cpp.

returnValue Objective::addLSQEndTerm ( const DMatrix S,
const std::string &  h 
)

Definition at line 665 of file objective.cpp.

returnValue Objective::addLSQEndTerm ( const BMatrix S,
const Function h 
)

Definition at line 679 of file objective.cpp.

returnValue Objective::addLSQEndTerm ( const BMatrix S,
const std::string &  h 
)

Definition at line 693 of file objective.cpp.

returnValue Objective::addLSQLinearTerms ( const DVector Slx,
const DVector Slu 
)

Definition at line 700 of file objective.cpp.

returnValue Objective::addLSQLinearTerms ( const BVector Slx,
const BVector Slu 
)

Definition at line 707 of file objective.cpp.

returnValue Objective::addMayerTerm ( const Expression arg)
inline

Adds an expression for the Mayer term.

Returns
SUCCESSFUL_RETURN
returnValue Objective::addMayerTerm ( const Function arg)
inline
returnValue Objective::evaluate ( const OCPiterate x)

Evaluates the objective with all its terms.

Returns
SUCCESSFUL_RETURN if the evaluation was successful.
of an error message if unsuccessful.

Definition at line 254 of file objective.cpp.

returnValue Objective::evaluateSensitivities ( )

Evaluates the objective gradient. (please use evaluate to specify
the evaluation point)

Returns
SUCCESSFUL_RETURN

Definition at line 271 of file objective.cpp.

returnValue Objective::evaluateSensitivities ( BlockMatrix hessian)

Evaluates the objective gradient and the associated Hessian.
(please use evaluate to specify the evaluation point)

Returns
SUCCESSFUL_RETURN

Definition at line 295 of file objective.cpp.

returnValue Objective::evaluateSensitivitiesGN ( BlockMatrix hessian)

Evaluates the objective gradient. (please use evaluate to specify
the evaluation point)
in addition a Gauss-Newton hessian approximation is provided

Returns
SUCCESSFUL_RETURN
RET_GAUSS_NEWTON_APPROXIMATION_NOT_SUPPORTED

Definition at line 319 of file objective.cpp.

returnValue Objective::getBackwardSensitivities ( BlockMatrix D,
int  order 
)
virtual

Returns the result for the backward sensitivities in BlockMatrix form.

Returns
SUCCESSFUL_RETURN
RET_INPUT_OUT_OF_RANGE
Parameters
Dthe result for the forward sensitivi- ties
orderthe order

Definition at line 472 of file objective.cpp.

returnValue Objective::getForwardSensitivities ( BlockMatrix D,
int  order 
)
virtual

Returns the result for the forward sensitivities in BlockMatrix form.

Returns
SUCCESSFUL_RETURN
RET_INPUT_OUT_OF_RANGE
Parameters
Dthe result for the forward sensitivi- ties
orderthe order

Definition at line 433 of file objective.cpp.

returnValue Objective::getLagrangeTerm ( uint  index,
Function lagrangeTerm 
) const

Definition at line 633 of file objective.cpp.

returnValue Objective::getLSQEndTerms ( LsqElements _elements) const

Definition at line 586 of file objective.cpp.

returnValue Objective::getLSQEndTerms ( LsqExternElements _elements) const

Definition at line 600 of file objective.cpp.

returnValue Objective::getLSQLinearTerms ( LsqLinearElements _elements) const

Definition at line 607 of file objective.cpp.

returnValue Objective::getLSQTerms ( LsqElements _elements) const

Definition at line 579 of file objective.cpp.

returnValue Objective::getLSQTerms ( LsqExternElements _elements) const

Definition at line 593 of file objective.cpp.

returnValue Objective::getMayerTerm ( uint  index,
Function mayerTerm 
) const

Definition at line 620 of file objective.cpp.

int Objective::getNP ( ) const
inline

Returns the number of parameters

Returns
The requested number of parameters.
int Objective::getNU ( ) const
inline

Returns the number of controls

Returns
The requested number of controls.
uint Objective::getNumLagrangeTerms ( ) const

Definition at line 627 of file objective.cpp.

uint Objective::getNumMayerTerms ( ) const

Definition at line 614 of file objective.cpp.

int Objective::getNW ( ) const
inline

Returns the number of disturbances

Returns
The requested number of disturbances.
int Objective::getNX ( ) const
inline

Returns the number of differential states

Returns
The requested number of differential states.
int Objective::getNXA ( ) const
inline

Returns the number of algebraic states

Returns
The requested number of algebraic states.
returnValue Objective::getObjectiveValue ( double &  objectiveValue)
virtual

Returns the result for the residuum of the bounds.

Returns
SUCCESSFUL_RETURN

Definition at line 402 of file objective.cpp.

BooleanType Objective::hasLSQform ( )
inline

Asks the objective whether all terms have Least-Square form. If the
returned answer is "BT_TRUE", the computation of Gauss-Newton hessian
approximation is supported.

Returns
BT_TRUE if all objective terms have LSQ form.
returnValue Objective::init ( const Grid grid_)

Sets the discretization grid.

Returns
SUCCESSFUL_RETURN

Definition at line 77 of file objective.cpp.

returnValue Objective::init ( const int  nStages,
const int  nTransitions,
DifferentialEquation **  fcn,
Transition transitions,
Constraint constraint_ 
)

Initializes the objective and reformulates Lagrange-Terms if
there are any. The RHS function that is passed in the argument
will be augmented by one component if there is a Lagrange term. If
the RHS function is NULL but there is Lagrange term then the
routine will allocate memory for fcn and add one component !!

Parameters
nStagesthe number of stages
nTransitionsthe number of transitions
fcnthe right-hand side functions
transitionsthe transition functions
constraint_the constraint (to be reformulated)

Returns
SUCCESSFUL_RETURN

Definition at line 511 of file objective.cpp.

BooleanType Objective::isAffine ( )
inline

returns whether the constraint element is affine.

BooleanType Objective::isConvex ( )
inline

returns whether the objective is convex.

BooleanType Objective::isEmpty ( ) const

Returns whether or not the objective is empty.

Returns
BT_TRUE if no objective is specified yet.
BT_FALSE otherwise.

Definition at line 571 of file objective.cpp.

BooleanType Objective::isQuadratic ( )
inline

returns whether the objective is quadratic.

Objective & Objective::operator= ( const Objective rhs)

Assignment operator (deep copy).

Definition at line 190 of file objective.cpp.

returnValue Objective::setBackwardSeed ( BlockMatrix seed,
int  order 
)
virtual

Define a backward seed in form of a block matrix.

Returns
SUCCESFUL_RETURN
RET_INPUT_OUT_OF_RANGE
Parameters
seedthe seed matrix
orderthe order of the seed.

Definition at line 370 of file objective.cpp.

returnValue Objective::setForwardSeed ( BlockMatrix xSeed_,
BlockMatrix xaSeed_,
BlockMatrix pSeed_,
BlockMatrix uSeed_,
BlockMatrix wSeed_,
int  order 
)
virtual

Define a forward seed in form of a block matrix.

Returns
SUCCESFUL RETURN
RET_INPUT_OUT_OF_RANGE
Parameters
xSeed_the seed in x -direction
xaSeed_the seed in xa-direction
pSeed_the seed in p -direction
uSeed_the seed in u -direction
wSeed_the seed in w -direction
orderthe order of the seed.

Definition at line 341 of file objective.cpp.

returnValue Objective::setReference ( const VariablesGrid ref)
inline

overwrites the reference (only for LSQ tracking objectives)

Returns
SUCCESSFUL_RETURN
returnValue Objective::setUnitBackwardSeed ( )
virtual

Defines the first order backward seed to be
a unit matrix.

Returns
SUCCESFUL_RETURN
RET_INPUT_OUT_OF_RANGE

Definition at line 394 of file objective.cpp.

Member Data Documentation

LsqExternElements Objective::cgExternLsqElements
protected

Definition at line 482 of file objective.hpp.

LsqExternElements Objective::cgExternLsqEndTermElements
protected

Definition at line 483 of file objective.hpp.

LsqElements Objective::cgLsqElements
protected

Definition at line 479 of file objective.hpp.

LsqElements Objective::cgLsqEndTermElements
protected

Definition at line 480 of file objective.hpp.

LsqLinearElements Objective::cgLsqLinearElements
protected

Definition at line 485 of file objective.hpp.

LSQEndTerm** Objective::lsqEndTerm
protected

The Least Square End Terms.

Definition at line 472 of file objective.hpp.

LSQTerm** Objective::lsqTerm
protected

The Least Square Terms.

Definition at line 471 of file objective.hpp.

MayerTerm** Objective::mayerTerm
protected

The Mayer Terms.

Definition at line 473 of file objective.hpp.

uint Objective::nEndLSQ
protected

number of end LSQ terms

Definition at line 476 of file objective.hpp.

uint Objective::nLSQ
protected

number of LSQ terms

Definition at line 475 of file objective.hpp.

uint Objective::nMayer
protected

number of Mayer terms

Definition at line 477 of file objective.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