AP_TECS: make _EAS a local variable

not used outside this one function

Co-authored-by: Michelle Rossouw <michelleros128@gmail.com>
This commit is contained in:
Peter Barker 2024-11-15 16:50:43 +11:00 committed by Peter Barker
parent 2115ad9c97
commit 4c72ca6ddc
2 changed files with 3 additions and 3 deletions

View File

@ -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());

View File

@ -271,9 +271,6 @@ private:
float _vel_dot;
float _vel_dot_lpf;
// Equivalent airspeed
float _EAS;
// True airspeed limits
float _TASmax;
float _TASmin;