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

Calculates the control inputs of the Process based on the Process outputs. More...

#include <controller.hpp>

Inheritance diagram for Controller:
Inheritance graph
[legend]

Public Member Functions

 Controller ()
 
 Controller (ControlLaw &_controlLaw, Estimator &_estimator, ReferenceTrajectory &_referenceTrajectory=emptyReferenceTrajectory)
 
 Controller (ControlLaw &_controlLaw, ReferenceTrajectory &_referenceTrajectory=emptyReferenceTrajectory)
 
 Controller (const Controller &rhs)
 
returnValue disable ()
 
returnValue enable ()
 
virtual returnValue feedbackStep (double currentTime, const DVector &_y, const VariablesGrid &_yRef=emptyConstVariablesGrid)
 
double getNextSamplingInstant (double currentTime)
 
uint getNP () const
 
uint getNU () const
 
uint getNY () const
 
returnValue getP (DVector &_p) const
 
double getPreviousRealRuntime ()
 
double getSamplingTimeControlLaw ()
 
double getSamplingTimeEstimator ()
 
returnValue getU (DVector &_u) const
 
BooleanType hasDynamicControlLaw () const
 
BooleanType hasEstimator () const
 
BooleanType hasReferenceTrajectory () const
 
BooleanType hasStaticControlLaw () const
 
virtual returnValue init (double startTime=0.0, const DVector &_x0=emptyConstVector, const DVector &_p=emptyConstVector, const VariablesGrid &_yRef=emptyConstVariablesGrid)
 
returnValue initializeAlgebraicStates (const VariablesGrid &_xa_init)
 
returnValue initializeAlgebraicStates (const char *fileName)
 
virtual returnValue obtainEstimates (double currentTime, const DVector &_y, DVector &xEst, DVector &pEst)
 
Controlleroperator= (const Controller &rhs)
 
virtual returnValue preparationStep (double nextTime=0.0, const VariablesGrid &_yRef=emptyConstVariablesGrid)
 
returnValue setControlLaw (ControlLaw &_controlLaw)
 
returnValue setEstimator (Estimator &_estimator)
 
returnValue setReferenceTrajectory (ReferenceTrajectory &_referenceTrajectory)
 
virtual returnValue step (double currentTime, const DVector &_y, const VariablesGrid &_yRef=emptyConstVariablesGrid)
 
virtual returnValue step (double currentTime, uint dim, const double *const _y, const VariablesGrid &_yRef=emptyConstVariablesGrid)
 
virtual ~Controller ()
 
- 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 getCurrentReference (double tStart, VariablesGrid &_yRef) const
 
virtual returnValue setupLogging ()
 
virtual returnValue setupOptions ()
 
- 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

ControlLawcontrolLaw
 
RealClock controlLawClock
 
Estimatorestimator
 
BooleanType isEnabled
 
ReferenceTrajectoryreferenceTrajectory
 
- 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

Calculates the control inputs of the Process based on the Process outputs.

The class Controller is one of the two main building-blocks within the SimulationEnvironment and complements the Process. It contains an online control law (e.g. a DynamicFeedbackLaw comprising a RealTimeAlgorithm) for obtaining the control inputs of the Process.

A state/parameter estimator as well as a ReferenceTrajectory can optionally be used to provide estimated quantities and a reference values to the control law. The reference trajectory can either be specified beforehand as member of the Controller or, alternatively, provided at each step in order to allow for reference trajectories that can be adapted online.

Author
Hans Joachim Ferreau, Boris Houska

Definition at line 71 of file controller.hpp.

Constructor & Destructor Documentation

BEGIN_NAMESPACE_ACADO Controller::Controller ( )

Default constructor.

Definition at line 45 of file controller.cpp.

Controller::Controller ( ControlLaw _controlLaw,
Estimator _estimator,
ReferenceTrajectory _referenceTrajectory = emptyReferenceTrajectory 
)

Constructor which takes a control law, an estimator and a reference trajectory for computing the control/parameter signals.

Parameters
[in]_controlLawControl law to be used for computing the control/parameter signals.
[in]_estimatorEstimator for estimating quantities required by the control law based on the process output.
[in]_referenceTrajectoryReference trajectory to be used by the control law.

Definition at line 60 of file controller.cpp.

Controller::Controller ( ControlLaw _controlLaw,
ReferenceTrajectory _referenceTrajectory = emptyReferenceTrajectory 
)

Constructor which takes a control law and a reference trajectory for computing the control/parameter signals.

