mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-04-14 10:07:39 +08:00
new library for atmosphere calculations
Signed-off-by: RomanBapst <bapstroman@gmail.com>
This commit is contained in:
parent
f120ebcdc0
commit
ecb78ca207
@ -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)
|
||||
|
||||
@ -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)
|
||||
@ -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;
|
||||
@ -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);
|
||||
|
||||
@ -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));
|
||||
}
|
||||
|
||||
@ -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;
|
||||
@ -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);
|
||||
|
||||
@ -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
|
||||
|
||||
37
src/lib/atmosphere/CMakeLists.txt
Normal file
37
src/lib/atmosphere/CMakeLists.txt
Normal file
@ -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
src/lib/atmosphere/atmosphere.cpp
Normal file
81
src/lib/atmosphere/atmosphere.cpp
Normal file
@ -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
src/lib/atmosphere/atmosphere.h
Normal file
80
src/lib/atmosphere/atmosphere.h
Normal file
@ -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_
|
||||
126
src/lib/atmosphere/test_atmosphere.cpp
Normal file
126
src/lib/atmosphere/test_atmosphere.cpp
Normal file
@ -0,0 +1,126 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* 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.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* To run this test only use: make tests TESTFILTER=atmosphere
|
||||
*/
|
||||
|
||||
#include <gtest/gtest.h>
|
||||
#include <lib/atmosphere/atmosphere.h>
|
||||
using namespace atmosphere;
|
||||
|
||||
TEST(TestAtmosphere, pressureFromAltitude)
|
||||
{
|
||||
// GIVEN pressure at seal level in standard atmosphere and sea level altitude
|
||||
const float pressureAtSeaLevel = 101325.f; // Pa
|
||||
float altitude = 0.0f;
|
||||
|
||||
// WHEN we calculate pressure based on altitude
|
||||
float pressure = getPressureFromAltitude(altitude);
|
||||
|
||||
// THEN expect seal level pressure for standard atmosphere
|
||||
EXPECT_FLOAT_EQ(pressure, pressureAtSeaLevel);
|
||||
|
||||
// WHEN we are at 3000m altitude
|
||||
altitude = 3000.0f;
|
||||
pressure = getPressureFromAltitude(altitude);
|
||||
|
||||
// THEN expect standard atmosphere pressure at 3000m (error of 10Pa corresponds to 1m altitude error in standard atmosphere when altitude is between 1000 and 2000m)
|
||||
EXPECT_NEAR(pressure, 70120.f, 10.0f);
|
||||
}
|
||||
|
||||
TEST(TestAtmosphere, altitudeFromPressure)
|
||||
{
|
||||
// GIVEN pressure at seal level in standard atmosphere
|
||||
const float pressureAtSealevel = 101325.f;
|
||||
float pressure = pressureAtSealevel;
|
||||
|
||||
// WHEN we calculate altitude from pressure
|
||||
float altitude = getAltitudeFromPressure(pressure, pressureAtSealevel);
|
||||
|
||||
// THEN expect resulting altitude to be near sea level
|
||||
EXPECT_FLOAT_EQ(altitude, 0.0f);
|
||||
|
||||
// GIVEN pressure is standard atmosphere pressure at 3000m
|
||||
pressure = 70109.f;
|
||||
|
||||
// WHEN we calculate altitude from pressure
|
||||
altitude = getAltitudeFromPressure(pressure, pressureAtSealevel);
|
||||
|
||||
// THEN expect altitude to be near 3000m
|
||||
EXPECT_NEAR(altitude, 3000.0f, 0.5f);
|
||||
}
|
||||
|
||||
TEST(TestAtmosphere, DensityFromPressure)
|
||||
{
|
||||
// GIVEN standard atmosphere at sea level
|
||||
const float pressureAtSealevel = 101325.f;
|
||||
const float tempSeaLevel = 15.f;
|
||||
|
||||
// WHEN we calculate density from pressure and temperature
|
||||
float density = getDensityFromPressureAndTemp(pressureAtSealevel, tempSeaLevel);
|
||||
|
||||
// THEN expect density at sea level in standard atmosphere
|
||||
EXPECT_NEAR(density, 1.225f, 0.001f);
|
||||
|
||||
// GIVEN standard atmosphere at 3000m
|
||||
const float pressure = 70109.f;
|
||||
const float tempAt3000m = -4.5f;
|
||||
|
||||
// WHEN we calculate density from pressure and temperature
|
||||
density = getDensityFromPressureAndTemp(pressure, tempAt3000m);
|
||||
|
||||
// THEN expect density at 3000m in standard atmosphere
|
||||
EXPECT_NEAR(density, 0.9091f, 0.001f);
|
||||
}
|
||||
|
||||
TEST(TestAtmosphere, StandardTemperature)
|
||||
{
|
||||
// GIVEN standard atmosphere at sea level
|
||||
float altitude = 0.f;
|
||||
|
||||
// WHEN we calculate standard temperature from altitude
|
||||
float temperature = getStandardTemperatureAtAltitude(altitude);
|
||||
|
||||
// THEN expect standard temperature at sea level
|
||||
EXPECT_NEAR(temperature, 15.f, 0.001f);
|
||||
|
||||
// GIVEN standard atmosphere at 3000m
|
||||
altitude = 3000.f;
|
||||
|
||||
// WHEN we calculate standard temperature from altitude
|
||||
temperature = getStandardTemperatureAtAltitude(altitude);
|
||||
|
||||
// THEN expect standard temperature at 3000m
|
||||
EXPECT_NEAR(temperature, -4.5f, 0.001f);
|
||||
}
|
||||
@ -40,4 +40,6 @@ target_link_libraries(vehicle_air_data
|
||||
data_validator
|
||||
px4_work_queue
|
||||
sensor_calibration
|
||||
PUBLIC
|
||||
atmosphere
|
||||
)
|
||||
|
||||
@ -36,11 +36,14 @@
|
||||
#include <px4_platform_common/log.h>
|
||||
#include <px4_platform_common/events.h>
|
||||
#include <lib/geo/geo.h>
|
||||
#include <lib/atmosphere/atmosphere.h>
|
||||
|
||||
|
||||
namespace sensors
|
||||
{
|
||||
|
||||
using namespace matrix;
|
||||
using namespace atmosphere;
|
||||
|
||||
static constexpr uint32_t SENSOR_TIMEOUT{300_ms};
|
||||
|
||||
@ -189,8 +192,9 @@ void VehicleAirData::Run()
|
||||
// pressure corrected with offset (if available)
|
||||
_calibration[uorb_index].SensorCorrectionsUpdate();
|
||||
const float pressure_corrected = _calibration[uorb_index].Correct(report.pressure);
|
||||
const float pressure_sealevel_pa = _param_sens_baro_qnh.get() * 100.f;
|
||||
|
||||
float data_array[3] {pressure_corrected, report.temperature, PressureToAltitude(pressure_corrected)};
|
||||
float data_array[3] {pressure_corrected, report.temperature, getAltitudeFromPressure(pressure_corrected, pressure_sealevel_pa)};
|
||||
_voter.put(uorb_index, report.timestamp, data_array, report.error_count, _priority[uorb_index]);
|
||||
|
||||
_timestamp_sample_sum[uorb_index] += report.timestamp_sample;
|
||||
@ -251,11 +255,11 @@ void VehicleAirData::Run()
|
||||
const float pressure_pa = _data_sum[instance] / _data_sum_count[instance];
|
||||
const float temperature = _temperature_sum[instance] / _data_sum_count[instance];
|
||||
|
||||
float altitude = PressureToAltitude(pressure_pa, temperature);
|
||||
const float pressure_sealevel_pa = _param_sens_baro_qnh.get() * 100.f;
|
||||
const float altitude = getAltitudeFromPressure(pressure_pa, pressure_sealevel_pa);
|
||||
|
||||
// calculate air density
|
||||
float air_density = pressure_pa / (CONSTANTS_AIR_GAS_CONST * (_air_temperature_celsius -
|
||||
CONSTANTS_ABSOLUTE_NULL_CELSIUS));
|
||||
const float air_density = getDensityFromPressureAndTemp(pressure_pa, temperature);
|
||||
|
||||
// populate vehicle_air_data with and publish
|
||||
vehicle_air_data_s out{};
|
||||
@ -295,32 +299,6 @@ void VehicleAirData::Run()
|
||||
perf_end(_cycle_perf);
|
||||
}
|
||||
|
||||
float VehicleAirData::PressureToAltitude(float pressure_pa, float temperature) const
|
||||
{
|
||||
// calculate altitude using the hypsometric equation
|
||||
static constexpr float T1 = 15.f - CONSTANTS_ABSOLUTE_NULL_CELSIUS; // temperature at base height in Kelvin
|
||||
static constexpr float a = -6.5f / 1000.f; // temperature gradient in degrees per metre
|
||||
|
||||
// current pressure at MSL in kPa (QNH in hPa)
|
||||
const float p1 = _param_sens_baro_qnh.get() * 0.1f;
|
||||
|
||||
// measured pressure in kPa
|
||||
const float p = pressure_pa * 0.001f;
|
||||
|
||||
/*
|
||||
* Solve:
|
||||
*
|
||||
* / -(aR / g) \
|
||||
* | (p / p1) . T1 | - T1
|
||||
* \ /
|
||||
* h = ------------------------------- + h1
|
||||
* a
|
||||
*/
|
||||
float altitude = (((powf((p / p1), (-(a * CONSTANTS_AIR_GAS_CONST) / CONSTANTS_ONE_G))) * T1) - T1) / a;
|
||||
|
||||
return altitude;
|
||||
}
|
||||
|
||||
void VehicleAirData::CheckFailover(const hrt_abstime &time_now_us)
|
||||
{
|
||||
// check failover and report (save failover report for a cycle where parameters didn't update)
|
||||
|
||||
@ -79,8 +79,6 @@ private:
|
||||
bool ParametersUpdate(bool force = false);
|
||||
void UpdateStatus();
|
||||
|
||||
float PressureToAltitude(float pressure_pa, float temperature = 15.f) const;
|
||||
|
||||
static constexpr int MAX_SENSOR_COUNT = 4;
|
||||
|
||||
uORB::Publication<sensors_status_s> _sensors_status_baro_pub{ORB_ID(sensors_status_baro)};
|
||||
|
||||
Loading…
x
Reference in New Issue
Block a user