diff --git a/libraries/AP_Airspeed/AP_Airspeed.cpp b/libraries/AP_Airspeed/AP_Airspeed.cpp index 3ef378eb98..127185b897 100644 --- a/libraries/AP_Airspeed/AP_Airspeed.cpp +++ b/libraries/AP_Airspeed/AP_Airspeed.cpp @@ -687,7 +687,7 @@ bool AP_Airspeed::use(uint8_t i) const return false; } #ifndef HAL_BUILD_AP_PERIPH - if (param[i].use == 2 && SRV_Channels::get_output_scaled(SRV_Channel::k_throttle) != 0) { + if (param[i].use == 2 && !is_zero(SRV_Channels::get_output_scaled(SRV_Channel::k_throttle))) { // special case for gliders with airspeed sensors behind the // propeller. Allow airspeed to be disabled when throttle is // running