Program Listing for File babel_fish.hpp

Return to documentation for file (include/ros_babel_fish/babel_fish.hpp)

// Copyright (c) 2021 Stefan Fabian. All rights reserved.
// Licensed under the MIT license. See LICENSE file in the project root for full license information.

#ifndef ROS_BABEL_FISH_BABEL_FISH_HPP
#define ROS_BABEL_FISH_BABEL_FISH_HPP

#include "ros_babel_fish/detail/babel_fish_action_client.hpp"
#include "ros_babel_fish/detail/babel_fish_publisher.hpp"
#include "ros_babel_fish/detail/babel_fish_service.hpp"
#include "ros_babel_fish/detail/babel_fish_service_client.hpp"
#include "ros_babel_fish/detail/babel_fish_subscription.hpp"
#include "ros_babel_fish/idl/type_support_provider.hpp"
#include "ros_babel_fish/messages/array_message.hpp"
#include "ros_babel_fish/messages/compound_message.hpp"
#include "ros_babel_fish/messages/value_message.hpp"

#include <rclcpp/node.hpp>

namespace ros_babel_fish
{

class BabelFish : public std::enable_shared_from_this<BabelFish>
{

public:
  RCLCPP_SMART_PTR_DEFINITIONS( BabelFish )


  BabelFish();

  explicit BabelFish( std::vector<TypeSupportProvider::SharedPtr> type_support_providers );

  ~BabelFish();

  template<typename CallbackT>
  BabelFishSubscription::SharedPtr
  create_subscription( rclcpp::Node &node, const std::string &topic, const rclcpp::QoS &qos,
                       CallbackT &&callback, rclcpp::CallbackGroup::SharedPtr group = nullptr,
                       rclcpp::SubscriptionOptions options = {},
                       std::chrono::nanoseconds timeout = std::chrono::nanoseconds( -1 ) )
  {
#if RCLCPP_VERSION_MAJOR >= 9
    rclcpp::AnySubscriptionCallback<CompoundMessage, std::allocator<void>> any_callback;
#else
    rclcpp::AnySubscriptionCallback<CompoundMessage, std::allocator<void>> any_callback(
        options.get_allocator() );
#endif
    any_callback.set( std::forward<CallbackT>( callback ) );
    return create_subscription( node, topic, qos, any_callback, std::move( group ),
                                std::move( options ), timeout );
  }

  BabelFishSubscription::SharedPtr create_subscription(
      rclcpp::Node &node, const std::string &topic, const rclcpp::QoS &qos,
      rclcpp::AnySubscriptionCallback<CompoundMessage, std::allocator<void>> callback,
      rclcpp::CallbackGroup::SharedPtr group = nullptr, rclcpp::SubscriptionOptions options = {},
      std::chrono::nanoseconds timeout = std::chrono::nanoseconds( -1 ) );

  template<typename CallbackT>
  BabelFishSubscription::SharedPtr
  create_subscription( rclcpp::Node &node, const std::string &topic, const std::string &type,
                       const rclcpp::QoS &qos, CallbackT &&callback,
                       rclcpp::CallbackGroup::SharedPtr group = nullptr,
                       rclcpp::SubscriptionOptions options = {} )
  {
#if RCLCPP_VERSION_MAJOR >= 9
    rclcpp::AnySubscriptionCallback<CompoundMessage, std::allocator<void>> any_callback;
#else
    rclcpp::AnySubscriptionCallback<CompoundMessage, std::allocator<void>> any_callback(
        options.get_allocator() );
#endif
    any_callback.set( std::forward<CallbackT>( callback ) );
    return create_subscription( node, topic, type, qos, any_callback, std::move( group ),
                                std::move( options ) );
  }

  BabelFishSubscription::SharedPtr create_subscription(
      rclcpp::Node &node, const std::string &topic, const std::string &type, const rclcpp::QoS &qos,
      rclcpp::AnySubscriptionCallback<CompoundMessage, std::allocator<void>> callback,
      rclcpp::CallbackGroup::SharedPtr group = nullptr, rclcpp::SubscriptionOptions options = {} );

  BabelFishPublisher::SharedPtr create_publisher( rclcpp::Node &node, const std::string &topic,
                                                  const std::string &type, const rclcpp::QoS &qos,
                                                  rclcpp::PublisherOptions options = {} );

  template<typename CallbackT>
  BabelFishService::SharedPtr
  create_service( rclcpp::Node &node, const std::string &service_name, const std::string &type,
                  CallbackT &&callback,
                  const rmw_qos_profile_t &qos_profile = rmw_qos_profile_services_default,
                  rclcpp::CallbackGroup::SharedPtr group = nullptr )
  {
    AnyServiceCallback any_callback( std::forward<CallbackT>( callback ) );
    return create_service( node, service_name, type, any_callback, qos_profile, group );
  }

  BabelFishService::SharedPtr
  create_service( rclcpp::Node &node, const std::string &service_name, const std::string &type,
                  AnyServiceCallback callback,
                  const rmw_qos_profile_t &qos_profile = rmw_qos_profile_services_default,
                  rclcpp::CallbackGroup::SharedPtr group = nullptr );

  BabelFishServiceClient::SharedPtr
  create_service_client( rclcpp::Node &node, const std::string &service_name, const std::string &type,
                         const rmw_qos_profile_t &qos_profile = rmw_qos_profile_services_default,
                         rclcpp::CallbackGroup::SharedPtr group = nullptr );

  BabelFishActionClient::SharedPtr create_action_client(
      rclcpp::Node &node, const std::string &name, const std::string &type,
      const rcl_action_client_options_t &options = rcl_action_client_get_default_options(),
      rclcpp::CallbackGroup::SharedPtr group = nullptr );

  CompoundMessage create_message( const std::string &type ) const;

  CompoundMessage::SharedPtr create_message_shared( const std::string &type ) const;

  CompoundMessage create_service_request( const std::string &type ) const;

  CompoundMessage::SharedPtr create_service_request_shared( const std::string &type ) const;

  MessageTypeSupport::ConstSharedPtr get_message_type_support( const std::string &type ) const;

  ServiceTypeSupport::ConstSharedPtr get_service_type_support( const std::string &type ) const;

  ActionTypeSupport::ConstSharedPtr get_action_type_support( const std::string &type ) const;

  std::vector<TypeSupportProvider::SharedPtr> type_support_providers();

private:
  std::vector<TypeSupportProvider::SharedPtr> type_support_providers_;
};
} // namespace ros_babel_fish

#endif // ROS_BABEL_FISH_BABEL_FISH_HPP