Skip to content

Commit

Permalink
Copter: cleanup EKF failsafe units and division
Browse files Browse the repository at this point in the history
  • Loading branch information
andyp1per committed Feb 9, 2024
1 parent e8b4010 commit 1837a9a
Show file tree
Hide file tree
Showing 2 changed files with 2 additions and 1 deletion.
1 change: 1 addition & 0 deletions ArduCopter/Parameters.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1238,6 +1238,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),

Expand Down
2 changes: 1 addition & 1 deletion ArduCopter/ekf_check.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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);
Expand Down

0 comments on commit 1837a9a

Please sign in to comment.