Copter: check all EKF cores for health on arming

This commit is contained in:
Michael du Breuil 2019-03-31 20:41:42 -07:00 committed by Andrew Tridgell
parent 4fda39a79a
commit 8290bd4e67
1 changed files with 6 additions and 2 deletions

View File

@ -286,8 +286,12 @@ bool AP_Arming_Copter::gps_checks(bool display_failure)
const AP_AHRS_NavEKF &ahrs = AP::ahrs_navekf();
// always check if inertial nav has started and is ready
if (!ahrs.healthy()) {
check_failed(ARMING_CHECK_NONE, display_failure, "AHRS not healthy");
if (!ahrs.prearm_healthy()) {
const char *reason = ahrs.prearm_failure_reason();
if (reason == nullptr) {
reason = "AHRS not healthy";
}
check_failed(ARMING_CHECK_NONE, display_failure, "%s", reason);
return false;
}