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 Randy Mackay
parent 5c8c1cf3c9
commit d9785d1a7d
1 changed files with 4 additions and 1 deletions

View File

@ -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;
}
}