mavsdk_tests: remove timeout for mission upload

Just use what is MAVSDK internal.
This commit is contained in:
Julian Oes 2021-02-12 11:39:56 +01:00 committed by Lorenz Meier
parent cf2ffb1086
commit b79553862e
1 changed files with 2 additions and 18 deletions

View File

@ -179,15 +179,7 @@ void AutopilotTester::prepare_square_mission(MissionOptions mission_options)
_mission->set_return_to_launch_after_mission(mission_options.rtl_at_end);
std::promise<void> prom;
auto fut = prom.get_future();
_mission->upload_mission_async(mission_plan, [&prom](Mission::Result result) {
REQUIRE(Mission::Result::Success == result);
prom.set_value();
});
REQUIRE(fut.wait_for(std::chrono::seconds(2)) == std::future_status::ready);
REQUIRE(_mission->upload_mission(mission_plan) == Mission::Result::Success);
}
void AutopilotTester::prepare_straight_mission(MissionOptions mission_options)
@ -203,15 +195,7 @@ void AutopilotTester::prepare_straight_mission(MissionOptions mission_options)
_mission->set_return_to_launch_after_mission(mission_options.rtl_at_end);
std::promise<void> prom;
auto fut = prom.get_future();
_mission->upload_mission_async(mission_plan, [&prom](Mission::Result result) {
REQUIRE(Mission::Result::Success == result);
prom.set_value();
});
REQUIRE(fut.wait_for(std::chrono::seconds(2)) == std::future_status::ready);
REQUIRE(_mission->upload_mission(mission_plan) == Mission::Result::Success);
}
void AutopilotTester::execute_mission()