Public Member Functions | Protected Member Functions | Protected Attributes

Implements a PID control law to be used within a Controller. More...

#include <pid_controller.hpp>

Inheritance diagram for PIDcontroller:
Inheritance graph
[legend]

List of all members.

Public Member Functions

virtual ControlLawclone () const
virtual uint getNP () const
virtual uint getNU () const
uint getNumInputs () const
uint getNumOutputs () const
virtual uint getNW () const
virtual uint getNX () const
virtual uint getNXA () const
virtual uint getNY () const
virtual returnValue init (double startTime=0.0, const DVector &x0_=emptyConstVector, const DVector &p_=emptyConstVector, const VariablesGrid &_yRef=emptyConstVariablesGrid)
virtual BooleanType isDynamic () const
virtual BooleanType isStatic () const
PIDcontrolleroperator= (const PIDcontroller &rhs)
 PIDcontroller ()
 PIDcontroller (uint _nInputs, uint _nOutputs, double _samplingTime=DEFAULT_SAMPLING_TIME)
 PIDcontroller (const PIDcontroller &rhs)
returnValue setDerivativeWeights (const DVector &_dWeights)
returnValue setIntegralWeights (const DVector &_iWeights)
returnValue setProportionalWeights (const DVector &_pWeights)
virtual returnValue step (double currentTime, const DVector &_x, const DVector &_p=emptyConstVector, const VariablesGrid &_yRef=emptyConstVariablesGrid)
virtual ~PIDcontroller ()

Protected Member Functions

returnValue determineControlAction (const DVector &error, DVector &output)

Protected Attributes

DVector dWeights
DVector iValue
DVector iWeights
DVector lastError
uint nInputs
uint nOutputs
DVector pWeights

Detailed Description

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.

Author:
Hans Joachim Ferreau, Boris Houska

Definition at line 67 of file pid_controller.hpp.


Constructor & Destructor Documentation

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.

Parameters:
[in]_nInputsNumber of inputs.
[in]_nOutputsNumber of outputs.
[in]_samplingTimeSampling time.

Definition at line 55 of file pid_controller.cpp.

Copy constructor (deep copy).

Parameters:
[in]rhsRight-hand side object.

Definition at line 88 of file pid_controller.cpp.

Destructor.

Definition at line 102 of file pid_controller.cpp.


Member Function Documentation

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

Clone constructor (deep copy).

Returns:
Pointer to deep copy of base class type

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.

Parameters:
[in]errorCurrent error (difference to reference value).
[out]outputCurrent control action.
Returns:
SUCCESSFUL_RETURN

Definition at line 321 of file pid_controller.cpp.

uint PIDcontroller::getNP ( ) const [virtual]

Returns number of parameters.

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.

Returns:
Number of controls

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.

Returns:
Number of input components
uint PIDcontroller::getNumOutputs ( ) const [inline]

Returns number of output components of the PID controller.

Returns:
Number of output components
uint PIDcontroller::getNW ( ) const [virtual]

Returns number of (estimated) disturbances.

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.

Returns:
Number of (estimated) differential states

Reimplemented from ControlLaw.

Definition at line 265 of file pid_controller.cpp.

uint PIDcontroller::getNXA ( ) const [virtual]

Returns number of (estimated) algebraic states.

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.

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.

Parameters:
[in]_startTimeStart time.
[in]_xInitial value for differential states.
[in]_pInitial value for parameters.
[in]_yRefInitial value for reference trajectory.
Returns:
SUCCESSFUL_RETURN

Implements ControlLaw.

Definition at line 173 of file pid_controller.cpp.

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

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.

Returns:
BT_TRUE iff control law is a static one,
BT_FALSE otherwise

Implements ControlLaw.

Definition at line 307 of file pid_controller.cpp.

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

Assignment operator (deep copy).

Parameters:
[in]rhsRight-hand side object.

Definition at line 107 of file pid_controller.cpp.

Assigns new derivative weights to the input components.

Parameters:
[in]_dWeightsNew derivative weights.
Returns:
SUCCESSFUL_RETURN,
RET_VECTOR_DIMENSION_MISMATCH

Definition at line 160 of file pid_controller.cpp.

Assigns new integral weights to the input components.

Parameters:
[in]_iWeightsNew integral weights.
Returns:
SUCCESSFUL_RETURN,
RET_VECTOR_DIMENSION_MISMATCH

Definition at line 148 of file pid_controller.cpp.

Assigns new proportional weights to the input components.

Parameters:
[in]_pWeightsNew proportional weights.
Returns:
SUCCESSFUL_RETURN,
RET_VECTOR_DIMENSION_MISMATCH

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.

Parameters:
[in]currentTimeCurrent time.
[in]_xMost recent value for differential states.
[in]_pMost recent value for parameters.
[in]_yRefCurrent piece of reference trajectory.
Returns:
SUCCESSFUL_RETURN,
RET_BLOCK_NOT_READY,
RET_VECTOR_DIMENSION_MISMATCH,
RET_CONTROLLAW_STEP_FAILED

Implements ControlLaw.

Definition at line 214 of file pid_controller.cpp.


Member Data Documentation

Derivative weights for all input components.

Definition at line 278 of file pid_controller.hpp.

Integrated value for each input component.

Definition at line 280 of file pid_controller.hpp.

Integral weights for all input components.

Definition at line 277 of file pid_controller.hpp.

Last error input (to be used for calculating the derivative via finite differences).

Definition at line 281 of file pid_controller.hpp.

Number of inputs.

Definition at line 273 of file pid_controller.hpp.

Number of outputs.

Definition at line 274 of file pid_controller.hpp.

Proportional weights for all input components.

Definition at line 276 of file pid_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:39