mirror of https://github.com/ArduPilot/ardupilot
AP_InertialSensor: Changing the default gyro filter from 10 to 4
This change is only for Rovers.
This commit is contained in:
parent
1770f314ac
commit
34fa2a39bd
|
@ -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
|
||||
|
|
Loading…
Reference in New Issue