From fbe87afb9cfbbf163d8491c2ccb2728461423f13 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Mon, 9 Feb 2015 21:35:34 +0900 Subject: [PATCH] Copter: pre-arm check of EKF origin vs home EKF origin must be within 50km of home or numerical errors get too large --- ArduCopter/motors.pde | 9 +++++++++ 1 file changed, 9 insertions(+) diff --git a/ArduCopter/motors.pde b/ArduCopter/motors.pde index 030be6954d..7235a269fd 100644 --- a/ArduCopter/motors.pde +++ b/ArduCopter/motors.pde @@ -551,6 +551,15 @@ static bool pre_arm_gps_checks(bool display_failure) return false; } + // check home and EKF origin are not too far + if (far_from_EKF_origin(ahrs.get_home())) { + if (display_failure) { + gcs_send_text_P(SEVERITY_HIGH,PSTR("PreArm: EKF-home variance")); + } + AP_Notify::flags.pre_arm_gps_check = false; + return false; + } + // warn about hdop separately - to prevent user confusion with no gps lock if (gps.get_hdop() > g.gps_hdop_good) { if (display_failure) {