Copter: cleanup EKF failsafe units and division

This commit is contained in:
Andy Piper 2024-02-09 10:33:47 +00:00 committed by Randy Mackay
parent 5216dc92f9
commit 9cc194bc8a
2 changed files with 2 additions and 1 deletions

View File

@ -1232,6 +1232,7 @@ const AP_Param::GroupInfo ParametersG2::var_info2[] = {
// @DisplayName: EKF Failsafe filter cutoff
// @Description: EKF Failsafe filter cutoff frequency. EKF variances are filtered using this value to avoid spurious failsafes from transient high variances. A higher value means the failsafe is more likely to trigger.
// @Range: 0 10
// @Units: Hz
// @User: Advanced
AP_GROUPINFO("FS_EKF_FILT", 8, ParametersG2, fs_ekf_filt_hz, FS_EKF_FILT_DEFAULT),

View File

@ -123,7 +123,7 @@ bool Copter::ekf_over_threshold()
}
uint32_t now_us = AP_HAL::micros();
float dt = (now_us - last_ekf_check_us) / 1000000.0f;
float dt = (now_us - last_ekf_check_us) * 1e-6f;
// always update filtered values as this serves the vibration check as well
position_var = pos_variance_filt.apply(position_var, dt);