mirror of https://github.com/ArduPilot/ardupilot
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:
parent
2115ad9c97
commit
4c72ca6ddc
|
@ -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());
|
||||
|
|
|
@ -271,9 +271,6 @@ private:
|
|||
float _vel_dot;
|
||||
float _vel_dot_lpf;
|
||||
|
||||
// Equivalent airspeed
|
||||
float _EAS;
|
||||
|
||||
// True airspeed limits
|
||||
float _TASmax;
|
||||
float _TASmin;
|
||||
|
|
Loading…
Reference in New Issue