mirror of https://github.com/ArduPilot/ardupilot
AC_AttControl: adjust default rate IMAX and Yaw Filt
Increase Roll, Pitch and Yaw IMAX from 0.444 or 0.222 to 0.5 Decrease Yaw Filter from 5hz to 2.5hz based on the results of autotunes on many vehicles which always seems to produce values between 2 and 3hz
This commit is contained in:
parent
b43f23561f
commit
406a7739a6
|
@ -17,7 +17,7 @@
|
||||||
# define AC_ATC_MULTI_RATE_RP_D 0.0036f
|
# define AC_ATC_MULTI_RATE_RP_D 0.0036f
|
||||||
#endif
|
#endif
|
||||||
#ifndef AC_ATC_MULTI_RATE_RP_IMAX
|
#ifndef AC_ATC_MULTI_RATE_RP_IMAX
|
||||||
# define AC_ATC_MULTI_RATE_RP_IMAX 0.444f
|
# define AC_ATC_MULTI_RATE_RP_IMAX 0.5f
|
||||||
#endif
|
#endif
|
||||||
#ifndef AC_ATC_MULTI_RATE_RP_FILT_HZ
|
#ifndef AC_ATC_MULTI_RATE_RP_FILT_HZ
|
||||||
# define AC_ATC_MULTI_RATE_RP_FILT_HZ 20.0f
|
# define AC_ATC_MULTI_RATE_RP_FILT_HZ 20.0f
|
||||||
|
@ -32,10 +32,10 @@
|
||||||
# define AC_ATC_MULTI_RATE_YAW_D 0.0f
|
# define AC_ATC_MULTI_RATE_YAW_D 0.0f
|
||||||
#endif
|
#endif
|
||||||
#ifndef AC_ATC_MULTI_RATE_YAW_IMAX
|
#ifndef AC_ATC_MULTI_RATE_YAW_IMAX
|
||||||
# define AC_ATC_MULTI_RATE_YAW_IMAX 0.222f
|
# define AC_ATC_MULTI_RATE_YAW_IMAX 0.5f
|
||||||
#endif
|
#endif
|
||||||
#ifndef AC_ATC_MULTI_RATE_YAW_FILT_HZ
|
#ifndef AC_ATC_MULTI_RATE_YAW_FILT_HZ
|
||||||
# define AC_ATC_MULTI_RATE_YAW_FILT_HZ 5.0f
|
# define AC_ATC_MULTI_RATE_YAW_FILT_HZ 2.5f
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue