AC_AttitudeControl: ensure yaw gets a FLTD default

This commit is contained in:
Andy Piper 2024-02-19 18:12:53 +00:00 committed by Randy Mackay
parent f1821ce4fc
commit 3721b434e1
1 changed files with 1 additions and 1 deletions

View File

@ -137,7 +137,7 @@ protected:
.imax = AC_ATC_MULTI_RATE_YAW_IMAX,
.filt_T_hz = AC_ATC_MULTI_RATE_RP_FILT_HZ,
.filt_E_hz = AC_ATC_MULTI_RATE_YAW_FILT_HZ,
.filt_D_hz = 0.0f,
.filt_D_hz = AC_ATC_MULTI_RATE_RP_FILT_HZ,
.srmax = 0,
.srtau = 1.0
}