From 5087eabbca6dd09f2b112ccfc1f73790858fab3f Mon Sep 17 00:00:00 2001 From: Joshua Henderson Date: Mon, 9 May 2022 18:23:38 -0400 Subject: [PATCH] AP_Airspeed: remove negative pressure set unhealthy --- libraries/AP_Airspeed/AP_Airspeed.cpp | 7 ------- 1 file changed, 7 deletions(-) diff --git a/libraries/AP_Airspeed/AP_Airspeed.cpp b/libraries/AP_Airspeed/AP_Airspeed.cpp index c8820e5d4a..a0d6d31e79 100644 --- a/libraries/AP_Airspeed/AP_Airspeed.cpp +++ b/libraries/AP_Airspeed/AP_Airspeed.cpp @@ -621,13 +621,6 @@ void AP_Airspeed::read(uint8_t i) state[i].airspeed = sqrtf(fabsf(state[i].filtered_pressure) * param[i].ratio); break; } - - if (state[i].last_pressure < -32) { - // we're reading more than about -8m/s. The user probably has - // the ports the wrong way around - state[i].healthy = false; - } - } // read all airspeed sensors