diff --git a/test/mavsdk_tests/autopilot_tester.cpp b/test/mavsdk_tests/autopilot_tester.cpp index 2c78bec640..cd9f887ee0 100644 --- a/test/mavsdk_tests/autopilot_tester.cpp +++ b/test/mavsdk_tests/autopilot_tester.cpp @@ -42,6 +42,17 @@ void AutopilotTester::wait_until_ready_local_position_only() }, std::chrono::seconds(20))); } +void AutopilotTester::store_home() +{ + request_ground_truth(); + _home = get_ground_truth_position(); +} + +void AutopilotTester::check_home_within(float acceptance_radius_m) +{ + CHECK(ground_truth_horizontal_position_close_to(_home, acceptance_radius_m)); +} + void AutopilotTester::set_takeoff_altitude(const float altitude_m) { CHECK(Action::Result::SUCCESS == _action->set_takeoff_altitude(altitude_m)); @@ -94,12 +105,12 @@ void AutopilotTester::wait_until_hovering() void AutopilotTester::prepare_square_mission(MissionOptions mission_options) { - const auto ct = _get_coordinate_transformation(); + const auto ct = get_coordinate_transformation(); std::vector> mission_items {}; - mission_items.push_back(_create_mission_item({mission_options.leg_length_m, 0.}, mission_options, ct)); - mission_items.push_back(_create_mission_item({mission_options.leg_length_m, mission_options.leg_length_m}, mission_options, ct)); - mission_items.push_back(_create_mission_item({0., mission_options.leg_length_m}, mission_options, ct)); + mission_items.push_back(create_mission_item({mission_options.leg_length_m, 0.}, mission_options, ct)); + mission_items.push_back(create_mission_item({mission_options.leg_length_m, mission_options.leg_length_m}, mission_options, ct)); + mission_items.push_back(create_mission_item({0., mission_options.leg_length_m}, mission_options, ct)); _mission->set_return_to_launch_after_mission(mission_options.rtl_at_end); @@ -132,7 +143,7 @@ void AutopilotTester::execute_mission() REQUIRE(fut.wait_for(std::chrono::seconds(1)) == std::future_status::ready); } -CoordinateTransformation AutopilotTester::_get_coordinate_transformation() +CoordinateTransformation AutopilotTester::get_coordinate_transformation() { const auto home = _telemetry->home_position(); REQUIRE(std::isfinite(home.latitude_deg)); @@ -140,7 +151,7 @@ CoordinateTransformation AutopilotTester::_get_coordinate_transformation() return CoordinateTransformation({home.latitude_deg, home.longitude_deg}); } -std::shared_ptr AutopilotTester::_create_mission_item( +std::shared_ptr AutopilotTester::create_mission_item( const CoordinateTransformation::LocalCoordinate& local_coordinate, const MissionOptions& mission_options, const CoordinateTransformation& ct) diff --git a/test/mavsdk_tests/autopilot_tester.h b/test/mavsdk_tests/autopilot_tester.h index 9ce340d280..3b0b6d8bf7 100644 --- a/test/mavsdk_tests/autopilot_tester.h +++ b/test/mavsdk_tests/autopilot_tester.h @@ -27,6 +27,8 @@ public: void connect(const std::string uri); void wait_until_ready(); void wait_until_ready_local_position_only(); + void store_home(); + void check_home_within(float acceptance_radius_m); void set_takeoff_altitude(const float altitude_m); void arm(); void takeoff(); @@ -41,25 +43,28 @@ public: void offboard_goto(const Offboard::PositionNEDYaw& target, float acceptance_radius = 0.3f, std::chrono::seconds timeout_duration = std::chrono::seconds(60)); void offboard_land(); - bool estimated_position_close_to(const Offboard::PositionNEDYaw& target_position, float acceptance_radius_m); - bool estimated_horizontal_position_close_to(const Offboard::PositionNEDYaw& target_pos, float acceptance_radius_m); void request_ground_truth(); - Telemetry::GroundTruth get_ground_truth_position(); - bool ground_truth_horizontal_position_close_to(const Telemetry::GroundTruth& target_pos, float acceptance_radius_m); private: - mavsdk::geometry::CoordinateTransformation _get_coordinate_transformation(); - std::shared_ptr _create_mission_item( + mavsdk::geometry::CoordinateTransformation get_coordinate_transformation(); + std::shared_ptr create_mission_item( const mavsdk::geometry::CoordinateTransformation::LocalCoordinate& local_coordinate, const MissionOptions& mission_options, const mavsdk::geometry::CoordinateTransformation& ct); + Telemetry::GroundTruth get_ground_truth_position(); + + bool ground_truth_horizontal_position_close_to(const Telemetry::GroundTruth& target_pos, float acceptance_radius_m); + bool estimated_position_close_to(const Offboard::PositionNEDYaw& target_position, float acceptance_radius_m); + bool estimated_horizontal_position_close_to(const Offboard::PositionNEDYaw& target_pos, float acceptance_radius_m); mavsdk::Mavsdk _mavsdk{}; std::unique_ptr _telemetry{}; std::unique_ptr _action{}; std::unique_ptr _mission{}; std::unique_ptr _offboard{}; + + Telemetry::GroundTruth _home{NAN, NAN, NAN}; }; template diff --git a/test/mavsdk_tests/test_multicopter_offboard.cpp b/test/mavsdk_tests/test_multicopter_offboard.cpp index 89552c8141..18430b2727 100644 --- a/test/mavsdk_tests/test_multicopter_offboard.cpp +++ b/test/mavsdk_tests/test_multicopter_offboard.cpp @@ -17,13 +17,12 @@ TEST_CASE("Takeoff and Land (Multicopter offboard)", "[multicopter_offboard]") Offboard::PositionNEDYaw takeoff_position {0.0f, 0.0f, -2.0f, 0.0f}; tester.connect(connection_url); tester.wait_until_ready_local_position_only(); - tester.request_ground_truth(); - Telemetry::GroundTruth home = tester.get_ground_truth_position(); + tester.store_home(); tester.arm(); tester.offboard_goto(takeoff_position, 0.5f); tester.offboard_land(); tester.wait_until_disarmed(); - REQUIRE(tester.ground_truth_horizontal_position_close_to(home, 0.5f)); + tester.check_home_within(0.5f); } TEST_CASE("Mission (Multicopter offboard )", "[multicopter_offboard]") @@ -35,8 +34,7 @@ TEST_CASE("Mission (Multicopter offboard )", "[multicopter_offboard]") Offboard::PositionNEDYaw setpoint_3 {5.0f, 0.0f, -4.0f, 90.0f}; tester.connect(connection_url); tester.wait_until_ready_local_position_only(); - tester.request_ground_truth(); - Telemetry::GroundTruth home = tester.get_ground_truth_position(); + tester.store_home(); tester.arm(); tester.offboard_goto(takeoff_position, 0.5f); tester.offboard_goto(setpoint_1, 1.0f); @@ -45,5 +43,5 @@ TEST_CASE("Mission (Multicopter offboard )", "[multicopter_offboard]") tester.offboard_goto(takeoff_position, 0.2f); tester.offboard_land(); tester.wait_until_disarmed(); - REQUIRE(tester.ground_truth_horizontal_position_close_to(home, 1.0f)); + tester.check_home_within(1.0f); }