Skip to content
Snippets Groups Projects
Commit 1017b0f6 authored by Andrew Tridgell's avatar Andrew Tridgell
Browse files

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.
parent 8f2904e6
No related branches found
No related tags found
No related merge requests found
...@@ -624,7 +624,7 @@ ...@@ -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 @@ ...@@ -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 @@ ...@@ -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
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment