From 0447f6216a4157fe0445343ae19d3976fa7941f5 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Tue, 24 Feb 2015 22:47:56 +0900 Subject: [PATCH] Copter: get_pilot_desired_lean_angles uses angle_max of at least 10deg Removes the unlikely event of a divide by zero if ANGLE_MAX is set to zero and sticks were in middle --- ArduCopter/Attitude.pde | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ArduCopter/Attitude.pde b/ArduCopter/Attitude.pde index 1dc0385cb9..5eecc8c206 100644 --- a/ArduCopter/Attitude.pde +++ b/ArduCopter/Attitude.pde @@ -11,7 +11,7 @@ float get_smoothing_gain() // returns desired angle in centi-degrees static void get_pilot_desired_lean_angles(float roll_in, float pitch_in, float &roll_out, float &pitch_out) { - float angle_max = constrain_float(aparm.angle_max,0,8000); + float angle_max = constrain_float(aparm.angle_max,1000,8000); float scaler = (float)angle_max/(float)ROLL_PITCH_INPUT_MAX; // scale roll_in, pitch_in to correct units