Browse Source

AP_Compass: fix calibrator update when step one fails

zr-v5.1
Randy Mackay 5 years ago committed by Andrew Tridgell
parent
commit
f97cfd1065
  1. 3
      libraries/AP_Compass/CompassCalibrator.cpp

3
libraries/AP_Compass/CompassCalibrator.cpp

@ -203,8 +203,9 @@ void CompassCalibrator::update(bool &failure) @@ -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();

Loading…
Cancel
Save