From 4ca58f240c00c8bc464e538e7bdb991901fa2fab Mon Sep 17 00:00:00 2001 From: Randy Mackay <rmackay9@yahoo.com> Date: Fri, 29 Mar 2013 01:03:49 +0900 Subject: [PATCH] Copter: INS_MPU6K_FILTER defaulted to 20hz --- libraries/AP_InertialSensor/AP_InertialSensor_MPU6000.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_InertialSensor/AP_InertialSensor_MPU6000.cpp b/libraries/AP_InertialSensor/AP_InertialSensor_MPU6000.cpp index 1c723fa1f..867e8e6ba 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor_MPU6000.cpp +++ b/libraries/AP_InertialSensor/AP_InertialSensor_MPU6000.cpp @@ -393,7 +393,7 @@ void AP_InertialSensor_MPU6000::hardware_init(Sample_rate sample_rate) break; case RATE_100HZ: rate = MPUREG_SMPLRT_100HZ; - default_filter = BITS_DLPF_CFG_42HZ; + default_filter = BITS_DLPF_CFG_20HZ; _micros_per_sample = 10000; break; case RATE_200HZ: -- GitLab