AP_Compass: correct is_calibrating check

before this we only ever looked at the first backend
This commit is contained in:
Peter Barker 2022-10-05 12:00:38 +11:00 committed by Randy Mackay
parent fa80cda260
commit 726efb9cf2
1 changed files with 3 additions and 1 deletions

View File

@ -334,7 +334,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: