Browse Source

AC_AutoTune: fixed missing else statement

master
Andrew Tridgell 6 years ago
parent
commit
d6a23fd22a
  1. 3
      libraries/AC_AutoTune/AC_AutoTune.cpp

3
libraries/AC_AutoTune/AC_AutoTune.cpp

@ -1276,10 +1276,11 @@ void AC_AutoTune::twitching_abort_rate(float angle, float rate, float angle_max,
step_scaler *= 0.9f; step_scaler *= 0.9f;
// ignore result and start test again // ignore result and start test again
step = WAITING_FOR_LEVEL; step = WAITING_FOR_LEVEL;
} } else {
step = UPDATE_GAINS; step = UPDATE_GAINS;
} }
} }
}
// twitching_test_angle - twitching tests // twitching_test_angle - twitching tests
// update min and max and test for end conditions // update min and max and test for end conditions

Loading…
Cancel
Save