AP_Arming: check for only first compass being disabled

If only the first compass is disabled, users may expect other enabled compasses to be used but they won't be
This commit is contained in:
Randy Mackay 2021-03-30 17:22:03 +09:00 committed by Andrew Tridgell
parent 64c4b6a42b
commit d343c569c2

View File

@ -414,6 +414,12 @@ bool AP_Arming::compass_checks(bool report)
if ((checks_to_perform) & ARMING_CHECK_ALL ||
(checks_to_perform) & ARMING_CHECK_COMPASS) {
// check for first compass being disabled but 2nd or 3rd being enabled
if (!_compass.use_for_yaw(0) && (_compass.get_num_enabled() > 0)) {
check_failed(ARMING_CHECK_COMPASS, report, "Compass1 disabled but others enabled");
return false;
}
// avoid Compass::use_for_yaw(void) as it implicitly calls healthy() which can
// incorrectly skip the remaining checks, pass the primary instance directly
if (!_compass.use_for_yaw(0)) {