51 AC_HELI_PID::AC_HELI_PID(
float initial_p,
float initial_i,
float initial_d,
float initial_imax,
float initial_filt_hz,
float dt,
float initial_ff) :
52 AC_PID(initial_p, initial_i, initial_d, initial_imax, initial_filt_hz, dt, initial_ff)
float _last_requested_rate
#define AP_GROUPINFO(name, idx, clazz, element, def)
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.
Helicopter Specific Rate PID algorithm, with EEPROM-backed storage of constants.
bool is_zero(const T fVal1)
#define AC_PID_FILT_HZ_DEFAULT
Copter PID control class.
DataFlash_Class::PID_Info _pid_info