Merge pull request #128 from ros2/create_subscription_with_queue_size
add version of create_subscription which just takes queue size and not a qos profile
This commit is contained in:
		
						commit
						a61e375436
					
				
					 2 changed files with 49 additions and 0 deletions
				
			
		| 
						 | 
					@ -114,6 +114,31 @@ public:
 | 
				
			||||||
  create_publisher(
 | 
					  create_publisher(
 | 
				
			||||||
    const std::string & topic_name, const rmw_qos_profile_t & qos_profile);
 | 
					    const std::string & topic_name, const rmw_qos_profile_t & qos_profile);
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					  /// Create and return a Subscription.
 | 
				
			||||||
 | 
					  /**
 | 
				
			||||||
 | 
					   * \param[in] topic_name The topic to subscribe on.
 | 
				
			||||||
 | 
					   * \param[in] qos_history_depth The depth of the subscription's incoming message queue.
 | 
				
			||||||
 | 
					   * \param[in] callback The user-defined callback function.
 | 
				
			||||||
 | 
					   * \param[in] group The callback group for this subscription. NULL for no callback group.
 | 
				
			||||||
 | 
					   * \param[in] ignore_local_publications True to ignore local publications.
 | 
				
			||||||
 | 
					   * \param[in] msg_mem_strat The message memory strategy to use for allocating messages.
 | 
				
			||||||
 | 
					   * \return Shared pointer to the created subscription.
 | 
				
			||||||
 | 
					   */
 | 
				
			||||||
 | 
					  /* TODO(jacquelinekay):
 | 
				
			||||||
 | 
					     Windows build breaks when static member function passed as default
 | 
				
			||||||
 | 
					     argument to msg_mem_strat, nullptr is a workaround.
 | 
				
			||||||
 | 
					   */
 | 
				
			||||||
 | 
					  template<typename MessageT, typename CallbackT>
 | 
				
			||||||
 | 
					  typename rclcpp::subscription::Subscription<MessageT>::SharedPtr
 | 
				
			||||||
 | 
					  create_subscription(
 | 
				
			||||||
 | 
					    const std::string & topic_name,
 | 
				
			||||||
 | 
					    size_t qos_history_depth,
 | 
				
			||||||
 | 
					    CallbackT callback,
 | 
				
			||||||
 | 
					    rclcpp::callback_group::CallbackGroup::SharedPtr group = nullptr,
 | 
				
			||||||
 | 
					    bool ignore_local_publications = false,
 | 
				
			||||||
 | 
					    typename rclcpp::message_memory_strategy::MessageMemoryStrategy<MessageT>::SharedPtr
 | 
				
			||||||
 | 
					    msg_mem_strat = nullptr);
 | 
				
			||||||
 | 
					
 | 
				
			||||||
  /// Create and return a Subscription.
 | 
					  /// Create and return a Subscription.
 | 
				
			||||||
  /**
 | 
					  /**
 | 
				
			||||||
   * \param[in] topic_name The topic to subscribe on.
 | 
					   * \param[in] topic_name The topic to subscribe on.
 | 
				
			||||||
| 
						 | 
					
 | 
				
			||||||
| 
						 | 
					@ -205,6 +205,30 @@ Node::group_in_node(callback_group::CallbackGroup::SharedPtr group)
 | 
				
			||||||
  return group_belongs_to_this_node;
 | 
					  return group_belongs_to_this_node;
 | 
				
			||||||
}
 | 
					}
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					template<typename MessageT, typename CallbackT>
 | 
				
			||||||
 | 
					typename rclcpp::subscription::Subscription<MessageT>::SharedPtr
 | 
				
			||||||
 | 
					Node::create_subscription(
 | 
				
			||||||
 | 
					  const std::string & topic_name,
 | 
				
			||||||
 | 
					  size_t qos_history_depth,
 | 
				
			||||||
 | 
					  CallbackT callback,
 | 
				
			||||||
 | 
					  rclcpp::callback_group::CallbackGroup::SharedPtr group,
 | 
				
			||||||
 | 
					  bool ignore_local_publications,
 | 
				
			||||||
 | 
					  typename rclcpp::message_memory_strategy::MessageMemoryStrategy<MessageT>::SharedPtr
 | 
				
			||||||
 | 
					  msg_mem_strat)
 | 
				
			||||||
 | 
					{
 | 
				
			||||||
 | 
					  rclcpp::subscription::AnySubscriptionCallback<MessageT> any_subscription_callback;
 | 
				
			||||||
 | 
					  any_subscription_callback.set(callback);
 | 
				
			||||||
 | 
					  rmw_qos_profile_t qos = rmw_qos_profile_default;
 | 
				
			||||||
 | 
					  qos.depth = qos_history_depth;
 | 
				
			||||||
 | 
					  return this->create_subscription_internal(
 | 
				
			||||||
 | 
					    topic_name,
 | 
				
			||||||
 | 
					    qos,
 | 
				
			||||||
 | 
					    any_subscription_callback,
 | 
				
			||||||
 | 
					    group,
 | 
				
			||||||
 | 
					    ignore_local_publications,
 | 
				
			||||||
 | 
					    msg_mem_strat);
 | 
				
			||||||
 | 
					}
 | 
				
			||||||
 | 
					
 | 
				
			||||||
template<typename MessageT, typename CallbackT>
 | 
					template<typename MessageT, typename CallbackT>
 | 
				
			||||||
typename rclcpp::subscription::Subscription<MessageT>::SharedPtr
 | 
					typename rclcpp::subscription::Subscription<MessageT>::SharedPtr
 | 
				
			||||||
Node::create_subscription(
 | 
					Node::create_subscription(
 | 
				
			||||||
| 
						 | 
					
 | 
				
			||||||
		Loading…
	
	Add table
		Add a link
		
	
		Reference in a new issue