Copter: minor rename of a circular limits variable

This commit is contained in:
Randy Mackay 2014-11-10 17:22:05 -08:00
parent a9205e1032
commit 83051c306d
1 changed files with 3 additions and 3 deletions

View File

@ -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; static int16_t _angle_max = 0;
// apply circular limit to pitch and roll inputs // 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) { if (total_in > ROLL_PITCH_INPUT_MAX) {
float ratio = (float)ROLL_PITCH_INPUT_MAX / total_out; float ratio = (float)ROLL_PITCH_INPUT_MAX / total_in;
roll_in *= ratio; roll_in *= ratio;
pitch_in *= ratio; pitch_in *= ratio;
} }