Template Class PID

Class Documentation

template<typename P = double, int dim = 3>
class PID

PID controller.

Template Parameters:
  • P – Precision

  • dim – Dimension

Public Functions

inline explicit PID(const PIDParams<P, dim> &pid_params = PIDParams<P, dim>(), const bool &verbose = false)

Construct a new PID.

Parameters:

verbose – Verbosity flag. Default: false

inline ~PID()
inline void update_pid_params(const PIDParams<P, dim> &params)

Update the PID controller with pid params.

Parameters:

paramsPIDParams struct

inline void reset_controller()

Reset the controller.

Reset the integral error

inline void set_output_saturation(const Vector &upper_saturation, const Vector &lower_saturation, bool proportional_saturation_flag = false)

Set the output saturation.

Parameters:
  • upper_saturation – Upper saturation

  • lower_saturation – Lower saturation

  • proportional_saturation_flag – Proportional saturation flag. Default: false

inline void disable_output_saturation()

Disable the output saturation.

Disable the output saturation. The output is not limited by the saturation limits. To enable the output saturation, use the set_output_saturation method.

Parameters:

saturation_flag – Saturation flag

inline Vector compute_control(const Scalar dt, const Vector &proportional_error)

Process the PID controller.

Parameters:
  • dt – Time step

  • proportional_error – Proportional error

Returns:

Vector PID output

inline Vector compute_control(const Scalar dt, const Vector &proportional_error, const Vector &derivative_error)

Process the PID controller with derivative feedback.

Derivative feedback is used to improve the controller performance.

Parameters:
  • dt – Time step (s)

  • state – Current state

  • reference – Reference state

  • state_dot – Current state derivative

  • reference_dot – Reference state derivative

Returns:

Vector

inline PIDParams<P, dim> get_params() const

Get the params.

Returns:

PIDParams<P, dim> PID parameters

inline void set_gains(const Vector &kp, const Vector &ki, const Vector &kd)

Set the Gains of the controller.

Parameters:
  • kp – Proportional gain

  • ki – Integral gain

  • kd – Derivative gain

inline void get_gains(Vector &kp, Vector &ki, Vector &kd) const

Get the gains.

Parameters:
  • kp – Proportional gain

  • ki – Integral gain

  • kd – Derivative gain

inline void set_gains_kp(const Vector &kp)

Set the gains kp.

Parameters:

kp – Proportional gain

inline Vector get_gains_kp() const

Get the gains kp.

Parameters:

kp – Proportional gain

inline void set_gains_ki(const Vector &ki)

Set the gains ki.

Parameters:

ki – Integral gain

inline Vector get_gains_ki() const

Get the gains ki.

Parameters:

ki – Integral gain

inline void set_gains_kd(const Vector &kd)

Set the gains kd.

Parameters:

kd – Derivative gain

inline Vector get_gains_kd() const

Get the gains kd.

Parameters:

kd – Derivative gain

inline void set_anti_windup(const Vector &anti_windup)

Set the anti windup.

Anti windup is a vector that limits the integral contribution of the controller. If the integral contribution is greater/lower than the anti windup, the integral contribution is set to anti windup value.

Parameters:

anti_windup – Anti windup

inline Vector get_anti_windup() const

Get the anti windup.

Anti windup is a value that limits the integral contribution of the controller. If the integral contribution is greater/lower than the anti windup, the integral contribution is set to anti windup value.

Parameters:

anti_windup – Anti windup

inline void set_alpha(const Vector alpha)

Set the alpha.

Alpha is a value that filters the derivative contribution of the controller. If alpha is 1, the derivative contribution is not filtered.

Parameters:

alpha – Alpha in (0, 1]

inline Vector get_alpha() const

Get the alpha.

Alpha is a value that filters the derivative contribution of the controller. If alpha is 1, the derivative contribution is not filtered.

Parameters:

alpha – Alpha in (0, 1]

inline void set_reset_integral_saturation_flag(bool reset_integral_flag)

Set the reset integral saturation flag.

If the flag is true, the integral contribution is reset to zero when the integral error is grater than the anti windup and the sign of the integral error is different from the sign of the proportional error.

Parameters:

reset_integral_flag – Reset integral saturation flag

inline bool get_reset_integral_saturation_flag() const

