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

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

#include <real_time_algorithm.hpp>

Inheritance diagram for RealTimeAlgorithm:
Inheritance graph
[legend]

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 ()
 
- Public Member Functions inherited from OptimizationAlgorithmBase
returnValue getAlgebraicStates (VariablesGrid &xa_) const
 
returnValue getAlgebraicStates (const char *fileName) const
 
returnValue getControls (VariablesGrid &p_) const
 
returnValue getControls (const char *fileName) const
 
returnValue getDifferentialStates (VariablesGrid &xd_) const
 
returnValue getDifferentialStates (const char *fileName) const
 
returnValue getDisturbances (VariablesGrid &w_) const
 
returnValue getDisturbances (const char *fileName) const
 
double getEndTime () const
 
double getObjectiveValue (const char *fileName) const
 
double getObjectiveValue () const
 
returnValue getParameters (VariablesGrid &u_) const
 
returnValue getParameters (DVector &u_) const
 
returnValue getParameters (const char *fileName) const
 
returnValue getSensitivitiesP (BlockMatrix &_sens) const
 
returnValue getSensitivitiesU (BlockMatrix &_sens) const
 
returnValue getSensitivitiesW (BlockMatrix &_sens) const
 
returnValue getSensitivitiesX (BlockMatrix &_sens) const
 
returnValue getSensitivitiesXA (BlockMatrix &_sens) const
 
double getStartTime () const
 
returnValue initializeAlgebraicStates (const char *fileName, BooleanType autoinit=BT_FALSE)
 
returnValue initializeAlgebraicStates (const VariablesGrid &xa_init_, BooleanType autoinit=BT_FALSE)
 
returnValue initializeControls (const char *fileName)
 
returnValue initializeControls (const VariablesGrid &p_init_)
 
returnValue initializeDifferentialStates (const char *fileName, BooleanType autoinit=BT_FALSE)
 
returnValue initializeDifferentialStates (const VariablesGrid &xd_init_, BooleanType autoinit=BT_FALSE)
 
returnValue initializeDisturbances (const char *fileName)
 
returnValue initializeDisturbances (const VariablesGrid &w_init_)
 
returnValue initializeParameters (const char *fileName)
 
returnValue initializeParameters (const VariablesGrid &u_init_)
 
OptimizationAlgorithmBaseoperator= (const OptimizationAlgorithmBase &arg)
 
 OptimizationAlgorithmBase ()
 
 OptimizationAlgorithmBase (const OCP &ocp_)
 
 OptimizationAlgorithmBase (const OptimizationAlgorithmBase &arg)
 
returnValue simulateStatesForInitialization ()
 
virtual ~OptimizationAlgorithmBase ()
 
- Public Member Functions inherited from ControlLaw
 ControlLaw ()
 
 ControlLaw (double _samplingTime)
 
 ControlLaw (const ControlLaw &rhs)
 
returnValue getP (DVector &_p) const
 
returnValue getU (DVector &_u) const
 
ControlLawoperator= (const ControlLaw &rhs)
 
virtual returnValue step (const DVector &_x, const DVector &_p=emptyConstVector, const VariablesGrid &_yRef=emptyConstVariablesGrid)
 
virtual ~ControlLaw ()
 
- Public Member Functions inherited from SimulationBlock
BlockName getName () const
 
double getSamplingTime () const
 
BooleanType isDefined () const
 
SimulationBlockoperator= (const SimulationBlock &rhs)
 
returnValue setName (BlockName _name)
 
returnValue setSamplingTime (double _samplingTime)
 
 SimulationBlock ()
 
 SimulationBlock (BlockName _name, double _samplingTime=DEFAULT_SAMPLING_TIME)
 
 SimulationBlock (const SimulationBlock &rhs)
 
virtual ~SimulationBlock ()
 
- Public Member Functions inherited from UserInteraction
virtual int addPlotWindow (PlotWindow &_window)
 
virtual int operator<< (PlotWindow &_window)
 
virtual int operator<< (LogRecord &_record)
 
UserInteractionoperator= (const UserInteraction &rhs)
 
 UserInteraction ()
 
 UserInteraction (const UserInteraction &rhs)
 
virtual ~UserInteraction ()
 
- Public Member Functions inherited from Options
returnValue addOptionsList ()
 
returnValue ensureConsistency ()
 
returnValue ensureConsistency ()
 
returnValue get (OptionsName name, int &value) const
 
