From fc2338612edcf1c6294112865aa71b2d12fcf7ce Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 9 Jul 2021 13:11:51 +1000 Subject: [PATCH] AP_Common: stop setting terrain pointer in test_location Also enable/disable as required for testing --- libraries/AP_Common/tests/test_location.cpp | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/libraries/AP_Common/tests/test_location.cpp b/libraries/AP_Common/tests/test_location.cpp index 5c385b7f28..b5f110d3f0 100644 --- a/libraries/AP_Common/tests/test_location.cpp +++ b/libraries/AP_Common/tests/test_location.cpp @@ -212,6 +212,7 @@ TEST(Location, Tests) EXPECT_EQ(Location::AltFrame::ABOVE_TERRAIN, test_location3.get_alt_frame()); // No TERRAIN, NO HOME, NO ORIGIN + AP::terrain()->set_enabled(false); for (auto current_frame = Location::AltFrame::ABSOLUTE; current_frame <= Location::AltFrame::ABOVE_TERRAIN; current_frame = static_cast( @@ -267,7 +268,7 @@ TEST(Location, Tests) } } // NO Origin - Location::set_terrain(&vehicle.terrain); + AP::terrain()->set_enabled(true); for (auto current_frame = Location::AltFrame::ABSOLUTE; current_frame <= Location::AltFrame::ABOVE_TERRAIN; current_frame = static_cast(