mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-11 17:13:56 -03:00
AP_AHRS: Reduce time constant on filtering of DCM error reporting
Reduces time constant from 2 to 1 second to make data more useful for pre-flight alignment checks by the EKF
This commit is contained in:
parent
7e43eaafab
commit
ea8217bd3a
@ -476,7 +476,7 @@ AP_AHRS_DCM::drift_correction_yaw(void)
|
||||
_omega_I_sum.z += error_z * _ki_yaw * yaw_deltat;
|
||||
}
|
||||
|
||||
_error_yaw = 0.9f * _error_yaw + 0.1f * fabsf(yaw_error);
|
||||
_error_yaw = 0.8f * _error_yaw + 0.2f * fabsf(yaw_error);
|
||||
}
|
||||
|
||||
|
||||
@ -736,7 +736,7 @@ AP_AHRS_DCM::drift_correction(float deltat)
|
||||
return;
|
||||
}
|
||||
|
||||
_error_rp = 0.9f * _error_rp + 0.1f * best_error;
|
||||
_error_rp = 0.8f * _error_rp + 0.2f * best_error;
|
||||
|
||||
// base the P gain on the spin rate
|
||||
float spin_rate = _omega.length();
|
||||
|
Loading…
Reference in New Issue
Block a user