AP_Airspeed: cope with zero ratio in SDP3X driver

needed for AP_Periph
This commit is contained in:
Andrew Tridgell 2020-11-17 09:53:20 +11:00
parent 857d905d9f
commit 73fda4e6a7

View File

@ -259,6 +259,10 @@ float AP_Airspeed_SDP3X::_correct_pressure(float press)
// airspeed ratio // airspeed ratio
float ratio = get_airspeed_ratio(); float ratio = get_airspeed_ratio();
if (!is_positive(ratio)) {
// cope with AP_Periph where ratio is 0
ratio = 2.0;
}
// calculate equivalent pressure correction. This formula comes // calculate equivalent pressure correction. This formula comes
// from turning the dv correction above into an equivalent // from turning the dv correction above into an equivalent