From 73fda4e6a74df78c796a709e8488b42147f05ac5 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 17 Nov 2020 09:53:20 +1100 Subject: [PATCH] AP_Airspeed: cope with zero ratio in SDP3X driver needed for AP_Periph --- libraries/AP_Airspeed/AP_Airspeed_SDP3X.cpp | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/libraries/AP_Airspeed/AP_Airspeed_SDP3X.cpp b/libraries/AP_Airspeed/AP_Airspeed_SDP3X.cpp index a8e066c515..b68ef886fa 100644 --- a/libraries/AP_Airspeed/AP_Airspeed_SDP3X.cpp +++ b/libraries/AP_Airspeed/AP_Airspeed_SDP3X.cpp @@ -259,6 +259,10 @@ float AP_Airspeed_SDP3X::_correct_pressure(float press) // 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 // from turning the dv correction above into an equivalent