Template Function rclcpp::create_subscription(NodeT&, const std::string&, const rclcpp::QoS&, CallbackT&&, const rclcpp::SubscriptionOptionsWithAllocator<AllocatorT>&, typename MessageMemoryStrategyT::SharedPtr)

Function Documentation

template<typename MessageT, typename CallbackT, typename AllocatorT = std::allocator<void>, typename SubscriptionT = rclcpp::Subscription<MessageT, AllocatorT>, typename MessageMemoryStrategyT = typename SubscriptionT::MessageMemoryStrategyType, typename NodeT>
std::shared_ptr<SubscriptionT> rclcpp::create_subscription(NodeT &node, const std::string &topic_name, const rclcpp::QoS &qos, CallbackT &&callback, const rclcpp::SubscriptionOptionsWithAllocator<AllocatorT> &options = (rclcpp::SubscriptionOptionsWithAllocator<AllocatorT>()), typename MessageMemoryStrategyT::SharedPtr msg_mem_strat = (MessageMemoryStrategyT::create_default()))

Create and return a subscription of the given MessageT type.

The NodeT type only needs to have a method called get_node_topics_interface() which returns a shared_ptr to a NodeTopicsInterface, or be a NodeTopicsInterface pointer itself.

In case options.qos_overriding_options is enabling qos parameter overrides, NodeT must also have a method called get_node_parameters_interface() which returns a shared_ptr to a NodeParametersInterface.

Template Parameters:
  • MessageT

  • CallbackT

  • AllocatorT

  • SubscriptionT

  • MessageMemoryStrategyT

  • NodeT

Parameters:
  • node

  • topic_name

  • qos

  • callback

  • options

  • msg_mem_strat

Throws:

std::invalid_argument – if topic statistics is enabled and the publish period is less than or equal to zero.

Returns:

the created subscription