Copter: skip ap arming check of GPS hdop if GPS is disabled

This commit is contained in:
Randy Mackay 2022-12-13 18:20:06 +09:00
parent 624e731ca5
commit 3ec8094cf6
1 changed files with 1 additions and 1 deletions

View File

@ -379,7 +379,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;