Skip to content

Commit

Permalink
Add option for the events executor to the isolated component container
Browse files Browse the repository at this point in the history
  • Loading branch information
Timple committed May 27, 2024
1 parent 22df1d5 commit 5deb093
Showing 1 changed file with 10 additions and 1 deletion.
11 changes: 10 additions & 1 deletion rclcpp_components/src/component_container_isolated.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -26,10 +26,15 @@ int main(int argc, char * argv[])
rclcpp::init(argc, argv);
// parse arguments
bool use_multi_threaded_executor{false};
bool use_events_executor{false};
std::vector<std::string> args = rclcpp::remove_ros_arguments(argc, argv);
for (auto & arg : args) {
if (arg == std::string("--use_multi_threaded_executor")) {
if (arg == std::string("--use_multi_threaded_executor") ||
arg == std::string("--use-multi-threaded-executor"))
{
use_multi_threaded_executor = true;
} else if (arg == std::string("--use-events-executor")) {
use_events_executor = true;
}
}
// create executor and component manager
Expand All @@ -39,6 +44,10 @@ int main(int argc, char * argv[])
using ComponentManagerIsolated =
rclcpp_components::ComponentManagerIsolated<rclcpp::executors::MultiThreadedExecutor>;
node = std::make_shared<ComponentManagerIsolated>(exec);
} else if (use_events_executor) {
using ComponentManagerIsolated =
rclcpp_components::ComponentManagerIsolated<rclcpp::experimental::executors::EventsExecutor>;
node = std::make_shared<ComponentManagerIsolated>(exec);
} else {
using ComponentManagerIsolated =
rclcpp_components::ComponentManagerIsolated<rclcpp::executors::SingleThreadedExecutor>;
Expand Down

0 comments on commit 5deb093

Please sign in to comment.