Public Member Functions | Protected Member Functions | Protected Attributes

User-interface to formulate and solve model predictive control problems. More...

#include <real_time_algorithm.hpp>

Inheritance diagram for RealTimeAlgorithm:
Inheritance graph
[legend]

List of all members.

Public Member Functions

virtual ControlLawclone () const
virtual returnValue feedbackStep (double currentTime, const DVector &_x, const DVector &_p=emptyConstVector, const VariablesGrid &_yRef=emptyConstVariablesGrid)
virtual double getLengthControlHorizon () const
virtual double getLengthPredictionHorizon () const
virtual uint getNP () const
virtual uint getNU () const
virtual uint getNW () const
virtual uint getNX () const
virtual uint getNXA () const
virtual uint getNY () const
virtual returnValue init ()
virtual returnValue init (double startTime, const DVector &_x=emptyConstVector, const DVector &_p=emptyConstVector, const VariablesGrid &_yRef=emptyConstVariablesGrid)
virtual returnValue initializeAlgebraicStates (const VariablesGrid &_xa_init)
virtual returnValue initializeAlgebraicStates (const char *fileName)
virtual returnValue initializeControls (const VariablesGrid &_u_init)
virtual returnValue initializeControls (const char *fileName)
virtual BooleanType isDynamic () const
virtual BooleanType isInRealTimeMode () const
virtual BooleanType isStatic () const
RealTimeAlgorithmoperator= (const RealTimeAlgorithm &rhs)
virtual returnValue preparationStep (double nextTime=0.0, const VariablesGrid &_yRef=emptyConstVariablesGrid)
 RealTimeAlgorithm ()
 RealTimeAlgorithm (const OCP &ocp_, double _samplingTime=DEFAULT_SAMPLING_TIME)
 RealTimeAlgorithm (const RealTimeAlgorithm &rhs)
virtual returnValue setReference (const VariablesGrid &ref)
virtual returnValue shift (double timeShift=-1.0)
virtual returnValue solve (double startTime, const DVector &_x, const DVector &_p=emptyConstVector, const VariablesGrid &_yRef=emptyConstVariablesGrid)
virtual returnValue step (double currentTime, const DVector &_x, const DVector &_p=emptyConstVector, const VariablesGrid &_yRef=emptyConstVariablesGrid)
virtual ~RealTimeAlgorithm ()

Protected Member Functions

virtual returnValue allocateNlpSolver (Objective *F, DynamicDiscretization *G, Constraint *H)
returnValue clear ()
virtual returnValue initializeNlpSolver (const OCPiterate &userInit)
virtual returnValue initializeObjective (Objective *F)
returnValue performFeedbackStep (double currentTime, const DVector &_x, const DVector &_p=emptyConstVector)
returnValue performPreparationStep (const VariablesGrid &_yRef=emptyConstVariablesGrid, BooleanType isLastIteration=BT_TRUE)
virtual returnValue setupLogging ()
virtual returnValue setupOptions ()

Protected Attributes

DVectorp0
VariablesGridreference
DVectorx0

Detailed Description

User-interface to formulate and solve model predictive control problems.

The class RealTimeAlgorithm serves as a user-interface to formulate and solve model predictive control problems.

Author:
Hans Joachim Ferreau, Boris Houska

Definition at line 56 of file real_time_algorithm.hpp.


Constructor & Destructor Documentation

Default constructor.

Definition at line 50 of file real_time_algorithm.cpp.

RealTimeAlgorithm::RealTimeAlgorithm ( const OCP ocp_,
double  _samplingTime = DEFAULT_SAMPLING_TIME 
)

Constructor which takes the optimal control problem to be solved online together with the sampling time.

Parameters:
[in]ocp_Optimal control problem to be solved online.
[in]_samplingTimeSampling time.

Definition at line 69 of file real_time_algorithm.cpp.

Copy constructor (deep copy).

Parameters:
[in]rhsRight-hand side object.

Definition at line 91 of file real_time_algorithm.cpp.

Destructor.

Definition at line 104 of file real_time_algorithm.cpp.


Member Function Documentation

(not yet documented).

Parameters:
[in]..
Returns:
SUCCESSFUL_RETURN

Implements OptimizationAlgorithmBase.

Definition at line 576 of file real_time_algorithm.cpp.

Frees memory of all members of the real time parameters.

Returns:
SUCCESSFUL_RETURN

Reimplemented from OptimizationAlgorithmBase.

Definition at line 551 of file real_time_algorithm.cpp.

ControlLaw * RealTimeAlgorithm::clone ( ) const [virtual]

Clone constructor (deep copy).

Returns:
Pointer to deep copy of base class type

Implements ControlLaw.

Definition at line 133 of file real_time_algorithm.cpp.

