mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 08:38:36 -04:00
AP_Compass: correct is_calibrating check
before this we only ever looked at the first backend
This commit is contained in:
parent
75919171b7
commit
05a638a639
@ -336,7 +336,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:
|
||||
|
Loading…
Reference in New Issue
Block a user