AC_PID is ArduPilot’s general-purpose PID controller, used throughout the flight control stack — most visibly in the attitude rate loops that stabilize roll, pitch, and yaw. It combines a classical P+I+D structure with several practical additions: low-pass filters on the target, error, and derivative signals; an integrator clamp (IMAX) for anti-windup; a slew rate limiter (SMAX) on the output; feed-forward and derivative feed-forward terms; and optional notch filters for vibration rejection. Gains are EEPROM-backed viaDocumentation Index
Fetch the complete documentation index at: https://mintlify.com/Ardupilot/ardupilot/llms.txt
Use this file to discover all available pages before exploring further.
AP_Param, so they survive power cycles and can be tuned in flight.
PID variants in the library
AC_PID
Full-featured controller with target filter (
filt_T_hz), error filter (filt_E_hz), derivative filter (filt_D_hz), feed-forward (kFF), derivative feed-forward (kDFF), slew rate limiter (SMAX), and optional notch filters. Used for attitude rate loops.AC_PID_Basic
Lightweight variant without target filtering, slew limiting, or notch filters. Exposes only error and derivative filters. Used where RAM and flash budget are tight or where those features are not needed.
AC_P
Proportional-only controller. A single
_kp parameter and a get_p(error) method. Used for the outer angle loops in AC_AttitudeControl (_p_angle_roll, _p_angle_pitch, _p_angle_yaw).Two additional 2D variants exist:
AC_PID_2D and AC_PI_2D. These accept 2-axis error vectors and share integrator state across axes, which is useful for position controllers.Key methods — AC_PID
update_all()
update_all()
The primary update function. Accepts the target setpoint and current measurement, computes the filtered error, updates the derivative and integrator, and returns the full PID output. If
limit is true, the integrator is held (anti-windup: it can shrink but not grow). The optional pd_scale and i_scale arguments allow per-loop gain scaling without modifying the stored parameters.update_error()
update_error()
Simplified interface that takes only an error value (target is assumed zero). Kept for legacy compatibility; new code should prefer
update_all().get_p() / get_i() / get_d() / get_ff()
get_p() / get_i() / get_d() / get_ff()
Return the individual contribution of each term from the most recent
update_all() call. Useful for logging and for manual output blending.reset_I()
reset_I()
Zeroes the integrator immediately. Called on mode transitions, arming, and whenever accumulated I-term wind-up could produce an unwanted transient on re-engagement.
reset_filter()
reset_filter()
Flags the input filter for reset so that on the next
update_all() call the filter state is re-seeded from the current input, avoiding a derivative spike from a sudden change in the target.relax_integrator()
relax_integrator()
Gradually moves the integrator toward a desired value using a first-order time constant. Used during mode transitions to smoothly bleed off accumulated I-term rather than zeroing it abruptly.
set_integrator()
set_integrator()
Directly sets the integrator value, clamped to ±IMAX. Also flags the I-term as externally set so
update_i() will respect it.set_notch_sample_rate()
set_notch_sample_rate()
Attaches optional notch filters to the target and error signals. The filters are configured through the
AP_Filter parameter system and dynamically allocated. Called when the rate controller sample rate changes.save_gains() / load_gains()
save_gains() / load_gains()
Writes current gain values to EEPROM (used by AutoTune to persist tuned gains) or reads them back.
Parameter structure
EachAC_PID instance exposes the following EEPROM-backed parameters. The prefix is set by the parent class’s AP_GROUPINFO table (e.g., ATC_RAT_RLL_P for the roll rate PID).
| Field | AP_Float member | Description |
|---|---|---|
P | _kp | Proportional gain |
I | _ki | Integral gain |
D | _kd | Derivative gain |
FF | _kff | Feed-forward (scales the target directly) |
IMAX | _kimax | Integrator clamp — maximum absolute integrator value |
PDMX | _kpdmax | Maximum combined P+D output |
FLTT | _filt_T_hz | Target low-pass filter cutoff (Hz); 0 = disabled |
FLTE | _filt_E_hz | Error low-pass filter cutoff (Hz); 0 = disabled |
FLTD | _filt_D_hz | Derivative low-pass filter cutoff (Hz); default 20 Hz |
SMAX | _slew_rate_max | Output slew rate limit (units/s); 0 = disabled |
DFF | _kdff | Derivative feed-forward (scales target rate) |
Anti-windup (IMAX)
The integrator is clamped to±_kimax by update_i(). When the output is saturated (i.e., the vehicle is physically unable to follow the command), the limit = true flag passed to update_all() puts the integrator into hold-only mode: it can decrease toward zero if the sign of the error allows, but it cannot increase further. This prevents the classic integrator windup that would cause overshoot when the saturation clears.
D-term filtering
The derivative is computed on the filtered error (or filtered target for target-derivative schemes). By default the D-term filter is set to 20 Hz (AC_PID_DFILT_HZ_DEFAULT) to suppress high-frequency noise from gyros. Raising this cutoff increases derivative responsiveness but makes the D-term susceptible to vibration. Lowering it reduces noise but introduces phase lag.
Slew rate limiting
When_slew_rate_max is non-zero, the controller’s total output is passed through a SlewLimiter that caps the rate of change (in output units per second). This limits the mechanical shock delivered to ESCs and motors on abrupt setpoint changes. get_slew_rate() returns the current measured slew rate from the limiter, which AutoTune uses to detect oscillation.
Instantiating AC_PID
Using AC_PID in a rate control loop
ACCEL-based PID limiting for copter rate loops
AC_AttitudeControl_Multi computes an acceleration-based PD output limit (ATC_RAT_RLL_PDMX, ATC_RAT_PIT_PDMX) derived from the vehicle’s configured acceleration limits. This caps the P and D contributions to prevent over-driving the motors during large angular rate errors, even before the IMAX limit is reached. The scaling is applied via the pd_scale argument to update_all().
Using AC_P for angle loops
AC_P is a minimal proportional-only controller with a single stored gain:
AC_AttitudeControl use the square-root controller formulation when _use_sqrt_controller is true, which provides deceleration proportional to the square root of the remaining angle error — giving faster response at large angles and smooth stop behaviour near the target.
Source location
libraries/AC_PID/AC_PID.h — full-featured PID controllerlibraries/AC_PID/AC_PID_Basic.h — lightweight PID without target filtering or slew limitinglibraries/AC_PID/AC_P.h — proportional-only controllerlibraries/AC_PID/AC_PID_2D.h — 2-axis PID for position controllers