diff --git a/ArduCopter/AP_Arming.cpp b/ArduCopter/AP_Arming.cpp index 7e6b05d1fc..5c3bf283e4 100644 --- a/ArduCopter/AP_Arming.cpp +++ b/ArduCopter/AP_Arming.cpp @@ -380,7 +380,7 @@ bool AP_Arming_Copter::gps_checks(bool display_failure) } // warn about hdop separately - to prevent user confusion with no gps lock - if (copter.gps.get_hdop() > copter.g.gps_hdop_good) { + if ((copter.gps.num_sensors() > 0) && (copter.gps.get_hdop() > copter.g.gps_hdop_good)) { check_failed(ARMING_CHECK_GPS, display_failure, "High GPS HDOP"); AP_Notify::flags.pre_arm_gps_check = false; return false;