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
This commit is contained in:
Randy Mackay 2015-02-24 22:47:56 +09:00
parent ecefe78417
commit 0447f6216a

View File

@ -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