From bcbf0feff0092063dfdb504c0294f401c05f7acd Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Wed, 13 Nov 2013 21:33:34 +0900 Subject: [PATCH] GPS Glitch: revert accel max to 10m/s/s This may not be the best real world value but it keeps the autotester from failing because it recovers from the glitch before the 5second time-out on the GPS failsafe --- libraries/AP_GPS/AP_GPS_Glitch.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_GPS/AP_GPS_Glitch.h b/libraries/AP_GPS/AP_GPS_Glitch.h index d965a57a1d..a347f45dbd 100644 --- a/libraries/AP_GPS/AP_GPS_Glitch.h +++ b/libraries/AP_GPS/AP_GPS_Glitch.h @@ -13,7 +13,7 @@ #include #include -#define GPS_GLITCH_ACCEL_MAX_CMSS 500.0f // vehicle can accelerate at up to 5m/s/s in any direction +#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 /// @class GPS_Glitch