AP_InertialSensor: reduce accel filter to 10hz

This commit is contained in:
Leonard Hall 2017-06-01 13:04:39 +09:00 committed by Randy Mackay
parent 54539fc5af
commit 23f594ef7d
1 changed files with 1 additions and 1 deletions

View File

@ -34,7 +34,7 @@ extern const AP_HAL::HAL& hal;
#if APM_BUILD_TYPE(APM_BUILD_ArduCopter)
#define DEFAULT_GYRO_FILTER 20
#define DEFAULT_ACCEL_FILTER 20
#define DEFAULT_ACCEL_FILTER 10
#define DEFAULT_STILL_THRESH 2.5f
#elif APM_BUILD_TYPE(APM_BUILD_APMrover2)
#define DEFAULT_GYRO_FILTER 4