Path: blob/master/libraries/AP_Common/tests/test_location.cpp
9418 views
#include <AP_gtest.h>1#include <AP_Common/Location.h>2#include <AP_Math/AP_Math.h>3#include <AP_AHRS/AP_AHRS.h>4#include <AP_Terrain/AP_Terrain.h>5#include <GCS_MAVLink/GCS_Dummy.h>67const AP_HAL::HAL& hal = AP_HAL::get_HAL();89AP_AHRS ahrs{AP_AHRS::FLAG_ALWAYS_USE_EKF};10AP_Terrain terrain;1112GCS_Dummy _gcs;1314#define EXPECT_VECTOR2F_EQ(v1, v2) \15do { \16EXPECT_FLOAT_EQ(v1[0], v2[0]); \17EXPECT_FLOAT_EQ(v1[1], v2[1]); \18} while (false);1920#define EXPECT_VECTOR3F_EQ(v1, v2) \21do { \22EXPECT_FLOAT_EQ(v1[0], v2[0]); \23EXPECT_FLOAT_EQ(v1[1], v2[1]); \24EXPECT_FLOAT_EQ(v1[2], v2[2]); \25} while (false);2627#define EXPECT_VECTOR2F_NEAR(v1, v2, acc) \28do { \29EXPECT_NEAR(v1[0], v2[0], acc); \30EXPECT_NEAR(v1[1], v2[1], acc); \31} while (false);3233#define EXPECT_VECTOR3F_NEAR(v1, v2, acc) \34do { \35EXPECT_NEAR(v1[0], v2[0], acc); \36EXPECT_NEAR(v1[1], v2[1], acc); \37EXPECT_NEAR(v1[2], v2[2], acc); \38} while (false);3940TEST(Location, LatLngWrapping)41{42struct {43int32_t start_lat;44int32_t start_lng;45Vector2f delta_metres_ne;46int32_t expected_lat;47int32_t expected_lng;48} tests[] {49{519634000, 1797560000, Vector2f{0, 100000}, 519634000, -1787860777}50};5152for (auto &test : tests) {53// forward54{55Location loc{test.start_lat, test.start_lng, 0, Location::AltFrame::ABOVE_HOME};56loc.offset(test.delta_metres_ne[0], test.delta_metres_ne[1]);57EXPECT_EQ(test.expected_lat, loc.lat);58EXPECT_EQ(test.expected_lng, loc.lng);59EXPECT_EQ(0, loc.alt);60}61// and now reverse62{63Location rev{test.expected_lat, test.expected_lng, 0, Location::AltFrame::ABOVE_HOME};64rev.offset(-test.delta_metres_ne[0], -test.delta_metres_ne[1]);65EXPECT_EQ(rev.lat, test.start_lat);66EXPECT_EQ(rev.lng, test.start_lng);67EXPECT_EQ(0, rev.alt);68}69}70}7172TEST(Location, LocOffsetDouble)73{74struct {75int32_t home_lat;76int32_t home_lng;77Vector2d delta_metres_ne1;78Vector2d delta_metres_ne2;79Vector2d expected_pos_change;80} tests[] {81-353632620, 1491652373,82Vector2d{4682795.4576701336, 5953662.7673837934},83Vector2d{4682797.1904749088, 5953664.1586009059},84Vector2d{1.7365739,1.4261966},85};8687for (auto &test : tests) {88Location home{test.home_lat, test.home_lng, 0, Location::AltFrame::ABOVE_HOME};89Location loc1 = home;90Location loc2 = home;91loc1.offset(test.delta_metres_ne1.x, test.delta_metres_ne1.y);92loc2.offset(test.delta_metres_ne2.x, test.delta_metres_ne2.y);93Vector2d diff = loc1.get_distance_NE_double(loc2);94EXPECT_FLOAT_EQ(diff.x, test.expected_pos_change.x);95EXPECT_FLOAT_EQ(diff.y, test.expected_pos_change.y);96}97}9899TEST(Location, LocOffset3DDouble)100{101Location loc {102-353632620, 1491652373, 60000, Location::AltFrame::ABSOLUTE103};104// this is ned, so our latitude should change, and our new105// location should be above the original:106loc.offset(Vector3d{1000, 0, -10});107EXPECT_EQ(loc.lat, -353542788);108EXPECT_EQ(loc.lng, 1491652373);109EXPECT_EQ(loc.alt, 61000);110}111112TEST(Location, Tests)113{114Location test_location;115EXPECT_TRUE(test_location.is_zero());116EXPECT_FALSE(test_location.initialised());117const Location test_home{-35362938, 149165085, 100, Location::AltFrame::ABSOLUTE};118EXPECT_EQ(-35362938, test_home.lat);119EXPECT_EQ(149165085, test_home.lng);120EXPECT_EQ(100, test_home.alt);121EXPECT_EQ(0, test_home.relative_alt);122EXPECT_EQ(0, test_home.terrain_alt);123EXPECT_EQ(0, test_home.origin_alt);124EXPECT_EQ(0, test_home.loiter_ccw);125EXPECT_EQ(0, test_home.loiter_xtrack);126EXPECT_TRUE(test_home.initialised());127128const Vector3f test_vect{-42, 42, 0};129Location test_location3{test_vect, Location::AltFrame::ABOVE_HOME};130EXPECT_EQ(0, test_location3.lat);131EXPECT_EQ(0, test_location3.lng);132EXPECT_EQ(0, test_location3.alt);133EXPECT_EQ(1, test_location3.relative_alt);134EXPECT_EQ(0, test_location3.terrain_alt);135EXPECT_EQ(0, test_location3.origin_alt);136EXPECT_EQ(0, test_location3.loiter_ccw);137EXPECT_EQ(0, test_location3.loiter_xtrack);138EXPECT_FALSE(test_location3.initialised());139// EXPECT_EXIT(test_location3.change_alt_frame(Location::AltFrame::ABSOLUTE), PANIC something); // TODO check PANIC140141test_location3.set_alt_cm(-420, Location::AltFrame::ABSOLUTE);142EXPECT_EQ(-420, test_location3.alt);143EXPECT_EQ(0, test_location3.relative_alt);144EXPECT_EQ(0, test_location3.terrain_alt);145EXPECT_EQ(0, test_location3.origin_alt);146EXPECT_EQ(Location::AltFrame::ABSOLUTE, test_location3.get_alt_frame());147148test_location3.set_alt_cm(420, Location::AltFrame::ABOVE_HOME);149EXPECT_EQ(420, test_location3.alt);150EXPECT_EQ(1, test_location3.relative_alt);151EXPECT_EQ(0, test_location3.terrain_alt);152EXPECT_EQ(0, test_location3.origin_alt);153EXPECT_EQ(Location::AltFrame::ABOVE_HOME, test_location3.get_alt_frame());154155test_location3.set_alt_cm(-420, Location::AltFrame::ABOVE_ORIGIN);156EXPECT_EQ(-420, test_location3.alt);157EXPECT_EQ(0, test_location3.relative_alt);158EXPECT_EQ(0, test_location3.terrain_alt);159EXPECT_EQ(1, test_location3.origin_alt);160EXPECT_EQ(Location::AltFrame::ABOVE_ORIGIN, test_location3.get_alt_frame());161162test_location3.set_alt_cm(420, Location::AltFrame::ABOVE_TERRAIN);163EXPECT_EQ(420, test_location3.alt);164EXPECT_EQ(1, test_location3.relative_alt);165EXPECT_EQ(1, test_location3.terrain_alt);166EXPECT_EQ(0, test_location3.origin_alt);167EXPECT_EQ(Location::AltFrame::ABOVE_TERRAIN, test_location3.get_alt_frame());168169// No TERRAIN, NO HOME, NO ORIGIN170AP::terrain()->set_enabled(false);171for (auto current_frame = Location::AltFrame::ABSOLUTE;172current_frame <= Location::AltFrame::ABOVE_TERRAIN;173current_frame = static_cast<Location::AltFrame>(174(uint8_t) current_frame + 1)) {175for (auto desired_frame = Location::AltFrame::ABSOLUTE;176desired_frame <= Location::AltFrame::ABOVE_TERRAIN;177desired_frame = static_cast<Location::AltFrame>(178(uint8_t) desired_frame + 1)) {179test_location3.set_alt_cm(420, current_frame);180if (current_frame == desired_frame) {181EXPECT_TRUE(test_location3.change_alt_frame(desired_frame));182continue;183}184if (current_frame == Location::AltFrame::ABOVE_TERRAIN185|| desired_frame == Location::AltFrame::ABOVE_TERRAIN) {186EXPECT_FALSE(test_location3.change_alt_frame(desired_frame));187} else if (current_frame == Location::AltFrame::ABOVE_ORIGIN188|| desired_frame == Location::AltFrame::ABOVE_ORIGIN) {189EXPECT_FALSE(test_location3.change_alt_frame(desired_frame));190} else if (current_frame == Location::AltFrame::ABOVE_HOME191|| desired_frame == Location::AltFrame::ABOVE_HOME) {192EXPECT_FALSE(test_location3.change_alt_frame(desired_frame));193} else {194EXPECT_TRUE(test_location3.change_alt_frame(desired_frame));195}196}197}198// NO TERRAIN, NO ORIGIN199EXPECT_TRUE(ahrs.set_home(test_home));200for (auto current_frame = Location::AltFrame::ABSOLUTE;201current_frame <= Location::AltFrame::ABOVE_TERRAIN;202current_frame = static_cast<Location::AltFrame>(203(uint8_t) current_frame + 1)) {204for (auto desired_frame = Location::AltFrame::ABSOLUTE;205desired_frame <= Location::AltFrame::ABOVE_TERRAIN;206desired_frame = static_cast<Location::AltFrame>(207(uint8_t) desired_frame + 1)) {208test_location3.set_alt_cm(420, current_frame);209if (current_frame == desired_frame) {210EXPECT_TRUE(test_location3.change_alt_frame(desired_frame));211continue;212}213if (current_frame == Location::AltFrame::ABOVE_TERRAIN214|| desired_frame == Location::AltFrame::ABOVE_TERRAIN) {215EXPECT_FALSE(test_location3.change_alt_frame(desired_frame));216} else if (current_frame == Location::AltFrame::ABOVE_ORIGIN217|| desired_frame == Location::AltFrame::ABOVE_ORIGIN) {218EXPECT_FALSE(test_location3.change_alt_frame(desired_frame));219} else {220EXPECT_TRUE(test_location3.change_alt_frame(desired_frame));221}222223}224}225// NO Origin226AP::terrain()->set_enabled(true);227for (auto current_frame = Location::AltFrame::ABSOLUTE;228current_frame <= Location::AltFrame::ABOVE_TERRAIN;229current_frame = static_cast<Location::AltFrame>(230(uint8_t) current_frame + 1)) {231for (auto desired_frame = Location::AltFrame::ABSOLUTE;232desired_frame <= Location::AltFrame::ABOVE_TERRAIN;233desired_frame = static_cast<Location::AltFrame>(234(uint8_t) desired_frame + 1)) {235test_location3.set_alt_cm(420, current_frame);236if (current_frame == desired_frame) {237EXPECT_TRUE(test_location3.change_alt_frame(desired_frame));238continue;239}240if (current_frame == Location::AltFrame::ABOVE_ORIGIN241|| desired_frame == Location::AltFrame::ABOVE_ORIGIN) {242EXPECT_FALSE(test_location3.change_alt_frame(desired_frame));243} else {244EXPECT_TRUE(test_location3.change_alt_frame(desired_frame));245}246}247}248249Vector2f test_vec2;250EXPECT_FALSE(test_home.get_vector_xy_from_origin_NE_cm(test_vec2));251Vector3f test_vec3;252EXPECT_FALSE(test_home.get_vector_from_origin_NEU_cm(test_vec3));253254Location test_origin = test_home;255test_origin.offset(2, 2);256const Vector3f test_vecto{200, 200, 10};257const Location test_location4{test_vecto, Location::AltFrame::ABOVE_ORIGIN};258EXPECT_EQ(10, test_location4.alt);259EXPECT_EQ(0, test_location4.relative_alt);260EXPECT_EQ(0, test_location4.terrain_alt);261EXPECT_EQ(1, test_location4.origin_alt);262EXPECT_EQ(0, test_location4.loiter_ccw);263EXPECT_EQ(0, test_location4.loiter_xtrack);264EXPECT_TRUE(test_location4.initialised());265266// test set_alt_m API:267Location loc = test_home;268loc.set_alt_m(1.71, Location::AltFrame::ABSOLUTE);269int32_t alt_in_cm_from_m;270EXPECT_TRUE(loc.get_alt_cm(Location::AltFrame::ABSOLUTE, alt_in_cm_from_m));271EXPECT_EQ(171, alt_in_cm_from_m);272273// can't create a Location using a vector here as there's no origin for the vector to be relative to:274// const Location test_location_empty{test_vect, Location::AltFrame::ABOVE_HOME};275// EXPECT_FALSE(test_location_empty.get_vector_from_origin_NEU_cm(test_vec3));276}277278TEST(Location, Distance)279{280const Location test_home{-35362938, 149165085, 100, Location::AltFrame::ABSOLUTE};281const Location test_home2{-35363938, 149165085, 100, Location::AltFrame::ABSOLUTE};282EXPECT_FLOAT_EQ(11.131885, test_home.get_distance(test_home2));283EXPECT_FLOAT_EQ(0, test_home.get_distance(test_home));284EXPECT_VECTOR2F_EQ(Vector2f(0, 0), test_home.get_distance_NE(test_home));285EXPECT_VECTOR2F_EQ(Vector2f(-11.131885, 0), test_home.get_distance_NE(test_home2));286EXPECT_VECTOR2F_EQ(Vector3f(0, 0, 0), test_home.get_distance_NED(test_home));287EXPECT_VECTOR2F_EQ(Vector3f(-11.131885, 0, 0), test_home.get_distance_NED(test_home2));288Location test_loc = test_home;289test_loc.offset(-11.131886, 0);290EXPECT_TRUE(test_loc.same_latlon_as(test_home2));291test_loc = test_home;292test_loc.offset(-11.131885, 0);293test_loc.offset_bearing(0, 11.131885);294EXPECT_TRUE(test_loc.same_latlon_as(test_home));295296test_loc.offset_bearing_and_pitch(0, 2, -11.14);297EXPECT_TRUE(test_loc.same_latlon_as(test_home2));298EXPECT_EQ(62, test_loc.alt);299300test_loc = Location(-35362633, 149165085, 0, Location::AltFrame::ABOVE_HOME);301int32_t bearing = test_home.get_bearing_to(test_loc);302EXPECT_EQ(0, bearing);303304test_loc = Location(-35363711, 149165085, 0, Location::AltFrame::ABOVE_HOME);305bearing = test_home.get_bearing_to(test_loc);306EXPECT_EQ(18000, bearing);307308test_loc = Location(-35362938, 149166085, 0, Location::AltFrame::ABOVE_HOME);309bearing = test_home.get_bearing_to(test_loc);310EXPECT_EQ(9000, bearing);311312test_loc = Location(-35362938, 149164085, 0, Location::AltFrame::ABOVE_HOME);313bearing = test_home.get_bearing_to(test_loc);314EXPECT_EQ(27000, bearing);315316test_loc = Location(-35361938, 149164085, 0, Location::AltFrame::ABOVE_HOME);317bearing = test_home.get_bearing_to(test_loc);318EXPECT_EQ(31503, bearing);319const float bearing_rad = test_home.get_bearing(test_loc);320EXPECT_FLOAT_EQ(5.4982867, bearing_rad);321322}323324TEST(Location, Sanitize)325{326// we will sanitize test_loc with test_default_loc327// test_home is just for reference328const Location test_home{-35362938, 149165085, 100, Location::AltFrame::ABSOLUTE};329EXPECT_TRUE(ahrs.set_home(test_home));330const Location test_default_loc{-35362938, 149165085, 200, Location::AltFrame::ABSOLUTE};331Location test_loc;332test_loc.set_alt_cm(0, Location::AltFrame::ABOVE_HOME);333EXPECT_TRUE(test_loc.sanitize(test_default_loc));334EXPECT_TRUE(test_loc.same_latlon_as(test_default_loc));335int32_t default_loc_alt;336// we should compare test_loc alt and test_default_loc alt in same frame , in this case, ABOVE HOME337EXPECT_TRUE(test_default_loc.get_alt_cm(Location::AltFrame::ABOVE_HOME, default_loc_alt));338EXPECT_EQ(test_loc.alt, default_loc_alt);339test_loc = Location(91*1e7, 0, 0, Location::AltFrame::ABSOLUTE);340EXPECT_TRUE(test_loc.sanitize(test_default_loc));341EXPECT_TRUE(test_loc.same_latlon_as(test_default_loc));342EXPECT_NE(test_default_loc.alt, test_loc.alt);343test_loc = Location(0, 181*1e7, 0, Location::AltFrame::ABSOLUTE);344EXPECT_TRUE(test_loc.sanitize(test_default_loc));345EXPECT_TRUE(test_loc.same_latlon_as(test_default_loc));346EXPECT_NE(test_default_loc.alt, test_loc.alt);347test_loc = Location(42*1e7, 42*1e7, 420, Location::AltFrame::ABSOLUTE);348EXPECT_FALSE(test_loc.sanitize(test_default_loc));349EXPECT_FALSE(test_loc.same_latlon_as(test_default_loc));350EXPECT_NE(test_default_loc.alt, test_loc.alt);351}352353TEST(Location, GetHeightAbove)354{355// we will sanitize test_loc with test_default_loc356// test_home is just for reference357const Location test_loc{-35362938, 149165085, 37900, Location::AltFrame::ABSOLUTE};358const Location test_origin{-35362938, 149165085, 20000, Location::AltFrame::ABSOLUTE};359360ftype alt_delta;361EXPECT_EQ(true, test_loc.get_height_above(test_origin, alt_delta));362EXPECT_FLOAT_EQ(179, alt_delta);363364EXPECT_EQ(true, test_origin.get_height_above(test_loc, alt_delta));365EXPECT_FLOAT_EQ(-179, alt_delta);366}367368369TEST(Location, Line)370{371const Location test_home{35362938, 149165085, 100, Location::AltFrame::ABSOLUTE};372const Location test_wp_last{35362960, 149165085, 100, Location::AltFrame::ABSOLUTE};373Location test_wp{35362940, 149165085, 100, Location::AltFrame::ABSOLUTE};374EXPECT_FALSE(test_wp.past_interval_finish_line(test_home, test_wp_last));375EXPECT_TRUE(test_wp.past_interval_finish_line(test_home, test_home));376test_wp.lat = 35362970;377EXPECT_TRUE(test_wp.past_interval_finish_line(test_home, test_wp_last));378}379380/*381check if we obey basic euclidean geometry rules of position382addition/subtraction383*/384TEST(Location, OffsetError)385{386// test at 10km from origin387const float ofs_ne = 10e3 / sqrtf(2.0);388for (float lat = -80; lat <= 80; lat += 10.0) {389Location origin{int32_t(lat*1e7), 0, 0, Location::AltFrame::ABOVE_HOME};390Location loc = origin;391loc.offset(ofs_ne, ofs_ne);392Location loc2 = loc;393loc2.offset(-ofs_ne, -ofs_ne);394float dist = origin.get_distance(loc2);395EXPECT_FLOAT_EQ(dist, 0);396}397}398399#define TEST_POLYGON_DISTANCE_POINTS(POLYGON, TEST_POINTS) \400do { \401for (uint32_t i = 0; i < ARRAY_SIZE(TEST_POINTS); i++) { \402Vector2f direction; \403Polygon_closest_distance_point(POLYGON, \404ARRAY_SIZE(POLYGON),\405TEST_POINTS[i].point, direction);\406EXPECT_TRUE(fabs(TEST_POINTS[i].distance - direction.length()) <= 1.0f); \407EXPECT_TRUE(fabs(degrees(TEST_POINTS[i].direction.angle()) - degrees(direction.angle())) <= 5.0f); \408} \409} while(0)410411static Vector2f scale_latlon_from_origin(const Vector2l &point)412{413// using some random australian location results in 15m errors.414// const Location origin{35362938, 149165085, 0, Location::AltFrame::ABOVE_HOME};415const Location origin { 515092732, -1267776, 0, Location::AltFrame::ABOVE_HOME }; // NW corner416Location tmp_loc { point.x, point.y, 0, Location::AltFrame::ABOVE_HOME };417return origin.get_distance_NE(tmp_loc);418}419420// Center of London (Charing Cross)421const int32_t CENTER_LAT = static_cast<int32_t>(51.5085 * 1E7); // 515085000422const int32_t CENTER_LON = static_cast<int32_t>(-0.1257 * 1E7); // -1257000423424const int32_t CENTER_NORTH_LAT = static_cast<int32_t>((51.5085 + 0.0003366)* 1E7); // 37.5m from edge425const int32_t CENTER_EAST_LON = static_cast<int32_t>((-0.1257 + 0.0005388)* 1E7); // 37.5m from edge426const int32_t CENTER_SOUTH_LAT = static_cast<int32_t>((51.5085 - 0.0003366) * 1E7); // 37.5m from edge427const int32_t CENTER_WEST_LON = static_cast<int32_t>((-0.1257 - 0.0005388) * 1E7); // 37.5m from edge428429// Bounding box coordinates (in 1E7 degrees)430const int32_t NORTH_WEST_LAT = static_cast<int32_t>((51.5085 + 0.0006732) * 1E7); // 515092732431const int32_t NORTH_WEST_LON = static_cast<int32_t>((-0.1257 - 0.0010776) * 1E7); // -1267776432433const int32_t NORTH_EAST_LAT = static_cast<int32_t>((51.5085 + 0.0006732) * 1E7); // 515092732434const int32_t NORTH_EAST_LON = static_cast<int32_t>((-0.1257 + 0.0010776) * 1E7); // -1246224435436const int32_t SOUTH_WEST_LAT = static_cast<int32_t>((51.5085 - 0.0006732) * 1E7); // 515080268437const int32_t SOUTH_WEST_LON = static_cast<int32_t>((-0.1257 - 0.0010776) * 1E7); // -1267776438439const int32_t SOUTH_EAST_LAT = static_cast<int32_t>((51.5085 - 0.0006732) * 1E7); // 515080268440const int32_t SOUTH_EAST_LON = static_cast<int32_t>((-0.1257 + 0.0010776) * 1E7); // -1246224441442#define CARTESIAN(lat, lng) (scale_latlon_from_origin(Vector2l(lat, lng)))443// Array of coordinates in cartesian pairs for each corner444static const Vector2f London_boundary[] {445CARTESIAN(NORTH_WEST_LAT, NORTH_WEST_LON), // Northwest corner446CARTESIAN(NORTH_EAST_LAT, NORTH_EAST_LON), // Northeast corner447CARTESIAN(SOUTH_EAST_LAT, SOUTH_EAST_LON), // Southeast corner448CARTESIAN(SOUTH_WEST_LAT, SOUTH_WEST_LON), // Southwest corner449CARTESIAN(NORTH_WEST_LAT, NORTH_WEST_LON), // Northwest corner450};451452static const struct {453Vector2f point;454float distance;455Vector2f direction;456} London_test_points[] = {457{ CARTESIAN(CENTER_LAT, CENTER_LON), 75.0f, { 0.0f, 75.0f }},458{ CARTESIAN(CENTER_NORTH_LAT, CENTER_LON), 37.5f, { 37.5f, 0.0f }},459{ CARTESIAN(CENTER_LAT, CENTER_EAST_LON), 37.5f, { 0.0f, 37.5f }},460{ CARTESIAN(CENTER_SOUTH_LAT, CENTER_LON), 37.5f, { -37.5f, 0.0f }},461{ CARTESIAN(CENTER_LAT, CENTER_WEST_LON), 37.5f, { 0.0f, -37.5f }},462};463464TEST(Location, London_distance)465{466TEST_POLYGON_DISTANCE_POINTS(London_boundary, London_test_points);467}468469470AP_GTEST_MAIN()471472473