diff --git a/libraries/AP_Compass/AP_Compass_Calibration.cpp b/libraries/AP_Compass/AP_Compass_Calibration.cpp index 67d51ab7c6..2578e8c101 100644 --- a/libraries/AP_Compass/AP_Compass_Calibration.cpp +++ b/libraries/AP_Compass/AP_Compass_Calibration.cpp @@ -336,7 +336,9 @@ bool Compass::is_calibrating() const case CompassCalibrator::Status::FAILED: case CompassCalibrator::Status::BAD_ORIENTATION: case CompassCalibrator::Status::BAD_RADIUS: - break; + // this backend isn't calibrating, + // but maybe the next one is: + continue; case CompassCalibrator::Status::WAITING_TO_START: case CompassCalibrator::Status::RUNNING_STEP_ONE: case CompassCalibrator::Status::RUNNING_STEP_TWO: