@@ -26,10 +26,15 @@ int main(int argc, char * argv[])
2626  rclcpp::init (argc, argv);
2727  //  parse arguments
2828  bool  use_multi_threaded_executor{false };
29+   bool  use_events_executor{false };
2930  std::vector<std::string> args = rclcpp::remove_ros_arguments (argc, argv);
3031  for  (auto  & arg : args) {
31-     if  (arg == std::string (" --use_multi_threaded_executor" 
32+     if  (arg == std::string (" --use_multi_threaded_executor" 
33+       arg == std::string (" --use-multi-threaded-executor" 
34+     {
3235      use_multi_threaded_executor = true ;
36+     } else  if  (arg == std::string (" --use-events-executor" 
37+       use_events_executor = true ;
3338    }
3439  }
3540  //  create executor and component manager
@@ -39,6 +44,10 @@ int main(int argc, char * argv[])
3944    using  ComponentManagerIsolated =
4045      rclcpp_components::ComponentManagerIsolated<rclcpp::executors::MultiThreadedExecutor>;
4146    node = std::make_shared<ComponentManagerIsolated>(exec);
47+   } else  if  (use_events_executor) {
48+     using  ComponentManagerIsolated =
49+       rclcpp_components::ComponentManagerIsolated<rclcpp::experimental::executors::EventsExecutor>;
50+     node = std::make_shared<ComponentManagerIsolated>(exec);
4251  } else  {
4352    using  ComponentManagerIsolated =
4453      rclcpp_components::ComponentManagerIsolated<rclcpp::executors::SingleThreadedExecutor>;
0 commit comments