Browse Source

AP_Baro: add get_air_density_ratio

mission-4.1.18
Jonathan Challinger 10 years ago committed by Randy Mackay
parent
commit
f381ef93e8
  1. 6
      libraries/AP_Baro/AP_Baro.cpp
  2. 3
      libraries/AP_Baro/AP_Baro.h

6
libraries/AP_Baro/AP_Baro.cpp

@ -208,6 +208,12 @@ float AP_Baro::get_EAS2TAS(void) @@ -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

3
libraries/AP_Baro/AP_Baro.h

@ -79,6 +79,9 @@ public: @@ -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);

Loading…
Cancel
Save