Book a Demo!
CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutPoliciesSign UpSign In
Ardupilot
GitHub Repository: Ardupilot/ardupilot
Path: blob/master/libraries/AP_Common/tests/test_location.cpp
9418 views
1
#include <AP_gtest.h>
2
#include <AP_Common/Location.h>
3
#include <AP_Math/AP_Math.h>
4
#include <AP_AHRS/AP_AHRS.h>
5
#include <AP_Terrain/AP_Terrain.h>
6
#include <GCS_MAVLink/GCS_Dummy.h>
7
8
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
9
10
AP_AHRS ahrs{AP_AHRS::FLAG_ALWAYS_USE_EKF};
11
AP_Terrain terrain;
12
13
GCS_Dummy _gcs;
14
15
#define EXPECT_VECTOR2F_EQ(v1, v2) \
16
do { \
17
EXPECT_FLOAT_EQ(v1[0], v2[0]); \
18
EXPECT_FLOAT_EQ(v1[1], v2[1]); \
19
} while (false);
20
21
#define EXPECT_VECTOR3F_EQ(v1, v2) \
22
do { \
23
EXPECT_FLOAT_EQ(v1[0], v2[0]); \
24
EXPECT_FLOAT_EQ(v1[1], v2[1]); \
25
EXPECT_FLOAT_EQ(v1[2], v2[2]); \
26
} while (false);
27
28
#define EXPECT_VECTOR2F_NEAR(v1, v2, acc) \
29
do { \
30
EXPECT_NEAR(v1[0], v2[0], acc); \
31
EXPECT_NEAR(v1[1], v2[1], acc); \
32
} while (false);
33
34
#define EXPECT_VECTOR3F_NEAR(v1, v2, acc) \
35
do { \
36
EXPECT_NEAR(v1[0], v2[0], acc); \
37
EXPECT_NEAR(v1[1], v2[1], acc); \
38
EXPECT_NEAR(v1[2], v2[2], acc); \
39
} while (false);
40
41
TEST(Location, LatLngWrapping)
42
{
43
struct {
44
int32_t start_lat;
45
int32_t start_lng;
46
Vector2f delta_metres_ne;
47
int32_t expected_lat;
48
int32_t expected_lng;
49
} tests[] {
50
{519634000, 1797560000, Vector2f{0, 100000}, 519634000, -1787860777}
51
};
52
53
for (auto &test : tests) {
54
// forward
55
{
56
Location loc{test.start_lat, test.start_lng, 0, Location::AltFrame::ABOVE_HOME};
57
loc.offset(test.delta_metres_ne[0], test.delta_metres_ne[1]);
58
EXPECT_EQ(test.expected_lat, loc.lat);
59
EXPECT_EQ(test.expected_lng, loc.lng);
60
EXPECT_EQ(0, loc.alt);
61
}
62
// and now reverse
63
{
64
Location rev{test.expected_lat, test.expected_lng, 0, Location::AltFrame::ABOVE_HOME};
65
rev.offset(-test.delta_metres_ne[0], -test.delta_metres_ne[1]);
66
EXPECT_EQ(rev.lat, test.start_lat);
67
EXPECT_EQ(rev.lng, test.start_lng);
68
EXPECT_EQ(0, rev.alt);
69
}
70
}
71
}
72
73
TEST(Location, LocOffsetDouble)
74
{
75
struct {
76
int32_t home_lat;
77
int32_t home_lng;
78
Vector2d delta_metres_ne1;
79
Vector2d delta_metres_ne2;
80
Vector2d expected_pos_change;
81
} tests[] {
82
-353632620, 1491652373,
83
Vector2d{4682795.4576701336, 5953662.7673837934},
84
Vector2d{4682797.1904749088, 5953664.1586009059},
85
Vector2d{1.7365739,1.4261966},
86
};
87
88
for (auto &test : tests) {
89
Location home{test.home_lat, test.home_lng, 0, Location::AltFrame::ABOVE_HOME};
90
Location loc1 = home;
91
Location loc2 = home;
92
loc1.offset(test.delta_metres_ne1.x, test.delta_metres_ne1.y);
93
loc2.offset(test.delta_metres_ne2.x, test.delta_metres_ne2.y);
94
Vector2d diff = loc1.get_distance_NE_double(loc2);
95
EXPECT_FLOAT_EQ(diff.x, test.expected_pos_change.x);
96
EXPECT_FLOAT_EQ(diff.y, test.expected_pos_change.y);
97
}
98
}
99
100
TEST(Location, LocOffset3DDouble)
101
{
102
Location loc {
103
-353632620, 1491652373, 60000, Location::AltFrame::ABSOLUTE
104
};
105
// this is ned, so our latitude should change, and our new
106
// location should be above the original:
107
loc.offset(Vector3d{1000, 0, -10});
108
EXPECT_EQ(loc.lat, -353542788);
109
EXPECT_EQ(loc.lng, 1491652373);
110
EXPECT_EQ(loc.alt, 61000);
111
}
112
113
TEST(Location, Tests)
114
{
115
Location test_location;
116
EXPECT_TRUE(test_location.is_zero());
117
EXPECT_FALSE(test_location.initialised());
118
const Location test_home{-35362938, 149165085, 100, Location::AltFrame::ABSOLUTE};
119
EXPECT_EQ(-35362938, test_home.lat);
120
EXPECT_EQ(149165085, test_home.lng);
121
EXPECT_EQ(100, test_home.alt);
122
EXPECT_EQ(0, test_home.relative_alt);
123
EXPECT_EQ(0, test_home.terrain_alt);
124
EXPECT_EQ(0, test_home.origin_alt);
125
EXPECT_EQ(0, test_home.loiter_ccw);
126
EXPECT_EQ(0, test_home.loiter_xtrack);
127
EXPECT_TRUE(test_home.initialised());
128
129
const Vector3f test_vect{-42, 42, 0};
130
Location test_location3{test_vect, Location::AltFrame::ABOVE_HOME};
131
EXPECT_EQ(0, test_location3.lat);
132
EXPECT_EQ(0, test_location3.lng);
133
EXPECT_EQ(0, test_location3.alt);
134
EXPECT_EQ(1, test_location3.relative_alt);
135
EXPECT_EQ(0, test_location3.terrain_alt);
136
EXPECT_EQ(0, test_location3.origin_alt);
137
EXPECT_EQ(0, test_location3.loiter_ccw);
138
EXPECT_EQ(0, test_location3.loiter_xtrack);
139
EXPECT_FALSE(test_location3.initialised());
140
// EXPECT_EXIT(test_location3.change_alt_frame(Location::AltFrame::ABSOLUTE), PANIC something); // TODO check PANIC
141
142
test_location3.set_alt_cm(-420, Location::AltFrame::ABSOLUTE);
143
EXPECT_EQ(-420, test_location3.alt);
144
EXPECT_EQ(0, test_location3.relative_alt);
145
EXPECT_EQ(0, test_location3.terrain_alt);
146
EXPECT_EQ(0, test_location3.origin_alt);
147
EXPECT_EQ(Location::AltFrame::ABSOLUTE, test_location3.get_alt_frame());
148
149
test_location3.set_alt_cm(420, Location::AltFrame::ABOVE_HOME);
150
EXPECT_EQ(420, test_location3.alt);
151
EXPECT_EQ(1, test_location3.relative_alt);
152
EXPECT_EQ(0, test_location3.terrain_alt);
153
EXPECT_EQ(0, test_location3.origin_alt);
154
EXPECT_EQ(Location::AltFrame::ABOVE_HOME, test_location3.get_alt_frame());
155
156
test_location3.set_alt_cm(-420, Location::AltFrame::ABOVE_ORIGIN);
157
EXPECT_EQ(-420, test_location3.alt);
158
EXPECT_EQ(0, test_location3.relative_alt);
159
EXPECT_EQ(0, test_location3.terrain_alt);
160
EXPECT_EQ(1, test_location3.origin_alt);
161
EXPECT_EQ(Location::AltFrame::ABOVE_ORIGIN, test_location3.get_alt_frame());
162
163
test_location3.set_alt_cm(420, Location::AltFrame::ABOVE_TERRAIN);
164
EXPECT_EQ(420, test_location3.alt);
165
EXPECT_EQ(1, test_location3.relative_alt);
166
EXPECT_EQ(1, test_location3.terrain_alt);
167
EXPECT_EQ(0, test_location3.origin_alt);
168
EXPECT_EQ(Location::AltFrame::ABOVE_TERRAIN, test_location3.get_alt_frame());
169
170
// No TERRAIN, NO HOME, NO ORIGIN
171
AP::terrain()->set_enabled(false);
172
for (auto current_frame = Location::AltFrame::ABSOLUTE;
173
current_frame <= Location::AltFrame::ABOVE_TERRAIN;
174
current_frame = static_cast<Location::AltFrame>(
175
(uint8_t) current_frame + 1)) {
176
for (auto desired_frame = Location::AltFrame::ABSOLUTE;
177
desired_frame <= Location::AltFrame::ABOVE_TERRAIN;
178
desired_frame = static_cast<Location::AltFrame>(
179
(uint8_t) desired_frame + 1)) {
180
test_location3.set_alt_cm(420, current_frame);
181
if (current_frame == desired_frame) {
182
EXPECT_TRUE(test_location3.change_alt_frame(desired_frame));
183
continue;
184
}
185
if (current_frame == Location::AltFrame::ABOVE_TERRAIN
186
|| desired_frame == Location::AltFrame::ABOVE_TERRAIN) {
187
EXPECT_FALSE(test_location3.change_alt_frame(desired_frame));
188
} else if (current_frame == Location::AltFrame::ABOVE_ORIGIN
189
|| desired_frame == Location::AltFrame::ABOVE_ORIGIN) {
190
EXPECT_FALSE(test_location3.change_alt_frame(desired_frame));
191
} else if (current_frame == Location::AltFrame::ABOVE_HOME
192
|| desired_frame == Location::AltFrame::ABOVE_HOME) {
193
EXPECT_FALSE(test_location3.change_alt_frame(desired_frame));
194
} else {
195
EXPECT_TRUE(test_location3.change_alt_frame(desired_frame));
196
}
197
}
198
}
199
// NO TERRAIN, NO ORIGIN
200
EXPECT_TRUE(ahrs.set_home(test_home));
201
for (auto current_frame = Location::AltFrame::ABSOLUTE;
202
current_frame <= Location::AltFrame::ABOVE_TERRAIN;
203
current_frame = static_cast<Location::AltFrame>(
204
(uint8_t) current_frame + 1)) {
205
for (auto desired_frame = Location::AltFrame::ABSOLUTE;
206
desired_frame <= Location::AltFrame::ABOVE_TERRAIN;
207
desired_frame = static_cast<Location::AltFrame>(
208
(uint8_t) desired_frame + 1)) {
209
test_location3.set_alt_cm(420, current_frame);
210
if (current_frame == desired_frame) {
211
EXPECT_TRUE(test_location3.change_alt_frame(desired_frame));
212
continue;
213
}
214
if (current_frame == Location::AltFrame::ABOVE_TERRAIN
215
|| desired_frame == Location::AltFrame::ABOVE_TERRAIN) {
216
EXPECT_FALSE(test_location3.change_alt_frame(desired_frame));
217
} else if (current_frame == Location::AltFrame::ABOVE_ORIGIN
218
|| desired_frame == Location::AltFrame::ABOVE_ORIGIN) {
219
EXPECT_FALSE(test_location3.change_alt_frame(desired_frame));
220
} else {
221
EXPECT_TRUE(test_location3.change_alt_frame(desired_frame));
222
}
223
224
}
225
}
226
// NO Origin
227
AP::terrain()->set_enabled(true);
228
for (auto current_frame = Location::AltFrame::ABSOLUTE;
229
current_frame <= Location::AltFrame::ABOVE_TERRAIN;
230
current_frame = static_cast<Location::AltFrame>(
231
(uint8_t) current_frame + 1)) {
232
for (auto desired_frame = Location::AltFrame::ABSOLUTE;
233
desired_frame <= Location::AltFrame::ABOVE_TERRAIN;
234
desired_frame = static_cast<Location::AltFrame>(
235
(uint8_t) desired_frame + 1)) {
236
test_location3.set_alt_cm(420, current_frame);
237
if (current_frame == desired_frame) {
238
EXPECT_TRUE(test_location3.change_alt_frame(desired_frame));
239
continue;
240
}
241
if (current_frame == Location::AltFrame::ABOVE_ORIGIN
242
|| desired_frame == Location::AltFrame::ABOVE_ORIGIN) {
243
EXPECT_FALSE(test_location3.change_alt_frame(desired_frame));
244
} else {
245
EXPECT_TRUE(test_location3.change_alt_frame(desired_frame));
246
}
247
}
248
}
249
250
Vector2f test_vec2;
251
EXPECT_FALSE(test_home.get_vector_xy_from_origin_NE_cm(test_vec2));
252
Vector3f test_vec3;
253
EXPECT_FALSE(test_home.get_vector_from_origin_NEU_cm(test_vec3));
254
255
Location test_origin = test_home;
256
test_origin.offset(2, 2);
257
const Vector3f test_vecto{200, 200, 10};
258
const Location test_location4{test_vecto, Location::AltFrame::ABOVE_ORIGIN};
259
EXPECT_EQ(10, test_location4.alt);
260
EXPECT_EQ(0, test_location4.relative_alt);
261
EXPECT_EQ(0, test_location4.terrain_alt);
262
EXPECT_EQ(1, test_location4.origin_alt);
263
EXPECT_EQ(0, test_location4.loiter_ccw);
264
EXPECT_EQ(0, test_location4.loiter_xtrack);
265
EXPECT_TRUE(test_location4.initialised());
266
267
// test set_alt_m API:
268
Location loc = test_home;
269
loc.set_alt_m(1.71, Location::AltFrame::ABSOLUTE);
270
int32_t alt_in_cm_from_m;
271
EXPECT_TRUE(loc.get_alt_cm(Location::AltFrame::ABSOLUTE, alt_in_cm_from_m));
272
EXPECT_EQ(171, alt_in_cm_from_m);
273
274
// can't create a Location using a vector here as there's no origin for the vector to be relative to:
275
// const Location test_location_empty{test_vect, Location::AltFrame::ABOVE_HOME};
276
// EXPECT_FALSE(test_location_empty.get_vector_from_origin_NEU_cm(test_vec3));
277
}
278
279
TEST(Location, Distance)
280
{
281
const Location test_home{-35362938, 149165085, 100, Location::AltFrame::ABSOLUTE};
282
const Location test_home2{-35363938, 149165085, 100, Location::AltFrame::ABSOLUTE};
283
EXPECT_FLOAT_EQ(11.131885, test_home.get_distance(test_home2));
284
EXPECT_FLOAT_EQ(0, test_home.get_distance(test_home));
285
EXPECT_VECTOR2F_EQ(Vector2f(0, 0), test_home.get_distance_NE(test_home));
286
EXPECT_VECTOR2F_EQ(Vector2f(-11.131885, 0), test_home.get_distance_NE(test_home2));
287
EXPECT_VECTOR2F_EQ(Vector3f(0, 0, 0), test_home.get_distance_NED(test_home));
288
EXPECT_VECTOR2F_EQ(Vector3f(-11.131885, 0, 0), test_home.get_distance_NED(test_home2));
289
Location test_loc = test_home;
290
test_loc.offset(-11.131886, 0);
291
EXPECT_TRUE(test_loc.same_latlon_as(test_home2));
292
test_loc = test_home;
293
test_loc.offset(-11.131885, 0);
294
test_loc.offset_bearing(0, 11.131885);
295
EXPECT_TRUE(test_loc.same_latlon_as(test_home));
296
297
test_loc.offset_bearing_and_pitch(0, 2, -11.14);
298
EXPECT_TRUE(test_loc.same_latlon_as(test_home2));
299
EXPECT_EQ(62, test_loc.alt);
300
301
test_loc = Location(-35362633, 149165085, 0, Location::AltFrame::ABOVE_HOME);
302
int32_t bearing = test_home.get_bearing_to(test_loc);
303
EXPECT_EQ(0, bearing);
304
305
test_loc = Location(-35363711, 149165085, 0, Location::AltFrame::ABOVE_HOME);
306
bearing = test_home.get_bearing_to(test_loc);
307
EXPECT_EQ(18000, bearing);
308
309
test_loc = Location(-35362938, 149166085, 0, Location::AltFrame::ABOVE_HOME);
310
bearing = test_home.get_bearing_to(test_loc);
311
EXPECT_EQ(9000, bearing);
312
313
test_loc = Location(-35362938, 149164085, 0, Location::AltFrame::ABOVE_HOME);
314
bearing = test_home.get_bearing_to(test_loc);
315
EXPECT_EQ(27000, bearing);
316
317
test_loc = Location(-35361938, 149164085, 0, Location::AltFrame::ABOVE_HOME);
318
bearing = test_home.get_bearing_to(test_loc);
319
EXPECT_EQ(31503, bearing);
320
const float bearing_rad = test_home.get_bearing(test_loc);
321
EXPECT_FLOAT_EQ(5.4982867, bearing_rad);
322
323
}
324
325
TEST(Location, Sanitize)
326
{
327
// we will sanitize test_loc with test_default_loc
328
// test_home is just for reference
329
const Location test_home{-35362938, 149165085, 100, Location::AltFrame::ABSOLUTE};
330
EXPECT_TRUE(ahrs.set_home(test_home));
331
const Location test_default_loc{-35362938, 149165085, 200, Location::AltFrame::ABSOLUTE};
332
Location test_loc;
333
test_loc.set_alt_cm(0, Location::AltFrame::ABOVE_HOME);
334
EXPECT_TRUE(test_loc.sanitize(test_default_loc));
335
EXPECT_TRUE(test_loc.same_latlon_as(test_default_loc));
336
int32_t default_loc_alt;
337
// we should compare test_loc alt and test_default_loc alt in same frame , in this case, ABOVE HOME
338
EXPECT_TRUE(test_default_loc.get_alt_cm(Location::AltFrame::ABOVE_HOME, default_loc_alt));
339
EXPECT_EQ(test_loc.alt, default_loc_alt);
340
test_loc = Location(91*1e7, 0, 0, Location::AltFrame::ABSOLUTE);
341
EXPECT_TRUE(test_loc.sanitize(test_default_loc));
342
EXPECT_TRUE(test_loc.same_latlon_as(test_default_loc));
343
EXPECT_NE(test_default_loc.alt, test_loc.alt);
344
test_loc = Location(0, 181*1e7, 0, Location::AltFrame::ABSOLUTE);
345
EXPECT_TRUE(test_loc.sanitize(test_default_loc));
346
EXPECT_TRUE(test_loc.same_latlon_as(test_default_loc));
347
EXPECT_NE(test_default_loc.alt, test_loc.alt);
348
test_loc = Location(42*1e7, 42*1e7, 420, Location::AltFrame::ABSOLUTE);
349
EXPECT_FALSE(test_loc.sanitize(test_default_loc));
350
EXPECT_FALSE(test_loc.same_latlon_as(test_default_loc));
351
EXPECT_NE(test_default_loc.alt, test_loc.alt);
352
}
353
354
TEST(Location, GetHeightAbove)
355
{
356
// we will sanitize test_loc with test_default_loc
357
// test_home is just for reference
358
const Location test_loc{-35362938, 149165085, 37900, Location::AltFrame::ABSOLUTE};
359
const Location test_origin{-35362938, 149165085, 20000, Location::AltFrame::ABSOLUTE};
360
361
ftype alt_delta;
362
EXPECT_EQ(true, test_loc.get_height_above(test_origin, alt_delta));
363
EXPECT_FLOAT_EQ(179, alt_delta);
364
365
EXPECT_EQ(true, test_origin.get_height_above(test_loc, alt_delta));
366
EXPECT_FLOAT_EQ(-179, alt_delta);
367
}
368
369
370
TEST(Location, Line)
371
{
372
const Location test_home{35362938, 149165085, 100, Location::AltFrame::ABSOLUTE};
373
const Location test_wp_last{35362960, 149165085, 100, Location::AltFrame::ABSOLUTE};
374
Location test_wp{35362940, 149165085, 100, Location::AltFrame::ABSOLUTE};
375
EXPECT_FALSE(test_wp.past_interval_finish_line(test_home, test_wp_last));
376
EXPECT_TRUE(test_wp.past_interval_finish_line(test_home, test_home));
377
test_wp.lat = 35362970;
378
EXPECT_TRUE(test_wp.past_interval_finish_line(test_home, test_wp_last));
379
}
380
381
/*
382
check if we obey basic euclidean geometry rules of position
383
addition/subtraction
384
*/
385
TEST(Location, OffsetError)
386
{
387
// test at 10km from origin
388
const float ofs_ne = 10e3 / sqrtf(2.0);
389
for (float lat = -80; lat <= 80; lat += 10.0) {
390
Location origin{int32_t(lat*1e7), 0, 0, Location::AltFrame::ABOVE_HOME};
391
Location loc = origin;
392
loc.offset(ofs_ne, ofs_ne);
393
Location loc2 = loc;
394
loc2.offset(-ofs_ne, -ofs_ne);
395
float dist = origin.get_distance(loc2);
396
EXPECT_FLOAT_EQ(dist, 0);
397
}
398
}
399
400
#define TEST_POLYGON_DISTANCE_POINTS(POLYGON, TEST_POINTS) \
401
do { \
402
for (uint32_t i = 0; i < ARRAY_SIZE(TEST_POINTS); i++) { \
403
Vector2f direction; \
404
Polygon_closest_distance_point(POLYGON, \
405
ARRAY_SIZE(POLYGON),\
406
TEST_POINTS[i].point, direction);\
407
EXPECT_TRUE(fabs(TEST_POINTS[i].distance - direction.length()) <= 1.0f); \
408
EXPECT_TRUE(fabs(degrees(TEST_POINTS[i].direction.angle()) - degrees(direction.angle())) <= 5.0f); \
409
} \
410
} while(0)
411
412
static Vector2f scale_latlon_from_origin(const Vector2l &point)
413
{
414
// using some random australian location results in 15m errors.
415
// const Location origin{35362938, 149165085, 0, Location::AltFrame::ABOVE_HOME};
416
const Location origin { 515092732, -1267776, 0, Location::AltFrame::ABOVE_HOME }; // NW corner
417
Location tmp_loc { point.x, point.y, 0, Location::AltFrame::ABOVE_HOME };
418
return origin.get_distance_NE(tmp_loc);
419
}
420
421
// Center of London (Charing Cross)
422
const int32_t CENTER_LAT = static_cast<int32_t>(51.5085 * 1E7); // 515085000
423
const int32_t CENTER_LON = static_cast<int32_t>(-0.1257 * 1E7); // -1257000
424
425
const int32_t CENTER_NORTH_LAT = static_cast<int32_t>((51.5085 + 0.0003366)* 1E7); // 37.5m from edge
426
const int32_t CENTER_EAST_LON = static_cast<int32_t>((-0.1257 + 0.0005388)* 1E7); // 37.5m from edge
427
const int32_t CENTER_SOUTH_LAT = static_cast<int32_t>((51.5085 - 0.0003366) * 1E7); // 37.5m from edge
428
const int32_t CENTER_WEST_LON = static_cast<int32_t>((-0.1257 - 0.0005388) * 1E7); // 37.5m from edge
429
430
// Bounding box coordinates (in 1E7 degrees)
431
const int32_t NORTH_WEST_LAT = static_cast<int32_t>((51.5085 + 0.0006732) * 1E7); // 515092732
432
const int32_t NORTH_WEST_LON = static_cast<int32_t>((-0.1257 - 0.0010776) * 1E7); // -1267776
433
434
const int32_t NORTH_EAST_LAT = static_cast<int32_t>((51.5085 + 0.0006732) * 1E7); // 515092732
435
const int32_t NORTH_EAST_LON = static_cast<int32_t>((-0.1257 + 0.0010776) * 1E7); // -1246224
436
437
const int32_t SOUTH_WEST_LAT = static_cast<int32_t>((51.5085 - 0.0006732) * 1E7); // 515080268
438
const int32_t SOUTH_WEST_LON = static_cast<int32_t>((-0.1257 - 0.0010776) * 1E7); // -1267776
439
440
const int32_t SOUTH_EAST_LAT = static_cast<int32_t>((51.5085 - 0.0006732) * 1E7); // 515080268
441
const int32_t SOUTH_EAST_LON = static_cast<int32_t>((-0.1257 + 0.0010776) * 1E7); // -1246224
442
443
#define CARTESIAN(lat, lng) (scale_latlon_from_origin(Vector2l(lat, lng)))
444
// Array of coordinates in cartesian pairs for each corner
445
static const Vector2f London_boundary[] {
446
CARTESIAN(NORTH_WEST_LAT, NORTH_WEST_LON), // Northwest corner
447
CARTESIAN(NORTH_EAST_LAT, NORTH_EAST_LON), // Northeast corner
448
CARTESIAN(SOUTH_EAST_LAT, SOUTH_EAST_LON), // Southeast corner
449
CARTESIAN(SOUTH_WEST_LAT, SOUTH_WEST_LON), // Southwest corner
450
CARTESIAN(NORTH_WEST_LAT, NORTH_WEST_LON), // Northwest corner
451
};
452
453
static const struct {
454
Vector2f point;
455
float distance;
456
Vector2f direction;
457
} London_test_points[] = {
458
{ CARTESIAN(CENTER_LAT, CENTER_LON), 75.0f, { 0.0f, 75.0f }},
459
{ CARTESIAN(CENTER_NORTH_LAT, CENTER_LON), 37.5f, { 37.5f, 0.0f }},
460
{ CARTESIAN(CENTER_LAT, CENTER_EAST_LON), 37.5f, { 0.0f, 37.5f }},
461
{ CARTESIAN(CENTER_SOUTH_LAT, CENTER_LON), 37.5f, { -37.5f, 0.0f }},
462
{ CARTESIAN(CENTER_LAT, CENTER_WEST_LON), 37.5f, { 0.0f, -37.5f }},
463
};
464
465
TEST(Location, London_distance)
466
{
467
TEST_POLYGON_DISTANCE_POINTS(London_boundary, London_test_points);
468
}
469
470
471
AP_GTEST_MAIN()
472
473