Parameters
[in]_controlLawControl law to be used for computing the control/parameter signals.
[in]_referenceTrajectoryReference trajectory to be used by the control law.

Definition at line 92 of file controller.cpp.

Controller::Controller ( const Controller rhs)

Copy constructor (deep copy).

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

Definition at line 120 of file controller.cpp.

Controller::~Controller ( )
virtual

Destructor.

Definition at line 141 of file controller.cpp.

Member Function Documentation

returnValue Controller::disable ( )
inline

Disables the controller (i.e. initial values kept and no steps are performed).

Returns
SUCCESSFUL_RETURN
returnValue Controller::enable ( )
inline

Enables the controller.

Returns
SUCCESSFUL_RETURN
returnValue Controller::feedbackStep ( double  currentTime,
const DVector _y,
const VariablesGrid _yRef = emptyConstVariablesGrid 
)
virtual

Performs next feedback step of the contoller based on given inputs.

@param[in]  currentTime     Current time.
@param[in]  _y                      Most recent process output.
@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,
RET_BLOCK_NOT_READY,
RET_CONTROLLER_STEP_FAILED,
RET_NO_CONTROLLAW_SPECIFIED

Definition at line 424 of file controller.cpp.

returnValue Controller::getCurrentReference ( double  tStart,
VariablesGrid _yRef 
) const
protectedvirtual

Returns current piece of the reference trajectory starting at given time.

@param[in]  tStart  Start time of reference piece.
@param[out] _yRef   Current piece of the reference trajectory.
Returns
SUCCESSFUL_RETURN,
RET_INVALID_ARGUMENTS

Definition at line 573 of file controller.cpp.

double Controller::getNextSamplingInstant ( double  currentTime)

Determines next sampling instant of controller based on the sampling times of control law and estimator

Parameters
[in]currentTimeCurrent time.
Returns
Next sampling instant of controller.

Definition at line 518 of file controller.cpp.

uint Controller::getNP ( ) const
inline

Returns number of parameter signals computed by the controller.

\return Number of parameter signals
uint Controller::getNU ( ) const
inline

Returns number of control signals computed by the controller.

\return Number of control signals
uint Controller::getNY ( ) const
inline

Returns number of process outputs expected by the controller.

\return Number of process outputs
returnValue Controller::getP ( DVector _p) const
inline

Returns computed parameter signals.

@param[out]  _y                     Computed parameter signals.
Returns
SUCCESSFUL_RETURN
double Controller::getPreviousRealRuntime ( )
inline

Returns previous real runtime of the controller (e.g. for determining computational delay).

Returns
Previous real runtime of the controller.
double Controller::getSamplingTimeControlLaw ( )
inline

Returns sampling time of control law.

Returns
Sampling time of control law.
double Controller::getSamplingTimeEstimator ( )
inline

Returns sampling time of estimator.

Returns
Sampling time of estimator.
returnValue Controller::getU ( DVector _u) const
inline

Returns computed control signals.

@param[out]  _y                     Computed control signals.
Returns
SUCCESSFUL_RETURN
BooleanType Controller::hasDynamicControlLaw ( ) const
inline

Returns whether controller comprises a dynamic control law.

Returns
BT_TRUE iff controller comprises a dynamic control law,
BT_FALSE otherwise
BooleanType Controller::hasEstimator ( ) const
inline

Returns whether controller comprises an estimator.

Returns
BT_TRUE iff controller comprises an estimator,
BT_FALSE otherwise
BooleanType Controller::hasReferenceTrajectory ( ) const
inline

Returns whether controller comprises a build-in reference trajectory.

Returns
BT_TRUE iff controller comprises a build-in reference trajectory,
BT_FALSE otherwise
BooleanType Controller::hasStaticControlLaw ( ) const
inline

Returns whether controller comprises a static control law.

Returns
BT_TRUE iff controller comprises a static control law,
BT_FALSE otherwise
returnValue Controller::init ( double  startTime = 0.0,
const DVector _x0 = emptyConstVector,
const DVector _p = emptyConstVector,
const VariablesGrid _yRef = emptyConstVariablesGrid 
)
virtual

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

Parameters
[in]_startTimeStart time.
[in]_x0Initial value for differential states.
[in]_pInitial value for parameters.
[in]_yRefInitial value for reference trajectory.
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,
RET_CONTROLLER_INIT_FAILED,
RET_NO_CONTROLLAW_SPECIFIED,
RET_BLOCK_DIMENSION_MISMATCH

Definition at line 270 of file controller.cpp.