returnValue get (OptionsName name, double &value) const
 
returnValue get (OptionsName name, std::string &value) const
 
returnValue get (uint idx, OptionsName name, int &value) const
 
returnValue get (uint idx, OptionsName name, double &value) const
 
returnValue get (uint idx, OptionsName name, std::string &value) const
 
uint getNumOptionsLists () const
 
Options getOptions (uint idx) const
 
Optionsoperator= (const Options &rhs)
 
Optionsoperator= (const Options &rhs)
 
 Options ()
 
 Options ()
 
 Options (const Options &rhs)
 
 Options (const Options &rhs)
 
 Options ()
 
 Options (const OptionsList &_optionsList)
 
returnValue print () const
 
returnValue print () const
 
returnValue printOptionsList () const
 
returnValue printOptionsList (uint idx) const
 
returnValue set (OptionsName name, int value)
 
returnValue set (OptionsName name, double value)
 
returnValue set (OptionsName name, const std::string &value)
 
returnValue set (uint idx, OptionsName name, int value)
 
returnValue set (uint idx, OptionsName name, double value)
 
returnValue set (uint idx, OptionsName name, const std::string &value)
 
returnValue setOptions (const Options &arg)
 
returnValue setOptions (uint idx, const Options &arg)
 
returnValue setToDefault ()
 
returnValue setToDefault ()
 
returnValue setToFast ()
 
returnValue setToFast ()
 
returnValue setToMPC ()
 
returnValue setToReliable ()
 
returnValue setToReliable ()
 
 ~Options ()
 
 ~Options ()
 
virtual ~Options ()
 
- Public Member Functions inherited from Logging
int addLogRecord (LogRecord &record)
 
returnValue getAll (LogName _name, MatrixVariablesGrid &values) const
 
returnValue getFirst (LogName _name, DMatrix &firstValue) const
 
returnValue getFirst (LogName _name, VariablesGrid &firstValue) const
 
returnValue getLast (LogName _name, DMatrix &lastValue) const
 
returnValue getLast (LogName _name, VariablesGrid &lastValue) const
 
returnValue getLogRecord (LogRecord &_record) const
 
uint getNumLogRecords () const
 
 Logging ()
 
int operator<< (LogRecord &record)
 
returnValue printLoggingInfo () const
 
returnValue printNumDoubles () const
 
returnValue setAll (LogName _name, const MatrixVariablesGrid &values)
 
returnValue setLast (LogName _name, const DMatrix &value, double time=-INFTY)
 
returnValue setLast (LogName _name, VariablesGrid &value, double time=-INFTY)
 
returnValue updateLogRecord (LogRecord &_record) const
 
virtual ~Logging ()
 
- Public Member Functions inherited from Plotting
int addPlotWindow (PlotWindow &_window)
 
uint getNumPlotWindows () const
 
returnValue getPlotWindow (uint idx, PlotWindow &_window) const
 
returnValue getPlotWindow (PlotWindow &_window) const
 
int operator<< (PlotWindow &_window)
 
Plottingoperator= (const Plotting &rhs)
 
virtual returnValue plot (PlotFrequency _frequency=PLOT_IN_ANY_CASE)
 
 Plotting ()
 
 Plotting (const Plotting &rhs)
 
virtual returnValue replot (PlotFrequency _frequency=PLOT_IN_ANY_CASE)
 
virtual ~Plotting ()
 

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 Member Functions inherited from OptimizationAlgorithmBase
returnValue clear ()
 
virtual returnValue determineDimensions (Objective *const _objective, DifferentialEquation **const _differentialEquation, Constraint *const _constraint, uint &_nx, uint &_nxa, uint &_np, uint &_nu, uint &_nw) const
 
virtual returnValue extractOCPdata (Objective **objective, DifferentialEquation ***differentialEquation, Constraint **constraint, Grid &unionGrid)
 
returnValue init (UserInteraction *_userIteraction)
 
virtual returnValue initializeOCPiterate (Constraint *const _constraint, const Grid &_unionGrid, uint nx, uint nxa, uint np, uint nu, uint nw)
 
BooleanType isLinearQuadratic (Objective *F, DynamicDiscretization *G, Constraint *H) const
 
virtual returnValue setupDifferentialEquation (Objective *objective, DifferentialEquation **differentialEquation, Constraint *constraint, Grid unionGrid)
 
