Class Pid
Defined in File pid.hpp
Nested Relationships
Nested Types
Class Documentation
-
class Pid
Generic Proportional–Integral–Derivative (PID) controller.
The PID (Proportional–Integral–Derivative) controller is a widely used feedback controller. This class implements a generic structure that can be used to create a wide range of PID controllers. It can function independently or be subclassed to provide more specific control loops. Integral retention on reset is supported, which prevents re-winding the integrator after temporary disabling in presence of constant disturbances.
PID Equation
The standard PID equation is:
\[ command = p\_term + i\_term + d\_term \]where:\( p\_term = p\_gain \times error \)
\( i\_term \mathrel{+}= i\_gain \times error \times dt \)
\( d\_term = d\_gain \times d\_error \) and:
\( error = desired\_state - measured\_state \)
\( d\_error = (error - error\_{last}) / dt \)
Parameters
Anti-Windup Strategies
Without anti-windup, clamping causes integral windup, leading to overshoot and sluggish recovery. This class provides two strategies:
BACK_CALCULATION
\[ i\_term \mathrel{+}= dt \times \Bigl(i\_gain \times error + \frac{1}{trk\_tc}\,(command_{sat} - command)\Bigr) \]Prevents excessive accumulation by correctingi_term
toward the saturation limit.CONDITIONAL_INTEGRATION Integrates only if
\[ (command - command_{sat} = 0)\quad\lor\quad(error \times command \le 0) \]Freezes integration when saturated and error drives further saturation.
Usage Example
Initialize and compute at each control step:
control_toolbox::Pid pid; pid.initialize(6.0, 1.0, 2.0, -5.0, 5.0, 2.0, control_toolbox::AntiwindupStrategy::BACK_CALCULATION); rclcpp::Time last = get_clock()->now(); while (running) { rclcpp::Time now = get_clock()->now(); double effort = pid.compute_command(setpoint - current(), now - last); last = now; }
- Param p:
Proportional gain. Reacts to current error.
- Param i:
Integral gain. Accumulates past error to eliminate steady-state error.
- Param d:
Derivative gain. Predicts future error to reduce overshoot and settling time.
- Param u_min:
Minimum bound for the controller output.
- Param u_max:
Maximum bound for the controller output.
- Param tracking_time_constant:
Tracking time constant for BACK_CALCULATION anti-windup. If zero, a default is chosen based on gains:
\( \sqrt{d\_gain / i\_gain} \) if
d_gain
≠ 0\( p\_gain / i\_gain \) otherwise.
- Param antiwindup_strat:
Anti-windup strategy:
NONE: no anti-windup (integral always accumulates).
BACK_CALCULATION: adjusts
i_term
based on difference between saturated and unsaturated outputs usingtracking_time_constant
.CONDITIONAL_INTEGRATION: only integrates when output is not saturated or error drives it away from saturation.
Public Functions
-
Pid(double p = 0.0, double i = 0.0, double d = 0.0, double i_max = 0.0, double i_min = -0.0, bool antiwindup = false)
Constructor, zeros out Pid values when created and initialize Pid-gains and integral term limits.
- Parameters:
p – The proportional gain.
i – The integral gain.
d – The derivative gain.
i_max – Upper integral clamp.
i_min – Lower integral clamp.
antiwindup – Anti-windup functionality. When set to true, limits the integral error to prevent windup; otherwise, constrains the integral contribution to the control output. i_max and i_min are applied in both scenarios.
- Throws:
An – std::invalid_argument exception is thrown if i_min > i_max
-
Pid(double p, double i, double d, double u_max, double u_min, const AntiWindupStrategy &antiwindup_strat)
Constructor, initialize Pid-gains and term limits.
- Parameters:
p – The proportional gain.
i – The integral gain.
d – The derivative gain.
u_max – Upper output clamp.
u_min – Lower output clamp.
antiwindup_strat – Specifies the anti-windup strategy. Options: ‘back_calculation’, ‘conditional_integration’, or ‘none’. Note that the ‘back_calculation’ strategy use the tracking_time_constant parameter to tune the anti-windup behavior.
- Throws:
An – std::invalid_argument exception is thrown if u_min > u_max
-
Pid(const Pid &source)
Copy constructor required for preventing mutexes from being copied.
- Parameters:
source – - Pid to copy
-
bool initialize(double p, double i, double d, double i_max, double i_min, bool antiwindup = false)
Zeros out Pid values and initialize Pid-gains and term limits.
Note
New gains are not applied if i_min_ > i_max_
- Parameters:
p – The proportional gain.
i – The integral gain.
d – The derivative gain.
i_max – Upper integral clamp.
i_min – Lower integral clamp.
antiwindup – Anti-windup functionality. When set to true, limits the integral error to prevent windup; otherwise, constrains the integral contribution to the control output. i_max and i_min are applied in both scenarios.
- Returns:
True if all parameters are successfully set, False otherwise.
-
void initPid(double p, double i, double d, double i_max, double i_min, bool antiwindup = false)
Initialize Pid-gains and term limits.
Note
New gains are not applied if i_min_ > i_max_
- Parameters:
p – The proportional gain.
i – The integral gain.
d – The derivative gain.
i_max – Upper integral clamp.
i_min – Lower integral clamp.
antiwindup – Antiwindup functionality. When set to true, limits the integral error to prevent windup; otherwise, constrains the integral contribution to the control output. i_max and i_min are applied in both scenarios.
-
bool initialize(double p, double i, double d, double u_max, double u_min, const AntiWindupStrategy &antiwindup_strat)
Initialize Pid-gains and term limits.
Note
New gains are not applied if i_min_ > i_max_ or u_min > u_max
- Parameters:
p – The proportional gain.
i – The integral gain.
d – The derivative gain.
u_max – Upper output clamp.
u_min – Lower output clamp.
antiwindup_strat – Specifies the anti-windup strategy. Options: ‘back_calculation’, ‘conditional_integration’, or ‘none’. Note that the ‘back_calculation’ strategy use the tracking_time_constant parameter to tune the anti-windup behavior.
- Returns:
True if all parameters are successfully set, False otherwise.
-
void reset()
Reset the state of this PID controller.
Note
The integral term is not retained and it is reset to zero
-
void reset(bool save_i_term)
Reset the state of this PID controller.
- Parameters:
save_i_term – boolean indicating if integral term is retained on reset()
-
void clear_saved_iterm()
Clear the saved integrator output of this controller.
-
void get_gains(double &p, double &i, double &d, double &i_max, double &i_min)
Get PID gains for the controller.
Note
This method is not RT safe
- Parameters:
p – The proportional gain.
i – The integral gain.
d – The derivative gain.
i_max – Upper integral clamp.
i_min – Lower integral clamp.
-
void getGains(double &p, double &i, double &d, double &i_max, double &i_min)
Get PID gains for the controller.
- Parameters:
p – The proportional gain.
i – The integral gain.
d – The derivative gain.
i_max – Upper integral clamp.
i_min – Lower integral clamp.
-
void get_gains(double &p, double &i, double &d, double &i_max, double &i_min, bool &antiwindup)
Get PID gains for the controller.
Note
This method is not RT safe
- Parameters:
p – The proportional gain.
i – The integral gain.
d – The derivative gain.
i_max – Upper integral clamp.
i_min – Lower integral clamp.
antiwindup – Anti-windup functionality. When set to true, limits the integral error to prevent windup; otherwise, constrains the integral contribution to the control output. i_max and i_min are applied in both scenarios.
-
void getGains(double &p, double &i, double &d, double &i_max, double &i_min, bool &antiwindup)
Get PID gains for the controller.
- Parameters:
p – The proportional gain.
i – The integral gain.
d – The derivative gain.
i_max – Upper integral clamp.
i_min – Lower integral clamp.
antiwindup – Antiwindup functionality. When set to true, limits the integral error to prevent windup; otherwise, constrains the integral contribution to the control output. i_max and i_min are applied in both scenarios.
-
void get_gains(double &p, double &i, double &d, double &u_max, double &u_min, AntiWindupStrategy &antiwindup_strat)
Get PID gains for the controller (preferred).
Note
This method is not RT safe
- Parameters:
p – The proportional gain.
i – The integral gain.
d – The derivative gain.
u_max – Upper output clamp.
u_min – Lower output clamp.
antiwindup_strat – Specifies the anti-windup strategy. Options: ‘back_calculation’, ‘conditional_integration’, or ‘none’. Note that the ‘back_calculation’ strategy use the tracking_time_constant parameter to tune the anti-windup behavior.
-
Gains get_gains()
Get PID gains for the controller.
Note
This method is not RT safe
- Returns:
gains A struct of the PID gain values
-
Gains getGains()
Get PID gains for the controller.
Note
This method is not RT safe
- Returns:
gains A struct of the PID gain values
-
inline Gains get_gains_rt()
Get PID gains for the controller.
Note
This method can be called from the RT loop
- Returns:
gains A struct of the PID gain values
-
bool set_gains(double p, double i, double d, double i_max, double i_min, bool antiwindup = false)
Set PID gains for the controller.
Note
New gains are not applied if i_min > i_max
Note
This method is not RT safe
- Parameters:
p – The proportional gain.
i – The integral gain.
d – The derivative gain.
i_max – Upper integral clamp.
i_min – Lower integral clamp.
antiwindup – Anti-windup functionality. When set to true, limits the integral error to prevent windup; otherwise, constrains the integral contribution to the control output. i_max and i_min are applied in both scenarios.
- Returns:
True if all parameters are successfully set, False otherwise.
-
void setGains(double p, double i, double d, double i_max, double i_min, bool antiwindup = false)
Set PID gains for the controller.
Note
New gains are not applied if i_min > i_max
- Parameters:
p – The proportional gain.
i – The integral gain.
d – The derivative gain.
i_max – Upper integral clamp.
i_min – Lower integral clamp.
antiwindup – Antiwindup functionality. When set to true, limits the integral error to prevent windup; otherwise, constrains the integral contribution to the control output. i_max and i_min are applied in both scenarios.
-
bool set_gains(double p, double i, double d, double u_max, double u_min, const AntiWindupStrategy &antiwindup_strat)
Set PID gains for the controller.
Note
New gains are not applied if i_min_ > i_max_ or u_min > u_max
Note
This method is not RT safe
- Parameters:
p – The proportional gain.
i – The integral gain.
d – The derivative gain.
u_max – Upper output clamp.
u_min – Lower output clamp.
antiwindup_strat – Specifies the anti-windup strategy. Options: ‘back_calculation’, ‘conditional_integration’, or ‘none’. Note that the ‘back_calculation’ strategy use the tracking_time_constant parameter to tune the anti-windup behavior.
- Returns:
True if all parameters are successfully set, False otherwise.
-
bool set_gains(const Gains &gains)
Set PID gains for the controller.
Note
New gains are not applied if gains.i_min_ > gains.i_max_
Note
This method is not RT safe
- Parameters:
gains – A struct of the PID gain values
- Returns:
True if all parameters are successfully set, False otherwise.
-
void setGains(const Gains &gains)
Set PID gains for the controller.
Note
New gains are not applied if gains.i_min_ > gains.i_max_
- Parameters:
gains – A struct of the PID gain values
-
double compute_command(double error, const double &dt_s)
Set the PID error and compute the PID command with nonuniform time step size. The derivative error is computed from the change in the error and the timestep
dt_s
.- Parameters:
error – Error since last call (error = target - state)
dt_s – Change in time since last call in seconds
- Returns:
PID command
-
double computeCommand(double error, uint64_t dt)
Set the PID error and compute the PID command with nonuniform time step size. The derivative error is computed from the change in the error and the timestep
dt
.- Parameters:
error – Error since last call (error = target - state)
dt – Change in time since last call in nanoseconds
- Returns:
PID command
-
double compute_command(double error, const rcl_duration_value_t &dt_ns)
Set the PID error and compute the PID command with nonuniform time step size. The derivative error is computed from the change in the error and the timestep
dt_ns
.- Parameters:
error – Error since last call (error = target - state)
dt_ns – Change in time since last call, measured in nanoseconds.
- Returns:
PID command
-
double compute_command(double error, const rclcpp::Duration &dt)
Set the PID error and compute the PID command with nonuniform time step size. The derivative error is computed from the change in the error and the timestep
dt
.- Parameters:
error – Error since last call (error = target - state)
dt – Change in time since last call
- Returns:
PID command
-
double compute_command(double error, const std::chrono::nanoseconds &dt_ns)
Set the PID error and compute the PID command with nonuniform time step size. The derivative error is computed from the change in the error and the timestep
dt_ns
.- Parameters:
error – Error since last call (error = target - state)
dt_ns – Change in time since last call
- Returns:
PID command
-
double compute_command(double error, double error_dot, const double &dt_s)
Set the PID error and compute the PID command with nonuniform time step size. This also allows the user to pass in a precomputed derivative error.
- Parameters:
error – Error since last call (error = target - state)
error_dot – d(Error)/dt_s since last call
dt_s – Change in time since last call in seconds
- Returns:
PID command
-
double computeCommand(double error, double error_dot, uint64_t dt)
Set the PID error and compute the PID command with nonuniform time step size. This also allows the user to pass in a precomputed derivative error.
- Parameters:
error – Error since last call (error = target - state)
error_dot – d(Error)/(dt/1e9) since last call
dt – Change in time since last call in nanoseconds
- Returns:
PID command
-
double compute_command(double error, double error_dot, const rcl_duration_value_t &dt_ns)
Set the PID error and compute the PID command with nonuniform time step size. This also allows the user to pass in a precomputed derivative error.
- Parameters:
error – Error since last call (error = target - state)
error_dot – d(Error)/dt_ns since last call
dt_ns – Change in time since last call, measured in nanoseconds.
- Returns:
PID command
-
double compute_command(double error, double error_dot, const rclcpp::Duration &dt)
Set the PID error and compute the PID command with nonuniform time step size. This also allows the user to pass in a precomputed derivative error.
- Parameters:
error – Error since last call (error = target - state)
error_dot – d(Error)/dt since last call
dt – Change in time since last call
- Returns:
PID command
-
double compute_command(double error, double error_dot, const std::chrono::nanoseconds &dt_ns)
Set the PID error and compute the PID command with nonuniform time step size. This also allows the user to pass in a precomputed derivative error.
- Parameters:
error – Error since last call (error = target - state)
error_dot – d(Error)/(dt_ns/1e9) since last call
dt_ns – Change in time since last call, measured in nanoseconds.
- Returns:
PID command
-
void set_current_cmd(double cmd)
Set current command for this PID controller.
-
void setCurrentCmd(double cmd)
Set current command for this PID controller.
-
double get_current_cmd()
Return current command for this PID controller.
-
double getCurrentCmd()
Return current command for this PID controller.
-
double getDerivativeError()
Return derivative error.
-
void get_current_pid_errors(double &pe, double &ie, double &de)
Return PID error terms for the controller.
- Parameters:
pe – The proportional error.
ie – The weighted integral error.
de – The derivative error.
-
void getCurrentPIDErrors(double &pe, double &ie, double &de)
Return PID error terms for the controller.
- Parameters:
pe – The proportional error.
ie – The integral error.
de – The derivative error.
Protected Attributes
-
Gains gains_{0.0, 0.0, 0.0, std::numeric_limits<double>::infinity(), -std::numeric_limits<double>::infinity(), AntiWindupStrategy()}
-
double p_error_last_ = 0
-
double p_error_ = 0
Save state for derivative state calculation.
-
double d_error_ = 0
Error.
-
double i_term_ = 0
Derivative of error.
-
double cmd_ = 0
Integrator state.
-
double cmd_unsat_ = 0
Command to send.
-
struct Gains
Store gains in a struct to allow easier realtime box usage.
Public Functions
-
inline Gains(double p, double i, double d, double i_max, double i_min)
Optional constructor for passing in values without antiwindup and saturation.
- Parameters:
p – The proportional gain.
i – The integral gain.
d – The derivative gain.
i_max – Upper integral clamp.
i_min – Lower integral clamp.
-
inline Gains(double p, double i, double d, double i_max, double i_min, bool antiwindup)
Optional constructor for passing in values without saturation.
- Parameters:
p – The proportional gain.
i – The integral gain.
d – The derivative gain.
i_max – Upper integral clamp.
i_min – Lower integral clamp.
antiwindup – Anti-windup functionality. When set to true, limits the integral error to prevent windup; otherwise, constrains the integral contribution to the control output. i_max and i_min are applied in both scenarios.
-
inline Gains(double p, double i, double d, double u_max, double u_min, const AntiWindupStrategy &antiwindup_strat)
Constructor for passing in values.
- Parameters:
p – The proportional gain.
i – The integral gain.
d – The derivative gain.
u_max – Upper output clamp.
u_min – Lower output clamp.
antiwindup_strat – Specifies the anti-windup strategy. Options: ‘back_calculation’, ‘conditional_integration’, or ‘none’. Note that the ‘back_calculation’ strategy use the tracking_time_constant parameter to tune the anti-windup behavior.
-
inline bool validate(std::string &error_msg) const
-
inline Gains()
-
inline void print() const
Public Members
-
double p_gain_ = 0.0
Proportional gain.
-
double i_gain_ = 0.0
Integral gain.
-
double d_gain_ = 0.0
Derivative gain.
-
double i_max_ = 0.0
Maximum allowable integral term.
-
double i_min_ = 0.0
Minimum allowable integral term.
-
double u_max_ = std::numeric_limits<double>::infinity()
Maximum allowable output.
-
double u_min_ = -std::numeric_limits<double>::infinity()
Minimum allowable output.
-
bool antiwindup_ = false
Anti-windup.
-
AntiWindupStrategy antiwindup_strat_
Anti-windup strategy.
-
inline Gains(double p, double i, double d, double i_max, double i_min)