Skip to content

Commit

Permalink
AP_TECS: make _EAS a local variable
Browse files Browse the repository at this point in the history
not used outside this one function

Co-authored-by: Michelle Rossouw <michelleros128@gmail.com>
  • Loading branch information
peterbarker and MichelleRos committed Nov 15, 2024
1 parent 2115ad9 commit 4c72ca6
Show file tree
Hide file tree
Showing 2 changed files with 3 additions and 3 deletions.
3 changes: 3 additions & 0 deletions libraries/AP_TECS/AP_TECS.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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());
Expand Down
3 changes: 0 additions & 3 deletions libraries/AP_TECS/AP_TECS.h
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand Down

0 comments on commit 4c72ca6

Please sign in to comment.