From bc631b656ebdf70ece4d18a317487812bcb7e67f Mon Sep 17 00:00:00 2001 From: Jason Short Date: Fri, 17 Aug 2012 23:03:59 -0700 Subject: [PATCH] ACM: Added a more sane limit to Angle boost --- ArduCopter/Attitude.pde | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ArduCopter/Attitude.pde b/ArduCopter/Attitude.pde index bb30341f5a..bf8433e706 100644 --- a/ArduCopter/Attitude.pde +++ b/ArduCopter/Attitude.pde @@ -504,7 +504,7 @@ static long static int16_t get_angle_boost(int16_t value) { float temp = cos_pitch_x * cos_roll_x; - temp = constrain(temp, .5, 1.0); + temp = constrain(temp, .75, 1.0); return ((float)(g.throttle_cruise + 80) / temp) - (g.throttle_cruise + 80); }