AC_AttControl_Multi: reduce rate gain defaults

This commit is contained in:
Randy Mackay 2016-02-17 19:58:44 +09:00
parent b30606bb22
commit ace58d114f

View File

@ -9,31 +9,31 @@
// default rate controller PID gains
#ifndef AC_ATC_MULTI_RATE_RP_P
# define AC_ATC_MULTI_RATE_RP_P 0.150f
# define AC_ATC_MULTI_RATE_RP_P 0.135f
#endif
#ifndef AC_ATC_MULTI_RATE_RP_I
# define AC_ATC_MULTI_RATE_RP_I 0.100f
# define AC_ATC_MULTI_RATE_RP_I 0.090f
#endif
#ifndef AC_ATC_MULTI_RATE_RP_D
# define AC_ATC_MULTI_RATE_RP_D 0.004f
# define AC_ATC_MULTI_RATE_RP_D 0.0036f
#endif
#ifndef AC_ATC_MULTI_RATE_RP_IMAX
# define AC_ATC_MULTI_RATE_RP_IMAX 2000.0f
# define AC_ATC_MULTI_RATE_RP_IMAX 0.444f
#endif
#ifndef AC_ATC_MULTI_RATE_RP_FILT_HZ
# define AC_ATC_MULTI_RATE_RP_FILT_HZ 20.0f
#endif
#ifndef AC_ATC_MULTI_RATE_YAW_P
# define AC_ATC_MULTI_RATE_YAW_P 0.200f
# define AC_ATC_MULTI_RATE_YAW_P 0.180f
#endif
#ifndef AC_ATC_MULTI_RATE_YAW_I
# define AC_ATC_MULTI_RATE_YAW_I 0.020f
# define AC_ATC_MULTI_RATE_YAW_I 0.018f
#endif
#ifndef AC_ATC_MULTI_RATE_YAW_D
# define AC_ATC_MULTI_RATE_YAW_D 0.0f
#endif
#ifndef AC_ATC_MULTI_RATE_YAW_IMAX
# define AC_ATC_MULTI_RATE_YAW_IMAX 1000.0f
# define AC_ATC_MULTI_RATE_YAW_IMAX 0.222f
#endif
#ifndef AC_ATC_MULTI_RATE_YAW_FILT_HZ
# define AC_ATC_MULTI_RATE_YAW_FILT_HZ 5.0f