From 93030b5f72896567df14bd151f992390b444cc43 Mon Sep 17 00:00:00 2001 From: Yadu Date: Fri, 9 Feb 2024 21:08:19 +0800 Subject: [PATCH] Allow users to configure the executor for executables in `demo_nodes_cpp` (#666) * Allow users to build demo executables to run with a different executor Signed-off-by: Yadunund Signed-off-by: Yadu Co-authored-by: Michael Carroll Co-authored-by: Tomoya Fujita --- demo_nodes_cpp/CMakeLists.txt | 5 ++++- demo_nodes_cpp/README.md | 8 ++++++++ 2 files changed, 12 insertions(+), 1 deletion(-) diff --git a/demo_nodes_cpp/CMakeLists.txt b/demo_nodes_cpp/CMakeLists.txt index ea9ff980f..d06f18d07 100644 --- a/demo_nodes_cpp/CMakeLists.txt +++ b/demo_nodes_cpp/CMakeLists.txt @@ -92,9 +92,12 @@ function(create_demo_library plugin executable) ARCHIVE DESTINATION lib LIBRARY DESTINATION lib RUNTIME DESTINATION bin) + set(DEMO_EXECUTOR "rclcpp::executors::SingleThreadedExecutor" CACHE STRING "The executor for the demo nodes") + message(STATUS "Setting executor of ${executable} to ${DEMO_EXECUTOR}") rclcpp_components_register_node(${library} PLUGIN ${plugin} - EXECUTABLE ${executable}) + EXECUTABLE ${executable} + EXECUTOR ${DEMO_EXECUTOR}) endfunction() # Timers diff --git a/demo_nodes_cpp/README.md b/demo_nodes_cpp/README.md index 6e70ebf45..fcb3ada8f 100644 --- a/demo_nodes_cpp/README.md +++ b/demo_nodes_cpp/README.md @@ -37,6 +37,14 @@ Run the command below to compile the `demo_nodes_cpp` ROS 2 package: colcon build --packages-up-to demo_nodes_cpp ``` +**Note**: By default, the demo executables will spin up the [SingleThreaded executor](https://docs.ros.org/en/rolling/Concepts/Intermediate/About-Executors.html#executors) if run in separate processes, i.e., not composed in the same component container. +To configure the demo executables to run with a different executor, build the package with the custom `DEMO_EXECUTOR` flag set to the fully qualified name of the executor. +For example, to run with the experimental `EventsExecutor`, + +```bash +colcon build --packages-select demo_nodes_cpp --cmake-args -DDEMO_EXECUTOR:STRING=rclcpp::experimental::executors::EventsExecutor +``` + ## **Run** ### Basic Talker & Listener