Browse Source

AP_InertialSensor: change copter filters to 20Hz

with the backend filters disabled 20Hz is closer to the old default of
30Hz
mission-4.1.18
Andrew Tridgell 10 years ago
parent
commit
07fd31c724
  1. 4
      libraries/AP_InertialSensor/AP_InertialSensor.cpp

4
libraries/AP_InertialSensor/AP_InertialSensor.cpp

@ -24,8 +24,8 @@ @@ -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…
Cancel
Save