mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-09 09:28:31 -04:00
Copter: reduce GPS_HDOP_GOOD params default to 140
This is required as part of the ublox change from pdop to hdop
This commit is contained in:
parent
5ccc58ffb4
commit
425e26c258
@ -227,7 +227,7 @@
|
|||||||
|
|
||||||
// prearm GPS hdop check
|
// prearm GPS hdop check
|
||||||
#ifndef GPS_HDOP_GOOD_DEFAULT
|
#ifndef GPS_HDOP_GOOD_DEFAULT
|
||||||
# define GPS_HDOP_GOOD_DEFAULT 230 // minimum hdop that represents a good position. used during pre-arm checks if fence is enabled
|
# define GPS_HDOP_GOOD_DEFAULT 140 // minimum hdop that represents a good position. used during pre-arm checks if fence is enabled
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// GCS failsafe
|
// GCS failsafe
|
||||||
|
Loading…
Reference in New Issue
Block a user