returnValue RealTimeAlgorithm::feedbackStep ( double  currentTime,
const DVector _x,
const DVector _p = emptyConstVector,
const VariablesGrid _yRef = emptyConstVariablesGrid 
) [virtual]

Performs next feedback step of the control law based on given inputs.

Parameters:
[in]currentTimeCurrent time.
[in]_xMost recent value for differential states.
[in]_pMost recent value for parameters.
[in]_yRefCurrent piece of reference trajectory (if not specified during previous preparationStep).
Note:
If a non-empty reference trajectory is provided, this one is used instead of the possibly set-up build-in one.
Returns:
SUCCESSFUL_RETURN

Definition at line 251 of file real_time_algorithm.cpp.

double RealTimeAlgorithm::getLengthControlHorizon ( ) const [virtual]

Returns length of the control horizon (for the case a predictive control law is used).

Returns:
Length of the control horizon

Reimplemented from ControlLaw.

Definition at line 442 of file real_time_algorithm.cpp.

Returns length of the prediction horizon (for the case a predictive control law is used).

Returns:
Length of the prediction horizon

Reimplemented from ControlLaw.

Definition at line 436 of file real_time_algorithm.cpp.

uint RealTimeAlgorithm::getNP ( ) const [virtual]

Returns number of parameters.

Returns:
Number of parameters

Reimplemented from ControlLaw.

Definition at line 418 of file real_time_algorithm.cpp.

uint RealTimeAlgorithm::getNU ( ) const [virtual]

Returns number of controls.

Returns:
Number of controls

Reimplemented from ControlLaw.

Definition at line 413 of file real_time_algorithm.cpp.

uint RealTimeAlgorithm::getNW ( ) const [virtual]

Returns number of (estimated) disturbances.

Returns:
Number of (estimated) disturbances

Reimplemented from ControlLaw.

Definition at line 423 of file real_time_algorithm.cpp.

uint RealTimeAlgorithm::getNX ( ) const [virtual]

Returns number of (estimated) differential states.

Returns:
Number of (estimated) differential states

Reimplemented from ControlLaw.

Definition at line 403 of file real_time_algorithm.cpp.

uint RealTimeAlgorithm::getNXA ( ) const [virtual]

Returns number of (estimated) algebraic states.

Returns:
Number of (estimated) algebraic states

Reimplemented from ControlLaw.

Definition at line 408 of file real_time_algorithm.cpp.

uint RealTimeAlgorithm::getNY ( ) const [virtual]

Returns number of process outputs.

Returns:
Number of process outputs

Reimplemented from ControlLaw.

Definition at line 429 of file real_time_algorithm.cpp.

Initializes the (internal) optimization algorithm part of the RealTimeAlgorithm.

Returns:
SUCCESSFUL_RETURN,
RET_OPTALG_INIT_FAILED

Definition at line 169 of file real_time_algorithm.cpp.

returnValue RealTimeAlgorithm::init ( double  startTime,
const DVector _x = emptyConstVector,
const DVector _p = emptyConstVector,
const VariablesGrid _yRef = emptyConstVariablesGrid 
) [virtual]

Initializes the control law with given start values and performs a number of consistency checks.

Parameters:
[in]_startTimeStart time.
[in]_xInitial value for differential states.
[in]_pInitial value for parameters.
[in]_yRefInitial value for reference trajectory.
Returns:
SUCCESSFUL_RETURN

Definition at line 183 of file real_time_algorithm.cpp.

Initializes algebraic states of the control law.

Parameters:
[in]_xa_initInitial value for algebraic states.
Returns:
SUCCESSFUL_RETURN

Reimplemented from ControlLaw.

Definition at line 140 of file real_time_algorithm.cpp.

returnValue RealTimeAlgorithm::initializeAlgebraicStates ( const char *  fileName) [virtual]

Initializes algebraic states of the control law from data file.

Parameters:
[in]fileNameName of file containing initial value for algebraic states.
Returns:
SUCCESSFUL_RETURN,
RET_FILE_CAN_NOT_BE_OPENED

Reimplemented from ControlLaw.

Definition at line 147 of file real_time_algorithm.cpp.

Initializes controls of the control law.

Parameters:
[in]_u_initInitial value for controls.
Returns:
SUCCESSFUL_RETURN

Reimplemented from ControlLaw.

Definition at line 154 of file real_time_algorithm.cpp.

returnValue RealTimeAlgorithm::initializeControls ( const char *  fileName) [virtual]

Initializes controls of the control law from data file.

Parameters:
[in]fileNameName of file containing initial value for controls.
Returns:
SUCCESSFUL_RETURN,
RET_FILE_CAN_NOT_BE_OPENED

Reimplemented from ControlLaw.

Definition at line 161 of file real_time_algorithm.cpp.

returnValue RealTimeAlgorithm::initializeNlpSolver ( const OCPiterate userInit) [protected, virtual]

(not yet documented).

