mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-13 18:14:19 -03:00
Copter: remove unused hgt_variance_filt
this filter is populated but never checked when checking variances
This commit is contained in:
parent
29655d149c
commit
8425bf46dd
@ -962,7 +962,6 @@ Copter::Copter(void)
|
||||
flight_modes(&g.flight_mode1),
|
||||
pos_variance_filt(FS_EKF_FILT_DEFAULT),
|
||||
vel_variance_filt(FS_EKF_FILT_DEFAULT),
|
||||
hgt_variance_filt(FS_EKF_FILT_DEFAULT),
|
||||
flightmode(&mode_stabilize),
|
||||
simple_cos_yaw(1.0f),
|
||||
super_simple_cos_yaw(1.0),
|
||||
|
@ -335,7 +335,6 @@ private:
|
||||
// thus failsafes should be triggered on filtered values in order to avoid transient errors
|
||||
LowPassFilterFloat pos_variance_filt;
|
||||
LowPassFilterFloat vel_variance_filt;
|
||||
LowPassFilterFloat hgt_variance_filt;
|
||||
bool variances_valid;
|
||||
uint32_t last_ekf_check_us;
|
||||
|
||||
|
@ -128,7 +128,6 @@ bool Copter::ekf_over_threshold()
|
||||
// always update filtered values as this serves the vibration check as well
|
||||
position_var = pos_variance_filt.apply(position_var, dt);
|
||||
vel_var = vel_variance_filt.apply(vel_var, dt);
|
||||
height_var = hgt_variance_filt.apply(height_var, dt);
|
||||
|
||||
last_ekf_check_us = now_us;
|
||||
|
||||
|
@ -200,7 +200,6 @@ void Copter::init_ardupilot()
|
||||
|
||||
pos_variance_filt.set_cutoff_frequency(g2.fs_ekf_filt_hz);
|
||||
vel_variance_filt.set_cutoff_frequency(g2.fs_ekf_filt_hz);
|
||||
hgt_variance_filt.set_cutoff_frequency(g2.fs_ekf_filt_hz);
|
||||
|
||||
// flag that initialisation has completed
|
||||
ap.initialised = true;
|
||||
|
Loading…
Reference in New Issue
Block a user