From 83a9a1fbe8f0de246eff7c27afa55619b57071ae Mon Sep 17 00:00:00 2001 From: Tim Clephas Date: Mon, 24 Jun 2024 08:54:41 +0200 Subject: [PATCH] Parse '--executor-type' Signed-off-by: Tim Clephas --- .../src/component_container_isolated.cpp | 54 ++++++++++++------- 1 file changed, 34 insertions(+), 20 deletions(-) diff --git a/rclcpp_components/src/component_container_isolated.cpp b/rclcpp_components/src/component_container_isolated.cpp index 2ca9f2d141..fff342ec50 100644 --- a/rclcpp_components/src/component_container_isolated.cpp +++ b/rclcpp_components/src/component_container_isolated.cpp @@ -13,8 +13,8 @@ // limitations under the License. #include -#include #include +#include #include "rclcpp/rclcpp.hpp" #include "rclcpp/utilities.hpp" @@ -22,37 +22,51 @@ int main(int argc, char * argv[]) { - /// Component container with dedicated single-threaded executors for each components. + /// Component container with dedicated executor for each component rclcpp::init(argc, argv); + // parse arguments - bool use_multi_threaded_executor{false}; - bool use_events_executor{false}; + // valid entries: --executor-type single-threaded, --executor-type multi-threaded, --executor-type events + // --use-multi-threaded-executor and --use_multi_threaded_executor are kept for backward compatibility std::vector args = rclcpp::remove_ros_arguments(argc, argv); - for (auto & arg : args) { - if (arg == std::string("--use_multi_threaded_executor") || - arg == std::string("--use-multi-threaded-executor")) + + std::string executor_type = "single-threaded"; // default + for (size_t i = 0; i < args.size(); ++i) { + if (args[i] == "--executor-type") { + if (i + 1 < args.size()) { + executor_type = args[i + 1]; + break; + } + } else if ( + args[i] == "--use-multi-threaded-executor" || args[i] == "--use_multi_threaded_executor") { - use_multi_threaded_executor = true; - } else if (arg == std::string("--use-events-executor")) { - use_events_executor = true; + executor_type = "multi-threaded"; } } + // create executor and component manager - auto exec = std::make_shared(); rclcpp::Node::SharedPtr node; - if (use_multi_threaded_executor) { - using ComponentManagerIsolated = - rclcpp_components::ComponentManagerIsolated; + std::shared_ptr exec; + if (executor_type == "events") { + using executor = rclcpp::experimental::executors::EventsExecutor; + using ComponentManagerIsolated = rclcpp_components::ComponentManagerIsolated; + exec = std::make_shared(); node = std::make_shared(exec); - } else if (use_events_executor) { - using ComponentManagerIsolated = - rclcpp_components::ComponentManagerIsolated; + } else if (executor_type == "multi-threaded") { + using executor = rclcpp::executors::MultiThreadedExecutor; + using ComponentManagerIsolated = rclcpp_components::ComponentManagerIsolated; + exec = std::make_shared(); node = std::make_shared(exec); - } else { - using ComponentManagerIsolated = - rclcpp_components::ComponentManagerIsolated; + } else if (executor_type == "single-threaded") { + using executor = rclcpp::executors::SingleThreadedExecutor; + using ComponentManagerIsolated = rclcpp_components::ComponentManagerIsolated; + exec = std::make_shared(); node = std::make_shared(exec); + } else { + std::cerr << "Invalid executor type: " << executor_type << std::endl; + return 1; } + exec->add_node(node); exec->spin(); }