virtual returnValue setupDynamicDiscretization (UserInteraction *_userIteraction, Objective *objective, DifferentialEquation **differentialEquation, Constraint *constraint, Grid unionGrid, DynamicDiscretization **dynamicDiscretization)
 
virtual returnValue setupObjective (Objective *objective, DifferentialEquation **differentialEquation, Constraint *constraint, Grid unionGrid)
 
- Protected Member Functions inherited from UserInteraction
virtual returnValue getPlotDataFromMemberLoggings (PlotWindow &_window) const
 
BlockStatus getStatus () const
 
returnValue setStatus (BlockStatus _status)
 
- Protected Member Functions inherited from Options
returnValue addOption (OptionsName name, int value)
 
returnValue addOption (OptionsName name, double value)
 
returnValue addOption (OptionsName name, const std::string &value)
 
returnValue addOption (uint idx, OptionsName name, int value)
 
returnValue addOption (uint idx, OptionsName name, double value)
 
returnValue addOption (uint idx, OptionsName name, const std::string &value)
 
returnValue clearOptionsList ()
 
returnValue copy (const Options &rhs)
 
returnValue copy (const Options &rhs)
 
returnValue declareOptionsUnchanged ()
 
returnValue declareOptionsUnchanged (uint idx)
 
BooleanType haveOptionsChanged () const
 
BooleanType haveOptionsChanged (uint idx) const
 

Protected Attributes

DVectorp0
 
VariablesGridreference
 
DVectorx0
 
- Protected Attributes inherited from OptimizationAlgorithmBase
OCPiterate iter
 
NLPsolvernlpSolver
 
OCPocp
 
OCPiterate userInit
 
- Protected Attributes inherited from ControlLaw
DVector p
 
DVector u
 
- Protected Attributes inherited from SimulationBlock
BlockName name
 
RealClock realClock
 
double samplingTime
 
- Protected Attributes inherited from UserInteraction
BlockStatus status
 
- Protected Attributes inherited from Options
std::vector< OptionsListlists
 
- Protected Attributes inherited from Logging
std::vector< LogRecordlogCollection
 
int logIdx
 
- Protected Attributes inherited from Plotting
PlotCollection plotCollection
 

Additional Inherited Members

- Public Attributes inherited from Options
real_t boundRelaxation
 
real_t boundTolerance
 
int dropBoundPriority
 
int_t dropBoundPriority
 
int dropEqConPriority
 
int_t dropEqConPriority
 
int dropIneqConPriority
 
int_t dropIneqConPriority
 
int enableCholeskyRefactorisation
 
int_t enableCholeskyRefactorisation
 
int enableDriftCorrection
 
int_t enableDriftCorrection
 
BooleanType enableDropInfeasibles
 
BooleanType enableEqualities
 
BooleanType enableFarBounds
 
BooleanType enableFlippingBounds
 
BooleanType enableFullLITests
 
BooleanType enableInertiaCorrection
 
BooleanType enableNZCTests
 
BooleanType enableRamping
 
BooleanType enableRegularisation
 
real_t epsDen
 
real_t epsFlipping
 
real_t epsIterRef
 
real_t epsLITests
 
real_t epsNum
 
real_t epsNZCTests
 
real_t epsRegularisation
 
real_t finalRamping
 
real_t growFarBounds
 
real_t initialFarBounds
 
real_t initialRamping
 
SubjectToStatus initialStatusBounds
 
real_t maxDualJump
 
real_t maxPrimalJump
 
int numRefinementSteps
 
int_t numRefinementSteps
 
int numRegularisationSteps
 
int_t numRegularisationSteps
 
PrintLevel printLevel
 
real_t rcondSMin
 
real_t terminationTolerance
 

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

BEGIN_NAMESPACE_ACADO RealTimeAlgorithm::RealTimeAlgorithm ( )

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.

RealTimeAlgorithm::RealTimeAlgorithm ( const RealTimeAlgorithm rhs)

Copy constructor (deep copy).

@param[in] rhs      Right-hand side object.

Definition at line 91 of file real_time_algorithm.cpp.

RealTimeAlgorithm::~RealTimeAlgorithm ( )
virtual

Destructor.

Definition at line 104 of file real_time_algorithm.cpp.

Member Function Documentation

returnValue RealTimeAlgorithm::allocateNlpSolver ( Objective F,
DynamicDiscretization G,
Constraint H 
)
protectedvirtual

(not yet documented).

