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

AP_TECS: make _EAS a local variable #28629

Merged
merged 1 commit into from
Nov 15, 2024
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
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
Loading