From d9785d1a7dd96a412dc1ac66b6040a5236d7cf02 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Wed, 5 Oct 2022 11:59:33 +1100 Subject: [PATCH] AP_Compass: remove default clause from calibrator status switch bad_radius should almost certainly be treated just like bad orientation --- libraries/AP_Compass/AP_Compass_Calibration.cpp | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) 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; } }