Public Member Functions | Protected Member Functions | Protected Attributes | List of all members

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

#include <pid_controller.hpp>

Inheritance diagram for PIDcontroller:
Inheritance graph
[legend]

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 ()
 
- Public Member Functions inherited from ControlLaw
 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
 
returnValue getP (DVector &_p) const
 
returnValue getU (DVector &_u) const
 
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 isInRealTimeMode () const
 
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 (const DVector &_x, const DVector &_p=emptyConstVector, const VariablesGrid &_yRef=emptyConstVariablesGrid)
 
virtual ~ControlLaw ()
 
- Public Member Functions inherited from SimulationBlock
BlockName getName () const
 
double getSamplingTime () const
 
BooleanType isDefined () const
 
SimulationBlockoperator= (const SimulationBlock &rhs)
 
returnValue setName (BlockName _name)
 
returnValue setSamplingTime (double _samplingTime)
 
 SimulationBlock ()
 
 SimulationBlock (BlockName _name, double _samplingTime=DEFAULT_SAMPLING_TIME)
 
 SimulationBlock (const SimulationBlock &rhs)
 
virtual ~SimulationBlock ()
 
- Public Member Functions inherited from UserInteraction
virtual int addPlotWindow (PlotWindow &_window)
 
virtual int operator<< (PlotWindow &_window)
 
virtual int operator<< (LogRecord &_record)
 
UserInteractionoperator= (const UserInteraction &rhs)
 
 UserInteraction ()
 
 UserInteraction (const UserInteraction &rhs)
 
virtual ~UserInteraction ()
 
- Public Member Functions inherited from Options
returnValue addOptionsList ()
 
returnValue ensureConsistency ()
 
returnValue ensureConsistency ()
 
returnValue get (OptionsName name, int &value) const
 
returnValue get (OptionsName name, double &value) const
 
returnValue get (OptionsName name, std::string &value) const
 
returnValue get (uint idx, OptionsName name, int &value) const
 
returnValue get (uint idx, OptionsName name, double &value) const
 
returnValue get (uint idx, OptionsName name, std::string &value) const
 
uint getNumOptionsLists () const
 
Options getOptions (uint idx) const
 
Optionsoperator= (const Options &rhs)
 
Optionsoperator= (const Options &rhs)
 
 Options ()
 
 Options ()
 
 Options (const Options &rhs)
 
 Options (const Options &rhs)
 
 Options ()
 
 Options (const OptionsList &_optionsList)
 
returnValue print () const
 
returnValue print () const
 
returnValue printOptionsList () const
 
returnValue printOptionsList (uint idx) const
 
returnValue set (OptionsName name, int value)
 
returnValue set (OptionsName name, double value)
 
returnValue set (OptionsName name, const std::string &value)
 
returnValue set (uint idx, OptionsName name, int value)
 
returnValue set (uint idx, OptionsName name, double value)
 
returnValue set (uint idx, OptionsName name, const std::string &value)
 
returnValue setOptions (const Options &arg)
 
returnValue setOptions (uint idx, const Options &arg)
 
returnValue setToDefault ()
 
returnValue setToDefault ()
 
returnValue setToFast ()
 
returnValue setToFast ()
 
returnValue setToMPC ()
 
returnValue setToReliable ()
 
returnValue setToReliable ()
 
 ~Options ()
 
 ~Options ()
 
virtual ~Options ()
 
- Public Member Functions inherited from Logging
int addLogRecord (LogRecord &record)
 
returnValue getAll (LogName _name, MatrixVariablesGrid &values) const
 
returnValue getFirst (LogName _name, DMatrix &firstValue) const
 
returnValue getFirst (LogName _name, VariablesGrid &firstValue) const
 
returnValue getLast (LogName _name, DMatrix &lastValue) const
 
returnValue getLast (LogName _name, VariablesGrid &lastValue) const
 
returnValue getLogRecord (LogRecord &_record) const
 
uint getNumLogRecords () const
 
 Logging ()
 
int operator<< (LogRecord &record)
 
returnValue printLoggingInfo () const
 
returnValue printNumDoubles () const
 
returnValue setAll (LogName _name, const MatrixVariablesGrid &values)
 
returnValue setLast (LogName _name, const DMatrix &value, double time=-INFTY)
 
returnValue setLast (LogName _name, VariablesGrid &value, double time=-INFTY)
 
returnValue updateLogRecord (LogRecord &_record) const
 
virtual ~Logging ()
 
- Public Member Functions inherited from Plotting
int addPlotWindow (PlotWindow &_window)
 
uint getNumPlotWindows () const
 
returnValue getPlotWindow (uint idx, PlotWindow &_window) const
 
returnValue getPlotWindow (PlotWindow &_window) const
 
int operator<< (PlotWindow &_window)
 
Plottingoperator= (const Plotting &rhs)
 
virtual returnValue plot (PlotFrequency _frequency=PLOT_IN_ANY_CASE)
 
 Plotting ()
 
 Plotting (const Plotting &rhs)
 
virtual returnValue replot (PlotFrequency _frequency=PLOT_IN_ANY_CASE)
 
virtual ~Plotting ()
 
- Public Member Functions inherited from ClippingFunctionality
 ClippingFunctionality ()
 
 ClippingFunctionality (uint _nU, uint _nP=0)
 
 ClippingFunctionality (const ClippingFunctionality &rhs)
 
ClippingFunctionalityoperator= (const ClippingFunctionality &rhs)
 
returnValue setControlLowerLimit (uint idx, double _lowerLimit)
 
