|
| 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.
|
|
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
- Parameters
-
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:
- \( \sqrt{d\_gain / i\_gain} \) if
d_gain ≠ 0
- \( p\_gain / i\_gain \) otherwise.
|
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 using tracking_time_constant .
- CONDITIONAL_INTEGRATION: only integrates when output is not saturated or error drives it away from saturation.
|
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 correcting i_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:
pid.initialize(6.0, 1.0, 2.0, 5.0, -5.0,
control_toolbox::AntiWindupStrategy::BACK_CALCULATION);
rclcpp::Time
last = get_clock()->now();
rclcpp::Time
now = get_clock()->now();
}