mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-11 17:13:56 -03:00
AP_Compass: fix calibrator update when step one fails
This commit is contained in:
parent
89fa324a2b
commit
f97cfd1065
@ -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);
|
||||
}
|
||||
set_status(COMPASS_CAL_RUNNING_STEP_TWO);
|
||||
} else {
|
||||
if (_fit_step == 0) {
|
||||
calc_initial_offset();
|
||||
|
Loading…
Reference in New Issue
Block a user