4141namespace rclcpp
4242{
4343
44- // / Create and return a subscription of the given MessageT type.
45- /* *
46- * The NodeT type only needs to have a method called get_node_topics_interface()
47- * which returns a shared_ptr to a NodeTopicsInterface, or be a
48- * NodeTopicsInterface pointer itself.
49- *
50- * \tparam MessageT
51- * \tparam CallbackT
52- * \tparam AllocatorT
53- * \tparam CallbackMessageT
54- * \tparam SubscriptionT
55- * \tparam MessageMemoryStrategyT
56- * \tparam NodeT
57- * \param node
58- * \param topic_name
59- * \param qos
60- * \param callback
61- * \param options
62- * \param msg_mem_strat
63- * \return the created subscription
64- * \throws std::invalid_argument if topic statistics is enabled and the publish period is
65- * less than or equal to zero.
66- */
44+ namespace detail
45+ {
6746template <
6847 typename MessageT,
6948 typename CallbackT,
70- typename AllocatorT = std::allocator<void >,
71- typename CallbackMessageT =
72- typename rclcpp::subscription_traits::has_message_type<CallbackT>::type,
73- typename SubscriptionT = rclcpp::Subscription<CallbackMessageT, AllocatorT>,
74- typename MessageMemoryStrategyT = rclcpp::message_memory_strategy::MessageMemoryStrategy<
75- CallbackMessageT,
76- AllocatorT
77- >,
78- typename NodeT>
49+ typename AllocatorT,
50+ typename CallbackMessageT,
51+ typename SubscriptionT,
52+ typename MessageMemoryStrategyT,
53+ typename NodeParametersT,
54+ typename NodeTopicsT>
7955typename std::shared_ptr<SubscriptionT>
8056create_subscription (
81- NodeT && node,
57+ NodeParametersT & node_parameters,
58+ NodeTopicsT & node_topics,
8259 const std::string & topic_name,
8360 const rclcpp::QoS & qos,
8461 CallbackT && callback,
@@ -91,14 +68,14 @@ create_subscription(
9168)
9269{
9370 using rclcpp::node_interfaces::get_node_topics_interface;
94- auto node_topics = get_node_topics_interface (std::forward<NodeT>(node) );
71+ auto node_topics_interface = get_node_topics_interface (node_topics );
9572
9673 std::shared_ptr<rclcpp::topic_statistics::SubscriptionTopicStatistics<CallbackMessageT>>
9774 subscription_topic_stats = nullptr ;
9875
9976 if (rclcpp::detail::resolve_enable_topic_statistics (
10077 options,
101- *node_topics ->get_node_base_interface ()))
78+ *node_topics_interface ->get_node_base_interface ()))
10279 {
10380 if (options.topic_stats_options .publish_period <= std::chrono::milliseconds (0 )) {
10481 throw std::invalid_argument (
@@ -107,15 +84,16 @@ create_subscription(
10784 " ms" );
10885 }
10986
110- std::shared_ptr<Publisher<statistics_msgs::msg::MetricsMessage>> publisher =
111- create_publisher<statistics_msgs::msg::MetricsMessage>(
112- node,
87+ std::shared_ptr<Publisher<statistics_msgs::msg::MetricsMessage>>
88+ publisher = rclcpp::detail::create_publisher<statistics_msgs::msg::MetricsMessage>(
89+ node_parameters,
90+ node_topics_interface,
11391 options.topic_stats_options .publish_topic ,
11492 qos);
11593
11694 subscription_topic_stats = std::make_shared<
11795 rclcpp::topic_statistics::SubscriptionTopicStatistics<CallbackMessageT>
118- >(node_topics ->get_node_base_interface ()->get_name (), publisher);
96+ >(node_topics_interface ->get_node_base_interface ()->get_name (), publisher);
11997
12098 std::weak_ptr<
12199 rclcpp::topic_statistics::SubscriptionTopicStatistics<CallbackMessageT>
@@ -127,14 +105,14 @@ create_subscription(
127105 }
128106 };
129107
130- auto node_timer_interface = node_topics ->get_node_timers_interface ();
108+ auto node_timer_interface = node_topics_interface ->get_node_timers_interface ();
131109
132110 auto timer = create_wall_timer (
133111 std::chrono::duration_cast<std::chrono::nanoseconds>(
134112 options.topic_stats_options .publish_period ),
135113 sub_call_back,
136114 options.callback_group ,
137- node_topics ->get_node_base_interface (),
115+ node_topics_interface ->get_node_base_interface (),
138116 node_timer_interface
139117 );
140118
@@ -148,11 +126,109 @@ create_subscription(
148126 subscription_topic_stats
149127 );
150128
151- auto sub = node_topics->create_subscription (topic_name, factory, qos);
152- node_topics->add_subscription (sub, options.callback_group );
129+ const rclcpp::QoS & actual_qos = options.qos_overriding_options .policy_kinds .size () ?
130+ rclcpp::detail::declare_qos_parameters (
131+ options.qos_overriding_options , node_parameters,
132+ node_topics_interface->resolve_topic_name (topic_name),
133+ qos, rclcpp::detail::SubscriptionQosParametersTraits{}) :
134+ qos;
135+
136+ auto sub = node_topics_interface->create_subscription (topic_name, factory, actual_qos);
137+ node_topics_interface->add_subscription (sub, options.callback_group );
153138
154139 return std::dynamic_pointer_cast<SubscriptionT>(sub);
155140}
141+ } // namespace detail
142+
143+ // / Create and return a subscription of the given MessageT type.
144+ /* *
145+ * The NodeT type only needs to have a method called get_node_topics_interface()
146+ * which returns a shared_ptr to a NodeTopicsInterface, or be a
147+ * NodeTopicsInterface pointer itself.
148+ *
149+ * \tparam MessageT
150+ * \tparam CallbackT
151+ * \tparam AllocatorT
152+ * \tparam CallbackMessageT
153+ * \tparam SubscriptionT
154+ * \tparam MessageMemoryStrategyT
155+ * \tparam NodeT
156+ * \param node
157+ * \param topic_name
158+ * \param qos
159+ * \param callback
160+ * \param options
161+ * \param msg_mem_strat
162+ * \return the created subscription
163+ * \throws std::invalid_argument if topic statistics is enabled and the publish period is
164+ * less than or equal to zero.
165+ */
166+ template <
167+ typename MessageT,
168+ typename CallbackT,
169+ typename AllocatorT = std::allocator<void >,
170+ typename CallbackMessageT =
171+ typename rclcpp::subscription_traits::has_message_type<CallbackT>::type,
172+ typename SubscriptionT = rclcpp::Subscription<CallbackMessageT, AllocatorT>,
173+ typename MessageMemoryStrategyT = rclcpp::message_memory_strategy::MessageMemoryStrategy<
174+ CallbackMessageT,
175+ AllocatorT
176+ >,
177+ typename NodeT>
178+ typename std::shared_ptr<SubscriptionT>
179+ create_subscription (
180+ NodeT & node,
181+ const std::string & topic_name,
182+ const rclcpp::QoS & qos,
183+ CallbackT && callback,
184+ const rclcpp::SubscriptionOptionsWithAllocator<AllocatorT> & options = (
185+ rclcpp::SubscriptionOptionsWithAllocator<AllocatorT>()
186+ ),
187+ typename MessageMemoryStrategyT::SharedPtr msg_mem_strat = (
188+ MessageMemoryStrategyT::create_default ()
189+ )
190+ )
191+ {
192+ return rclcpp::detail::create_subscription<
193+ MessageT, CallbackT, AllocatorT, CallbackMessageT, SubscriptionT, MessageMemoryStrategyT>(
194+ node, node, topic_name, qos, std::forward<CallbackT>(callback), options, msg_mem_strat);
195+ }
196+
197+ // / Create and return a subscription of the given MessageT type.
198+ /* *
199+ * See \ref create_subscription().
200+ */
201+ template <
202+ typename MessageT,
203+ typename CallbackT,
204+ typename AllocatorT = std::allocator<void >,
205+ typename CallbackMessageT =
206+ typename rclcpp::subscription_traits::has_message_type<CallbackT>::type,
207+ typename SubscriptionT = rclcpp::Subscription<CallbackMessageT, AllocatorT>,
208+ typename MessageMemoryStrategyT = rclcpp::message_memory_strategy::MessageMemoryStrategy<
209+ CallbackMessageT,
210+ AllocatorT
211+ >>
212+ typename std::shared_ptr<SubscriptionT>
213+ create_subscription (
214+ rclcpp::node_interfaces::NodeParametersInterface::SharedPtr & node_parameters,
215+ rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr & node_topics,
216+ const std::string & topic_name,
217+ const rclcpp::QoS & qos,
218+ CallbackT && callback,
219+ const rclcpp::SubscriptionOptionsWithAllocator<AllocatorT> & options = (
220+ rclcpp::SubscriptionOptionsWithAllocator<AllocatorT>()
221+ ),
222+ typename MessageMemoryStrategyT::SharedPtr msg_mem_strat = (
223+ MessageMemoryStrategyT::create_default ()
224+ )
225+ )
226+ {
227+ return rclcpp::detail::create_subscription<
228+ MessageT, CallbackT, AllocatorT, CallbackMessageT, SubscriptionT, MessageMemoryStrategyT>(
229+ node_parameters, node_topics, topic_name, qos,
230+ std::forward<CallbackT>(callback), options, msg_mem_strat);
231+ }
156232
157233} // namespace rclcpp
158234
0 commit comments