AC_PID Detailed Reference¶
Header¶
File: libraries/AC_PID/AC_PID.h
#include <AC_PID.h>
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¶
-
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)¶
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:
:doxygen:`AC_PID_2D` - 2D PID controller
:doxygen:`AC_PI` - PI controller (no derivative)
:doxygen:`AC_P` - P controller only
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)
Reset Methods¶
Gain Setting Methods¶
-
void AC_PID::set_imax(float v)¶
Set integral limit (maximum absolute integral term).
- Parameters:
v – Maximum integral value
-
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
Gain Getting Methods¶
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
-
void AC_PID::set_target_rate(float target)¶
Set target rate directly.
- Parameters:
target – Target value
Persistence¶
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