mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-23 00:58:37 -04:00
AP_Baro: Avoid a FPE when ground pressure is negative
This commit is contained in:
parent
f60e7df309
commit
f14667225d
@ -520,7 +520,7 @@ void AP_Baro::update(void)
|
||||
if (sensors[i].healthy) {
|
||||
// update altitude calculation
|
||||
float ground_pressure = sensors[i].ground_pressure;
|
||||
if (is_zero(ground_pressure) || isnan(ground_pressure) || isinf(ground_pressure)) {
|
||||
if (!is_positive(ground_pressure) || isnan(ground_pressure) || isinf(ground_pressure)) {
|
||||
sensors[i].ground_pressure = sensors[i].pressure;
|
||||
}
|
||||
float altitude = sensors[i].altitude;
|
||||
|
Loading…
Reference in New Issue
Block a user