mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-08 08:53:56 -04:00
AP_Airspeed: ignore temperatures below -80
ETS driver on PX4 returns -1000
This commit is contained in:
parent
8b5f1575ad
commit
1c270d17a8
@ -76,6 +76,11 @@ bool AP_Airspeed_PX4::get_differential_pressure(float &pressure)
|
|||||||
// read the temperature
|
// read the temperature
|
||||||
bool AP_Airspeed_PX4::get_temperature(float &temperature)
|
bool AP_Airspeed_PX4::get_temperature(float &temperature)
|
||||||
{
|
{
|
||||||
|
if (_temperature < -80) {
|
||||||
|
// almost certainly a bad reading. The ETS driver on PX4
|
||||||
|
// returns -1000
|
||||||
|
return false;
|
||||||
|
}
|
||||||
temperature = _temperature;
|
temperature = _temperature;
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user