mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-01 21:48:28 -04:00
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
This commit is contained in:
parent
f5b1114aea
commit
bcbf0feff0
@ -13,7 +13,7 @@
|
||||
#include <AP_Math.h>
|
||||
#include <AP_GPS.h>
|
||||
|
||||
#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
|
||||
|
Loading…
Reference in New Issue
Block a user