mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-02 14:08:45 -04:00
AP_Compass: fix calibrator update when step one fails
This commit is contained in:
parent
d9fde84ccb
commit
b87f42bc07
@ -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
|
if (is_equal(_fitness, _initial_fitness) || isnan(_fitness)) { // if true, means that fitness is diverging instead of converging
|
||||||
set_status(COMPASS_CAL_FAILED);
|
set_status(COMPASS_CAL_FAILED);
|
||||||
failure = true;
|
failure = true;
|
||||||
|
} else {
|
||||||
|
set_status(COMPASS_CAL_RUNNING_STEP_TWO);
|
||||||
}
|
}
|
||||||
set_status(COMPASS_CAL_RUNNING_STEP_TWO);
|
|
||||||
} else {
|
} else {
|
||||||
if (_fit_step == 0) {
|
if (_fit_step == 0) {
|
||||||
calc_initial_offset();
|
calc_initial_offset();
|
||||||
|
Loading…
Reference in New Issue
Block a user