diff --git a/rclcpp_components/src/node_main.cpp b/rclcpp_components/src/node_main.cpp deleted file mode 100644 index a8ea6e7b5f..0000000000 --- a/rclcpp_components/src/node_main.cpp +++ /dev/null @@ -1,68 +0,0 @@ -// Copyright 2016 Open Source Robotics Foundation, Inc. -// -// 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. - -#include -#include -#include - -#include "class_loader/class_loader.hpp" -#include "rclcpp/rclcpp.hpp" -#include "rclcpp_components/node_factory.hpp" - -#define NODE_MAIN_LOGGER_NAME "node_main" - -int main(int argc, char * argv[]) -{ - // Force flush of the stdout buffer. - setvbuf(stdout, NULL, _IONBF, BUFSIZ); - - auto args = rclcpp::init_and_remove_ros_arguments(argc, argv); - rclcpp::Logger logger = rclcpp::get_logger(NODE_MAIN_LOGGER_NAME); - rclcpp::executors::SingleThreadedExecutor exec; - rclcpp::NodeOptions options; - options.arguments(args); - std::vector loaders; - std::vector node_wrappers; - - std::vector libraries = { - // all classes from libraries linked by the linker (rather then dlopen) - // are registered under the library_path "" - "", - }; - for (auto library : libraries) { - RCLCPP_DEBUG(logger, "Loading library %s", library.c_str()); - auto loader = new class_loader::ClassLoader(library); - auto classes = loader->getAvailableClasses(); - for (auto clazz : classes) { - RCLCPP_DEBUG(logger, "Instantiate class %s", clazz.c_str()); - auto node_factory = loader->createInstance(clazz); - auto wrapper = node_factory->create_node_instance(options); - auto node = wrapper.get_node_base_interface(); - node_wrappers.push_back(wrapper); - exec.add_node(node); - } - loaders.push_back(loader); - } - - exec.spin(); - - for (auto wrapper : node_wrappers) { - exec.remove_node(wrapper.get_node_base_interface()); - } - node_wrappers.clear(); - - rclcpp::shutdown(); - - return 0; -}