diff --git a/mock/cpp_mock_scenarios/src/cpp_scenario_node.cpp b/mock/cpp_mock_scenarios/src/cpp_scenario_node.cpp index 5376b050fa7..b91c22772bb 100644 --- a/mock/cpp_mock_scenarios/src/cpp_scenario_node.cpp +++ b/mock/cpp_mock_scenarios/src/cpp_scenario_node.cpp @@ -113,33 +113,14 @@ void CppScenarioNode::spawnEgoEntity( return configuration; }()); api_.requestAssignRoute("ego", goal_lanelet_poses); + using namespace std::chrono_literals; - // std::atomic initialized(false); - // auto initialize_thread = std::thread([&]() { - // while (!api_.asFieldOperatorApplication("ego").engaged()) { - // api_.updateFrame(); - // std::this_thread::sleep_for(std::chrono::duration(1.0 / 20.0)); - // } - // initialized.store(true); - // }); - // std::atomic engaged(false); - // auto engage_thread = std::thread([&]() { while (!api_.asFieldOperatorApplication("ego").engaged()) { if (api_.asFieldOperatorApplication("ego").engageable()) api_.asFieldOperatorApplication("ego").engage(); api_.updateFrame(); std::this_thread::sleep_for(std::chrono::duration(1.0 / 20.0)); - // std::this_thread::sleep_for(1000ms); } - // engaged.store(true); - // }); - // while (!api_.asFieldOperatorApplication("ego").engaged() && - // !(initialized.load() && engaged.load())) { - // RCLCPP_INFO_STREAM(get_logger(), "Waiting for Autoware initialization..."); - // std::this_thread::sleep_for(std::chrono::duration(1.0 / 20.0)); - // } - // initialize_thread.join(); - // engage_thread.join(); } void CppScenarioNode::checkConfiguration(const traffic_simulator::Configuration & configuration)