AP_Compass: remove default clause from calibrator status switch

bad_radius should almost certainly be treated just like bad orientation
This commit is contained in:
Peter Barker 2022-10-05 11:59:33 +11:00 committed by Peter Barker
parent d6c5a0ab2b
commit 75919171b7

View File

@ -335,8 +335,11 @@ bool Compass::is_calibrating() const
case CompassCalibrator::Status::SUCCESS: case CompassCalibrator::Status::SUCCESS:
case CompassCalibrator::Status::FAILED: case CompassCalibrator::Status::FAILED:
case CompassCalibrator::Status::BAD_ORIENTATION: case CompassCalibrator::Status::BAD_ORIENTATION:
case CompassCalibrator::Status::BAD_RADIUS:
break; break;
default: case CompassCalibrator::Status::WAITING_TO_START:
case CompassCalibrator::Status::RUNNING_STEP_ONE:
case CompassCalibrator::Status::RUNNING_STEP_TWO:
return true; return true;
} }
} }