pub struct Pid { /* private fields */ }
Expand description
PID controller.
The PID controller is one of the most widely used feedback control algorithms in industrial control systems, robotics, and process control. It computes a control signal based on three terms: proportional, integral, and derivative.
§Components
-
The proportional term produces an output proportional to the current error, multiplied by the gain constant
kp
. This provides the main control action: larger errors result in larger corrective responses and vice versa. -
The integral term sums the error over time, multiplied by the gain constant
ki
. This term eliminates steady-state error by ensuring that even small errors will eventually accumulate a large enough response to reach the setpoint. Without integral action, a system might stabilize with a small, persistent error if the control signal becomes too small to overcome system friction, gravity, or other external factors on the system. For example, a motor might need some minimum voltage to start moving, or a drone might need extra thrust to hover against gravity. The integral term accumulates over time to provide this additional correction. -
The derivative term measures the error’s change over time, multiplied by the gain constant
kd
. This provides a damping effect that reduces overshoot and oscillation by counteracting rapid changes in error. The derivative term helps anticipate and smooth out the system’s response, preventing sudden changes resulting from large proportional or integral gains.
§Tuning
Tuning a PID controller requires adjusting kp
, ki
, and kd
to allow the system to reach a setpoint
in a reasonable amount of time without oscillations (rapid, unpredictable changes in output).
Tuning methods are typically dependent on the application that the PID controller is used in, but a common method is as follows:
-
Start with all gains at zero (
kp = 0.0
,ki = 0.0
,kd = 0.0
). -
Tune proportional gain first:
- Gradually increase
kp
until the system starts to oscillate around the setpoint. - Oscillation occurs when the system reaches and overshoots the setpoint, then repeatedly overadjusts itself around the setpoint, resulting in a “back-and-fourth” motion around the setpoint.
- Gradually increase
-
Tune the derivative gain:
- Start with a very small
kd
gain (0.05 ×kp
or less is a safe bet to start with). - Gradually increase by small increments until oscillations from the proportional term stop occurring.
- Start with a very small
-
Add integral gain if necessary:
- Integral gain is only necessary if your controller’s proportional and derivative terms become small enough to where they can no longer overcome some external factor (such as friction) of the system, resulting in what’s called steady-state error.
- Start with a very small
ki
gain (such as 0.01 ×kp
). - Increase
ki
slowly until steady-state errors are eliminated within an acceptable time. - If oscillation occurs, reduce both
ki
andkp
slightly.
Common signs of poor tuning:
- Slow response:
kp
is too low. - Excessive overshoot:
kd
is too low orki
is too high. - Oscillation:
kp
is too high orkd
is too low. - Noisy, unpredictable response:
kd
is too high.
§Integral Windup (and Mitigations)
In some scenarios, a PID controller may be prone to integral windup, where a controlled system reaches a saturation point preventing the error from decreasing. In this case, integral will rapidly accumulate, causing large and unpredictable control signals. This specific implementation provides two mitigations for integral windup:
- Sign-based reset: When the sign of error changes (in other words, when the controller has crossed/overshot its target), the integral value is reset to prevent overshoot of the target.
- Integration bounds: An optional
integration_range
value can be passed to the controller, which defines a range of error where integration will occur. When|error| > integration_range
, no integration will occur if used.
Implementations§
Source§impl Pid
impl Pid
Sourcepub const fn new(
kp: f64,
ki: f64,
kd: f64,
integration_range: Option<f64>,
) -> Self
pub const fn new( kp: f64, ki: f64, kd: f64, integration_range: Option<f64>, ) -> Self
Construct a new PID controller from gain constants and an optional integration range.
Sourcepub const fn gains(&self) -> (f64, f64, f64)
pub const fn gains(&self) -> (f64, f64, f64)
Get the current PID gains as a tuple (kp
, ki
, kd
).
Sourcepub const fn integration_range(&self) -> Option<f64>
pub const fn integration_range(&self) -> Option<f64>
Returns the controller’s integration range.
Integration range is the minimum error range required to start integrating error. This is optionally applied to the controller as a mitigation for integral windup.
Sourcepub const fn output_limit(&self) -> Option<f64>
pub const fn output_limit(&self) -> Option<f64>
Returns the controller’s output limit, or None
if there is no
limit applied.
Sourcepub const fn set_gains(&mut self, kp: f64, ki: f64, kd: f64)
pub const fn set_gains(&mut self, kp: f64, ki: f64, kd: f64)
Sets the PID gains to provided values.
Sourcepub const fn set_integration_range(&mut self, range: Option<f64>)
pub const fn set_integration_range(&mut self, range: Option<f64>)
Sets the controller’s integration range.
Integration range is the minimum error range required to start integrating error. This is optionally applied to the controller as a mitigation for integral windup.
Sourcepub const fn set_output_limit(&mut self, range: Option<f64>)
pub const fn set_output_limit(&mut self, range: Option<f64>)
Sets the controller’s output limit.
This sets a maximum range for the controller’s output signal. It will effectively limit how fast the controller is able to drive the system, which may be desirable in some cases (e.g. limiting the maximum speed of a robot’s motion).