GPSGlitch: reduce radius to 2m
This commit is contained in:
parent
0c97136cbd
commit
8146ef7c00
@ -14,7 +14,7 @@
|
||||
#include <AP_GPS.h>
|
||||
|
||||
#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
|
||||
|
Loading…
Reference in New Issue
Block a user