Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Path: blob/master/libraries/AP_Baro/AP_Baro_atmosphere.cpp
Views: 1798
#include "AP_Baro.h"1#include <AP_InternalError/AP_InternalError.h>23/*4This program is free software: you can redistribute it and/or modify5it under the terms of the GNU General Public License as published by6the Free Software Foundation, either version 3 of the License, or7(at your option) any later version.89This program is distributed in the hope that it will be useful,10but WITHOUT ANY WARRANTY; without even the implied warranty of11MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the12GNU General Public License for more details.1314You should have received a copy of the GNU General Public License15along with this program. If not, see <http://www.gnu.org/licenses/>.16*/1718/* 1976 U.S. Standard Atmosphere: https://ntrs.nasa.gov/api/citations/19770009539/downloads/19770009539.pdf?attachment=true1920The US Standard Atmosphere defines the atmopshere in terms of whether the temperature is an iso-thermal or gradient layer.21Ideal gas laws apply thus P = rho * R_specific * T : P = pressure, rho = density, R_specific = air gas constant, T = temperature2223Note: the 1976 model is the same as the 1962 US Standard Atomsphere up to 51km.24R_universal: the universal gas constant is slightly off in the 1976 model and thus R_specific is different than today's value2526*/2728/* Model Constants29R_universal = 8.31432e-3; // Universal gas constant (J/(kmol-K)) incorrect to the redefined 2019 value of 8.31446261815324 J⋅K−1⋅mol−130M_air = (0.78084 * 28.0134 + 0.209476 * 31.9988 + 9.34e-3 * 39.948 + 3.14e-4 * 44.00995 + 1.818e-5 * 20.183 + 5.24E-6 * 4.0026 + 1.14E-6 * 83.8 + 8.7E-7 * 131.30 + 2E-6 * 16.04303 + 5E-7 * 2.01594) * 1E-3; (kg/mol)31M_air = 28.9644 // Molecular weight of air (kg/kmol) see page 332R_specific = 287.053072 // air specifc gas constant (J⋅kg−1⋅K−1), R_universal / M_air;33gama = 1.4; // specific heat ratio of air used to determine the speed of sound3435R0 = 6356.766E3; // Earth's radius (in m)36g0 = 9.80665; // gravity (m/s^2)3738Sea-Level Constants39H_asml = 0 meters40T0 = 288.150 K41P0 = 101325 Pa42rho0 = 1.2250 kg/m^343T0_slope = -6.5E-3 (K/m')4445The tables list altitudes -5 km to 0 km using the same equations as 0 km to 11 km.46*/4748/*49return altitude difference in meters between current pressure and a50given base_pressure in Pascal. This is a simple atmospheric model51good to about 11km AMSL.52*/53float AP_Baro::get_altitude_difference_simple(float base_pressure, float pressure) const54{55float ret;56float temp_K = C_TO_KELVIN(get_ground_temperature());57float scaling = pressure / base_pressure;5859// This is an exact calculation that is within +-2.5m of the standard60// atmosphere tables in the troposphere (up to 11,000 m amsl).61ret = 153.8462f * temp_K * (1.0f - expf(0.190259f * logf(scaling)));6263return ret;64}6566#if AP_BARO_1976_STANDARD_ATMOSPHERE_ENABLED || AP_SIM_ENABLED6768/*69Note parameters are as defined in the 1976 model.70These are slightly different from the ones in definitions.h71*/72static const float radius_earth = 6356.766E3; // Earth's radius (in m)73static const float R_specific = 287.053072; // air specifc gas constant (J⋅kg−1⋅K−1) in 1976 model, R_universal / M_air;7475static const struct {76float amsl_m; // geopotential height above mean sea-level (km')77float temp_K; // Temperature (K)78float pressure_Pa; // Pressure (Pa)79float density; // Density (Pa/kg)80float temp_lapse; // Temperature gradients rates (K/m'), see page 381} atmospheric_1976_consts[] = {82{ -5000, 320.650, 177687, 1.930467, -6.5E-3 },83{ 11000, 216.650, 22632.1, 0.363918, 0 },84{ 20000, 216.650, 5474.89, 8.80349E-2, 1E-3 },85{ 32000, 228.650, 868.019, 1.32250E-2, 2.8E-3 },86{ 47000, 270.650, 110.906, 1.42753E-3, 0 },87{ 51000, 270.650, 66.9389, 8.61606E-4, -2.8E-3 },88{ 71000, 214.650, 3.95642, 6.42110E-5, -2.0E-3 },89{ 84852, 186.946, 0.37338, 6.95788E-6, 0 },90};9192/*93find table entry given geopotential altitude in meters. This returns at least 194*/95static uint8_t find_atmosphere_layer_by_altitude(float alt_m)96{97for (uint8_t idx = 1; idx < ARRAY_SIZE(atmospheric_1976_consts); idx++) {98if(alt_m < atmospheric_1976_consts[idx].amsl_m) {99return idx - 1;100}101}102103// Over the largest altitude return the last index104return ARRAY_SIZE(atmospheric_1976_consts) - 1;105}106107/*108find table entry given pressure (Pa). This returns at least 1109*/110static uint8_t find_atmosphere_layer_by_pressure(float pressure)111{112for (uint8_t idx = 1; idx < ARRAY_SIZE(atmospheric_1976_consts); idx++) {113if (atmospheric_1976_consts[idx].pressure_Pa < pressure) {114return idx - 1;115}116}117118// pressure is less than the smallest pressure return the last index119return ARRAY_SIZE(atmospheric_1976_consts) - 1;120121}122123// Convert geopotential altitude to geometric altitude124//125float AP_Baro::geopotential_alt_to_geometric(float alt)126{127return (radius_earth * alt) / (radius_earth - alt);128}129130float AP_Baro::geometric_alt_to_geopotential(float alt)131{132return (radius_earth * alt) / (radius_earth + alt);133}134135/*136Compute expected temperature for a given geometric altitude and altitude layer.137*/138float AP_Baro::get_temperature_from_altitude(float alt) const139{140alt = geometric_alt_to_geopotential(alt);141const uint8_t idx = find_atmosphere_layer_by_altitude(alt);142return get_temperature_by_altitude_layer(alt, idx);143}144145/*146Compute expected temperature for a given geopotential altitude and altitude layer.147*/148float AP_Baro::get_temperature_by_altitude_layer(float alt, int8_t idx)149{150if (is_zero(atmospheric_1976_consts[idx].temp_lapse)) {151return atmospheric_1976_consts[idx].temp_K;152}153return atmospheric_1976_consts[idx].temp_K + atmospheric_1976_consts[idx].temp_lapse * (alt - atmospheric_1976_consts[idx].amsl_m);154}155156/*157return geometric altitude (m) given a pressure (Pa)158*/159float AP_Baro::get_altitude_from_pressure(float pressure) const160{161const uint8_t idx = find_atmosphere_layer_by_pressure(pressure);162const float pressure_ratio = pressure / atmospheric_1976_consts[idx].pressure_Pa;163164// Pressure ratio is nonsensical return an error??165if (!is_positive(pressure_ratio)) {166INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control);167return get_altitude_AMSL();168}169170float alt;171const float temp_slope = atmospheric_1976_consts[idx].temp_lapse;172if (is_zero(temp_slope)) { // Iso-thermal layer173const float fac = -(atmospheric_1976_consts[idx].temp_K * R_specific) / GRAVITY_MSS;174alt = atmospheric_1976_consts[idx].amsl_m + fac * logf(pressure_ratio);175} else { // Gradient temperature layer176const float fac = -(temp_slope * R_specific) / GRAVITY_MSS;177alt = atmospheric_1976_consts[idx].amsl_m + (atmospheric_1976_consts[idx].temp_K / atmospheric_1976_consts[idx].temp_lapse) * (powf(pressure_ratio, fac) - 1);178}179180return geopotential_alt_to_geometric(alt);181}182183/*184Compute expected pressure and temperature for a given geometric altitude. Used for SITL185*/186void AP_Baro::get_pressure_temperature_for_alt_amsl(float alt_amsl, float &pressure, float &temperature_K)187{188alt_amsl = geometric_alt_to_geopotential(alt_amsl);189190const uint8_t idx = find_atmosphere_layer_by_altitude(alt_amsl);191const float temp_slope = atmospheric_1976_consts[idx].temp_lapse;192temperature_K = get_temperature_by_altitude_layer(alt_amsl, idx);193194// Previous versions used the current baro temperature instead of an estimate we could try to incorporate this??? non-standard atmosphere195// const float temp = get_temperature();196197if (is_zero(temp_slope)) { // Iso-thermal layer198const float fac = expf(-GRAVITY_MSS / (temperature_K * R_specific) * (alt_amsl - atmospheric_1976_consts[idx].amsl_m));199pressure = atmospheric_1976_consts[idx].pressure_Pa * fac;200} else { // Gradient temperature layer201const float fac = GRAVITY_MSS / (temp_slope * R_specific);202const float temp_ratio = temperature_K / atmospheric_1976_consts[idx].temp_K; // temperature ratio [unitless]203pressure = atmospheric_1976_consts[idx].pressure_Pa * powf(temp_ratio, -fac);204}205}206207/*208return air density (kg/m^3), given geometric altitude (m)209*/210float AP_Baro::get_air_density_for_alt_amsl(float alt_amsl)211{212alt_amsl = geometric_alt_to_geopotential(alt_amsl);213214const uint8_t idx = find_atmosphere_layer_by_altitude(alt_amsl);215const float temp_slope = atmospheric_1976_consts[idx].temp_lapse;216const float temp = get_temperature_by_altitude_layer(alt_amsl, idx);217// const float temp = get_temperature();218219float rho;220if (is_zero(temp_slope)) { // Iso-thermal layer221const float fac = expf(-GRAVITY_MSS / (temp * R_specific) * (alt_amsl - atmospheric_1976_consts[idx].amsl_m));222rho = atmospheric_1976_consts[idx].density * fac;223} else { // Gradient temperature layer224const float fac = GRAVITY_MSS / (temp_slope * R_specific);225const float temp_ratio = temp / atmospheric_1976_consts[idx].temp_K; // temperature ratio [unitless]226rho = atmospheric_1976_consts[idx].density * powf(temp_ratio, -(fac + 1));227}228return rho;229}230231/*232return current scale factor that converts from equivalent to true airspeed233*/234float AP_Baro::get_EAS2TAS_extended(float altitude) const235{236float density = get_air_density_for_alt_amsl(altitude);237if (!is_positive(density)) {238// above this height we are getting closer to spacecraft territory...239const uint8_t table_size = ARRAY_SIZE(atmospheric_1976_consts);240density = atmospheric_1976_consts[table_size-1].density;241}242return sqrtf(SSL_AIR_DENSITY / density);243}244245/*246Given the geometric altitude (m)247return scale factor that converts from equivalent to true airspeed248used by SITL only249*/250float AP_Baro::get_EAS2TAS_for_alt_amsl(float alt_amsl)251{252const float density = get_air_density_for_alt_amsl(alt_amsl);253return sqrtf(SSL_AIR_DENSITY / MAX(0.00001,density));254}255256#endif // AP_BARO_1976_STANDARD_ATMOSPHERE_ENABLED || AP_SIM_ENABLED257258/*259return geometric altitude difference in meters between current pressure and a260given base_pressure in Pascal.261*/262float AP_Baro::get_altitude_difference(float base_pressure, float pressure) const263{264#if AP_BARO_1976_STANDARD_ATMOSPHERE_ENABLED265const float alt1 = get_altitude_from_pressure(base_pressure);266const float alt2 = get_altitude_from_pressure(pressure);267return alt2 - alt1;268#else269return get_altitude_difference_simple(base_pressure, pressure);270#endif271}272273/*274return current scale factor that converts from equivalent to true airspeed275valid for altitudes up to 11km AMSL276assumes USA 1976 standard atmosphere lapse rate277*/278float AP_Baro::get_EAS2TAS_simple(float altitude, float pressure) const279{280if (is_zero(pressure)) {281return 1.0f;282}283284// only estimate lapse rate for the difference from the ground location285// provides a more consistent reading then trying to estimate a complete286// ISA model atmosphere287float tempK = C_TO_KELVIN(get_ground_temperature()) - ISA_LAPSE_RATE * altitude;288const float eas2tas_squared = SSL_AIR_DENSITY / (pressure / (ISA_GAS_CONSTANT * tempK));289if (!is_positive(eas2tas_squared)) {290return 1.0f;291}292return sqrtf(eas2tas_squared);293}294295/*296return current scale factor that converts from equivalent to true airspeed297*/298float AP_Baro::_get_EAS2TAS(void) const299{300const float altitude = get_altitude_AMSL();301302#if AP_BARO_1976_STANDARD_ATMOSPHERE_ENABLED303return get_EAS2TAS_extended(altitude);304#else305// otherwise use function306return get_EAS2TAS_simple(altitude, get_pressure());307#endif308}309310#if AP_BARO_1976_STANDARD_ATMOSPHERE_ENABLED || AP_SIM_ENABLED311// lookup expected temperature in degrees C for a given altitude. Used for SITL backend312float AP_Baro::get_temperatureC_for_alt_amsl(const float alt_amsl)313{314float pressure, temp_K;315get_pressure_temperature_for_alt_amsl(alt_amsl, pressure, temp_K);316return KELVIN_TO_C(temp_K);317}318319// lookup expected pressure in Pa for a given altitude. Used for SITL backend320float AP_Baro::get_pressure_for_alt_amsl(const float alt_amsl)321{322float pressure, temp_K;323get_pressure_temperature_for_alt_amsl(alt_amsl, pressure, temp_K);324return pressure;325}326#endif // AP_BARO_1976_STANDARD_ATMOSPHERE_ENABLED327328/*329return sea level pressure given a current altitude and pressure reading330this is the pressure p0 such that331get_altitude_difference(p0, pressure) == altitude332this function is used during calibration333*/334float AP_Baro::get_sealevel_pressure(float pressure, float altitude) const335{336const float min_pressure = 0.01;337const float max_pressure = 1e6;338float p0 = pressure;339/*340use a simple numerical gradient descent method so we don't need341the inverse function. This typically converges in about 5 steps,342we limit it to 20 steps to prevent possible high CPU usage343*/344uint16_t count = 20;345while (count--) {346const float delta = 0.1;347const float err1 = get_altitude_difference(p0, pressure) - altitude;348const float err2 = get_altitude_difference(p0+delta, pressure) - altitude;349const float dalt = err2 - err1;350if (fabsf(err1) < 0.01) {351break;352}353p0 -= err1 * delta / dalt;354p0 = constrain_float(p0, min_pressure, max_pressure);355}356return p0;357}358359360