Public Member Functions | Protected Attributes

Base class for interfacing online feedback laws to be used within a Controller. More...

#include <control_law.hpp>

Inheritance diagram for ControlLaw:
Inheritance graph
[legend]

List of all members.

Public Member Functions

virtual ControlLawclone () const =0
 ControlLaw ()
 ControlLaw (double _samplingTime)
 ControlLaw (const ControlLaw &rhs)
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
returnValue getP (DVector &_p) const
returnValue getU (DVector &_u) const
virtual returnValue init (double startTime=0.0, const DVector &_x=emptyConstVector, const DVector &_p=emptyConstVector, const VariablesGrid &_yRef=emptyConstVariablesGrid)=0
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 =0
virtual BooleanType isInRealTimeMode () const
virtual BooleanType isStatic () const =0
ControlLawoperator= (const ControlLaw &rhs)
virtual returnValue preparationStep (double nextTime=0.0, const VariablesGrid &_yRef=emptyConstVariablesGrid)
virtual returnValue shift (double timeShift=-1.0)
virtual returnValue step (double currentTime, const DVector &_x, const DVector &_p=emptyConstVector, const VariablesGrid &_yRef=emptyConstVariablesGrid)=0
virtual returnValue step (const DVector &_x, const DVector &_p=emptyConstVector, const VariablesGrid &_yRef=emptyConstVariablesGrid)
virtual ~ControlLaw ()

Protected Attributes

DVector p
DVector u

Detailed Description

Base class for interfacing online feedback laws to be used within a Controller.

The class ControlLaw serves as a base class for interfacing online control laws to be used within a Controller. Most prominently, the control law can be a RealTimeAlgorithm solving dynamic optimization problems. But also classical feedback laws like LQR or PID controller or feedforward laws can be interfaced.

After initialization, the ControlLaw is evaluated with a given fixed sampling time by calling the step-routines. Additionally, the steps can be divided into a preparation step and a feedback step that actually computes the feedback. This feature has mainly been added to deal with RealTimeAlgorithm can make use of this division in order to reduce the feedback delay.

Author:
Hans Joachim Ferreau, Boris Houska

Definition at line 64 of file control_law.hpp.


Constructor & Destructor Documentation

Default constructor.

Definition at line 45 of file control_law.cpp.

ControlLaw::ControlLaw ( double  _samplingTime)

Constructor which takes the sampling time.

Parameters:
[in]_samplingTimeSampling time.

Definition at line 50 of file control_law.cpp.

Copy constructor (deep copy).

Parameters:
[in]rhsRight-hand side object.

Definition at line 56 of file control_law.cpp.

ControlLaw::~ControlLaw ( ) [virtual]

Destructor.

Definition at line 63 of file control_law.cpp.


Member Function Documentation

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

Clone constructor (deep copy).

Returns:
Pointer to deep copy of base class type

Implemented in PIDcontroller, FeedforwardLaw, LinearStateFeedback, and RealTimeAlgorithm.

returnValue ControlLaw::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).
Returns:
SUCCESSFUL_RETURN,
RET_BLOCK_NOT_READY,
RET_VECTOR_DIMENSION_MISMATCH,
RET_CONTROLLAW_STEP_FAILED

Definition at line 119 of file control_law.cpp.

double ControlLaw::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 in RealTimeAlgorithm.

Definition at line 190 of file control_law.cpp.

double ControlLaw::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 in RealTimeAlgorithm.

Definition at line 184 of file control_law.cpp.

uint ControlLaw::getNP ( ) const [virtual]

Returns number of parameters.

Returns:
Number of parameters

Reimplemented in RealTimeAlgorithm, PIDcontroller, FeedforwardLaw, and LinearStateFeedback.

Definition at line 166 of file control_law.cpp.

uint ControlLaw::getNU ( ) const [virtual]

Returns number of controls.

Returns:
Number of controls

Reimplemented in RealTimeAlgorithm, PIDcontroller, FeedforwardLaw, and LinearStateFeedback.

Definition at line 160 of file control_law.cpp.

uint ControlLaw::getNW ( ) const [virtual]

Returns number of (estimated) disturbances.

Returns:
Number of (estimated) disturbances

Reimplemented in RealTimeAlgorithm, PIDcontroller, FeedforwardLaw, and LinearStateFeedback.

Definition at line 172 of file control_law.cpp.

uint ControlLaw::getNX ( ) const [virtual]

Returns number of (estimated) differential states.

Returns:
Number of (estimated) differential states

Reimplemented in RealTimeAlgorithm, PIDcontroller, FeedforwardLaw, and LinearStateFeedback.

Definition at line 148 of file control_law.cpp.

uint ControlLaw::getNXA ( ) const [virtual]

Returns number of (estimated) algebraic states.

Returns:
Number of (estimated) algebraic states

Reimplemented in RealTimeAlgorithm, PIDcontroller, FeedforwardLaw, and LinearStateFeedback.

Definition at line 154 of file control_law.cpp.

uint ControlLaw::getNY ( ) const [virtual]

Returns number of process outputs.

Returns:
Number of process outputs

Reimplemented in RealTimeAlgorithm, PIDcontroller, FeedforwardLaw, and LinearStateFeedback.

Definition at line 178 of file control_law.cpp.

returnValue ControlLaw::getP ( DVector _p) const [inline]

Returns parameter signal as determined by the control law.

Parameters:
[out]_pParameter signal as determined by the control law.
Returns:
SUCCESSFUL_RETURN
returnValue ControlLaw::getU ( DVector _u) const [inline]

Returns control signal as determined by the control law.

Parameters:
[out]_uControl signal as determined by the control law.
Returns:
SUCCESSFUL_RETURN
virtual returnValue ControlLaw::init ( double  startTime = 0.0,
const DVector _x = emptyConstVector,
const DVector _p = emptyConstVector,
const VariablesGrid _yRef = emptyConstVariablesGrid 
) [pure 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,
RET_CONTROLLAW_INIT_FAILED

Implemented in PIDcontroller, FeedforwardLaw, and LinearStateFeedback.

Initializes algebraic states of the control law.

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

Reimplemented in RealTimeAlgorithm.

Definition at line 83 of file control_law.cpp.

returnValue ControlLaw::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 in RealTimeAlgorithm.

Definition at line 89 of file control_law.cpp.

Initializes controls of the control law.

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

Reimplemented in RealTimeAlgorithm.

Definition at line 96 of file control_law.cpp.

returnValue ControlLaw::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 in RealTimeAlgorithm.

Definition at line 102 of file control_law.cpp.

virtual BooleanType ControlLaw::isDynamic ( ) const [pure 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

Implemented in RealTimeAlgorithm, PIDcontroller, FeedforwardLaw, and LinearStateFeedback.

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 in RealTimeAlgorithm.

Definition at line 200 of file control_law.cpp.

virtual BooleanType ControlLaw::isStatic ( ) const [pure 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

Implemented in RealTimeAlgorithm, PIDcontroller, FeedforwardLaw, and LinearStateFeedback.

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

Assignment operator (deep copy).

Parameters:
[in]rhsRight-hand side object.

Definition at line 68 of file control_law.cpp.

returnValue ControlLaw::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 in RealTimeAlgorithm.

Definition at line 130 of file control_law.cpp.

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

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

Returns:
RET_NOT_YET_IMPLEMENTED

Reimplemented in RealTimeAlgorithm.

Definition at line 140 of file control_law.cpp.

virtual returnValue ControlLaw::step ( double  currentTime,
const DVector _x,
const DVector _p = emptyConstVector,
const VariablesGrid _yRef = emptyConstVariablesGrid 
) [pure 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,
RET_BLOCK_NOT_READY,
RET_VECTOR_DIMENSION_MISMATCH,
RET_CONTROLLAW_STEP_FAILED

Implemented in PIDcontroller, FeedforwardLaw, and LinearStateFeedback.

returnValue ControlLaw::step ( 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]_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,
RET_BLOCK_NOT_READY,
RET_VECTOR_DIMENSION_MISMATCH,
RET_CONTROLLAW_STEP_FAILED

Definition at line 110 of file control_law.cpp.


Member Data Documentation

DVector ControlLaw::p [protected]

Time-constant parameter signals as determined by the control law.

Definition at line 342 of file control_law.hpp.

DVector ControlLaw::u [protected]

First piece of time-varying control signals as determined by the control law.

Definition at line 341 of file control_law.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