- 3.0.2 core module.
ct::core::PIDController< SCALAR > Class Template Reference

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 &parameters=parameters_t(), const setpoint_t &setpoint=setpoint_t())
 default constructor More...
 
 PIDController (const PIDController &other)
 copy constructor More...
 
virtual ~PIDController ()
 destructor More...
 
PIDControllerclone () 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 &parameters)
 change the control parameters More...
 
parameters_tParameters ()
 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...
 

Detailed Description

template<typename SCALAR = double>
class ct::core::PIDController< SCALAR >

A standard PIDController.

Implements a standard PID feedback law with anti wind-up:

\[ u(x,t) = -k_p (x-x_d) - k_d (\dot{x} - \dot{x}_d) - k_i \int_0^t (x-x_d) dt \]

subject to the saturation

\[ u_{min} \leq u(x,t) \leq u_{max} \]

  • The state derivative $\dot{x}$ can be provided or is computed using finite differences between current and previous state
  • The anti-windup ensures that the I part stays within fixed boundaries, i.e. saturates

Constructor & Destructor Documentation

◆ PIDController() [1/2]

template<typename SCALAR >
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
parametersThe parameters for the PID controller
setpointThe setpoint for the PID controller

◆ PIDController() [2/2]

template<typename SCALAR >
ct::core::PIDController< SCALAR >::PIDController ( const PIDController< SCALAR > &  other)

copy constructor

◆ ~PIDController()

template<typename SCALAR >
ct::core::PIDController< SCALAR >::~PIDController ( )
virtual

destructor

Member Function Documentation

◆ clone()

template<typename SCALAR >
PIDController< SCALAR > * ct::core::PIDController< SCALAR >::clone ( ) const

clone operator

◆ setInitialState()

template<typename SCALAR >
void ct::core::PIDController< SCALAR >::setInitialState ( const SCALAR state)

set the initial state

Set the initial state for finite differencing for the D-part

Parameters
statethe initial state

References ct::core::PIDController< SCALAR >::statePrevious_.

◆ setDesiredState() [1/2]

template<typename SCALAR >
void ct::core::PIDController< SCALAR >::setDesiredState ( const SCALAR state)

set the state

Parameters
stateThe setpoint to set

References ct::core::PIDController< SCALAR >::setpoint_, and ct::core::PIDController< SCALAR >::setpoint_t::stateDesired_.

◆ setDesiredState() [2/2]

template<typename SCALAR >
void ct::core::PIDController< SCALAR >::setDesiredState ( const SCALAR state,
const SCALAR stateDerivative 
)

set the desired state and derivative

Parameters
statethe desired state
stateDerivativethe desired state derivative

References ct::core::PIDController< SCALAR >::setpoint_, ct::core::PIDController< SCALAR >::setpoint_t::stateDerivativeDesired_, and ct::core::PIDController< SCALAR >::setpoint_t::stateDesired_.

◆ computeControl() [1/2]

◆ computeControl() [2/2]

◆ changeParameters()

template<typename SCALAR = double>
void ct::core::PIDController< SCALAR >::changeParameters ( const parameters_t parameters)

change the control parameters

Parameters
parametersthe new PID controller parameters

References ct::core::PIDController< SCALAR >::parameters_.

◆ Parameters()

template<typename SCALAR >
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

Returns
reference to the parameters

References ct::core::PIDController< SCALAR >::parameters_.

◆ reset()

Member Data Documentation

◆ statePrevious_

◆ I_

template<typename SCALAR = double>
SCALAR ct::core::PIDController< SCALAR >::I_
protected

the previous state used for finite differences

Referenced by ct::core::PIDController< SCALAR >::computeControl(), and ct::core::PIDController< SCALAR >::reset().

◆ parameters_

◆ setpoint_

template<typename SCALAR = double>
setpoint_t ct::core::PIDController< SCALAR >::setpoint_
protected

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