Implements a PID control law to be used within a Controller. More...
#include <pid_controller.hpp>
Implements a PID control law to be used within a Controller.
The class PIDcontroller implements a PID control law to be used within a Controller.
For each input component, the weight for the proportional, integral and derivative term can be specified. The PID controller can be used in one of two different modes, depending on the number of inputs and outputs:
i) nOutputs = nInputs: Each output component is determined by the sum of the P, I, and D weight on the corresponding input component.
ii) nOutputs = 1: The component is determined by the sum of the P, I, and D weights on all input components.
Definition at line 67 of file pid_controller.hpp.
Default constructor.
Definition at line 46 of file pid_controller.cpp.
PIDcontroller::PIDcontroller | ( | uint | _nInputs, |
uint | _nOutputs, | ||
double | _samplingTime = DEFAULT_SAMPLING_TIME |
||
) |
Constructor which takes the number of inputs and outputs of the PID controller as well as the sampling time.
[in] | _nInputs | Number of inputs. |
[in] | _nOutputs | Number of outputs. |
[in] | _samplingTime | Sampling time. |
Definition at line 55 of file pid_controller.cpp.
PIDcontroller::PIDcontroller | ( | const PIDcontroller & | rhs | ) |
Copy constructor (deep copy).
[in] | rhs | Right-hand side object. |
Definition at line 88 of file pid_controller.cpp.
PIDcontroller::~PIDcontroller | ( | ) | [virtual] |
Destructor.
Definition at line 102 of file pid_controller.cpp.
ControlLaw * PIDcontroller::clone | ( | ) | const [virtual] |
Clone constructor (deep copy).
Implements ControlLaw.
Definition at line 129 of file pid_controller.cpp.
returnValue PIDcontroller::determineControlAction | ( | const DVector & | error, |
DVector & | output | ||
) | [protected] |
Actually calculates the current control action based on the given current error.
[in] | error | Current error (difference to reference value). |
[out] | output | Current control action. |
Definition at line 321 of file pid_controller.cpp.
uint PIDcontroller::getNP | ( | ) | const [virtual] |
Returns number of parameters.
Reimplemented from ControlLaw.
Definition at line 283 of file pid_controller.cpp.
uint PIDcontroller::getNU | ( | ) | const [virtual] |
Returns number of controls. This is the same as the number of outputs.
Reimplemented from ControlLaw.
Definition at line 277 of file pid_controller.cpp.
uint PIDcontroller::getNumInputs | ( | ) | const [inline] |
Returns number of input components of the PID controller.
uint PIDcontroller::getNumOutputs | ( | ) | const [inline] |
Returns number of output components of the PID controller.
uint PIDcontroller::getNW | ( | ) | const [virtual] |
Returns number of (estimated) disturbances.
Reimplemented from ControlLaw.
Definition at line 289 of file pid_controller.cpp.
uint PIDcontroller::getNX | ( | ) | const [virtual] |
Returns number of (estimated) differential states. This is the same as the number of inputs.
Reimplemented from ControlLaw.
Definition at line 265 of file pid_controller.cpp.
uint PIDcontroller::getNXA | ( | ) | const [virtual] |
Returns number of (estimated) algebraic states.
Reimplemented from ControlLaw.
Definition at line 271 of file pid_controller.cpp.
uint PIDcontroller::getNY | ( | ) | const [virtual] |
Returns number of process outputs.
Reimplemented from ControlLaw.
Definition at line 295 of file pid_controller.cpp.
returnValue PIDcontroller::init | ( | double | startTime = 0.0 , |
const DVector & | x0_ = 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.
[in] | _startTime | Start time. |
[in] | _x | Initial value for differential states. |
[in] | _p | Initial value for parameters. |
[in] | _yRef | Initial value for reference trajectory. |
Implements ControlLaw.
Definition at line 173 of file pid_controller.cpp.
BooleanType PIDcontroller::isDynamic | ( | ) | const [virtual] |
Returns whether the control law is based on dynamic optimization or a static one.
Implements ControlLaw.
Definition at line 301 of file pid_controller.cpp.
BooleanType PIDcontroller::isStatic | ( | ) | const [virtual] |
Returns whether the control law is a static one or based on dynamic optimization.
Implements ControlLaw.
Definition at line 307 of file pid_controller.cpp.
PIDcontroller & PIDcontroller::operator= | ( | const PIDcontroller & | rhs | ) |
Assignment operator (deep copy).
[in] | rhs | Right-hand side object. |
Definition at line 107 of file pid_controller.cpp.
returnValue PIDcontroller::setDerivativeWeights | ( | const DVector & | _dWeights | ) |
Assigns new derivative weights to the input components.
[in] | _dWeights | New derivative weights. |
Definition at line 160 of file pid_controller.cpp.
returnValue PIDcontroller::setIntegralWeights | ( | const DVector & | _iWeights | ) |
Assigns new integral weights to the input components.
[in] | _iWeights | New integral weights. |
Definition at line 148 of file pid_controller.cpp.
returnValue PIDcontroller::setProportionalWeights | ( | const DVector & | _pWeights | ) |
Assigns new proportional weights to the input components.
[in] | _pWeights | New proportional weights. |
Definition at line 136 of file pid_controller.cpp.
returnValue PIDcontroller::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.
[in] | currentTime | Current time. |
[in] | _x | Most recent value for differential states. |
[in] | _p | Most recent value for parameters. |
[in] | _yRef | Current piece of reference trajectory. |
Implements ControlLaw.
Definition at line 214 of file pid_controller.cpp.
DVector PIDcontroller::dWeights [protected] |
Derivative weights for all input components.
Definition at line 278 of file pid_controller.hpp.
DVector PIDcontroller::iValue [protected] |
Integrated value for each input component.
Definition at line 280 of file pid_controller.hpp.
DVector PIDcontroller::iWeights [protected] |
Integral weights for all input components.
Definition at line 277 of file pid_controller.hpp.
DVector PIDcontroller::lastError [protected] |
Last error input (to be used for calculating the derivative via finite differences).
Definition at line 281 of file pid_controller.hpp.
uint PIDcontroller::nInputs [protected] |
Number of inputs.
Definition at line 273 of file pid_controller.hpp.
uint PIDcontroller::nOutputs [protected] |
Number of outputs.
Definition at line 274 of file pid_controller.hpp.
DVector PIDcontroller::pWeights [protected] |
Proportional weights for all input components.
Definition at line 276 of file pid_controller.hpp.