Skip to content

Commit 93030b5

Browse files
Yadunundmjcarrollfujitatomoya
authored
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 <[email protected]> Signed-off-by: Yadu <[email protected]> Co-authored-by: Michael Carroll <[email protected]> Co-authored-by: Tomoya Fujita <[email protected]>
1 parent 5b81fcc commit 93030b5

File tree

2 files changed

+12
-1
lines changed

2 files changed

+12
-1
lines changed

demo_nodes_cpp/CMakeLists.txt

Lines changed: 4 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -92,9 +92,12 @@ function(create_demo_library plugin executable)
9292
ARCHIVE DESTINATION lib
9393
LIBRARY DESTINATION lib
9494
RUNTIME DESTINATION bin)
95+
set(DEMO_EXECUTOR "rclcpp::executors::SingleThreadedExecutor" CACHE STRING "The executor for the demo nodes")
96+
message(STATUS "Setting executor of ${executable} to ${DEMO_EXECUTOR}")
9597
rclcpp_components_register_node(${library}
9698
PLUGIN ${plugin}
97-
EXECUTABLE ${executable})
99+
EXECUTABLE ${executable}
100+
EXECUTOR ${DEMO_EXECUTOR})
98101
endfunction()
99102

100103
# Timers

demo_nodes_cpp/README.md

Lines changed: 8 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -37,6 +37,14 @@ Run the command below to compile the `demo_nodes_cpp` ROS 2 package:
3737
colcon build --packages-up-to demo_nodes_cpp
3838
```
3939

40+
**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.
41+
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.
42+
For example, to run with the experimental `EventsExecutor`,
43+
44+
```bash
45+
colcon build --packages-select demo_nodes_cpp --cmake-args -DDEMO_EXECUTOR:STRING=rclcpp::experimental::executors::EventsExecutor
46+
```
47+
4048
## **Run**
4149

4250
### Basic Talker & Listener

0 commit comments

Comments
 (0)