diff --git a/test/mavsdk_tests/test_multicopter_failsafe.cpp b/test/mavsdk_tests/test_multicopter_failsafe.cpp index 68fa56f6dd..13896d68fb 100644 --- a/test/mavsdk_tests/test_multicopter_failsafe.cpp +++ b/test/mavsdk_tests/test_multicopter_failsafe.cpp @@ -34,7 +34,7 @@ #include "autopilot_tester.h" -TEST_CASE("Land on GPS lost during mission (baro height mode)", "[multicopter][vtol]") +TEST_CASE("Land on GPS lost during mission (baro height mode)", "[multicopter]") { AutopilotTester tester; tester.connect(connection_url); @@ -51,7 +51,7 @@ TEST_CASE("Land on GPS lost during mission (baro height mode)", "[multicopter][v tester.wait_until_disarmed(until_disarmed_timeout); } -TEST_CASE("Land on GPS lost during mission (GPS height mode)", "[multicopter][vtol]") +TEST_CASE("Land on GPS lost during mission (GPS height mode)", "[multicopter]") { AutopilotTester tester; tester.connect(connection_url); @@ -68,7 +68,7 @@ TEST_CASE("Land on GPS lost during mission (GPS height mode)", "[multicopter][vt tester.wait_until_disarmed(until_disarmed_timeout); } -TEST_CASE("Continue on mag lost during mission", "[multicopter][vtol]") +TEST_CASE("Continue on mag lost during mission", "[multicopter]") { AutopilotTester tester; tester.connect(connection_url); @@ -102,7 +102,7 @@ TEST_CASE("Continue on mag stuck during mission", "[multicopter][vtol]") } #endif -TEST_CASE("Continue on baro lost during mission (baro height mode)", "[multicopter][vtol]") +TEST_CASE("Continue on baro lost during mission (baro height mode)", "[multicopter]") { AutopilotTester tester; tester.connect(connection_url); @@ -118,7 +118,7 @@ TEST_CASE("Continue on baro lost during mission (baro height mode)", "[multicopt tester.wait_until_disarmed(until_disarmed_timeout); } -TEST_CASE("Continue on baro lost during mission (GPS height mode)", "[multicopter][vtol]") +TEST_CASE("Continue on baro lost during mission (GPS height mode)", "[multicopter]") { AutopilotTester tester; tester.connect(connection_url); @@ -134,7 +134,7 @@ TEST_CASE("Continue on baro lost during mission (GPS height mode)", "[multicopte tester.wait_until_disarmed(until_disarmed_timeout); } -TEST_CASE("Continue on baro stuck during mission (baro height mode)", "[multicopter][vtol]") +TEST_CASE("Continue on baro stuck during mission (baro height mode)", "[multicopter]") { AutopilotTester tester; tester.connect(connection_url); @@ -150,7 +150,7 @@ TEST_CASE("Continue on baro stuck during mission (baro height mode)", "[multicop tester.wait_until_disarmed(until_disarmed_timeout); } -TEST_CASE("Continue on baro stuck during mission (GPS height mode)", "[multicopter][vtol]") +TEST_CASE("Continue on baro stuck during mission (GPS height mode)", "[multicopter]") { AutopilotTester tester; tester.connect(connection_url); diff --git a/test/mavsdk_tests/test_multicopter_mission.cpp b/test/mavsdk_tests/test_multicopter_mission.cpp index 3ddd566d9d..8ce54f0c1b 100644 --- a/test/mavsdk_tests/test_multicopter_mission.cpp +++ b/test/mavsdk_tests/test_multicopter_mission.cpp @@ -48,7 +48,7 @@ TEST_CASE("Takeoff and Land", "[multicopter][vtol]") tester.wait_until_disarmed(until_disarmed_timeout); } -TEST_CASE("Fly square Multicopter Missions including RTL", "[multicopter][vtol]") +TEST_CASE("Fly square Multicopter Missions including RTL", "[multicopter]") { AutopilotTester tester; tester.connect(connection_url); @@ -63,7 +63,7 @@ TEST_CASE("Fly square Multicopter Missions including RTL", "[multicopter][vtol]" tester.wait_until_disarmed(until_disarmed_timeout); } -TEST_CASE("Fly square Multicopter Missions with manual RTL", "[multicopter][vtol]") +TEST_CASE("Fly square Multicopter Missions with manual RTL", "[multicopter]") { AutopilotTester tester; tester.connect(connection_url);