Skip to main content

Documentation 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.

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 via 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

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.
float update_all(
    float target,
    float measurement,
    float dt,
    bool  limit    = false,
    float pd_scale = 1.0f,
    float i_scale  = 1.0f);
Simplified interface that takes only an error value (target is assumed zero). Kept for legacy compatibility; new code should prefer update_all().
float update_error(float error, float dt, bool limit = false);
Return the individual contribution of each term from the most recent update_all() call. Useful for logging and for manual output blending.
float get_p()  const;
float get_i()  const;
float get_d()  const;
float get_ff() const;   // target × kFF
float get_ff_component() const;   // kFF contribution only
float get_dff_component() const;  // kDFF contribution only
Zeroes the integrator immediately. Called on mode transitions, arming, and whenever accumulated I-term wind-up could produce an unwanted transient on re-engagement.
void reset_I();
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.
void reset_filter();
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.
void relax_integrator(float integrator, float dt, float time_constant);
Directly sets the integrator value, clamped to ±IMAX. Also flags the I-term as externally set so update_i() will respect it.
void set_integrator(float i);
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.
void set_notch_sample_rate(float sample_rate);
Writes current gain values to EEPROM (used by AutoTune to persist tuned gains) or reads them back.
void save_gains();
void load_gains();

Parameter structure

Each AC_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).
FieldAP_Float memberDescription
P_kpProportional gain
I_kiIntegral gain
D_kdDerivative gain
FF_kffFeed-forward (scales the target directly)
IMAX_kimaxIntegrator clamp — maximum absolute integrator value
PDMX_kpdmaxMaximum combined P+D output
FLTT_filt_T_hzTarget low-pass filter cutoff (Hz); 0 = disabled
FLTE_filt_E_hzError low-pass filter cutoff (Hz); 0 = disabled
FLTD_filt_D_hzDerivative low-pass filter cutoff (Hz); default 20 Hz
SMAX_slew_rate_maxOutput slew rate limit (units/s); 0 = disabled
DFF_kdffDerivative feed-forward (scales target rate)
Accessor methods follow a consistent pattern:
AC_PID pid(0.135f, 0.135f, 0.0036f, 0.0f, 0.5f, 20.0f, 0.0f, 20.0f);

pid.kP().set(0.180f);           // set P gain (not saved to EEPROM)
pid.set_imax(0.5f);             // set IMAX
pid.filt_D_hz().set(20.0f);     // set derivative filter
pid.save_gains();               // persist all gains to EEPROM

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.
// Rate controller pattern — pass motor saturation flag:
bool motors_saturated = motors.is_throttle_saturated();
float output = rate_pid.update_all(target_rate, actual_rate, dt, motors_saturated);

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.
On vehicles with poor vibration isolation, start with the D-term filter at 10–15 Hz and increase it only after the frame is balanced and props are in good condition.

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.
float current_slew = pid.get_slew_rate();

Instantiating AC_PID

#include <AC_PID/AC_PID.h>

// Constructor: p, i, d, ff, imax, filt_T_hz, filt_E_hz, filt_D_hz
AC_PID my_pid(
    0.135f,   // kP
    0.135f,   // kI
    0.0036f,  // kD
    0.0f,     // kFF
    0.5f,     // IMAX
    20.0f,    // target filter (Hz)
    0.0f,     // error filter (Hz) — disabled
    20.0f     // derivative filter (Hz)
);

// Or using the Defaults struct (preferred for readability):
AC_PID my_pid{AC_PID::Defaults{
    .p         = 0.135f,
    .i         = 0.135f,
    .d         = 0.0036f,
    .ff        = 0.0f,
    .imax      = 0.5f,
    .filt_T_hz = 20.0f,
    .filt_E_hz = 0.0f,
    .filt_D_hz = 20.0f,
    .srmax     = 0.0f,
    .srtau     = 1.0f,
}};

Using AC_PID in a rate control loop

// Typical 400 Hz rate controller loop:
void MyRateController::update(float dt)
{
    const float target_rate = attitude_controller.rate_bf_targets().x;
    const float actual_rate = ahrs.get_gyro().x;
    const bool  limit       = motors.is_throttle_saturated();

    float output = _pid_roll.update_all(target_rate, actual_rate, dt, limit);

    // Log individual terms:
    // _pid_roll.get_p(), get_i(), get_d(), get_ff()

    motors.set_roll(output);
}

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:
#include <AC_PID/AC_P.h>

AC_P angle_p(4.5f);                 // default kP = 4.5

float rate_target = angle_p.get_p(angle_error_rad);
The angle P controllers in 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 controller
libraries/AC_PID/AC_PID_Basic.h — lightweight PID without target filtering or slew limiting
libraries/AC_PID/AC_P.h — proportional-only controller
libraries/AC_PID/AC_PID_2D.h — 2-axis PID for position controllers

Build docs developers (and LLMs) love