From ed099a73a3251de392ee0283c72c0b5aaaec8eca Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Mon, 10 Nov 2014 17:22:22 -0800 Subject: [PATCH] Copter: minor rename of ACRO circular limits variable --- ArduCopter/control_acro.pde | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/ArduCopter/control_acro.pde b/ArduCopter/control_acro.pde index 0fc37b97c7..e5903dd7e6 100644 --- a/ArduCopter/control_acro.pde +++ b/ArduCopter/control_acro.pde @@ -48,10 +48,10 @@ static void get_pilot_desired_angle_rates(int16_t roll_in, int16_t pitch_in, int Vector3f rate_ef_level, rate_bf_level, rate_bf_request; // 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; }