From 8eb46ced53317fe26ac390e29f9b3f88381766bb Mon Sep 17 00:00:00 2001 From: Randy Mackay <rmackay9@yahoo.com> Date: Fri, 22 Nov 2013 09:53:21 +0900 Subject: [PATCH] Copter: revert pre-arm check for slow GPS --- ArduCopter/motors.pde | 8 -------- 1 file changed, 8 deletions(-) diff --git a/ArduCopter/motors.pde b/ArduCopter/motors.pde index 094da4226..9c989911f 100644 --- a/ArduCopter/motors.pde +++ b/ArduCopter/motors.pde @@ -424,14 +424,6 @@ static bool pre_arm_gps_checks(bool display_failure) return false; } - // check for missed gps updates (i.e. not arriving at at least 4hz) - if (inertial_nav.error_count() > 0) { - if (display_failure) { - gcs_send_text_P(SEVERITY_HIGH,PSTR("PreArm: Slow GPS")); - } - return false; - } - // if we got here all must be ok return true; } -- GitLab