CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutSign UpSign In
Ardupilot

Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.

GitHub Repository: Ardupilot/ardupilot
Path: blob/master/libraries/AP_Baro/tests/test_baro_atmosphere.cpp
Views: 1799
1
/*
2
test atmospheric model
3
to build, use:
4
./waf configure --board sitl --debug
5
./waf --target tests/test_baro_atmosphere
6
*/
7
#include <AP_gtest.h>
8
9
#include <AP_Baro/AP_Baro.h>
10
11
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
12
13
TEST(AP_Baro, get_air_density_for_alt_amsl)
14
{
15
float accuracy = 1E-6;
16
17
EXPECT_NEAR(AP_Baro::get_air_density_for_alt_amsl(-4000), 1.7697266, accuracy);
18
EXPECT_NEAR(AP_Baro::get_air_density_for_alt_amsl(6000), 0.66011156, accuracy);
19
EXPECT_NEAR(AP_Baro::get_air_density_for_alt_amsl(17500), 131.5688E-3, accuracy);
20
EXPECT_NEAR(AP_Baro::get_air_density_for_alt_amsl(25000), 40.08393E-3, accuracy);
21
EXPECT_NEAR(AP_Baro::get_air_density_for_alt_amsl(40000), 3.99567824728293E-3, accuracy);
22
EXPECT_NEAR(AP_Baro::get_air_density_for_alt_amsl(49000), 1.16276961471707E-3, accuracy);
23
EXPECT_NEAR(AP_Baro::get_air_density_for_alt_amsl(65000), 163.210100967015E-6, accuracy);
24
EXPECT_NEAR(AP_Baro::get_air_density_for_alt_amsl(78000), 25.2385188936996E-6, accuracy);
25
}
26
27
TEST(AP_Baro, get_altitude_from_pressure)
28
{
29
AP_Baro baro;
30
float accuracy = 1.5E-1;
31
32
EXPECT_NEAR(baro.get_altitude_from_pressure(159598.2), -4000, accuracy);
33
EXPECT_NEAR(baro.get_altitude_from_pressure(47217.6), 6000, accuracy);
34
EXPECT_NEAR(baro.get_altitude_from_pressure(8182.3), 17500, accuracy);
35
EXPECT_NEAR(baro.get_altitude_from_pressure(2549.2), 25000, accuracy);
36
EXPECT_NEAR(baro.get_altitude_from_pressure(287.1441), 40000, accuracy);
37
EXPECT_NEAR(baro.get_altitude_from_pressure(90.3365), 49000, accuracy);
38
EXPECT_NEAR(baro.get_altitude_from_pressure(10.9297), 65000, accuracy);
39
EXPECT_NEAR(baro.get_altitude_from_pressure(1.4674), 78000, accuracy);
40
}
41
42
TEST(AP_Baro, get_temperature_from_altitude)
43
{
44
AP_Baro baro;
45
46
EXPECT_FLOAT_EQ(baro.get_temperature_from_altitude(-4000), 314.166370821781);
47
EXPECT_FLOAT_EQ(baro.get_temperature_from_altitude(6000), 249.186776458540);
48
EXPECT_FLOAT_EQ(baro.get_temperature_from_altitude(17500), 216.650000000000);
49
EXPECT_FLOAT_EQ(baro.get_temperature_from_altitude(25000), 221.552064726284);
50
EXPECT_FLOAT_EQ(baro.get_temperature_from_altitude(40000), 250.349646102421);
51
EXPECT_FLOAT_EQ(baro.get_temperature_from_altitude(49000), 270.650000000000);
52
EXPECT_FLOAT_EQ(baro.get_temperature_from_altitude(65000), 233.292172386848);
53
EXPECT_FLOAT_EQ(baro.get_temperature_from_altitude(78000), 202.540977853740);
54
}
55
56
TEST(AP_Baro, geopotential_alt_to_geometric)
57
{
58
EXPECT_FLOAT_EQ(AP_Baro::geopotential_alt_to_geometric(-4002.51858796625), -4000);
59
EXPECT_FLOAT_EQ(AP_Baro::geopotential_alt_to_geometric(5994.34208330151), 6000.0);
60
EXPECT_FLOAT_EQ(AP_Baro::geopotential_alt_to_geometric(17451.9552525734), 17500);
61
EXPECT_FLOAT_EQ(AP_Baro::geopotential_alt_to_geometric(24902.0647262842), 25000);
62
EXPECT_FLOAT_EQ(AP_Baro::geopotential_alt_to_geometric(39749.8736080075), 40000);
63
EXPECT_FLOAT_EQ(AP_Baro::geopotential_alt_to_geometric(48625.1814380981), 49000);
64
EXPECT_FLOAT_EQ(AP_Baro::geopotential_alt_to_geometric(64342.0812904114), 65000);
65
EXPECT_FLOAT_EQ(AP_Baro::geopotential_alt_to_geometric(77054.5110731299), 78000);
66
}
67
68
TEST(AP_Baro, geometric_alt_to_geopotential)
69
{
70
EXPECT_FLOAT_EQ(AP_Baro::geometric_alt_to_geopotential(-4000), -4002.51858796625);
71
EXPECT_FLOAT_EQ(AP_Baro::geometric_alt_to_geopotential(6000), 5994.34208330151);
72
EXPECT_FLOAT_EQ(AP_Baro::geometric_alt_to_geopotential(17500), 17451.9552525734);
73
EXPECT_FLOAT_EQ(AP_Baro::geometric_alt_to_geopotential(25000), 24902.0647262842);
74
EXPECT_FLOAT_EQ(AP_Baro::geometric_alt_to_geopotential(40000), 39749.8736080075);
75
EXPECT_FLOAT_EQ(AP_Baro::geometric_alt_to_geopotential(49000), 48625.1814380981);
76
EXPECT_FLOAT_EQ(AP_Baro::geometric_alt_to_geopotential(65000), 64342.0812904114);
77
EXPECT_FLOAT_EQ(AP_Baro::geometric_alt_to_geopotential(78000), 77054.5110731299);
78
}
79
80
TEST(AP_Baro, get_pressure_temperature_for_alt_amsl)
81
{
82
float accuracy = 1E-6;
83
84
// layer 0 -4000 m
85
float pressure, temperature_K;
86
AP_Baro::get_pressure_temperature_for_alt_amsl(-4000, pressure, temperature_K);
87
// EXPECT_FLOAT_EQ(pressure, 159598.164433755); // Matlab
88
EXPECT_FLOAT_EQ(pressure, 159598.09375);
89
EXPECT_FLOAT_EQ(temperature_K, 314.166370821781);
90
91
// layer 0: 6000 m
92
AP_Baro::get_pressure_temperature_for_alt_amsl(6000, pressure, temperature_K);
93
EXPECT_FLOAT_EQ(pressure, 47217.6489854302);
94
EXPECT_FLOAT_EQ(temperature_K, 249.186776458540);
95
96
// layer 1: 17500 m
97
AP_Baro::get_pressure_temperature_for_alt_amsl(17500, pressure, temperature_K);
98
EXPECT_FLOAT_EQ(pressure, 8182.27857345022);
99
EXPECT_FLOAT_EQ(temperature_K, 216.650000000000);
100
101
// layer 2: 25000m
102
AP_Baro::get_pressure_temperature_for_alt_amsl(25000, pressure, temperature_K);
103
// EXPECT_FLOAT_EQ(pressure, 2549.22361148236); // Matlab
104
EXPECT_FLOAT_EQ(pressure, 2549.2251);
105
EXPECT_FLOAT_EQ(temperature_K, 221.552064726284);
106
107
// layer 3: 40000m
108
AP_Baro::get_pressure_temperature_for_alt_amsl(40000, pressure, temperature_K);
109
EXPECT_FLOAT_EQ(pressure, 287.144059695555);
110
EXPECT_FLOAT_EQ(temperature_K, 250.349646102421);
111
112
// layer 4: 49000m
113
AP_Baro::get_pressure_temperature_for_alt_amsl(49000, pressure, temperature_K);
114
EXPECT_FLOAT_EQ(pressure, 90.3365441635632);
115
EXPECT_FLOAT_EQ(temperature_K, 270.650000000000);
116
117
// layer 5: 65000m
118
AP_Baro::get_pressure_temperature_for_alt_amsl(65000, pressure, temperature_K);
119
// EXPECT_FLOAT_EQ(pressure, 10.9297197424037); // Matlab
120
EXPECT_FLOAT_EQ(pressure, 10.929715);
121
EXPECT_FLOAT_EQ(temperature_K, 233.292172386848);
122
123
// layer 6: 78000m
124
AP_Baro::get_pressure_temperature_for_alt_amsl(78000, pressure, temperature_K);
125
// EXPECT_FLOAT_EQ(pressure, 1.46736727632119); // matlab
126
EXPECT_NEAR(pressure, 1.4673687, accuracy);
127
EXPECT_FLOAT_EQ(temperature_K, 202.540977853740);
128
}
129
130
AP_GTEST_MAIN()
131
132