Get the reset integral saturation flag.

If the flag is true, the integral contribution is reset to zero when the integral error is grater than the anti windup and the sign of the integral error is different from the sign of the proportional error.

Parameters:

reset_integral_flag – Reset integral saturation flag

inline void set_proportional_saturation_flag(bool proportional_saturation_flag)

Set the proportional saturation flag.

If the flag is true, the output is saturated proportionally to the saturation limits. So, the output vector keeps the same direction but its norm is limited to the saturation

Parameters:

proportional_saturation_flag – Proportional saturation flag

inline bool get_proportional_saturation_flag() const

Get the proportional saturation flag.

If the flag is true, the output is saturated proportionally to the saturation limits. So, the output vector keeps the same direction but its norm is limited to the saturation

Parameters:

proportional_saturation_flag – Proportional saturation flag

inline void get_saturation_limits(Vector &saturation_upper_limit, Vector &saturation_lower_limit) const

Get the saturation limits.

Parameters:

saturation_limits – Saturation limits

inline bool get_output_saturation_flag() const

Get the output saturation flag.

Returns:

true Saturation is enabled

Returns:

false Saturation is disabled

inline const Vector &get_proportional_error() const

Get the proportional error.

Returns:

Vector Proportional error

inline const Vector &get_derivative_error() const

Get the derivative error.

Returns:

Vector Derivative error

inline const Vector &get_proportional_error_contribution() const

Get the proportional error contribution.

Returns:

Vector Proportional error contribution

inline const Vector &get_integral_error_contribution() const

Get the integral error contribution.

Returns:

Vector Integral error contribution

inline const Vector &get_derivative_error_contribution() const

Get the derivative error contribution.

Returns:

Vector Derivative error contribution

inline const Vector &get_output() const

Get the output.

Returns:

Vector Output

inline explicit PID(const PIDParams<P, dim> &pid_params = PIDParams<P, dim>(), const bool &verbose = false)

Construct a new PID.

Parameters:

verbose – Verbosity flag. Default: false

inline ~PID()
inline void update_pid_params(const PIDParams<P, dim> &params)

Update the PID controller with pid params.

Parameters:

paramsPIDParams struct

inline void reset_controller()

Reset the controller.

Reset the integral error

inline void set_output_saturation(const Vector &upper_saturation, const Vector &lower_saturation, bool proportional_saturation_flag = false)

Set the output saturation.

Parameters:
  • upper_saturation – Upper saturation

  • lower_saturation – Lower saturation

  • proportional_saturation_flag – Proportional saturation flag. Default: false

inline void disable_output_saturation()

Disable the output saturation.

Disable the output saturation. The output is not limited by the saturation limits. To enable the output saturation, use the set_output_saturation method.

Parameters:

saturation_flag – Saturation flag

inline Vector compute_control(const Scalar dt, const Vector &proportional_error)

Process the PID controller.

Parameters:
  • dt – Time step

  • proportional_error – Proportional error

Returns:

Vector PID output

inline Vector compute_control(const Scalar dt, const Vector &proportional_error, const Vector &derivative_error)

Process the PID controller with derivative feedback.

Derivative feedback is used to improve the controller performance.

Parameters:
  • dt – Time step (s)

  • state – Current state

  • reference – Reference state

  • state_dot – Current state derivative

  • reference_dot – Reference state derivative

Returns:

Vector

inline PIDParams<P, dim> get_params() const

Get the params.

Returns:

PIDParams<P, dim> PID parameters

inline void set_gains(const Vector &kp, const Vector &ki, const Vector &kd)

Set the Gains of the controller.

Parameters:
  • kp – Proportional gain

  • ki – Integral gain

  • kd – Derivative gain

inline void get_gains(Vector &kp, Vector &ki, Vector &kd) const

Get the gains.

Parameters:
  • kp – Proportional gain

  • ki – Integral gain

  • kd – Derivative gain

inline void set_gains_kp(const Vector &kp)

Set the gains kp.

Parameters:

kp – Proportional gain

inline Vector get_gains_kp() const

Get the gains kp.

Parameters:

kp – Proportional gain

inline void set_gains_ki(const Vector &ki)

Set the gains ki.

Parameters:

ki – Integral gain

inline Vector get_gains_ki() const

