From 4c72ca6ddc364a5f8af6393ae7fe84d4e3499840 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 15 Nov 2024 16:50:43 +1100 Subject: [PATCH] AP_TECS: make _EAS a local variable not used outside this one function Co-authored-by: Michelle Rossouw --- libraries/AP_TECS/AP_TECS.cpp | 3 +++ libraries/AP_TECS/AP_TECS.h | 3 --- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/libraries/AP_TECS/AP_TECS.cpp b/libraries/AP_TECS/AP_TECS.cpp index f25cf5294e6f9..49277cfce07ba 100644 --- a/libraries/AP_TECS/AP_TECS.cpp +++ b/libraries/AP_TECS/AP_TECS.cpp @@ -427,6 +427,9 @@ void AP_TECS::_update_speed(float DT) // Get measured airspeed or default to trim speed and constrain to range between min and max if // airspeed sensor data cannot be used + + // Equivalent airspeed + float _EAS; if (!use_airspeed || !_ahrs.airspeed_estimate(_EAS)) { // If no airspeed available use average of min and max _EAS = constrain_float(aparm.airspeed_cruise.get(), (float)aparm.airspeed_min.get(), (float)aparm.airspeed_max.get()); diff --git a/libraries/AP_TECS/AP_TECS.h b/libraries/AP_TECS/AP_TECS.h index 5bc757c0b79a7..57748edba1a07 100644 --- a/libraries/AP_TECS/AP_TECS.h +++ b/libraries/AP_TECS/AP_TECS.h @@ -271,9 +271,6 @@ class AP_TECS { float _vel_dot; float _vel_dot_lpf; - // Equivalent airspeed - float _EAS; - // True airspeed limits float _TASmax; float _TASmin;