mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-24 01:28:29 -04:00
AP_Baro: Avoid a FPE when ground pressure is negative
This commit is contained in:
parent
6ab92d78bd
commit
685b28f51d
@ -523,7 +523,7 @@ void AP_Baro::update(void)
|
|||||||
if (sensors[i].healthy) {
|
if (sensors[i].healthy) {
|
||||||
// update altitude calculation
|
// update altitude calculation
|
||||||
float ground_pressure = sensors[i].ground_pressure;
|
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;
|
sensors[i].ground_pressure = sensors[i].pressure;
|
||||||
}
|
}
|
||||||
float altitude = sensors[i].altitude;
|
float altitude = sensors[i].altitude;
|
||||||
|
Loading…
Reference in New Issue
Block a user