Parameters:
[in]..
Returns:
SUCCESSFUL_RETURN

Implements OptimizationAlgorithmBase.

Definition at line 587 of file real_time_algorithm.cpp.

(not yet documented).

Parameters:
[in]..
Returns:
SUCCESSFUL_RETURN

Implements OptimizationAlgorithmBase.

Definition at line 603 of file real_time_algorithm.cpp.

Returns whether the control law is based on dynamic optimization or a static one.

Returns:
BT_TRUE iff control law is based on dynamic optimization,
BT_FALSE otherwise

Implements ControlLaw.

Definition at line 449 of file real_time_algorithm.cpp.

Returns whether the control law is working in real-time mode.

Returns:
BT_TRUE iff control law is working in real-time mode,
BT_FALSE otherwise

Reimplemented from ControlLaw.

Definition at line 464 of file real_time_algorithm.cpp.

Returns whether the control law is a static one or based on dynamic optimization.

Returns:
BT_TRUE iff control law is a static one,
BT_FALSE otherwise

Implements ControlLaw.

Definition at line 455 of file real_time_algorithm.cpp.

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

Assignment operator (deep copy).

Parameters:
[in]rhsRight-hand side object.

Definition at line 111 of file real_time_algorithm.cpp.

returnValue RealTimeAlgorithm::performFeedbackStep ( double  currentTime,
const DVector _x,
const DVector _p = emptyConstVector 
) [protected]

(not yet documented).

Parameters:
[in]..
Returns:
SUCCESSFUL_RETURN

Definition at line 618 of file real_time_algorithm.cpp.

(not yet documented).

Parameters:
[in]..
Returns:
SUCCESSFUL_RETURN

Definition at line 648 of file real_time_algorithm.cpp.

returnValue RealTimeAlgorithm::preparationStep ( double  nextTime = 0.0,
const VariablesGrid _yRef = emptyConstVariablesGrid 
) [virtual]

Performs next preparation step of the control law based on given inputs.

Parameters:
[in]nextTimeTime at next step.
[in]_yRefPiece of reference trajectory for next step (required for hotstarting).
Returns:
SUCCESSFUL_RETURN

Reimplemented from ControlLaw.

Definition at line 318 of file real_time_algorithm.cpp.

Assigns new reference trajectory for the next real-time step.

Parameters:
[in]refCurrent piece of new reference trajectory.
Returns:
SUCCESSFUL_RETURN,
RET_REFERENCE_SHIFTING_WORKS_FOR_LSQ_TERMS_ONLY,
RET_MEMBER_NOT_INITIALISED

Definition at line 391 of file real_time_algorithm.cpp.

returnValue RealTimeAlgorithm::setupLogging ( ) [protected, virtual]

Sets-up default logging information.

Returns:
SUCCESSFUL_RETURN

Reimplemented from Logging.

Definition at line 539 of file real_time_algorithm.cpp.

returnValue RealTimeAlgorithm::setupOptions ( ) [protected, virtual]

Sets-up default options.

Returns:
SUCCESSFUL_RETURN

Reimplemented from Options.

Definition at line 484 of file real_time_algorithm.cpp.

returnValue RealTimeAlgorithm::shift ( double  timeShift = -1.0) [virtual]

Shifts the data for preparating the next real-time step.

Returns:
RET_NOT_YET_IMPLEMENTED

Reimplemented from ControlLaw.

Definition at line 379 of file real_time_algorithm.cpp.

returnValue RealTimeAlgorithm::solve ( double  startTime,
const DVector _x,
const DVector _p = emptyConstVector,
const VariablesGrid _yRef = emptyConstVariablesGrid 
) [virtual]

(not yet documented).

Parameters:
[in]..
Returns:
SUCCESSFUL_RETURN

Definition at line 331 of file real_time_algorithm.cpp.

returnValue RealTimeAlgorithm::step ( double  currentTime,
const DVector _x,
const DVector _p = emptyConstVector,
const VariablesGrid _yRef = emptyConstVariablesGrid 
) [virtual]

Performs next step of the control law based on given inputs.

Parameters:
[in]currentTimeCurrent time.
[in]_xMost recent value for differential states.
[in]_pMost recent value for parameters.
[in]_yRefCurrent piece of reference trajectory or piece of reference trajectory for next step (required for hotstarting).
Returns:
SUCCESSFUL_RETURN

Definition at line 235 of file real_time_algorithm.cpp.


Member Data Documentation

Deep copy of the most recent parameter.

Definition at line 398 of file real_time_algorithm.hpp.

Deep copy of the most recent reference.

Definition at line 400 of file real_time_algorithm.hpp.

Deep copy of the most recent initial value of differential states.

Definition at line 397 of file real_time_algorithm.hpp.


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


acado
Author(s): Milan Vukov, Rien Quirynen
autogenerated on Sat Jun 8 2019 19:40:25