Skip to content

Commit

Permalink
Allow users to configure the executor for executables in `demo_nodes_…
Browse files Browse the repository at this point in the history
…cpp` (#666)

* Allow users to build demo executables to run with a different executor

Signed-off-by: Yadunund <yadunund@openrobotics.org>
Signed-off-by: Yadu <yadunund@gmail.com>
Co-authored-by: Michael Carroll <michael@openrobotics.org>
Co-authored-by: Tomoya Fujita <Tomoya.Fujita@sony.com>
  • Loading branch information
3 people committed Feb 9, 2024
1 parent 5b81fcc commit 93030b5
Show file tree
Hide file tree
Showing 2 changed files with 12 additions and 1 deletion.
5 changes: 4 additions & 1 deletion demo_nodes_cpp/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
8 changes: 8 additions & 0 deletions demo_nodes_cpp/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down

0 comments on commit 93030b5

Please sign in to comment.