Browse Source

AP_Airspeed: use floats for get/set output scaled

gps-1.3.1
Iampete1 3 years ago committed by Andrew Tridgell
parent
commit
89c0a8ea04
  1. 2
      libraries/AP_Airspeed/AP_Airspeed.cpp

2
libraries/AP_Airspeed/AP_Airspeed.cpp

@ -687,7 +687,7 @@ bool AP_Airspeed::use(uint8_t i) const @@ -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

Loading…
Cancel
Save