Browse Source

AP_Airspeed: remove negative pressure set unhealthy

apm_2208
Joshua Henderson 3 years ago committed by Andrew Tridgell
parent
commit
5087eabbca
  1. 7
      libraries/AP_Airspeed/AP_Airspeed.cpp

7
libraries/AP_Airspeed/AP_Airspeed.cpp

@ -621,13 +621,6 @@ void AP_Airspeed::read(uint8_t i) @@ -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

Loading…
Cancel
Save