mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-02 22:18:29 -04:00
AP_Airspeed: analog: check valid pin
This commit is contained in:
parent
d4d78720ca
commit
0731af751a
@ -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…
Reference in New Issue
Block a user