mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
AP_InertialSensor: reduce accel filter to 10hz
This commit is contained in:
parent
010dc103be
commit
447b20efa5
@ -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
|
||||
|
Loading…
Reference in New Issue
Block a user