AP_Arming: Correct an edge case that would not run compass checks

This commit is contained in:
Michael du Breuil 2018-06-21 18:07:34 -07:00 committed by Andrew Tridgell
parent cd5c59773b
commit d977ca091a

View File

@ -314,7 +314,9 @@ bool AP_Arming::compass_checks(bool report)
if ((checks_to_perform) & ARMING_CHECK_ALL || if ((checks_to_perform) & ARMING_CHECK_ALL ||
(checks_to_perform) & ARMING_CHECK_COMPASS) { (checks_to_perform) & ARMING_CHECK_COMPASS) {
if (!_compass.use_for_yaw()) { // 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(_compass.get_primary())) {
// compass use is disabled // compass use is disabled
return true; return true;
} }