From eed50a087244dd8c306b7964b337ce794e8f3dba Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 16 Apr 2024 08:30:41 +1000 Subject: [PATCH] AP_DAL: change gyro filter to 10Hz this improved EKF3 IMU position correction for noise --- libraries/AP_DAL/AP_DAL_InertialSensor.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/AP_DAL/AP_DAL_InertialSensor.cpp b/libraries/AP_DAL/AP_DAL_InertialSensor.cpp index e8332cb7ad..136e905f52 100644 --- a/libraries/AP_DAL/AP_DAL_InertialSensor.cpp +++ b/libraries/AP_DAL/AP_DAL_InertialSensor.cpp @@ -54,9 +54,9 @@ void AP_DAL_InertialSensor::start_frame() void AP_DAL_InertialSensor::update_filtered(uint8_t i) { if (!is_positive(alpha)) { - // we use a constant 20Hz for EKF filtered accel/gyro, making the EKF + // we use a constant 10Hz for EKF filtered accel/gyro, making the EKF // independent of the INS filter settings - const float cutoff_hz = 20.0; + const float cutoff_hz = 10.0; alpha = calc_lowpass_alpha_dt(get_loop_delta_t(), cutoff_hz); } if (is_positive(_RISI[i].delta_angle_dt)) {