mirror of https://github.com/ArduPilot/ardupilot
AP_Common: fix location sanitize unit test
This commit is contained in:
parent
41a5afdf64
commit
560e24385a
|
@ -317,24 +317,31 @@ TEST(Location, Distance)
|
|||
|
||||
TEST(Location, Sanitize)
|
||||
{
|
||||
// we will sanitize test_loc with test_default_loc
|
||||
// test_home is just for reference
|
||||
const Location test_home{-35362938, 149165085, 100, Location::AltFrame::ABSOLUTE};
|
||||
EXPECT_TRUE(vehicle.ahrs.set_home(test_home));
|
||||
const Location test_default_loc{-35362938, 149165085, 200, Location::AltFrame::ABSOLUTE};
|
||||
Location test_loc;
|
||||
test_loc.set_alt_cm(0, Location::AltFrame::ABOVE_HOME);
|
||||
EXPECT_TRUE(test_loc.sanitize(test_home));
|
||||
EXPECT_TRUE(test_loc.same_latlon_as(test_home));
|
||||
EXPECT_EQ(test_home.alt, test_loc.alt);
|
||||
EXPECT_TRUE(test_loc.sanitize(test_default_loc));
|
||||
EXPECT_TRUE(test_loc.same_latlon_as(test_default_loc));
|
||||
int32_t default_loc_alt;
|
||||
// we should compare test_loc alt and test_default_loc alt in same frame , in this case, ABOVE HOME
|
||||
EXPECT_TRUE(test_default_loc.get_alt_cm(Location::AltFrame::ABOVE_HOME, default_loc_alt));
|
||||
EXPECT_EQ(test_loc.alt, default_loc_alt);
|
||||
test_loc = Location(91*1e7, 0, 0, Location::AltFrame::ABSOLUTE);
|
||||
EXPECT_TRUE(test_loc.sanitize(test_home));
|
||||
EXPECT_TRUE(test_loc.same_latlon_as(test_home));
|
||||
EXPECT_NE(test_home.alt, test_loc.alt);
|
||||
EXPECT_TRUE(test_loc.sanitize(test_default_loc));
|
||||
EXPECT_TRUE(test_loc.same_latlon_as(test_default_loc));
|
||||
EXPECT_NE(test_default_loc.alt, test_loc.alt);
|
||||
test_loc = Location(0, 181*1e7, 0, Location::AltFrame::ABSOLUTE);
|
||||
EXPECT_TRUE(test_loc.sanitize(test_home));
|
||||
EXPECT_TRUE(test_loc.same_latlon_as(test_home));
|
||||
EXPECT_NE(test_home.alt, test_loc.alt);
|
||||
EXPECT_TRUE(test_loc.sanitize(test_default_loc));
|
||||
EXPECT_TRUE(test_loc.same_latlon_as(test_default_loc));
|
||||
EXPECT_NE(test_default_loc.alt, test_loc.alt);
|
||||
test_loc = Location(42*1e7, 42*1e7, 420, Location::AltFrame::ABSOLUTE);
|
||||
EXPECT_FALSE(test_loc.sanitize(test_home));
|
||||
EXPECT_FALSE(test_loc.same_latlon_as(test_home));
|
||||
EXPECT_NE(test_home.alt, test_loc.alt);
|
||||
EXPECT_FALSE(test_loc.sanitize(test_default_loc));
|
||||
EXPECT_FALSE(test_loc.same_latlon_as(test_default_loc));
|
||||
EXPECT_NE(test_default_loc.alt, test_loc.alt);
|
||||
}
|
||||
|
||||
TEST(Location, Line)
|
||||
|
|
Loading…
Reference in New Issue