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/tests/test_baro_atmosphere.cpp
Views: 1799
/*1test atmospheric model2to build, use:3./waf configure --board sitl --debug4./waf --target tests/test_baro_atmosphere5*/6#include <AP_gtest.h>78#include <AP_Baro/AP_Baro.h>910const AP_HAL::HAL& hal = AP_HAL::get_HAL();1112TEST(AP_Baro, get_air_density_for_alt_amsl)13{14float accuracy = 1E-6;1516EXPECT_NEAR(AP_Baro::get_air_density_for_alt_amsl(-4000), 1.7697266, accuracy);17EXPECT_NEAR(AP_Baro::get_air_density_for_alt_amsl(6000), 0.66011156, accuracy);18EXPECT_NEAR(AP_Baro::get_air_density_for_alt_amsl(17500), 131.5688E-3, accuracy);19EXPECT_NEAR(AP_Baro::get_air_density_for_alt_amsl(25000), 40.08393E-3, accuracy);20EXPECT_NEAR(AP_Baro::get_air_density_for_alt_amsl(40000), 3.99567824728293E-3, accuracy);21EXPECT_NEAR(AP_Baro::get_air_density_for_alt_amsl(49000), 1.16276961471707E-3, accuracy);22EXPECT_NEAR(AP_Baro::get_air_density_for_alt_amsl(65000), 163.210100967015E-6, accuracy);23EXPECT_NEAR(AP_Baro::get_air_density_for_alt_amsl(78000), 25.2385188936996E-6, accuracy);24}2526TEST(AP_Baro, get_altitude_from_pressure)27{28AP_Baro baro;29float accuracy = 1.5E-1;3031EXPECT_NEAR(baro.get_altitude_from_pressure(159598.2), -4000, accuracy);32EXPECT_NEAR(baro.get_altitude_from_pressure(47217.6), 6000, accuracy);33EXPECT_NEAR(baro.get_altitude_from_pressure(8182.3), 17500, accuracy);34EXPECT_NEAR(baro.get_altitude_from_pressure(2549.2), 25000, accuracy);35EXPECT_NEAR(baro.get_altitude_from_pressure(287.1441), 40000, accuracy);36EXPECT_NEAR(baro.get_altitude_from_pressure(90.3365), 49000, accuracy);37EXPECT_NEAR(baro.get_altitude_from_pressure(10.9297), 65000, accuracy);38EXPECT_NEAR(baro.get_altitude_from_pressure(1.4674), 78000, accuracy);39}4041TEST(AP_Baro, get_temperature_from_altitude)42{43AP_Baro baro;4445EXPECT_FLOAT_EQ(baro.get_temperature_from_altitude(-4000), 314.166370821781);46EXPECT_FLOAT_EQ(baro.get_temperature_from_altitude(6000), 249.186776458540);47EXPECT_FLOAT_EQ(baro.get_temperature_from_altitude(17500), 216.650000000000);48EXPECT_FLOAT_EQ(baro.get_temperature_from_altitude(25000), 221.552064726284);49EXPECT_FLOAT_EQ(baro.get_temperature_from_altitude(40000), 250.349646102421);50EXPECT_FLOAT_EQ(baro.get_temperature_from_altitude(49000), 270.650000000000);51EXPECT_FLOAT_EQ(baro.get_temperature_from_altitude(65000), 233.292172386848);52EXPECT_FLOAT_EQ(baro.get_temperature_from_altitude(78000), 202.540977853740);53}5455TEST(AP_Baro, geopotential_alt_to_geometric)56{57EXPECT_FLOAT_EQ(AP_Baro::geopotential_alt_to_geometric(-4002.51858796625), -4000);58EXPECT_FLOAT_EQ(AP_Baro::geopotential_alt_to_geometric(5994.34208330151), 6000.0);59EXPECT_FLOAT_EQ(AP_Baro::geopotential_alt_to_geometric(17451.9552525734), 17500);60EXPECT_FLOAT_EQ(AP_Baro::geopotential_alt_to_geometric(24902.0647262842), 25000);61EXPECT_FLOAT_EQ(AP_Baro::geopotential_alt_to_geometric(39749.8736080075), 40000);62EXPECT_FLOAT_EQ(AP_Baro::geopotential_alt_to_geometric(48625.1814380981), 49000);63EXPECT_FLOAT_EQ(AP_Baro::geopotential_alt_to_geometric(64342.0812904114), 65000);64EXPECT_FLOAT_EQ(AP_Baro::geopotential_alt_to_geometric(77054.5110731299), 78000);65}6667TEST(AP_Baro, geometric_alt_to_geopotential)68{69EXPECT_FLOAT_EQ(AP_Baro::geometric_alt_to_geopotential(-4000), -4002.51858796625);70EXPECT_FLOAT_EQ(AP_Baro::geometric_alt_to_geopotential(6000), 5994.34208330151);71EXPECT_FLOAT_EQ(AP_Baro::geometric_alt_to_geopotential(17500), 17451.9552525734);72EXPECT_FLOAT_EQ(AP_Baro::geometric_alt_to_geopotential(25000), 24902.0647262842);73EXPECT_FLOAT_EQ(AP_Baro::geometric_alt_to_geopotential(40000), 39749.8736080075);74EXPECT_FLOAT_EQ(AP_Baro::geometric_alt_to_geopotential(49000), 48625.1814380981);75EXPECT_FLOAT_EQ(AP_Baro::geometric_alt_to_geopotential(65000), 64342.0812904114);76EXPECT_FLOAT_EQ(AP_Baro::geometric_alt_to_geopotential(78000), 77054.5110731299);77}7879TEST(AP_Baro, get_pressure_temperature_for_alt_amsl)80{81float accuracy = 1E-6;8283// layer 0 -4000 m84float pressure, temperature_K;85AP_Baro::get_pressure_temperature_for_alt_amsl(-4000, pressure, temperature_K);86// EXPECT_FLOAT_EQ(pressure, 159598.164433755); // Matlab87EXPECT_FLOAT_EQ(pressure, 159598.09375);88EXPECT_FLOAT_EQ(temperature_K, 314.166370821781);8990// layer 0: 6000 m91AP_Baro::get_pressure_temperature_for_alt_amsl(6000, pressure, temperature_K);92EXPECT_FLOAT_EQ(pressure, 47217.6489854302);93EXPECT_FLOAT_EQ(temperature_K, 249.186776458540);9495// layer 1: 17500 m96AP_Baro::get_pressure_temperature_for_alt_amsl(17500, pressure, temperature_K);97EXPECT_FLOAT_EQ(pressure, 8182.27857345022);98EXPECT_FLOAT_EQ(temperature_K, 216.650000000000);99100// layer 2: 25000m101AP_Baro::get_pressure_temperature_for_alt_amsl(25000, pressure, temperature_K);102// EXPECT_FLOAT_EQ(pressure, 2549.22361148236); // Matlab103EXPECT_FLOAT_EQ(pressure, 2549.2251);104EXPECT_FLOAT_EQ(temperature_K, 221.552064726284);105106// layer 3: 40000m107AP_Baro::get_pressure_temperature_for_alt_amsl(40000, pressure, temperature_K);108EXPECT_FLOAT_EQ(pressure, 287.144059695555);109EXPECT_FLOAT_EQ(temperature_K, 250.349646102421);110111// layer 4: 49000m112AP_Baro::get_pressure_temperature_for_alt_amsl(49000, pressure, temperature_K);113EXPECT_FLOAT_EQ(pressure, 90.3365441635632);114EXPECT_FLOAT_EQ(temperature_K, 270.650000000000);115116// layer 5: 65000m117AP_Baro::get_pressure_temperature_for_alt_amsl(65000, pressure, temperature_K);118// EXPECT_FLOAT_EQ(pressure, 10.9297197424037); // Matlab119EXPECT_FLOAT_EQ(pressure, 10.929715);120EXPECT_FLOAT_EQ(temperature_K, 233.292172386848);121122// layer 6: 78000m123AP_Baro::get_pressure_temperature_for_alt_amsl(78000, pressure, temperature_K);124// EXPECT_FLOAT_EQ(pressure, 1.46736727632119); // matlab125EXPECT_NEAR(pressure, 1.4673687, accuracy);126EXPECT_FLOAT_EQ(temperature_K, 202.540977853740);127}128129AP_GTEST_MAIN()130131132