From ccc806844300533b8471250106622db49aa2719d Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Mon, 18 Aug 2014 12:56:22 +0900 Subject: [PATCH] Copter: range check ACRO_EXPO to be no more than 1 --- ArduCopter/control_acro.pde | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/ArduCopter/control_acro.pde b/ArduCopter/control_acro.pde index 0b928adb42..c7975f5da8 100644 --- a/ArduCopter/control_acro.pde +++ b/ArduCopter/control_acro.pde @@ -59,6 +59,11 @@ static void get_pilot_desired_angle_rates(int16_t roll_in, int16_t pitch_in, int // expo variables float rp_in, rp_in3, rp_out; + // range check expo + if (g.acro_expo > 1.0f) { + g.acro_expo = 1.0f; + } + // roll expo rp_in = float(roll_in)/ROLL_PITCH_INPUT_MAX; rp_in3 = rp_in*rp_in*rp_in;