returnValue Controller::initializeAlgebraicStates ( const VariablesGrid _xa_init)

Initializes algebraic states of the control law.

@param[in]  _xa_init        Initial value for algebraic states.
Returns
SUCCESSFUL_RETURN

Definition at line 246 of file controller.cpp.

returnValue Controller::initializeAlgebraicStates ( const char *  fileName)

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

Definition at line 256 of file controller.cpp.

returnValue Controller::obtainEstimates ( double  currentTime,
const DVector _y,
DVector xEst,
DVector pEst 
)
virtual

Definition at line 383 of file controller.cpp.

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

Assignment operator (deep copy).

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

Definition at line 154 of file controller.cpp.

returnValue Controller::preparationStep ( double  nextTime = 0.0,
const VariablesGrid _yRef = emptyConstVariablesGrid 
)
virtual

Performs next preparation step of the contoller based on given inputs.

@param[in]  nextTime        Time at next step.
@param[in]  _yRef           Piece of reference trajectory for next step (required for hotstarting).

\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,
RET_CONTROLLER_STEP_FAILED,
RET_NO_CONTROLLAW_SPECIFIED

Definition at line 474 of file controller.cpp.

returnValue Controller::setControlLaw ( ControlLaw _controlLaw)

Assigns new control law to be used for computing control/parameter signals.

@param[in]  _controlLaw             New control law.
Returns
SUCCESSFUL_RETURN

Definition at line 192 of file controller.cpp.

returnValue Controller::setEstimator ( Estimator _estimator)

Assigns new estimator for estimating quantities required by the control law based on the process output.

Parameters
[in]_estimatorNew estimator.
Returns
SUCCESSFUL_RETURN

Definition at line 209 of file controller.cpp.

returnValue Controller::setReferenceTrajectory ( ReferenceTrajectory _referenceTrajectory)

Assigns new reference trajectory to be used by the control law.

@param[in]  _referenceTrajectory    New reference trajectory.
Returns
SUCCESSFUL_RETURN

Definition at line 227 of file controller.cpp.

returnValue Controller::setupLogging ( )
protectedvirtual

Sets-up default logging information.

Returns
SUCCESSFUL_RETURN

Reimplemented from Logging.

Definition at line 558 of file controller.cpp.

returnValue Controller::setupOptions ( )
protectedvirtual

Sets-up default options.

Returns
SUCCESSFUL_RETURN

Reimplemented from Options.

Definition at line 550 of file controller.cpp.

returnValue Controller::step ( double  currentTime,
const DVector _y,
const VariablesGrid _yRef = emptyConstVariablesGrid 
)
virtual

Performs next step of the contoller based on given inputs.

@param[in]  currentTime     Current time.
@param[in]  _y                      Most recent process output.
@param[in]  _yRef           Current piece of reference trajectory or piece of reference trajectory for next step (required for hotstarting).

\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,
RET_BLOCK_NOT_READY,
RET_CONTROLLER_STEP_FAILED,
RET_NO_CONTROLLAW_SPECIFIED

Definition at line 338 of file controller.cpp.

returnValue Controller::step ( double  currentTime,
uint  dim,
const double *const  _y,
const VariablesGrid _yRef = emptyConstVariablesGrid 
)
virtual

Performs next step of the contoller based on given inputs.

@param[in]  currentTime     Current time.
@param[in]  dim                     Dimension of process output.
@param[in]  _y                      Most recent process output.
@param[in]  _yRef           Current piece of reference trajectory or piece of reference trajectory for next step (required for hotstarting).

\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,
RET_BLOCK_NOT_READY,
RET_CONTROLLER_STEP_FAILED,
RET_NO_CONTROLLAW_SPECIFIED

Definition at line 371 of file controller.cpp.

Member Data Documentation

ControlLaw* Controller::controlLaw
protected

Control law (usually including a dynamic optimizer) to be used for computing the control/parameter signals.

Definition at line 424 of file controller.hpp.

RealClock Controller::controlLawClock
protected

Clock required to determine runtime of control law.

Definition at line 430 of file controller.hpp.

Estimator* Controller::estimator
protected

Estimator for estimating quantities required by the control law based on the process output.

Definition at line 425 of file controller.hpp.

BooleanType Controller::isEnabled
protected

Flag indicating whether controller is enabled or not.

Definition at line 428 of file controller.hpp.

ReferenceTrajectory* Controller::referenceTrajectory
protected

Reference trajectory to be used by the control law.

Definition at line 426 of file controller.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:22