From 8f86caa3ff618ed98a4f1457c03dc7c3587ee069 Mon Sep 17 00:00:00 2001 From: Jason Short Date: Sat, 21 Jan 2012 11:57:42 -0800 Subject: [PATCH] limiting the pitch throttle compensation --- ArduCopter/Attitude.pde | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/ArduCopter/Attitude.pde b/ArduCopter/Attitude.pde index d6efca9a10..e32ea0cd9d 100644 --- a/ArduCopter/Attitude.pde +++ b/ArduCopter/Attitude.pde @@ -321,9 +321,9 @@ static int get_angle_boost(int value) { float temp = cos_pitch_x * cos_roll_x; temp = 1.0 - constrain(temp, .5, 1.0); -// int16_t output = temp * value; -// return constrain(output, 0, 100); - return (int)(temp * value); + int16_t output = temp * value; + return constrain(output, 0, 100); +// return (int)(temp * value); } #define NUM_G_SAMPLES 40