mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 23:33:57 -04:00
AP_DAL: change gyro filter to 10Hz
this improved EKF3 IMU position correction for noise
This commit is contained in:
parent
fe9fcf445e
commit
eed50a0872
@ -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)) {
|
||||
|
Loading…
Reference in New Issue
Block a user