From 5a3c7b2d35fc30a2a52d17546412bdd1ab2fa139 Mon Sep 17 00:00:00 2001
From: Randy Mackay <rmackay9@yahoo.com>
Date: Thu, 31 Jan 2013 16:30:03 +0900
Subject: [PATCH] Copter: use scaled throttle for accel-throttle's I term

Accel throttle's I term is taken from scaled manual throttle
---
 ArduCopter/ArduCopter.pde | 2 +-
 ArduCopter/Attitude.pde   | 4 ++--
 2 files changed, 3 insertions(+), 3 deletions(-)

diff --git a/ArduCopter/ArduCopter.pde b/ArduCopter/ArduCopter.pde
index 983e59ccf..63728fa74 100644
--- a/ArduCopter/ArduCopter.pde
+++ b/ArduCopter/ArduCopter.pde
@@ -1800,7 +1800,7 @@ bool set_throttle_mode( uint8_t new_throttle_mode )
             set_new_altitude(current_loc.alt);          // by default hold the current altitude
             if ( throttle_mode <= THROTTLE_MANUAL_TILT_COMPENSATED ) {      // reset the alt hold I terms if previous throttle mode was manual
                 reset_throttle_I();
-                set_accel_throttle_I_from_pilot_throttle();
+                set_accel_throttle_I_from_pilot_throttle(get_pilot_desired_throttle(g.rc_3.control_in));
             }
             throttle_initialised = true;
             break;
diff --git a/ArduCopter/Attitude.pde b/ArduCopter/Attitude.pde
index 4aa846e38..eb39a3b28 100644
--- a/ArduCopter/Attitude.pde
+++ b/ArduCopter/Attitude.pde
@@ -1196,10 +1196,10 @@ static void reset_throttle_I(void)
     g.pid_throttle_accel.reset_I();
 }
 
-static void set_accel_throttle_I_from_pilot_throttle(void)
+static void set_accel_throttle_I_from_pilot_throttle(int16_t pilot_throttle)
 {
     // shift difference between pilot's throttle and hover throttle into accelerometer I
-    g.pid_throttle_accel.set_integrator(g.rc_3.control_in-g.throttle_cruise);
+    g.pid_throttle_accel.set_integrator(pilot_throttle-g.throttle_cruise);
 }
 
 static void reset_stability_I(void)
-- 
GitLab