mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_Airspeed: check for baro baro data in SDP3X
this matters for SDP3X as AP_Periph sensor with no baro
This commit is contained in:
parent
30e23052a0
commit
3f67917c26
@ -223,16 +223,25 @@ float AP_Airspeed_SDP3X::_correct_pressure(float press)
|
|||||||
|
|
||||||
AP_Baro *baro = AP_Baro::get_singleton();
|
AP_Baro *baro = AP_Baro::get_singleton();
|
||||||
|
|
||||||
if (baro == nullptr) {
|
float baro_pressure;
|
||||||
return press;
|
if (baro == nullptr || baro->num_instances() == 0) {
|
||||||
|
// with no baro assume sea level
|
||||||
|
baro_pressure = SSL_AIR_PRESSURE;
|
||||||
|
} else {
|
||||||
|
baro_pressure = baro->get_pressure();
|
||||||
}
|
}
|
||||||
|
|
||||||
float temperature;
|
float temperature;
|
||||||
if (!get_temperature(temperature)) {
|
if (!get_temperature(temperature)) {
|
||||||
return press;
|
// assume 25C if no temperature
|
||||||
|
temperature = 25;
|
||||||
}
|
}
|
||||||
|
|
||||||
float rho_air = baro->get_pressure() / (ISA_GAS_CONSTANT * (temperature + C_TO_KELVIN));
|
float rho_air = baro_pressure / (ISA_GAS_CONSTANT * (temperature + C_TO_KELVIN));
|
||||||
|
if (!is_positive(rho_air)) {
|
||||||
|
// bad pressure
|
||||||
|
return press;
|
||||||
|
}
|
||||||
|
|
||||||
/*
|
/*
|
||||||
the constants in the code below come from a calibrated test of
|
the constants in the code below come from a calibrated test of
|
||||||
|
Loading…
Reference in New Issue
Block a user