mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
AC_AttitudeControl: ensure yaw gets a FLTD default
This commit is contained in:
parent
f1821ce4fc
commit
3721b434e1
@ -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
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user