Skip to content

Commit

Permalink
AP_DAL: change gyro filter to 10Hz
Browse files Browse the repository at this point in the history
this improved EKF3 IMU position correction for noise
  • Loading branch information
tridge committed Apr 17, 2024
1 parent fe9fcf4 commit eed50a0
Showing 1 changed file with 2 additions and 2 deletions.
4 changes: 2 additions & 2 deletions libraries/AP_DAL/AP_DAL_InertialSensor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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)) {
Expand Down

0 comments on commit eed50a0

Please sign in to comment.