mirror of https://github.com/ArduPilot/ardupilot
Revert "AP_Arming: check for only first compass being disabled"
This reverts commit d343c569c2
.
This commit is contained in:
parent
8590bfea63
commit
1d29619e51
|
@ -414,12 +414,6 @@ 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)) {
|
||||
|
|
Loading…
Reference in New Issue