Program Listing for File node_interfaces.hpp

Return to documentation for file (include/rclcpp/node_interfaces/node_interfaces.hpp)

// Copyright 2022 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__NODE_INTERFACES__NODE_INTERFACES_HPP_
#define RCLCPP__NODE_INTERFACES__NODE_INTERFACES_HPP_

#include <memory>

#include "rclcpp/detail/template_unique.hpp"
#include "rclcpp/node_interfaces/detail/node_interfaces_helpers.hpp"

#define ALL_RCLCPP_NODE_INTERFACES \
  rclcpp::node_interfaces::NodeBaseInterface, \
  rclcpp::node_interfaces::NodeClockInterface, \
  rclcpp::node_interfaces::NodeGraphInterface, \
  rclcpp::node_interfaces::NodeLoggingInterface, \
  rclcpp::node_interfaces::NodeParametersInterface, \
  rclcpp::node_interfaces::NodeServicesInterface, \
  rclcpp::node_interfaces::NodeTimeSourceInterface, \
  rclcpp::node_interfaces::NodeTimersInterface, \
  rclcpp::node_interfaces::NodeTopicsInterface, \
  rclcpp::node_interfaces::NodeTypeDescriptionsInterface, \
  rclcpp::node_interfaces::NodeWaitablesInterface


namespace rclcpp
{
namespace node_interfaces
{


template<typename ... InterfaceTs>
class NodeInterfaces
  : public detail::NodeInterfacesSupportCheck<
    detail::NodeInterfacesStorage<InterfaceTs ...>,
    InterfaceTs ...
  >,
  public detail::NodeInterfacesSupports<
    detail::NodeInterfacesStorage<InterfaceTs ...>,
    InterfaceTs ...
  >
{
  static_assert(
    0 != sizeof ...(InterfaceTs),
    "must provide at least one interface as a template argument");
  static_assert(
    rclcpp::detail::template_unique_v<InterfaceTs ...>,
    "must provide unique template parameters");

  using NodeInterfacesSupportsT = detail::NodeInterfacesSupports<
    detail::NodeInterfacesStorage<InterfaceTs ...>,
    InterfaceTs ...
  >;

public:

  template<typename NodeT>
  NodeInterfaces(NodeT & node)  // NOLINT(runtime/explicit)
  : NodeInterfacesSupportsT(node)
  {}

  // Create a NodeInterfaces object with no bound interfaces
  NodeInterfaces()
  : NodeInterfacesSupportsT()
  {}

  explicit NodeInterfaces(std::shared_ptr<InterfaceTs>... args)
  : NodeInterfacesSupportsT(args ...)
  {}
};


}  // namespace node_interfaces
}  // namespace rclcpp

#endif  // RCLCPP__NODE_INTERFACES__NODE_INTERFACES_HPP_