![]() |
ros2_control - rolling
|
Generic Proportional–Integral–Derivative (PID) controller. More...
#include <pid.hpp>

Classes | |
| struct | Gains |
| Store gains in a struct to allow easier realtime box usage. More... | |
Public Member Functions | |
| Pid (double p=0.0, double i=0.0, double d=0.0, double u_max=std::numeric_limits< double >::infinity(), double u_min=-std::numeric_limits< double >::infinity(), const AntiWindupStrategy &antiwindup_strat=AntiWindupStrategy()) | |
| Constructor, initialize Pid-gains and term limits. | |
| Pid (const Pid &source) | |
| Copy constructor required for preventing mutexes from being copied. | |
| ~Pid () | |
| Destructor of Pid class. | |
| bool | initialize (double p, double i, double d, double u_max, double u_min, const AntiWindupStrategy &antiwindup_strat) |
| Initialize Pid-gains and term limits. | |
| void | reset () |
| Reset the state of this PID controller. | |
| void | reset (bool save_i_term) |
| Reset the state of this PID controller. | |
| void | clear_saved_iterm () |
| Clear the saved integrator output of this controller. | |
| 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). | |
| Gains | get_gains () |
| Get PID gains for the controller. | |
| Gains | get_gains_rt () |
| Get PID gains for the controller. | |
| 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. | |
| bool | set_gains (const Gains &gains) |
| Set PID gains for the controller. | |
| 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. | |
| 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. | |
| 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. | |
| 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. | |
| 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. | |
| 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. | |
| 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. | |
| 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. | |
| void | set_current_cmd (double cmd) |
| Set current command for this PID controller. | |
| double | get_current_cmd () |
| Return current command for this PID controller. | |
| void | get_current_pid_errors (double &pe, double &ie, double &de) |
| Return PID error terms for the controller. | |
| Pid & | operator= (const Pid &source) |
| Custom assignment operator Does not initialize dynamic reconfigure for PID gains. | |
Protected Attributes | |
| Gains | gains_ |
| realtime_tools::RealtimeThreadSafeBox< Gains > | gains_box_ {gains_} |
| double | p_error_last_ = 0 |
| double | p_error_ = 0 |
| double | d_error_ = 0 |
| double | i_term_ = 0 |
| double | cmd_ = 0 |
| double | cmd_unsat_ = 0 |
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.
The standard PID equation is:
\[ command = p\_term + i\_term + d\_term \]
where:
| p | Proportional gain. Reacts to current error. |
| i | Integral gain. Accumulates past error to eliminate steady-state error. |
| d | Derivative gain. Predicts future error to reduce overshoot and settling time. |
| u_min | Minimum bound for the controller output. |
| u_max | Maximum bound for the controller output. |
| tracking_time_constant | Tracking time constant for BACK_CALCULATION anti-windup. If zero, a default is chosen based on gains:
|
| antiwindup_strat | Anti-windup strategy:
|
Without anti-windup, clamping causes integral windup, leading to overshoot and sluggish recovery. This class provides two strategies:
\[ 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.\[ (command - command_{sat} = 0)\quad\lor\quad(error \times command \le 0) \]
Freezes integration when saturated and error drives further saturation.Initialize and compute at each control step:
| control_toolbox::Pid::Pid | ( | double | p = 0.0, |
| double | i = 0.0, |
||
| double | d = 0.0, |
||
| double | u_max = std::numeric_limits<double>::infinity(), |
||
| double | u_min = -std::numeric_limits<double>::infinity(), |
||
| const AntiWindupStrategy & | antiwindup_strat = AntiWindupStrategy() |
||
| ) |
Constructor, initialize Pid-gains and term limits.
| 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. |
| An | std::invalid_argument exception is thrown if u_min >= u_max. |
| control_toolbox::Pid::Pid | ( | const Pid & | source | ) |
Copy constructor required for preventing mutexes from being copied.
| source | - Pid to copy |
| double control_toolbox::Pid::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.
| error | Error since last call (error = target - state) |
| dt_s | Change in time since last call in seconds. |
| double control_toolbox::Pid::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.
| error | Error since last call (error = target - state) |
| dt_ns | Change in time since last call, measured in nanoseconds. |
| double control_toolbox::Pid::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.
| error | Error since last call (error = target - state) |
| dt | Change in time since last call |
| double control_toolbox::Pid::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.
| error | Error since last call (error = target - state) |
| dt_ns | Change in time since last call |
| double control_toolbox::Pid::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.
| 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 |
| double control_toolbox::Pid::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.
| 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. |
| double control_toolbox::Pid::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.
| error | Error since last call (error = target - state) |
| error_dot | d(Error)/dt since last call |
| dt | Change in time since last call |
| double control_toolbox::Pid::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.
| 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. |
| void control_toolbox::Pid::get_current_pid_errors | ( | double & | pe, |
| double & | ie, | ||
| double & | de | ||
| ) |
Return PID error terms for the controller.
| pe | The proportional error. |
| ie | The weighted integral error. |
| de | The derivative error. |
| Pid::Gains control_toolbox::Pid::get_gains | ( | ) |
Get PID gains for the controller.
| void control_toolbox::Pid::get_gains | ( | double & | p, |
| double & | i, | ||
| double & | d, | ||
| double & | u_max, | ||
| double & | u_min, | ||
| AntiWindupStrategy & | antiwindup_strat | ||
| ) |
Get PID gains for the controller (preferred).
| 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 |
Get PID gains for the controller.
| bool control_toolbox::Pid::initialize | ( | double | p, |
| double | i, | ||
| double | d, | ||
| double | u_max, | ||
| double | u_min, | ||
| const AntiWindupStrategy & | antiwindup_strat | ||
| ) |
Initialize Pid-gains and term limits.
| 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. |
| void control_toolbox::Pid::reset | ( | ) |
Reset the state of this PID controller.
| void control_toolbox::Pid::reset | ( | bool | save_i_term | ) |
Reset the state of this PID controller.
| save_i_term | boolean indicating if integral term is retained on reset() |
| bool control_toolbox::Pid::set_gains | ( | const Gains & | gains | ) |
Set PID gains for the controller.
| gains | A struct of the PID gain values. |
| bool control_toolbox::Pid::set_gains | ( | double | p, |
| double | i, | ||
| double | d, | ||
| double | u_max, | ||
| double | u_min, | ||
| const AntiWindupStrategy & | antiwindup_strat | ||
| ) |
Set PID gains for the controller.
| 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. |
|
protected |
Integrator state.
|
protected |
Command to send.
|
protected |
Error.
|
protected |
|
protected |
Derivative of error.
|
protected |
Save state for derivative state calculation.