Program Listing for File component_manager.hpp

Return to documentation for file (include/rclcpp_components/component_manager.hpp)

// Copyright 2019 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.

#ifndef RCLCPP_COMPONENTS__COMPONENT_MANAGER_HPP__
#define RCLCPP_COMPONENTS__COMPONENT_MANAGER_HPP__

#include <map>
#include <memory>
#include <string>
#include <utility>
#include <vector>

#include "composition_interfaces/srv/load_node.hpp"
#include "composition_interfaces/srv/unload_node.hpp"
#include "composition_interfaces/srv/list_nodes.hpp"

#include "rclcpp/executor.hpp"
#include "rclcpp/node_options.hpp"
#include "rclcpp/rclcpp.hpp"

#include "rclcpp_components/node_factory.hpp"
#include "rclcpp_components/visibility_control.hpp"

namespace class_loader
{
class ClassLoader;
}  // namespace class_loader

namespace rclcpp_components
{

class ComponentManagerException : public std::runtime_error
{
public:
  explicit ComponentManagerException(const std::string & error_desc)
  : std::runtime_error(error_desc) {}
};

class ComponentManager : public rclcpp::Node
{
public:
  using LoadNode = composition_interfaces::srv::LoadNode;
  using UnloadNode = composition_interfaces::srv::UnloadNode;
  using ListNodes = composition_interfaces::srv::ListNodes;


  using ComponentResource = std::pair<std::string, std::string>;


  RCLCPP_COMPONENTS_PUBLIC
  ComponentManager(
    std::weak_ptr<rclcpp::Executor> executor =
    std::weak_ptr<rclcpp::executors::MultiThreadedExecutor>(),
    std::string node_name = "ComponentManager",
    const rclcpp::NodeOptions & node_options = rclcpp::NodeOptions()
    .start_parameter_services(false)
    .start_parameter_event_publisher(false));

  RCLCPP_COMPONENTS_PUBLIC
  virtual ~ComponentManager();


  RCLCPP_COMPONENTS_PUBLIC
  virtual std::vector<ComponentResource>
  get_component_resources(
    const std::string & package_name,
    const std::string & resource_index = "rclcpp_components") const;


  RCLCPP_COMPONENTS_PUBLIC
  virtual std::shared_ptr<rclcpp_components::NodeFactory>
  create_component_factory(const ComponentResource & resource);


  RCLCPP_COMPONENTS_PUBLIC
  virtual void
  set_executor(const std::weak_ptr<rclcpp::Executor> executor);

protected:

  RCLCPP_COMPONENTS_PUBLIC
  virtual rclcpp::NodeOptions
  create_node_options(const std::shared_ptr<LoadNode::Request> request);


  RCLCPP_COMPONENTS_PUBLIC
  virtual void
  add_node_to_executor(uint64_t node_id);


  RCLCPP_COMPONENTS_PUBLIC
  virtual void
  remove_node_from_executor(uint64_t node_id);


  RCLCPP_COMPONENTS_PUBLIC
  virtual void
  on_load_node(
    const std::shared_ptr<rmw_request_id_t> request_header,
    const std::shared_ptr<LoadNode::Request> request,
    std::shared_ptr<LoadNode::Response> response);

  [[deprecated("Use on_load_node() instead")]]
  RCLCPP_COMPONENTS_PUBLIC
  virtual void
  OnLoadNode(
    const std::shared_ptr<rmw_request_id_t> request_header,
    const std::shared_ptr<LoadNode::Request> request,
    std::shared_ptr<LoadNode::Response> response)
  {
    on_load_node(request_header, request, response);
  }


  RCLCPP_COMPONENTS_PUBLIC
  virtual void
  on_unload_node(
    const std::shared_ptr<rmw_request_id_t> request_header,
    const std::shared_ptr<UnloadNode::Request> request,
    std::shared_ptr<UnloadNode::Response> response);

  [[deprecated("Use on_unload_node() instead")]]
  RCLCPP_COMPONENTS_PUBLIC
  virtual void
  OnUnloadNode(
    const std::shared_ptr<rmw_request_id_t> request_header,
    const std::shared_ptr<UnloadNode::Request> request,
    std::shared_ptr<UnloadNode::Response> response)
  {
    on_unload_node(request_header, request, response);
  }


  RCLCPP_COMPONENTS_PUBLIC
  virtual void
  on_list_nodes(
    const std::shared_ptr<rmw_request_id_t> request_header,
    const std::shared_ptr<ListNodes::Request> request,
    std::shared_ptr<ListNodes::Response> response);

  [[deprecated("Use on_list_nodes() instead")]]
  RCLCPP_COMPONENTS_PUBLIC
  virtual void
  OnListNodes(
    const std::shared_ptr<rmw_request_id_t> request_header,
    const std::shared_ptr<ListNodes::Request> request,
    std::shared_ptr<ListNodes::Response> response)
  {
    on_list_nodes(request_header, request, response);
  }

protected:
  std::weak_ptr<rclcpp::Executor> executor_;

  uint64_t unique_id_ {1};
  std::map<std::string, std::unique_ptr<class_loader::ClassLoader>> loaders_;
  std::map<uint64_t, rclcpp_components::NodeInstanceWrapper> node_wrappers_;

  rclcpp::Service<LoadNode>::SharedPtr loadNode_srv_;
  rclcpp::Service<UnloadNode>::SharedPtr unloadNode_srv_;
  rclcpp::Service<ListNodes>::SharedPtr listNodes_srv_;
};

}  // namespace rclcpp_components

#endif  // RCLCPP_COMPONENTS__COMPONENT_MANAGER_HPP__