12 #define AC_PID_LEAK_MIN 0.1 // Default I-term Leak Minimum 20 AC_HELI_PID(
float initial_p,
float initial_i,
float initial_d,
float initial_imax,
float initial_filt_hz,
float dt,
float initial_ff);
float _last_requested_rate
Generic PID algorithm, with EEPROM-backed storage of constants.
float get_leaky_i(float leak_rate)
get_leaky_i - replacement for get_i but output is leaded at leak_rate
static const struct AP_Param::GroupInfo var_info[]
AC_HELI_PID(float initial_p, float initial_i, float initial_d, float initial_imax, float initial_filt_hz, float dt, float initial_ff)
Constructor for PID.
A system for managing and storing variables that are of general interest to the system.
Common definitions and utility routines for the ArduPilot libraries.
Copter PID control class.