From f381ef93e886152ce5e1b5f2bd70067ac66353a6 Mon Sep 17 00:00:00 2001 From: Jonathan Challinger Date: Tue, 28 Apr 2015 11:15:49 -0700 Subject: [PATCH] AP_Baro: add get_air_density_ratio --- libraries/AP_Baro/AP_Baro.cpp | 6 ++++++ libraries/AP_Baro/AP_Baro.h | 3 +++ 2 files changed, 9 insertions(+) diff --git a/libraries/AP_Baro/AP_Baro.cpp b/libraries/AP_Baro/AP_Baro.cpp index 45f7c27385..f412fe4f5b 100644 --- a/libraries/AP_Baro/AP_Baro.cpp +++ b/libraries/AP_Baro/AP_Baro.cpp @@ -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 diff --git a/libraries/AP_Baro/AP_Baro.h b/libraries/AP_Baro/AP_Baro.h index 91f9bee174..6a0eed037b 100644 --- a/libraries/AP_Baro/AP_Baro.h +++ b/libraries/AP_Baro/AP_Baro.h @@ -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);