mirror of https://github.com/ArduPilot/ardupilot
Copter: skip ap arming check of GPS hdop if GPS is disabled
This commit is contained in:
parent
3ae61ce5d3
commit
cbe0569179
|
@ -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;
|
||||
|
|
Loading…
Reference in New Issue