mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-23 00:04:02 -04:00
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:
parent
d44fff71cf
commit
07fd31c724
@ -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
|
||||
|
Loading…
Reference in New Issue
Block a user