Get the gains ki.

Parameters:

ki – Integral gain

inline void set_gains_kd(const Vector &kd)

Set the gains kd.

Parameters:

kd – Derivative gain

inline Vector get_gains_kd() const

Get the gains kd.

Parameters:

kd – Derivative gain

inline void set_anti_windup(const Vector &anti_windup)

Set the anti windup.

Anti windup is a vector that limits the integral contribution of the controller. If the integral contribution is greater/lower than the anti windup, the integral contribution is set to anti windup value.

Parameters:

anti_windup – Anti windup

inline Vector get_anti_windup() const

Get the anti windup.

Anti windup is a value that limits the integral contribution of the controller. If the integral contribution is greater/lower than the anti windup, the integral contribution is set to anti windup value.

Parameters:

anti_windup – Anti windup

inline void set_alpha(const Vector alpha)

Set the alpha.

Alpha is a value that filters the derivative contribution of the controller. If alpha is 1, the derivative contribution is not filtered.

Parameters:

alpha – Alpha in (0, 1]

inline Vector get_alpha() const

Get the alpha.

Alpha is a value that filters the derivative contribution of the controller. If alpha is 1, the derivative contribution is not filtered.

Parameters:

alpha – Alpha in (0, 1]

inline void set_reset_integral_saturation_flag(bool reset_integral_flag)

Set the reset integral saturation flag.

If the flag is true, the integral contribution is reset to zero when the integral error is grater than the anti windup and the sign of the integral error is different from the sign of the proportional error.

Parameters:

reset_integral_flag – Reset integral saturation flag

inline bool get_reset_integral_saturation_flag() const

Get the reset integral saturation flag.

If the flag is true, the integral contribution is reset to zero when the integral error is grater than the anti windup and the sign of the integral error is different from the sign of the proportional error.

Parameters:

reset_integral_flag – Reset integral saturation flag

inline void set_proportional_saturation_flag(bool proportional_saturation_flag)

Set the proportional saturation flag.

If the flag is true, the output is saturated proportionally to the saturation limits. So, the output vector keeps the same direction but its norm is limited to the saturation

Parameters:

proportional_saturation_flag – Proportional saturation flag

inline bool get_proportional_saturation_flag() const

Get the proportional saturation flag.

If the flag is true, the output is saturated proportionally to the saturation limits. So, the output vector keeps the same direction but its norm is limited to the saturation

Parameters:

proportional_saturation_flag – Proportional saturation flag

inline void get_saturation_limits(Vector &saturation_upper_limit, Vector &saturation_lower_limit) const

Get the saturation limits.

Parameters:

saturation_limits – Saturation limits

inline bool get_output_saturation_flag() const

Get the output saturation flag.

Returns:

true Saturation is enabled

Returns:

false Saturation is disabled

inline const Vector &get_proportional_error() const

Get the proportional error.

Returns:

Vector Proportional error

inline const Vector &get_derivative_error() const

Get the derivative error.

Returns:

Vector Derivative error

inline const Vector &get_proportional_error_contribution() const

Get the proportional error contribution.

Returns:

Vector Proportional error contribution

inline const Vector &get_integral_error_contribution() const

Get the integral error contribution.

Returns:

Vector Integral error contribution

inline const Vector &get_derivative_error_contribution() const

Get the derivative error contribution.

Returns:

Vector Derivative error contribution

inline const Vector &get_output() const

Get the output.

Returns:

Vector Output

Public Static Functions

static inline Vector get_error(const Vector &state, const Vector &reference)

Get the proportional error.

Parameters:
  • state – Current state

  • reference – Reference state

Returns:

Vector Error

static inline void get_error(const Vector &state, const Vector &reference, const Vector &state_dot, const Vector &reference_dot, Vector &proportional_error, Vector &derivative_error)

Get the proportional and derivative error.

Parameters:
  • state – State

  • reference – Reference

  • state_dot – State derivative

  • reference_dot – Reference derivative

  • proportional_error – Output proportional error

  • derivative_error – Output derivative error

static inline Vector saturate_output(const Vector &output, const Vector &upper_limits, const Vector &lower_limits, const bool proportional_saturation = false)

Saturation function.

