AP_Airspeed: remove negative pressure set unhealthy

This commit is contained in:
Joshua Henderson 2022-05-09 18:23:38 -04:00 committed by Andrew Tridgell
parent 69508804b4
commit 5087eabbca

View File

@ -621,13 +621,6 @@ void AP_Airspeed::read(uint8_t i)
state[i].airspeed = sqrtf(fabsf(state[i].filtered_pressure) * param[i].ratio); state[i].airspeed = sqrtf(fabsf(state[i].filtered_pressure) * param[i].ratio);
break; 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 // read all airspeed sensors