AC_AutoTune: fixed missing else statement

This commit is contained in:
Andrew Tridgell 2018-12-22 10:40:31 +11:00
parent ce27eb5de1
commit d6a23fd22a

View File

@ -1276,8 +1276,9 @@ void AC_AutoTune::twitching_abort_rate(float angle, float rate, float angle_max,
step_scaler *= 0.9f;
// ignore result and start test again
step = WAITING_FOR_LEVEL;
} else {
step = UPDATE_GAINS;
}
step = UPDATE_GAINS;
}
}