Skip to content

Commit

Permalink
new library for atmosphere calculations
Browse files Browse the repository at this point in the history
Signed-off-by: RomanBapst <[email protected]>
  • Loading branch information
RomanBapst authored Oct 21, 2023
1 parent f120ebc commit ecb78ca
Show file tree
Hide file tree
Showing 10 changed files with 341 additions and 57 deletions.
1 change: 1 addition & 0 deletions src/lib/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -33,6 +33,7 @@

add_subdirectory(adsb EXCLUDE_FROM_ALL)
add_subdirectory(airspeed EXCLUDE_FROM_ALL)
add_subdirectory(atmosphere EXCLUDE_FROM_ALL)
add_subdirectory(avoidance EXCLUDE_FROM_ALL)
add_subdirectory(battery EXCLUDE_FROM_ALL)
add_subdirectory(bezier EXCLUDE_FROM_ALL)
Expand Down
30 changes: 6 additions & 24 deletions src/lib/airspeed/airspeed.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -44,6 +44,9 @@

#include <px4_platform_common/defines.h>
#include <lib/geo/geo.h>
#include <lib/atmosphere/atmosphere.h>

using atmosphere::getDensityFromPressureAndTemp;

float calc_IAS_corrected(enum AIRSPEED_COMPENSATION_MODEL pmodel, enum AIRSPEED_SENSOR_MODEL smodel,
float tube_len, float tube_dia_mm, float differential_pressure, float pressure_ambient, float temperature_celsius)
Expand All @@ -53,7 +56,7 @@ float calc_IAS_corrected(enum AIRSPEED_COMPENSATION_MODEL pmodel, enum AIRSPEED_
}

// air density in kg/m3
const float rho_air = get_air_density(pressure_ambient, temperature_celsius);
const float rho_air = getDensityFromPressureAndTemp(pressure_ambient, temperature_celsius);

const float dp = fabsf(differential_pressure);
float dp_tot = dp;
Expand Down Expand Up @@ -153,18 +156,6 @@ float calc_IAS_corrected(enum AIRSPEED_COMPENSATION_MODEL pmodel, enum AIRSPEED_
break;
}

// if (!PX4_ISFINITE(dp_tube)) {
// dp_tube = 0.0f;
// }

// if (!PX4_ISFINITE(dp_pitot)) {
// dp_pitot = 0.0f;
// }

// if (!PX4_ISFINITE(dv)) {
// dv = 0.0f;
// }

// computed airspeed without correction for inflow-speed at tip of pitot-tube
const float airspeed_uncorrected = sqrtf(2.0f * dp_tot / CONSTANTS_AIR_DENSITY_SEA_LEVEL_15C);

Expand Down Expand Up @@ -192,7 +183,7 @@ float calc_TAS_from_CAS(float speed_calibrated, float pressure_ambient, float te
temperature_celsius = 15.f; // ICAO Standard Atmosphere 15 degrees Celsius
}

