Public Member Functions | Protected Member Functions | Protected Attributes

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

#include <controller.hpp>

Inheritance diagram for Controller:
Inheritance graph
[legend]

List of all members.

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

Protected Member Functions

virtual returnValue getCurrentReference (double tStart, VariablesGrid &_yRef) const
virtual returnValue setupLogging ()
virtual returnValue setupOptions ()

Protected Attributes

ControlLawcontrolLaw
RealClock controlLawClock
Estimatorestimator
BooleanType isEnabled
ReferenceTrajectoryreferenceTrajectory

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

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.

Copy constructor (deep copy).

Parameters:
[in]rhsRight-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

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

Returns:
SUCCESSFUL_RETURN

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.

Parameters:
[in]currentTimeCurrent time.
[in]_yMost recent process output.
[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,
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 [protected, virtual]

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

Parameters:
[in]tStartStart time of reference piece.
[out]_yRefCurrent 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.

Returns:
Number of parameter signals
uint Controller::getNU ( ) const [inline]

Returns number of control signals computed by the controller.

Returns:
Number of control signals
uint Controller::getNY ( ) const [inline]

Returns number of process outputs expected by the controller.

Returns:
Number of process outputs
returnValue Controller::getP ( DVector _p) const [inline]

Returns computed parameter signals.

Parameters:
[out]_yComputed parameter signals.
Returns:
SUCCESSFUL_RETURN

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

Returns:
Previous real runtime of the controller.

Returns sampling time of control law.

Returns:
Sampling time of control law.

Returns sampling time of estimator.

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

Returns computed control signals.

Parameters:
[out]_yComputed control signals.
Returns:
SUCCESSFUL_RETURN

Returns whether controller comprises a dynamic control law.

Returns:
BT_TRUE iff controller comprises a dynamic control law,
BT_FALSE otherwise

Returns whether controller comprises an estimator.

Returns:
BT_TRUE iff controller comprises an estimator,
BT_FALSE otherwise

Returns whether controller comprises a build-in reference trajectory.

Returns:
BT_TRUE iff controller comprises a build-in reference trajectory,
BT_FALSE otherwise

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.

Initializes algebraic states of the control law.

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

Definition at line 246 of file controller.cpp.

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

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

Parameters:
[in]rhsRight-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.

Parameters:
[in]nextTimeTime at next step.
[in]_yRefPiece 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.

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

Parameters:
[in]_controlLawNew control law.
Returns:
SUCCESSFUL_RETURN

Definition at line 192 of file controller.cpp.

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.

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

Parameters:
[in]_referenceTrajectoryNew reference trajectory.
Returns:
SUCCESSFUL_RETURN

Definition at line 227 of file controller.cpp.

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

Sets-up default logging information.

Returns:
SUCCESSFUL_RETURN

Reimplemented from Logging.

Definition at line 558 of file controller.cpp.

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

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.

Parameters:
[in]currentTimeCurrent time.
[in]_yMost recent process output.
[in]_yRefCurrent 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.

Parameters:
[in]currentTimeCurrent time.
[in]dimDimension of process output.
[in]_yMost recent process output.
[in]_yRefCurrent 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

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

Definition at line 424 of file controller.hpp.

Clock required to determine runtime of control law.

Definition at line 430 of file controller.hpp.

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

Definition at line 425 of file controller.hpp.

Flag indicating whether controller is enabled or not.

Definition at line 428 of file controller.hpp.

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 Thu Aug 27 2015 12:01:37