If the output is greater than the upper limit, the output is saturated to the upper limit. If the output is lower than the lower limit, the output is saturated to the lower limit. If proportional_saturation is true, the output is saturated proportionally to the limits, keeping the vector direction.

Parameters:
  • output – Vector to saturate

  • upper_limits – Upper limits vector

  • lower_limits – Lower limits vector

  • proportional_saturation – Proportional saturation flag. Default: false

Returns:

Vector Saturated vector

static inline Vector get_error(const Vector &state, const Vector &reference)

Get the proportional error.

Parameters:
  • state – Current state

  • reference – Reference state

Returns:

Vector Error

static inline void get_error(const Vector &state, const Vector &reference, const Vector &state_dot, const Vector &reference_dot, Vector &proportional_error, Vector &derivative_error)

Get the proportional and derivative error.

Parameters:
  • state – State

  • reference – Reference

  • state_dot – State derivative

  • reference_dot – Reference derivative

  • proportional_error – Output proportional error

  • derivative_error – Output derivative error

static inline Vector saturate_output(const Vector &output, const Vector &upper_limits, const Vector &lower_limits, const bool proportional_saturation = false)

Saturation function.

If the output is greater than the upper limit, the output is saturated to the upper limit. If the output is lower than the lower limit, the output is saturated to the lower limit. If proportional_saturation is true, the output is saturated proportionally to the limits, keeping the vector direction.

Parameters:
  • output – Vector to saturate

  • upper_limits – Upper limits vector

  • lower_limits – Lower limits vector

  • proportional_saturation – Proportional saturation flag. Default: false

Returns:

Vector Saturated vector

Protected Functions

inline Vector compute_integral_contribution(const Scalar dt, const Vector &proportional_error)

Compute the integral contribution of the controller.

Parameters:
  • dt – Delta time (s)

  • proportional_error – Proportional error

Returns:

Vector Integral contribution

inline Vector compute_derivative_contribution_by_deriving(const Scalar dt, const Vector &proportional_error)

Compute the derivative contribution of the controller.

Parameters:
  • dt – Delta time (s)

  • proportional_error – Proportional error

Returns:

Vector Derivative contribution

inline Vector compute_derivative_contribution(const Vector &derivate_error)

Compute the derivative contribution of the controller.

For controllers with derivative feedback, the derivative contribution is computed using the state and reference derivatives.

Parameters:
  • state_dot – State derivative

  • reference_dot – Reference derivative

Returns:

Vector Derivative contribution

inline Vector compute_integral_contribution(const Scalar dt, const Vector &proportional_error)

Compute the integral contribution of the controller.

Parameters:
  • dt – Delta time (s)

  • proportional_error – Proportional error

Returns:

Vector Integral contribution

inline Vector compute_derivative_contribution_by_deriving(const Scalar dt, const Vector &proportional_error)

Compute the derivative contribution of the controller.

Parameters:
  • dt – Delta time (s)

  • proportional_error – Proportional error

Returns:

Vector Derivative contribution

inline Vector compute_derivative_contribution(const Vector &derivate_error)

Compute the derivative contribution of the controller.

For controllers with derivative feedback, the derivative contribution is computed using the state and reference derivatives.

Parameters:
  • state_dot – State derivative

  • reference_dot – Reference derivative

Returns:

Vector Derivative contribution

Protected Attributes

bool verbose_ = false
Matrix Kp_lin_mat_ = Matrix::Identity()
Matrix Ki_lin_mat_ = Matrix::Identity()
Matrix Kd_lin_mat_ = Matrix::Identity()
Vector antiwindup_cte_ = Vector::Zero()
Vector alpha_ = Vector::Zero()
bool reset_integral_flag_ = false
bool saturation_flag_ = false
bool proportional_saturation_flag_ = false
Vector upper_output_saturation_ = Vector::Zero()
Vector lower_output_saturation_ = Vector::Zero()
bool first_run_ = true
Vector integral_accum_error_ = Vector::Zero()
Vector filtered_derivate_error_ = Vector::Zero()
Vector proportional_error_ = Vector::Zero()
Vector derivative_error_ = Vector::Zero()
Vector proportional_error_contribution_ = Vector::Zero()
Vector integral_error_contribution_ = Vector::Zero()
Vector derivate_error_contribution_ = Vector::Zero()
Vector output_ = Vector::Zero()