return speed_calibrated * sqrtf(CONSTANTS_AIR_DENSITY_SEA_LEVEL_15C / get_air_density(pressure_ambient,
return speed_calibrated * sqrtf(CONSTANTS_AIR_DENSITY_SEA_LEVEL_15C / getDensityFromPressureAndTemp(pressure_ambient,
temperature_celsius));
}

Expand All @@ -203,7 +194,7 @@ float calc_CAS_from_IAS(float speed_indicated, float scale)

float calc_TAS(float total_pressure, float static_pressure, float temperature_celsius)
{
float density = get_air_density(static_pressure, temperature_celsius);
float density = getDensityFromPressureAndTemp(static_pressure, temperature_celsius);

if (density < 0.0001f || !PX4_ISFINITE(density)) {
density = CONSTANTS_AIR_DENSITY_SEA_LEVEL_15C;
Expand All @@ -219,15 +210,6 @@ float calc_TAS(float total_pressure, float static_pressure, float temperature_ce
}
}

float get_air_density(float static_pressure, float temperature_celsius)
{
if (!PX4_ISFINITE(temperature_celsius)) {
temperature_celsius = 15.f; // ICAO Standard Atmosphere 15 degrees Celsius
}

return static_pressure / (CONSTANTS_AIR_GAS_CONST * (temperature_celsius - CONSTANTS_ABSOLUTE_NULL_CELSIUS));
}

float calc_calibrated_from_true_airspeed(float speed_true, float air_density)
{
return speed_true * sqrtf(air_density / CONSTANTS_AIR_DENSITY_SEA_LEVEL_15C);
Expand Down
1 change: 0 additions & 1 deletion src/lib/airspeed/airspeed.h
Original file line number Diff line number Diff line change
Expand Up @@ -127,7 +127,6 @@ __EXPORT float calc_TAS(float total_pressure, float static_pressure, float tempe
* @param static_pressure ambient pressure in millibar
* @param temperature_celcius air / ambient temperature in Celsius
*/
__EXPORT float get_air_density(float static_pressure, float temperature_celsius);

/**
* @brief Calculates calibrated airspeed from true airspeed and air density
Expand Down
37 changes: 37 additions & 0 deletions src/lib/atmosphere/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,37 @@
############################################################################
#
# Copyright (c) 2023 PX4 Development Team. All rights reserved.
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
# are met:
#
# 1. Redistributions of source code must retain the above copyright
# notice, this list of conditions and the following disclaimer.
# 2. Redistributions in binary form must reproduce the above copyright
# notice, this list of conditions and the following disclaimer in
# the documentation and/or other materials provided with the
# distribution.
# 3. Neither the name PX4 nor the names of its contributors may be
# used to endorse or promote products derived from this software
# without specific prior written permission.
#
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# POSSIBILITY OF SUCH DAMAGE.
#
############################################################################

px4_add_library(atmosphere
atmosphere.cpp
)
px4_add_unit_gtest(SRC test_atmosphere.cpp LINKLIBS atmosphere)
81 changes: 81 additions & 0 deletions src/lib/atmosphere/atmosphere.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,81 @@
/****************************************************************************
*
* Copyright (C) 2023 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/

/**
* @file atmosphere.cpp
*
*/

#include <geo/geo.h>
#include "atmosphere.h"
namespace atmosphere
{

static constexpr float kTempRefKelvin = 15.f - CONSTANTS_ABSOLUTE_NULL_CELSIUS; // temperature at base height in Kelvin
static constexpr float kTempGradient = -6.5f / 1000.f; // temperature gradient in degrees per meter
static constexpr float kPressRefSeaLevelPa = 101325.f; // pressure at sea level in Pa

float getDensityFromPressureAndTemp(const float pressure_pa, const float temperature_celsius)
{
return (pressure_pa / (CONSTANTS_AIR_GAS_CONST * (temperature_celsius - CONSTANTS_ABSOLUTE_NULL_CELSIUS)));
}
float getPressureFromAltitude(const float altitude_m)
{

return kPressRefSeaLevelPa * powf((altitude_m * kTempGradient + kTempRefKelvin) / kTempRefKelvin,
-CONSTANTS_ONE_G / (kTempGradient * CONSTANTS_AIR_GAS_CONST));
}
float getAltitudeFromPressure(float pressure_pa, float pressure_sealevel_pa)
{
// calculate altitude using the hypsometric equation

const float pressure_ratio = pressure_pa / pressure_sealevel_pa;

/*
* Solve:
*
* / -(aR / g) \
* | (p / p1) . T1 | - T1
* \ /
* h = ------------------------------- + h1
* a
*/
return (((powf(pressure_ratio, (-(kTempGradient * CONSTANTS_AIR_GAS_CONST) / CONSTANTS_ONE_G))) * kTempRefKelvin) -
kTempRefKelvin) / kTempGradient;

}
float getStandardTemperatureAtAltitude(float altitude_m)
{
return 15.0f + kTempGradient * altitude_m;
}
}
80 changes: 80 additions & 0 deletions src/lib/atmosphere/atmosphere.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,80 @@
/****************************************************************************
*
* Copyright (c) 2023 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/

/**
* @file atmosphere.h
*
*/

#ifndef PX4_SRC_LIB_ATMOSPHERE_ATMOSPHERE_H_
#define PX4_SRC_LIB_ATMOSPHERE_ATMOSPHERE_H_

namespace atmosphere
{

// NOTE: We are currently only modelling the first layer of the US Standard Atmosphere 1976.
// This means that the functions are only valid up to an altitude of 11km.

/**
* Calculate air density given air pressure and temperature.
*
* @param pressure_pa ambient pressure in Pa
* @param temperature_celsius ambient temperature in degrees Celsius
*/
float getDensityFromPressureAndTemp(const float pressure_pa, const float temperature_celsius);

/**
* Calculate standard airpressure given altitude.
*
* @param altitude_m altitude above MSL in meters in the standard atmosphere
*/
float getPressureFromAltitude(const float altitude_m);

/**
* Calculate altitude from air pressure and temperature.
*
* @param pressure_pa ambient pressure in Pa
* @param pressure_sealevel_pa sea level pressure in Pa
*/
float getAltitudeFromPressure(float pressure_pa, float pressure_sealevel_pa);

/**
* Get standard temperature at altitude.
*
* @param altitude_m Altitude msl in meters
* @return Standard temperature in degrees Celsius
*/
float getStandardTemperatureAtAltitude(float altitude_m);
}

#endif //PX4_SRC_LIB_ATMOSPHERE_ATMOSPHERE_H_
Loading

0 comments on commit ecb78ca

Please sign in to comment.