diff --git a/libraries/AP_Compass/AP_Compass_Calibration.cpp b/libraries/AP_Compass/AP_Compass_Calibration.cpp index 95d432896c..24548fae58 100644 --- a/libraries/AP_Compass/AP_Compass_Calibration.cpp +++ b/libraries/AP_Compass/AP_Compass_Calibration.cpp @@ -333,8 +333,11 @@ bool Compass::is_calibrating() const case CompassCalibrator::Status::SUCCESS: case CompassCalibrator::Status::FAILED: case CompassCalibrator::Status::BAD_ORIENTATION: + case CompassCalibrator::Status::BAD_RADIUS: break; - default: + case CompassCalibrator::Status::WAITING_TO_START: + case CompassCalibrator::Status::RUNNING_STEP_ONE: + case CompassCalibrator::Status::RUNNING_STEP_TWO: return true; } }