Base class for interfacing online feedback laws to be used within a Controller. More...
#include <control_law.hpp>
Protected Attributes | |
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< OptionsList > | lists |
Protected Attributes inherited from Logging | |
std::vector< LogRecord > | logCollection |
int | logIdx |
Protected Attributes inherited from Plotting | |
PlotCollection | plotCollection |
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.
Definition at line 64 of file control_law.hpp.
BEGIN_NAMESPACE_ACADO ControlLaw::ControlLaw | ( | ) |
Default constructor.
Definition at line 45 of file control_law.cpp.
ControlLaw::ControlLaw | ( | double | _samplingTime | ) |
Constructor which takes the sampling time.
@param[in] _samplingTime Sampling time.
Definition at line 50 of file control_law.cpp.
ControlLaw::ControlLaw | ( | const ControlLaw & | rhs | ) |
Copy constructor (deep copy).
@param[in] rhs Right-hand side object.
Definition at line 56 of file control_law.cpp.
|
virtual |
Destructor.
Definition at line 63 of file control_law.cpp.
|
pure virtual |
Clone constructor (deep copy).
\return Pointer to deep copy of base class type
Implemented in PIDcontroller, FeedforwardLaw, LinearStateFeedback, and RealTimeAlgorithm.
|
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).
Reimplemented in RealTimeAlgorithm.
Definition at line 119 of file control_law.cpp.
|
virtual |
Returns length of the control horizon (for the case a predictive control law is used).
Reimplemented in RealTimeAlgorithm.
Definition at line 190 of file control_law.cpp.
|
virtual |
Returns length of the prediction horizon (for the case a predictive control law is used).
Reimplemented in RealTimeAlgorithm.
Definition at line 184 of file control_law.cpp.
|
virtual |
Returns number of parameters.
Reimplemented in RealTimeAlgorithm, PIDcontroller, FeedforwardLaw, and LinearStateFeedback.
Definition at line 166 of file control_law.cpp.
|
virtual |
Returns number of controls.
Reimplemented in RealTimeAlgorithm, PIDcontroller, FeedforwardLaw, and LinearStateFeedback.
Definition at line 160 of file control_law.cpp.
|
virtual |
Returns number of (estimated) disturbances.
Reimplemented in RealTimeAlgorithm, PIDcontroller, FeedforwardLaw, and LinearStateFeedback.
Definition at line 172 of file control_law.cpp.
|
virtual |
Returns number of (estimated) differential states.
Reimplemented in RealTimeAlgorithm, PIDcontroller, FeedforwardLaw, and LinearStateFeedback.
Definition at line 148 of file control_law.cpp.
|
virtual |
Returns number of (estimated) algebraic states.
Reimplemented in RealTimeAlgorithm, PIDcontroller, FeedforwardLaw, and LinearStateFeedback.
Definition at line 154 of file control_law.cpp.
|
virtual |
Returns number of process outputs.
Reimplemented in RealTimeAlgorithm, PIDcontroller, FeedforwardLaw, and LinearStateFeedback.
Definition at line 178 of file control_law.cpp.
|
inline |
Returns parameter signal as determined by the control law.
@param[out] _p Parameter signal as determined by the control law.
|
inline |
Returns control signal as determined by the control law.
@param[out] _u Control signal as determined by the control law.
|
pure virtual |
Initializes the control law with given start values and performs a number of consistency checks.
[in] | _startTime | Start time. |
[in] | _x | Initial value for differential states. |
[in] | _p | Initial value for parameters. |
[in] | _yRef | Initial value for reference trajectory. |
Implemented in RealTimeAlgorithm, PIDcontroller, FeedforwardLaw, and LinearStateFeedback.
|
virtual |
Initializes algebraic states of the control law.
@param[in] _xa_init Initial value for algebraic states.
Reimplemented in RealTimeAlgorithm.
Definition at line 83 of file control_law.cpp.
|
virtual |
Initializes algebraic states of the control law from data file.
@param[in] fileName Name of file containing initial value for algebraic states.
Reimplemented in RealTimeAlgorithm.
Definition at line 89 of file control_law.cpp.
|
virtual |
Initializes controls of the control law.
@param[in] _u_init Initial value for controls.
Reimplemented in RealTimeAlgorithm.
Definition at line 96 of file control_law.cpp.
|
virtual |
Initializes controls of the control law from data file.
@param[in] fileName Name of file containing initial value for controls.
Reimplemented in RealTimeAlgorithm.
Definition at line 102 of file control_law.cpp.
|
pure virtual |
Returns whether the control law is based on dynamic optimization or a static one.
Implemented in RealTimeAlgorithm, PIDcontroller, FeedforwardLaw, and LinearStateFeedback.
|
virtual |
Returns whether the control law is working in real-time mode.
Reimplemented in RealTimeAlgorithm.
Definition at line 200 of file control_law.cpp.
|
pure virtual |
Returns whether the control law is a static one or based on dynamic optimization.
Implemented in RealTimeAlgorithm, PIDcontroller, FeedforwardLaw, and LinearStateFeedback.
ControlLaw & ControlLaw::operator= | ( | const ControlLaw & | rhs | ) |
Assignment operator (deep copy).
@param[in] rhs Right-hand side object.
Definition at line 68 of file control_law.cpp.
|
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).
Reimplemented in RealTimeAlgorithm.
Definition at line 130 of file control_law.cpp.
|
virtual |
Shifts the data for preparating the next real-time step.
\return RET_NOT_YET_IMPLEMENTED
Reimplemented in RealTimeAlgorithm.
Definition at line 140 of file control_law.cpp.
|
pure 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).
Implemented in PIDcontroller, RealTimeAlgorithm, FeedforwardLaw, and LinearStateFeedback.
|
virtual |
Performs next step of the control law based on given inputs.
@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).
Definition at line 110 of file control_law.cpp.
|
protected |
Time-constant parameter signals as determined by the control law.
Definition at line 342 of file control_law.hpp.
|
protected |
First piece of time-varying control signals as determined by the control law.
Definition at line 341 of file control_law.hpp.