returnValue setControlLowerLimits (const DVector &_lowerLimit)
 
returnValue setControlUpperLimit (uint idx, double _upperLimit)
 
returnValue setControlUpperLimits (const DVector &_upperLimit)
 
returnValue setParameterLowerLimit (uint idx, double _lowerLimit)
 
returnValue setParameterLowerLimits (const DVector &_lowerLimit)
 
returnValue setParameterUpperLimit (uint idx, double _upperLimit)
 
returnValue setParameterUpperLimits (const DVector &_upperLimit)
 
 ~ClippingFunctionality ()
 

Protected Member Functions

returnValue determineControlAction (const DVector &error, DVector &output)
 
- Protected Member Functions inherited from UserInteraction
virtual returnValue getPlotDataFromMemberLoggings (PlotWindow &_window) const
 
BlockStatus getStatus () const
 
returnValue setStatus (BlockStatus _status)
 
- Protected Member Functions inherited from Options
returnValue addOption (OptionsName name, int value)
 
returnValue addOption (OptionsName name, double value)
 
returnValue addOption (OptionsName name, const std::string &value)
 
returnValue addOption (uint idx, OptionsName name, int value)
 
returnValue addOption (uint idx, OptionsName name, double value)
 
returnValue addOption (uint idx, OptionsName name, const std::string &value)
 
returnValue clearOptionsList ()
 
returnValue copy (const Options &rhs)
 
returnValue copy (const Options &rhs)
 
returnValue declareOptionsUnchanged ()
 
returnValue declareOptionsUnchanged (uint idx)
 
BooleanType haveOptionsChanged () const
 
BooleanType haveOptionsChanged (uint idx) const
 
virtual returnValue setupOptions ()
 
- Protected Member Functions inherited from Logging
virtual returnValue setupLogging ()
 
- Protected Member Functions inherited from ClippingFunctionality
returnValue clipSignals (VariablesGrid &_u, VariablesGrid &_p=emptyVariablesGrid)
 
returnValue clipSignals (DVector &_u, DVector &_p=emptyVector)
 
uint getNumControlLimits () const
 
uint getNumParameterLimits () const
 

Protected Attributes

DVector dWeights
 
DVector iValue
 
DVector iWeights
 
DVector lastError
 
uint nInputs
 
uint nOutputs
 
DVector pWeights
 
- Protected Attributes inherited from ControlLaw
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< OptionsListlists
 
- Protected Attributes inherited from Logging
std::vector< LogRecordlogCollection
 
int logIdx
 
- Protected Attributes inherited from Plotting
PlotCollection plotCollection
 
- Protected Attributes inherited from ClippingFunctionality
DVector lowerLimitControls
 
DVector lowerLimitParameters
 
DVector upperLimitControls
 
DVector upperLimitParameters
 

Additional Inherited Members

- Public Attributes inherited from Options
real_t boundRelaxation
 
real_t boundTolerance
 
int dropBoundPriority
 
int_t dropBoundPriority
 
int dropEqConPriority
 
int_t dropEqConPriority
 
int dropIneqConPriority
 
int_t dropIneqConPriority
 
int enableCholeskyRefactorisation
 
int_t enableCholeskyRefactorisation
 
int enableDriftCorrection
 
int_t enableDriftCorrection
 
BooleanType enableDropInfeasibles
 
BooleanType enableEqualities
 
BooleanType enableFarBounds
 
BooleanType enableFlippingBounds
 
BooleanType enableFullLITests
 
BooleanType enableInertiaCorrection
 
BooleanType enableNZCTests
 
BooleanType enableRamping
 
BooleanType enableRegularisation
 
real_t epsDen
 
real_t epsFlipping
 
real_t epsIterRef
 
real_t epsLITests
 
real_t epsNum
 
real_t epsNZCTests
 
real_t epsRegularisation
 
real_t finalRamping
 
real_t growFarBounds
 
real_t initialFarBounds
 
real_t initialRamping
 
SubjectToStatus initialStatusBounds
 
real_t maxDualJump
 
real_t maxPrimalJump
 
int numRefinementSteps
 
int_t numRefinementSteps
 
int numRegularisationSteps
 
int_t numRegularisationSteps
 
PrintLevel printLevel
 
real_t rcondSMin
 
real_t terminationTolerance
 

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

BEGIN_NAMESPACE_ACADO PIDcontroller::PIDcontroller ( )

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.

PIDcontroller::PIDcontroller ( const PIDcontroller rhs)

Copy constructor (deep copy).

@param[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.

Member Function Documentation

ControlLaw * PIDcontroller::clone ( ) const
virtual

Clone constructor (deep copy).

\return 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.

BooleanType PIDcontroller::isDynamic ( ) const
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

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

@param[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.

@param[in]  _dWeights               New derivative weights.
Returns
SUCCESSFUL_RETURN,
RET_VECTOR_DIMENSION_MISMATCH

Definition at line 160 of file pid_controller.cpp.

returnValue PIDcontroller::setIntegralWeights ( const DVector _iWeights)

Assigns new integral weights to the input components.

@param[in]  _iWeights               New integral weights.
Returns
SUCCESSFUL_RETURN,
RET_VECTOR_DIMENSION_MISMATCH

Definition at line 148 of file pid_controller.cpp.

returnValue PIDcontroller::setProportionalWeights ( const DVector _pWeights)

Assigns new proportional weights to the input components.

@param[in]  _pWeights               New 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.

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

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.


The documentation for this class was generated from the following files:


acado
Author(s): Milan Vukov, Rien Quirynen
autogenerated on Mon Jun 10 2019 12:35:25