AP_ADSB: fixed a crash in ADSB when baro not healthy

zero pressure leads to a floating point exception
This commit is contained in:
Andrew Tridgell 2023-12-30 08:32:05 +11:00
parent 9428e41301
commit ce9c7dfdd1
1 changed files with 3 additions and 1 deletions

View File

@ -365,7 +365,9 @@ void AP_ADSB::update(void)
// Altitude difference between sea level pressure and current // Altitude difference between sea level pressure and current
// pressure (in metres) // pressure (in metres)
if (loc.baro_is_healthy) {
loc.baro_alt_press_diff_sea_level = baro.get_altitude_difference(SSL_AIR_PRESSURE, baro.get_pressure()); loc.baro_alt_press_diff_sea_level = baro.get_altitude_difference(SSL_AIR_PRESSURE, baro.get_pressure());
}
update(loc); update(loc);
} }