Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Copter: remove unused hgt_variance_filt #29168

Merged
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
1 change: 0 additions & 1 deletion ArduCopter/Copter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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),
Expand Down
1 change: 0 additions & 1 deletion ArduCopter/Copter.h
Original file line number Diff line number Diff line change
Expand Up @@ -335,7 +335,6 @@ class Copter : public AP_Vehicle {
// 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;

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

Expand Down
1 change: 0 additions & 1 deletion ArduCopter/system.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand Down
Loading