diff --git a/libraries/AP_TECS/AP_TECS.cpp b/libraries/AP_TECS/AP_TECS.cpp index e049d31cbb..f5892d6858 100644 --- a/libraries/AP_TECS/AP_TECS.cpp +++ b/libraries/AP_TECS/AP_TECS.cpp @@ -390,7 +390,7 @@ void AP_TECS::_update_speed(float DT) _vel_dot_lpf = _vel_dot_lpf * (1.0f - alpha) + _vel_dot * alpha; } - bool use_airspeed = _use_synthetic_airspeed_once || _use_synthetic_airspeed.get() || _ahrs.airspeed_sensor_enabled(); + bool use_airspeed = _use_synthetic_airspeed_once || _use_synthetic_airspeed.get() || _ahrs.using_airspeed_sensor(); // Convert equivalent airspeeds to true airspeeds and harmonise limits @@ -923,7 +923,7 @@ void AP_TECS::_update_pitch(void) // A SKE_weighting of 2 provides 100% priority to speed control. This is used when an underspeed condition is detected. In this instance, if airspeed // rises above the demanded value, the pitch angle will be increased by the TECS controller. _SKE_weighting = constrain_float(_spdWeight, 0.0f, 2.0f); - if (!(_ahrs.airspeed_sensor_enabled() || _use_synthetic_airspeed)) { + if (!(_ahrs.using_airspeed_sensor() || _use_synthetic_airspeed)) { _SKE_weighting = 0.0f; } else if (_flight_stage == AP_FixedWing::FlightStage::VTOL) { // if we are in VTOL mode then control pitch without regard to @@ -1346,7 +1346,7 @@ void AP_TECS::update_pitch_throttle(int32_t hgt_dem_cm, // Note that caller can demand the use of // synthetic airspeed for one loop if needed. This is required // during QuadPlane transition when pitch is constrained - if (_ahrs.airspeed_sensor_enabled() || _use_synthetic_airspeed || _use_synthetic_airspeed_once) { + if (_ahrs.using_airspeed_sensor() || _use_synthetic_airspeed || _use_synthetic_airspeed_once) { _update_throttle_with_airspeed(); _use_synthetic_airspeed_once = false; _using_airspeed_for_throttle = true;