mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-14 11:54:01 -04:00
Baro: get_air_density_ratio gets div-by-zero check
This commit is contained in:
parent
0dbe94c9a1
commit
1b381b5675
@ -208,10 +208,15 @@ float AP_Baro::get_EAS2TAS(void)
|
|||||||
return _EAS2TAS;
|
return _EAS2TAS;
|
||||||
}
|
}
|
||||||
|
|
||||||
// return air density / sea level density - decreases in altitude
|
// return air density / sea level density - decreases as altitude climbs
|
||||||
float AP_Baro::get_air_density_ratio(void)
|
float AP_Baro::get_air_density_ratio(void)
|
||||||
{
|
{
|
||||||
|
float eas2tas = get_EAS2TAS();
|
||||||
|
if (eas2tas > 0.0f) {
|
||||||
return 1.0f/(sq(get_EAS2TAS()));
|
return 1.0f/(sq(get_EAS2TAS()));
|
||||||
|
} else {
|
||||||
|
return 1.0f;
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
// return current climb_rate estimeate relative to time that calibrate()
|
// return current climb_rate estimeate relative to time that calibrate()
|
||||||
|
@ -79,7 +79,7 @@ public:
|
|||||||
// get scale factor required to convert equivalent to true airspeed
|
// get scale factor required to convert equivalent to true airspeed
|
||||||
float get_EAS2TAS(void);
|
float get_EAS2TAS(void);
|
||||||
|
|
||||||
// get air density / sea level density - decreases in altitude
|
// get air density / sea level density - decreases as altitude climbs
|
||||||
float get_air_density_ratio(void);
|
float get_air_density_ratio(void);
|
||||||
|
|
||||||
// get current climb rate in meters/s. A positive number means
|
// get current climb rate in meters/s. A positive number means
|
||||||
|
Loading…
Reference in New Issue
Block a user