diff --git a/ArduCopter/motors.pde b/ArduCopter/motors.pde
index 094da42265efdd3590aae4790f6c9efa9d1c3548..9c989911f1dc283f4519ef7a785d613a6a768fd1 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;
 }