- 3.0.2 core module.
|
A standard PIDController. More...
#include <PIDController.h>
Classes | |
struct | parameters_t |
Parameters of a PID Controller. More... | |
struct | setpoint_t |
setpoint for the PID controller More... | |
Public Member Functions | |
PIDController (const parameters_t ¶meters=parameters_t(), const setpoint_t &setpoint=setpoint_t()) | |
default constructor More... | |
PIDController (const PIDController &other) | |
copy constructor More... | |
virtual | ~PIDController () |
destructor More... | |
PIDController * | clone () const |
clone operator More... | |
void | setInitialState (const SCALAR &state) |
set the initial state More... | |
void | setDesiredState (const SCALAR &state) |
set the state More... | |
void | setDesiredState (const SCALAR &state, const SCALAR &stateDerivative) |
set the desired state and derivative More... | |
SCALAR | computeControl (const SCALAR &state, const Time &t) |
computes the control input based on the current state and time More... | |
SCALAR | computeControl (const SCALAR &state, const SCALAR &stateDerivative, const Time &t) |
computes the control input More... | |
void | changeParameters (const parameters_t ¶meters) |
change the control parameters More... | |
parameters_t & | Parameters () |
returns a reference to the parameters More... | |
void | reset () |
resets the controller More... | |
Protected Attributes | |
SCALAR | statePrevious_ |
SCALAR | I_ |
the previous state used for finite differences More... | |
parameters_t | parameters_ |
the current I part (integrated) More... | |
setpoint_t | setpoint_ |
the parameters of the PID controller More... | |
A standard PIDController.
Implements a standard PID feedback law with anti wind-up:
subject to the saturation
ct::core::PIDController< SCALAR >::PIDController | ( | const parameters_t & | parameters = parameters_t() , |
const setpoint_t & | setpoint = setpoint_t() |
||
) |
default constructor
Initializes setpoints and parameters to their default values
parameters | The parameters for the PID controller |
setpoint | The setpoint for the PID controller |
ct::core::PIDController< SCALAR >::PIDController | ( | const PIDController< SCALAR > & | other | ) |
copy constructor
|
virtual |
destructor
PIDController< SCALAR > * ct::core::PIDController< SCALAR >::clone | ( | ) | const |
clone operator
void ct::core::PIDController< SCALAR >::setInitialState | ( | const SCALAR & | state | ) |
set the initial state
Set the initial state for finite differencing for the D-part
state | the initial state |
References ct::core::PIDController< SCALAR >::statePrevious_.
void ct::core::PIDController< SCALAR >::setDesiredState | ( | const SCALAR & | state | ) |
set the state
state | The setpoint to set |
References ct::core::PIDController< SCALAR >::setpoint_, and ct::core::PIDController< SCALAR >::setpoint_t::stateDesired_.
void ct::core::PIDController< SCALAR >::setDesiredState | ( | const SCALAR & | state, |
const SCALAR & | stateDerivative | ||
) |
set the desired state and derivative
state | the desired state |
stateDerivative | the desired state derivative |
References ct::core::PIDController< SCALAR >::setpoint_, ct::core::PIDController< SCALAR >::setpoint_t::stateDerivativeDesired_, and ct::core::PIDController< SCALAR >::setpoint_t::stateDesired_.
SCALAR ct::core::PIDController< SCALAR >::computeControl | ( | const SCALAR & | state, |
const Time & | t | ||
) |
computes the control input based on the current state and time
uses finite-differences for computing the state derivative
state | the current state |
t | the current time |
References ct::core::PIDController< SCALAR >::parameters_t::dt, ct::core::PIDController< SCALAR >::I_, ct::core::PIDController< SCALAR >::parameters_t::k_d, ct::core::PIDController< SCALAR >::parameters_t::k_p, ct::core::PIDController< SCALAR >::parameters_, ct::core::PIDController< SCALAR >::setpoint_, ct::core::PIDController< SCALAR >::setpoint_t::stateDerivativeDesired_, ct::core::PIDController< SCALAR >::setpoint_t::stateDesired_, ct::core::PIDController< SCALAR >::statePrevious_, and u.
SCALAR ct::core::PIDController< SCALAR >::computeControl | ( | const SCALAR & | state, |
const SCALAR & | stateDerivative, | ||
const Time & | t | ||
) |
computes the control input
state | the current state |
stateDerivative | the current state derivative |
t | the current time |
References ct::core::PIDController< SCALAR >::I_, ct::core::PIDController< SCALAR >::parameters_t::k_d, ct::core::PIDController< SCALAR >::parameters_t::k_p, ct::core::PIDController< SCALAR >::parameters_, ct::core::PIDController< SCALAR >::setpoint_, ct::core::PIDController< SCALAR >::setpoint_t::stateDerivativeDesired_, ct::core::PIDController< SCALAR >::setpoint_t::stateDesired_, ct::core::PIDController< SCALAR >::statePrevious_, u, ct::core::PIDController< SCALAR >::parameters_t::uMax, and ct::core::PIDController< SCALAR >::parameters_t::uMin.
void ct::core::PIDController< SCALAR >::changeParameters | ( | const parameters_t & | parameters | ) |
change the control parameters
parameters | the new PID controller parameters |
References ct::core::PIDController< SCALAR >::parameters_.
PIDController< SCALAR >::parameters_t & ct::core::PIDController< SCALAR >::Parameters | ( | ) |
returns a reference to the parameters
Changes to the parameters can be directly made through this reference
References ct::core::PIDController< SCALAR >::parameters_.
void ct::core::PIDController< SCALAR >::reset | ( | ) |
resets the controller
resets the I part as well as the previous state
References ct::core::PIDController< SCALAR >::parameters_t::dt, ct::core::PIDController< SCALAR >::I_, ct::core::PIDController< SCALAR >::parameters_t::Imax, ct::core::PIDController< SCALAR >::parameters_t::k_i, ct::core::PIDController< SCALAR >::parameters_, and ct::core::PIDController< SCALAR >::statePrevious_.
|
protected |
|
protected |
the previous state used for finite differences
Referenced by ct::core::PIDController< SCALAR >::computeControl(), and ct::core::PIDController< SCALAR >::reset().
|
protected |
the current I part (integrated)
Referenced by ct::core::PIDController< SCALAR >::changeParameters(), ct::core::PIDController< SCALAR >::computeControl(), ct::core::PIDController< SCALAR >::Parameters(), and ct::core::PIDController< SCALAR >::reset().
|
protected |
the parameters of the PID controller
Referenced by ct::core::PIDController< SCALAR >::computeControl(), and ct::core::PIDController< SCALAR >::setDesiredState().