From 4bbf623cac6d20e8d918096ff75aae7371691591 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Wed, 30 Sep 2020 11:28:22 +1000 Subject: [PATCH] AP_Soaring: remove unused variables --- libraries/AP_Soaring/AP_Soaring.h | 3 +-- libraries/AP_Soaring/Variometer.h | 5 ----- 2 files changed, 1 insertion(+), 7 deletions(-) diff --git a/libraries/AP_Soaring/AP_Soaring.h b/libraries/AP_Soaring/AP_Soaring.h index e7a628d5d7..0208909b81 100644 --- a/libraries/AP_Soaring/AP_Soaring.h +++ b/libraries/AP_Soaring/AP_Soaring.h @@ -55,7 +55,6 @@ class SoaringController { float McCready(float alt); float _thermalability; - float _expected_sink; LowPassFilter _position_x_filter; LowPassFilter _position_y_filter; @@ -148,4 +147,4 @@ private: bool _exit_commanded; }; -#endif // HAL_SOARING_ENABLED \ No newline at end of file +#endif // HAL_SOARING_ENABLED diff --git a/libraries/AP_Soaring/Variometer.h b/libraries/AP_Soaring/Variometer.h index ce5a4ed6b1..632fb1f818 100644 --- a/libraries/AP_Soaring/Variometer.h +++ b/libraries/AP_Soaring/Variometer.h @@ -21,14 +21,9 @@ class Variometer { // store time of last update uint64_t _prev_update_time; - float _last_alt; - float _aspd_filt; float _aspd_filt_constrained; - float _last_aspd; - float _last_roll; - float _last_total_E; float _expected_thermalling_sink; // declares a 5point average filter using floats