AC_PID Detailed Reference

Class Documentation

class AC_PID

Copter PID control class.

Subclassed by AC_HELI_PID

Public Functions

AC_PID(float initial_p, float initial_i, float initial_d, float initial_ff, float initial_imax, float initial_filt_T_hz, float initial_filt_E_hz, float initial_filt_D_hz, float initial_srmax = 0, float initial_srtau = 1.0, float initial_dff = 0)

Constructor for PID controller with EEPROM-backed gain. Parameters are initialized from defaults or EEPROM at runtime.

struct ac_pid_flags
struct Defaults

Detailed Description

AC_PID is a generic PID (Proportional-Integral-Derivative) controller implementation used throughout ArduPilot for rate control, position control, and many other control loops.

Key Features:

  • P (Proportional), I (Integral), D (Derivative) terms

  • FF (Feedforward) term for improved response

  • DFF (Derivative Feedforward) term

  • Configurable filter frequencies for each term

  • Integral windup protection

  • Slew rate limiting

  • PD limiting (proportional-derivative max output)

  • Notch filter support for derivative

Inheritance

This class does not inherit from any other class. It is a standalone controller class.

Related Classes:

Public Member Functions

Constructor

AC_PID::AC_PID(float initial_p, float initial_i, float initial_d, float initial_ff, float initial_imax, float initial_filt_T_hz, float initial_filt_E_hz, float initial_filt_D_hz, float initial_srmax, float initial_srtau, float initial_dff)

Constructor with all parameters.

Parameters:
  • initial_p – Initial proportional gain (P)

  • initial_i – Initial integral gain (I)

  • initial_d – Initial derivative gain (D)

  • initial_ff – Initial feedforward gain (FF)

  • initial_imax – Initial integral limit (imax)

  • initial_filt_T_hz – Initial derivative filter frequency (Hz)

  • initial_filt_E_hz – Initial error filter frequency (Hz)

  • initial_filt_D_hz – Initial derivative input filter frequency (Hz)

  • initial_srmax – Slew rate maximum

  • initial_srtau – Slew rate time constant

  • initial_dff – Initial derivative feedforward gain

Main Control Methods

float AC_PID::update_all(float target, float measurement, float dt, bool limit = false, float pd_scale = 1.0f, float i_scale = 1.0f)

Run full PID update combining P, I, D terms.

Parameters:
  • target – Target value (setpoint)

  • measurement – Measured value (feedback)

  • dt – Time delta since last update in seconds

  • limit – True if output is being limited

  • pd_scale – Scale factor for P and D terms

  • i_scale – Scale factor for I term

Returns:

Control output (sum of P + I + D + FF)

float AC_PID::update_error(float error, float dt, bool limit = false)

Run PID with error input (target - measurement).

Parameters:
  • error – Error (target - measurement)

  • dt – Time delta in seconds

  • limit – True if output is being limited

Returns:

Control output

Reset Methods

void AC_PID::reset_I()

Reset integral term to zero. Call when changing setpoints or entering new flight mode.

void AC_PID::reset_filter()

Reset all filter states to zero.

Gain Setting Methods

void AC_PID::set_kP(float v)

Set proportional gain.

Parameters:

v – Proportional gain value

void AC_PID::set_kI(float v)

Set integral gain.

Parameters:

v – Integral gain value

void AC_PID::set_kD(float v)

Set derivative gain.

Parameters:

v – Derivative gain value

void AC_PID::set_ff(float v)

Set feedforward gain.

Parameters:

v – Feedforward gain value

void AC_PID::set_imax(float v)

Set integral limit (maximum absolute integral term).

Parameters:

v – Maximum integral value

void AC_PID::set_pdmax(float v)

Set PD maximum limit.

Parameters:

v – Maximum P+D output

void AC_PID::set_filt_T_hz(float v)

Set derivative filter time constant.

Parameters:

v – Filter frequency in Hz

void AC_PID::set_filt_E_hz(float v)

Set error filter frequency.

Parameters:

v – Filter frequency in Hz

void AC_PID::set_filt_D_hz(float v)

Set derivative input filter frequency.

Parameters:

v – Filter frequency in Hz

void AC_PID::set_slew_limit(float v)

Set slew rate limit.

Parameters:

v – Slew rate limit

void AC_PID::set_kDff(float v)

Set derivative feedforward gain.

Parameters:

v – DFF gain value

Gain Getting Methods

float AC_PID::get_p() const

Get proportional term from last update.

Returns:

P term value

float AC_PID::get_i() const

Get integral term from last update.

Returns:

I term value

float AC_PID::get_d() const

Get derivative term from last update.

Returns:

D term value

float AC_PID::get_ff() const

Get feedforward term from last update.

Returns:

FF term value

float AC_PID::get_ff_component() const

Get feedforward component.

Returns:

FF component value

float AC_PID::get_dff_component() const

Get derivative feedforward component.

Returns:

DFF component value

float AC_PID::imax() const

Get integral limit.

Returns:

Maximum integral value

float AC_PID::pdmax() const

Get PD maximum limit.

Returns:

Maximum P+D value

Information & Diagnostics

const AP_PIDInfo &AC_PID::get_pid_info(void) const

Get PID information structure.

Returns:

PID info containing target, actual, error, P, I, D, FF, DFF values

float AC_PID::get_slew_rate(void) const

Get current slew rate.

Returns:

Current slew rate

void AC_PID::set_target_rate(float target)

Set target rate directly.

Parameters:

target – Target value

void AC_PID::set_actual_rate(float actual)

Set actual/measurement value directly.

Parameters:

actual – Actual value

void AC_PID::set_integrator(float i)

Set integrator to specific value.

Parameters:

i – Integrator value

Persistence

void AC_PID::load_gains()

Load PID gains from parameters.

void AC_PID::save_gains()

Save PID gains to parameters.

Usage Example

#include <AC_PID.h>

// Create PID controller
AC_PID pid(1.0f,   // P gain
           0.5f,   // I gain
           0.1f,   // D gain
           0.0f,   // FF gain
           1000.0f, // IMAX (integral limit)
           20.0f,   // derivative filter Hz
           2.0f,    // error filter Hz
           0.0f,    // derivative input filter Hz
           0.0f,    // slew rate max
           0.0f,    // slew rate tau
           0.0f);   // DFF

void setup() {
    // Optionally load saved gains
    pid.load_gains();
}

void loop() {
    // In control loop (e.g., 100Hz)
    float target = 100.0f;      // Target value
    float measurement = 80.0f;   // Current measured value
    float dt = 0.01f;           // 10ms timestep

    // Run PID controller
    float output = pid.update_all(target, measurement, dt);

    // Apply output to motors or actuators
    // motors->set_throttle(output);

    // Get individual components for debugging
    float p_term = pid.get_p();
    float i_term = pid.get_i();
    float d_term = pid.get_d();
    float ff_term = pid.get_ff();

    Serial.printf("PID: total=%.2f P=%.2f I=%.2f D=%.2f FF=%.2f\n",
                output, p_term, i_term, d_term, ff_term);

    // When changing modes or setpoints, reset integrator
    // pid.reset_I();
}

See Also

  • Control Libraries - Overview of control libraries

  • Control Libraries - AC_AttitudeControl (uses PID controllers internally)

  • AC_PID_2D - 2D PID variant

  • AC_PI - PI controller without derivative