mirror of https://github.com/ArduPilot/ardupilot
AP_ADSB: fixed a crash in ADSB when baro not healthy
zero pressure leads to a floating point exception
This commit is contained in:
parent
9428e41301
commit
ce9c7dfdd1
|
@ -365,7 +365,9 @@ void AP_ADSB::update(void)
|
|||
|
||||
// Altitude difference between sea level pressure and current
|
||||
// pressure (in metres)
|
||||
loc.baro_alt_press_diff_sea_level = baro.get_altitude_difference(SSL_AIR_PRESSURE, baro.get_pressure());
|
||||
if (loc.baro_is_healthy) {
|
||||
loc.baro_alt_press_diff_sea_level = baro.get_altitude_difference(SSL_AIR_PRESSURE, baro.get_pressure());
|
||||
}
|
||||
|
||||
update(loc);
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue