Browse Source

AP_Airspeed: analog: check valid pin

gps-1.3.1
Iampete1 3 years ago committed by Andrew Tridgell
parent
commit
0731af751a
  1. 5
      libraries/AP_Airspeed/AP_Airspeed_analog.cpp

5
libraries/AP_Airspeed/AP_Airspeed_analog.cpp

@ -41,11 +41,10 @@ bool AP_Airspeed_Analog::init() @@ -41,11 +41,10 @@ bool AP_Airspeed_Analog::init()
// read the airspeed sensor
bool AP_Airspeed_Analog::get_differential_pressure(float &pressure)
{
if (_source == nullptr) {
// allow pin to change
if (_source == nullptr || !_source->set_pin(get_pin())) {
return false;
}
// allow pin to change
_source->set_pin(get_pin());
pressure = _source->voltage_average_ratiometric() * VOLTS_TO_PASCAL / get_psi_range();
return true;
}

Loading…
Cancel
Save