diff --git a/libraries/AP_InertialSensor/AP_InertialSensor.cpp b/libraries/AP_InertialSensor/AP_InertialSensor.cpp index b2c5e31e1c..4ac5ff707b 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor.cpp +++ b/libraries/AP_InertialSensor/AP_InertialSensor.cpp @@ -42,7 +42,7 @@ extern const AP_HAL::HAL& hal; #define DEFAULT_ACCEL_FILTER 20 #define DEFAULT_STILL_THRESH 2.5f #elif APM_BUILD_TYPE(APM_BUILD_APMrover2) -#define DEFAULT_GYRO_FILTER 10 +#define DEFAULT_GYRO_FILTER 4 #define DEFAULT_ACCEL_FILTER 10 #define DEFAULT_STILL_THRESH 0.1f #else