AP_Airspeed: use floats for get/set output scaled

This commit is contained in:
Iampete1 2021-09-18 18:55:41 +01:00 committed by Andrew Tridgell
parent 14b9e99020
commit 89c0a8ea04

View File

@ -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