diff --git a/rclcpp_components/CMakeLists.txt b/rclcpp_components/CMakeLists.txt index 7d4135051c..561f2402cd 100644 --- a/rclcpp_components/CMakeLists.txt +++ b/rclcpp_components/CMakeLists.txt @@ -56,6 +56,12 @@ add_executable( ) target_link_libraries(component_container component_manager rclcpp::rclcpp) +add_executable( + component_container_event + src/component_container_event.cpp +) +target_link_libraries(component_container_event component_manager rclcpp::rclcpp) + set(node_main_template_install_dir "share/${PROJECT_NAME}") install(FILES src/node_main.cpp.in @@ -145,7 +151,7 @@ install( # Install executables install( - TARGETS component_container component_container_mt component_container_isolated + TARGETS component_container component_container_mt component_container_isolated component_container_event RUNTIME DESTINATION lib/${PROJECT_NAME} ) diff --git a/rclcpp_components/src/component_container_event.cpp b/rclcpp_components/src/component_container_event.cpp new file mode 100644 index 0000000000..28c56d6b1f --- /dev/null +++ b/rclcpp_components/src/component_container_event.cpp @@ -0,0 +1,30 @@ +// Copyright 2025 Open Source Robotics Foundation, Inc.Add commentMore actions +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License.Add commentMore actions + +#include + +#include "rclcpp/rclcpp.hpp" +#include "rclcpp/experimental/executors/events_executor/events_executor.hpp" + +#include "rclcpp_components/component_manager.hpp" + +int main(int argc, char * argv[]) +{ + /// Component container with an events executor. + rclcpp::init(argc, argv); + auto exec = std::make_shared(); + auto node = std::make_shared(exec); + exec->add_node(node); + exec->spin(); +}