From daa32f9b627f56c4856a53ccb34416fffa0c1749 Mon Sep 17 00:00:00 2001
From: Andrew Tridgell <tridge@samba.org>
Date: Mon, 25 Aug 2014 08:20:37 +1000
Subject: [PATCH] Plane: reset steering integrator on mode change and when not
 moving

this prevents an old integrator from causing problems on takeoff
---
 ArduPlane/Attitude.pde | 5 +++++
 ArduPlane/system.pde   | 1 +
 2 files changed, 6 insertions(+)

diff --git a/ArduPlane/Attitude.pde b/ArduPlane/Attitude.pde
index 2f16e57cb..af70bef98 100644
--- a/ArduPlane/Attitude.pde
+++ b/ArduPlane/Attitude.pde
@@ -364,6 +364,11 @@ static void stabilize()
         rollController.reset_I();
         pitchController.reset_I();
         yawController.reset_I();
+
+        // if moving very slowly also zero the steering integrator
+        if (gps.ground_speed() < 1) {
+            steerController.reset_I();            
+        }
     }
 }
 
diff --git a/ArduPlane/system.pde b/ArduPlane/system.pde
index 537faa230..48f4a20fa 100644
--- a/ArduPlane/system.pde
+++ b/ArduPlane/system.pde
@@ -390,6 +390,7 @@ static void set_mode(enum FlightMode mode)
     rollController.reset_I();
     pitchController.reset_I();
     yawController.reset_I();    
+    steerController.reset_I();    
 }
 
 // exit_mode - perform any cleanup required when leaving a flight mode
-- 
GitLab