diff --git a/libraries/AP_GPS/AP_GPS_Glitch.h b/libraries/AP_GPS/AP_GPS_Glitch.h index a347f45dbd..63e72b23cb 100644 --- a/libraries/AP_GPS/AP_GPS_Glitch.h +++ b/libraries/AP_GPS/AP_GPS_Glitch.h @@ -14,7 +14,7 @@ #include #define GPS_GLITCH_ACCEL_MAX_CMSS 1000.0f // vehicle can accelerate at up to 5m/s/s in any direction -#define GPS_GLITCH_RADIUS_CM 500.0f // gps movement within 5m of current position are always ok +#define GPS_GLITCH_RADIUS_CM 200.0f // gps movement within 2m of current position are always ok /// @class GPS_Glitch /// @brief GPS Glitch protection class