mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_Airspeed: remove negative pressure set unhealthy
This commit is contained in:
parent
69508804b4
commit
5087eabbca
@ -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
|
||||||
|
Loading…
Reference in New Issue
Block a user