From 83051c306da70543a7a76a1fb20099493751d6d7 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Mon, 10 Nov 2014 17:22:05 -0800 Subject: [PATCH] Copter: minor rename of a circular limits variable --- ArduCopter/Attitude.pde | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/ArduCopter/Attitude.pde b/ArduCopter/Attitude.pde index 3755c47a78..91fb26b128 100644 --- a/ArduCopter/Attitude.pde +++ b/ArduCopter/Attitude.pde @@ -15,10 +15,10 @@ static void get_pilot_desired_lean_angles(int16_t roll_in, int16_t pitch_in, int static int16_t _angle_max = 0; // apply circular limit to pitch and roll inputs - float total_out = pythagorous2((float)pitch_in, (float)roll_in); + float total_in = pythagorous2((float)pitch_in, (float)roll_in); - if (total_out > ROLL_PITCH_INPUT_MAX) { - float ratio = (float)ROLL_PITCH_INPUT_MAX / total_out; + if (total_in > ROLL_PITCH_INPUT_MAX) { + float ratio = (float)ROLL_PITCH_INPUT_MAX / total_in; roll_in *= ratio; pitch_in *= ratio; }