5
0
mirror of https://github.com/ArduPilot/ardupilot synced 2025-01-05 23:48:31 -04:00

AP_Baro: add get_air_density_ratio

This commit is contained in:
Jonathan Challinger 2015-04-28 11:15:49 -07:00 committed by Randy Mackay
parent 36cc832931
commit f381ef93e8
2 changed files with 9 additions and 0 deletions
libraries/AP_Baro

View File

@ -208,6 +208,12 @@ float AP_Baro::get_EAS2TAS(void)
return _EAS2TAS;
}
// return air density / sea level density - decreases in altitude
float AP_Baro::get_air_density_ratio(void)
{
return 1.0f/(sq(get_EAS2TAS()));
}
// return current climb_rate estimeate relative to time that calibrate()
// was called. Returns climb rate in meters/s, positive means up
// note that this relies on read() being called regularly to get new data

View File

@ -79,6 +79,9 @@ public:
// get scale factor required to convert equivalent to true airspeed
float get_EAS2TAS(void);
// get air density / sea level density - decreases in altitude
float get_air_density_ratio(void);
// get current climb rate in meters/s. A positive number means
// going up
float get_climb_rate(void);