From fd55a2d9c409cb4a27ea9eaf1f5d734e9d29f791 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Mon, 15 Dec 2014 10:45:50 +0900 Subject: [PATCH] Copter: increase GPS_HDOP_GOOD default to 2.3 --- ArduCopter/config.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ArduCopter/config.h b/ArduCopter/config.h index 2708415bf0..4dc231c36e 100644 --- a/ArduCopter/config.h +++ b/ArduCopter/config.h @@ -297,7 +297,7 @@ # define FAILSAFE_GPS_TIMEOUT_MS 5000 // gps failsafe triggers after 5 seconds with no GPS #endif #ifndef GPS_HDOP_GOOD_DEFAULT - # define GPS_HDOP_GOOD_DEFAULT 200 // minimum hdop that represents a good position. used during pre-arm checks if fence is enabled + # define GPS_HDOP_GOOD_DEFAULT 230 // minimum hdop that represents a good position. used during pre-arm checks if fence is enabled #endif // GCS failsafe