From b7632194cc2e341a283af76694b2e2fcb8c3af96 Mon Sep 17 00:00:00 2001 From: Jonathan Challinger Date: Tue, 5 May 2015 00:08:26 -0700 Subject: [PATCH] Copter: check EKF health specifically in pre_arm_gps_checks --- ArduCopter/motors.pde | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ArduCopter/motors.pde b/ArduCopter/motors.pde index 02ad6bc7a5..59f96af735 100644 --- a/ArduCopter/motors.pde +++ b/ArduCopter/motors.pde @@ -574,7 +574,7 @@ static void pre_arm_rc_checks() static bool pre_arm_gps_checks(bool display_failure) { // always check if inertial nav has started and is ready - if(!ahrs.healthy()) { + if(!ahrs.get_NavEKF().healthy()) { if (display_failure) { gcs_send_text_P(SEVERITY_HIGH,PSTR("PreArm: Waiting for Nav Checks")); }