APM-nav: set NAV I value defaults to 0.1

a small I value is good on most planes, so I think this is a better
default than 0. Thanks to Chris for asking about this.
This commit is contained in:
Andrew Tridgell 2012-04-30 12:25:57 +10:00
parent 3d2c00bb15
commit 8fab91e063
1 changed files with 3 additions and 3 deletions

View File

@ -624,7 +624,7 @@
# define NAV_ROLL_P 0.7 # define NAV_ROLL_P 0.7
#endif #endif
#ifndef NAV_ROLL_I #ifndef NAV_ROLL_I
# define NAV_ROLL_I 0.0 # define NAV_ROLL_I 0.1
#endif #endif
#ifndef NAV_ROLL_D #ifndef NAV_ROLL_D
# define NAV_ROLL_D 0.02 # define NAV_ROLL_D 0.02
@ -637,7 +637,7 @@
# define NAV_PITCH_ASP_P 0.65 # define NAV_PITCH_ASP_P 0.65
#endif #endif
#ifndef NAV_PITCH_ASP_I #ifndef NAV_PITCH_ASP_I
# define NAV_PITCH_ASP_I 0.0 # define NAV_PITCH_ASP_I 0.1
#endif #endif
#ifndef NAV_PITCH_ASP_D #ifndef NAV_PITCH_ASP_D
# define NAV_PITCH_ASP_D 0.0 # define NAV_PITCH_ASP_D 0.0
@ -650,7 +650,7 @@
# define NAV_PITCH_ALT_P 0.65 # define NAV_PITCH_ALT_P 0.65
#endif #endif
#ifndef NAV_PITCH_ALT_I #ifndef NAV_PITCH_ALT_I
# define NAV_PITCH_ALT_I 0.0 # define NAV_PITCH_ALT_I 0.1
#endif #endif
#ifndef NAV_PITCH_ALT_D #ifndef NAV_PITCH_ALT_D
# define NAV_PITCH_ALT_D 0.0 # define NAV_PITCH_ALT_D 0.0