AP_InertialSensor: change copter filters to 20Hz

with the backend filters disabled 20Hz is closer to the old default of
30Hz
This commit is contained in:
Andrew Tridgell 2015-03-12 13:11:17 +11:00
parent d44fff71cf
commit 07fd31c724

View File

@ -24,8 +24,8 @@
extern const AP_HAL::HAL& hal;
#if APM_BUILD_TYPE(APM_BUILD_ArduCopter)
#define DEFAULT_GYRO_FILTER 30
#define DEFAULT_ACCEL_FILTER 30
#define DEFAULT_GYRO_FILTER 20
#define DEFAULT_ACCEL_FILTER 20
#elif APM_BUILD_TYPE(APM_BUILD_APMrover2)
#define DEFAULT_GYRO_FILTER 10
#define DEFAULT_ACCEL_FILTER 10