From bcedf0f8a13ffa3cab155ea6732ac11383c39769 Mon Sep 17 00:00:00 2001
From: Randy Mackay <rmackay9@yahoo.com>
Date: Sat, 30 Mar 2013 09:20:29 +0900
Subject: [PATCH] Copter: bug fix for throttle after acro flip

Throttle was kept a min if user switched out of ACRO mode while inverted
---
 ArduCopter/Attitude.pde | 7 +++++--
 1 file changed, 5 insertions(+), 2 deletions(-)

diff --git a/ArduCopter/Attitude.pde b/ArduCopter/Attitude.pde
index 4258bc5a0..9896ab103 100644
--- a/ArduCopter/Attitude.pde
+++ b/ArduCopter/Attitude.pde
@@ -737,9 +737,12 @@ static int16_t get_angle_boost(int16_t throttle)
     int16_t throttle_out;
 
     temp = constrain(temp, .5, 1.0);
-    temp = constrain(9000-max(labs(roll_axis),labs(pitch_axis)), 0, 3000) / (3000 * temp);
+
+    // reduce throttle if we go inverted
+    temp = constrain(9000-max(labs(ahrs.roll_sensor),labs(ahrs.pitch_sensor)), 0, 3000) / (3000 * temp);
+
+    // apply scale and constrain throttle
     throttle_out = constrain((float)(throttle-g.throttle_min) * temp + g.throttle_min, g.throttle_min, 1000);
-    //Serial.printf("Thin:%4.2f  sincos:%4.2f  temp:%4.2f  roll_axis:%4.2f  Out:%4.2f   \n", 1.0*throttle, 1.0*cos_pitch_x * cos_roll_x, 1.0*temp, 1.0*roll_axis, 1.0*constrain((float)value * temp, 0, 1000));
 
     // to allow logging of angle boost
     angle_boost = throttle_out - throttle;
-- 
GitLab