mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
AP_Common: update tests for 4.1
This commit is contained in:
parent
1d91353867
commit
8165a81256
@ -139,7 +139,7 @@ TEST(Location, LocOffsetDouble)
|
||||
-353632620, 1491652373,
|
||||
Vector2d{4682795.4576701336, 5953662.7673837934},
|
||||
Vector2d{4682797.1904749088, 5953664.1586009059},
|
||||
Vector2d{1.7365739867091179,1.7025913001452864},
|
||||
Vector2d{1.7365739867091179,1.2050807},
|
||||
};
|
||||
|
||||
for (auto &test : tests) {
|
||||
@ -409,4 +409,23 @@ TEST(Location, Line)
|
||||
EXPECT_TRUE(test_wp.past_interval_finish_line(test_home, test_wp_last));
|
||||
}
|
||||
|
||||
/*
|
||||
check if we obey basic euclidian geometry rules of position
|
||||
addition/subtraction
|
||||
*/
|
||||
TEST(Location, OffsetError)
|
||||
{
|
||||
// test at 10km from origin
|
||||
const float ofs_ne = 10e3 / sqrtf(2.0);
|
||||
for (float lat = -80; lat <= 80; lat += 10.0) {
|
||||
Location origin{int32_t(lat*1e7), 0, 0, Location::AltFrame::ABOVE_HOME};
|
||||
Location loc = origin;
|
||||
loc.offset(ofs_ne, ofs_ne);
|
||||
Location loc2 = loc;
|
||||
loc2.offset(-ofs_ne, -ofs_ne);
|
||||
float dist = origin.get_distance(loc2);
|
||||
EXPECT_FLOAT_EQ(dist, 0);
|
||||
}
|
||||
}
|
||||
|
||||
AP_GTEST_MAIN()
|
||||
|
Loading…
Reference in New Issue
Block a user