From 1017b0f6a34ae4973b7832cf5ece1cab4b0b93c2 Mon Sep 17 00:00:00 2001
From: Andrew Tridgell <tridge@samba.org>
Date: Mon, 30 Apr 2012 12:25:57 +1000
Subject: [PATCH] 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.
---
 ArduPlane/config.h | 6 +++---
 1 file changed, 3 insertions(+), 3 deletions(-)

diff --git a/ArduPlane/config.h b/ArduPlane/config.h
index 65a48cd7d..79bbc6947 100644
--- a/ArduPlane/config.h
+++ b/ArduPlane/config.h
@@ -624,7 +624,7 @@
 # define NAV_ROLL_P           0.7
 #endif
 #ifndef NAV_ROLL_I
-# define NAV_ROLL_I           0.0
+# define NAV_ROLL_I           0.1
 #endif
 #ifndef NAV_ROLL_D
 # define NAV_ROLL_D           0.02
@@ -637,7 +637,7 @@
 # define NAV_PITCH_ASP_P      0.65
 #endif
 #ifndef NAV_PITCH_ASP_I
-# define NAV_PITCH_ASP_I      0.0
+# define NAV_PITCH_ASP_I      0.1
 #endif
 #ifndef NAV_PITCH_ASP_D
 # define NAV_PITCH_ASP_D      0.0
@@ -650,7 +650,7 @@
 # define NAV_PITCH_ALT_P      0.65
 #endif
 #ifndef NAV_PITCH_ALT_I
-# define NAV_PITCH_ALT_I      0.0
+# define NAV_PITCH_ALT_I      0.1
 #endif
 #ifndef NAV_PITCH_ALT_D
 # define NAV_PITCH_ALT_D      0.0
-- 
GitLab