AP_Compass: fix calibrator update when step one fails

This commit is contained in:
Randy Mackay 2019-11-19 19:12:21 +09:00 committed by Andrew Tridgell
parent 80b4eaa87a
commit 537d91e7e1

View File

@ -203,8 +203,9 @@ void CompassCalibrator::update(bool &failure)
if (is_equal(_fitness, _initial_fitness) || isnan(_fitness)) { // if true, means that fitness is diverging instead of converging
set_status(COMPASS_CAL_FAILED);
failure = true;
}
} else {
set_status(COMPASS_CAL_RUNNING_STEP_TWO);
}
} else {
if (_fit_step == 0) {
calc_initial_offset();