@param[in]  .               .
Returns
SUCCESSFUL_RETURN

Implements OptimizationAlgorithmBase.

Definition at line 576 of file real_time_algorithm.cpp.

returnValue RealTimeAlgorithm::clear ( )
protected

Frees memory of all members of the real time parameters.

Returns
SUCCESSFUL_RETURN

Definition at line 551 of file real_time_algorithm.cpp.

ControlLaw * RealTimeAlgorithm::clone ( ) const
virtual

Clone constructor (deep copy).

\return 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.

@param[in]  currentTime     Current time.
@param[in]  _x                      Most recent value for differential states.
@param[in]  _p                      Most recent value for parameters.
@param[in]  _yRef           Current 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

Reimplemented from ControlLaw.

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.

double RealTimeAlgorithm::getLengthPredictionHorizon ( ) const
virtual

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.

returnValue RealTimeAlgorithm::init ( )
virtual

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

Implements ControlLaw.

Definition at line 183 of file real_time_algorithm.cpp.

returnValue RealTimeAlgorithm::initializeAlgebraicStates ( const VariablesGrid _xa_init)
virtual

Initializes algebraic states of the control law.

@param[in]  _xa_init        Initial 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.

@param[in]  fileName        Name 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.

returnValue RealTimeAlgorithm::initializeControls ( const VariablesGrid _u_init)
virtual

Initializes controls of the control law.

@param[in]  _u_init Initial 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.

@param[in]  fileName        Name 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)
protectedvirtual

(not yet documented).

@param[in]  .               .
Returns
SUCCESSFUL_RETURN

Implements OptimizationAlgorithmBase.

Definition at line 587 of file real_time_algorithm.cpp.

returnValue RealTimeAlgorithm::initializeObjective ( Objective F)
protectedvirtual

(not yet documented).

@param[in]  .               .
Returns
SUCCESSFUL_RETURN

Implements OptimizationAlgorithmBase.

Definition at line 603 of file real_time_algorithm.cpp.

BooleanType RealTimeAlgorithm::isDynamic ( ) const
virtual

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.

BooleanType RealTimeAlgorithm::isInRealTimeMode ( ) const
virtual

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.

BooleanType RealTimeAlgorithm::isStatic ( ) const
virtual

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).

@param[in] rhs      Right-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).

@param[in]  .               .
Returns
SUCCESSFUL_RETURN

Definition at line 618 of file real_time_algorithm.cpp.

returnValue RealTimeAlgorithm::performPreparationStep ( const VariablesGrid _yRef = emptyConstVariablesGrid,
BooleanType  isLastIteration = BT_TRUE 
)
protected

(not yet documented).

@param[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.

@param[in]  nextTime        Time at next step.
@param[in]  _yRef           Piece 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.

returnValue RealTimeAlgorithm::setReference ( const VariablesGrid ref)
virtual

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

@param[in]  ref             Current piece of new reference trajectory.

\return SUCCESSFUL_RETURN, \n
        RET_REFERENCE_SHIFTING_WORKS_FOR_LSQ_TERMS_ONLY, \n
        RET_MEMBER_NOT_INITIALISED

Definition at line 391 of file real_time_algorithm.cpp.

returnValue RealTimeAlgorithm::setupLogging ( )
protectedvirtual

Sets-up default logging information.

Returns
SUCCESSFUL_RETURN

Reimplemented from Logging.

Definition at line 539 of file real_time_algorithm.cpp.

returnValue RealTimeAlgorithm::setupOptions ( )
protectedvirtual

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.

\return 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).

@param[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.

@param[in]  currentTime     Current time.
@param[in]  _x                      Most recent value for differential states.
@param[in]  _p                      Most recent value for parameters.
@param[in]  _yRef           Current piece of reference trajectory or piece of reference trajectory for next step (required for hotstarting).
Returns
SUCCESSFUL_RETURN

Implements ControlLaw.

Definition at line 235 of file real_time_algorithm.cpp.

Member Data Documentation

DVector* RealTimeAlgorithm::p0
protected

Deep copy of the most recent parameter.

Definition at line 398 of file real_time_algorithm.hpp.

VariablesGrid* RealTimeAlgorithm::reference
protected

Deep copy of the most recent reference.

Definition at line 400 of file real_time_algorithm.hpp.

DVector* RealTimeAlgorithm::x0
protected

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 Mon Jun 10 2019 12:35:26