rclcpp  master
C++ ROS Client Library API
create_subscription.hpp
Go to the documentation of this file.
1 // Copyright 2016 Open Source Robotics Foundation, Inc.
2 //
3 // Licensed under the Apache License, Version 2.0 (the "License");
4 // you may not use this file except in compliance with the License.
5 // You may obtain a copy of the License at
6 //
7 // http://www.apache.org/licenses/LICENSE-2.0
8 //
9 // Unless required by applicable law or agreed to in writing, software
10 // distributed under the License is distributed on an "AS IS" BASIS,
11 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 // See the License for the specific language governing permissions and
13 // limitations under the License.
14 
15 #ifndef RCLCPP__CREATE_SUBSCRIPTION_HPP_
16 #define RCLCPP__CREATE_SUBSCRIPTION_HPP_
17 
18 #include <chrono>
19 #include <functional>
20 #include <memory>
21 #include <stdexcept>
22 #include <string>
23 #include <utility>
24 
26 
31 
33 #include "rclcpp/create_timer.hpp"
34 #include "rclcpp/qos.hpp"
37 #include "rclcpp/timer.hpp"
39 #include "rmw/qos_profiles.h"
40 
41 namespace rclcpp
42 {
43 
44 namespace detail
45 {
46 template<
47  typename MessageT,
48  typename CallbackT,
49  typename AllocatorT,
50  typename CallbackMessageT,
51  typename SubscriptionT,
52  typename MessageMemoryStrategyT,
53  typename NodeParametersT,
54  typename NodeTopicsT>
57  NodeParametersT & node_parameters,
58  NodeTopicsT & node_topics,
59  const std::string & topic_name,
60  const rclcpp::QoS & qos,
61  CallbackT && callback,
64  ),
65  typename MessageMemoryStrategyT::SharedPtr msg_mem_strat = (
66  MessageMemoryStrategyT::create_default()
67  )
68 )
69 {
71  auto node_topics_interface = get_node_topics_interface(node_topics);
72 
74  subscription_topic_stats = nullptr;
75 
77  options,
78  *node_topics_interface->get_node_base_interface()))
79  {
80  if (options.topic_stats_options.publish_period <= std::chrono::milliseconds(0)) {
82  "topic_stats_options.publish_period must be greater than 0, specified value of " +
83  std::to_string(options.topic_stats_options.publish_period.count()) +
84  " ms");
85  }
86 
88  publisher = rclcpp::detail::create_publisher<statistics_msgs::msg::MetricsMessage>(
89  node_parameters,
90  node_topics_interface,
91  options.topic_stats_options.publish_topic,
92  qos);
93 
94  subscription_topic_stats = std::make_shared<
96  >(node_topics_interface->get_node_base_interface()->get_name(), publisher);
97 
100  > weak_subscription_topic_stats(subscription_topic_stats);
101  auto sub_call_back = [weak_subscription_topic_stats]() {
102  auto subscription_topic_stats = weak_subscription_topic_stats.lock();
103  if (subscription_topic_stats) {
104  subscription_topic_stats->publish_message_and_reset_measurements();
105  }
106  };
107 
108  auto node_timer_interface = node_topics_interface->get_node_timers_interface();
109 
110  auto timer = create_wall_timer(
111  std::chrono::duration_cast<std::chrono::nanoseconds>(
112  options.topic_stats_options.publish_period),
113  sub_call_back,
114  options.callback_group,
115  node_topics_interface->get_node_base_interface(),
116  node_timer_interface
117  );
118 
119  subscription_topic_stats->set_publisher_timer(timer);
120  }
121 
122  auto factory = rclcpp::create_subscription_factory<MessageT>(
123  std::forward<CallbackT>(callback),
124  options,
125  msg_mem_strat,
126  subscription_topic_stats
127  );
128 
129  const rclcpp::QoS & actual_qos = options.qos_overriding_options.get_policy_kinds().size() ?
131  options.qos_overriding_options, node_parameters,
132  node_topics_interface->resolve_topic_name(topic_name),
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);
138 
139  return std::dynamic_pointer_cast<SubscriptionT>(sub);
140 }
141 } // namespace detail
142 
144 
170 template<
171  typename MessageT,
172  typename CallbackT,
173  typename AllocatorT = std::allocator<void>,
174  typename CallbackMessageT =
177  typename MessageMemoryStrategyT = rclcpp::message_memory_strategy::MessageMemoryStrategy<
178  CallbackMessageT,
179  AllocatorT
180  >,
181  typename NodeT>
184  NodeT & node,
185  const std::string & topic_name,
186  const rclcpp::QoS & qos,
187  CallbackT && callback,
190  ),
191  typename MessageMemoryStrategyT::SharedPtr msg_mem_strat = (
192  MessageMemoryStrategyT::create_default()
193  )
194 )
195 {
197  MessageT, CallbackT, AllocatorT, CallbackMessageT, SubscriptionT, MessageMemoryStrategyT>(
198  node, node, topic_name, qos, std::forward<CallbackT>(callback), options, msg_mem_strat);
199 }
200 
202 
205 template<
206  typename MessageT,
207  typename CallbackT,
208  typename AllocatorT = std::allocator<void>,
209  typename CallbackMessageT =
212  typename MessageMemoryStrategyT = rclcpp::message_memory_strategy::MessageMemoryStrategy<
213  CallbackMessageT,
214  AllocatorT
215  >>
218  rclcpp::node_interfaces::NodeParametersInterface::SharedPtr & node_parameters,
219  rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr & node_topics,
220  const std::string & topic_name,
221  const rclcpp::QoS & qos,
222  CallbackT && callback,
225  ),
226  typename MessageMemoryStrategyT::SharedPtr msg_mem_strat = (
227  MessageMemoryStrategyT::create_default()
228  )
229 )
230 {
232  MessageT, CallbackT, AllocatorT, CallbackMessageT, SubscriptionT, MessageMemoryStrategyT>(
233  node_parameters, node_topics, topic_name, qos,
234  std::forward<CallbackT>(callback), options, msg_mem_strat);
235 }
236 
237 } // namespace rclcpp
238 
239 #endif // RCLCPP__CREATE_SUBSCRIPTION_HPP_
get_node_topics_interface.hpp
rclcpp::topic_statistics::SubscriptionTopicStatistics
Definition: subscription_topic_statistics.hpp:55
rclcpp::create_wall_timer
rclcpp::WallTimer< CallbackT >::SharedPtr create_wall_timer(std::chrono::duration< DurationRepT, DurationT > period, CallbackT callback, rclcpp::CallbackGroup::SharedPtr group, node_interfaces::NodeBaseInterface *node_base, node_interfaces::NodeTimersInterface *node_timers)
Convenience method to create a timer with node resources.
Definition: create_timer.hpp:90
std::string
std::shared_ptr
std::make_shared
T make_shared(T... args)
std::chrono::milliseconds
get_node_timers_interface.hpp
rclcpp::SubscriptionOptionsWithAllocator
Structure containing optional configuration for Subscriptions.
Definition: subscription_options.hpp:87
rclcpp::detail::declare_qos_parameters
std::enable_if_t< rclcpp::node_interfaces::has_node_parameters_interface< decltype(std::declval< typename rcpputils::remove_pointer< NodeT >::type >))>::value||std::is_same< typename std::decay_t< NodeT >, rclcpp::node_interfaces::NodeParametersInterface::SharedPtr >::value, rclcpp::QoS > declare_qos_parameters(const ::rclcpp::QosOverridingOptions &options, NodeT &node, const std::string &topic_name, const ::rclcpp::QoS &default_qos, EntityQosParametersTraits)
Definition: qos_parameters.hpp:126
rclcpp
This header provides the get_node_base_interface() template function.
Definition: allocator_common.hpp:24
rclcpp::subscription_traits::extract_message_type< rclcpp::function_traits::function_traits< CallbackT >::template argument_type< 0 > >::type
typename std::remove_cv_t< std::remove_reference_t< rclcpp::function_traits::function_traits< CallbackT >::template argument_type< 0 > > > type
Definition: subscription_traits.hpp:67
qos.hpp
timer.hpp
rclcpp::Subscription
Subscription implementation, templated on the type of message this subscription receives.
Definition: subscription.hpp:69
node_topics_interface.hpp
rclcpp::QoS
Encapsulation of Quality of Service settings.
Definition: qos.hpp:110
std::to_string
T to_string(T... args)
std::invalid_argument
rclcpp::detail::SubscriptionQosParametersTraits
Definition: qos_parameters.hpp:62
create_timer.hpp
rclcpp::node_interfaces::get_node_topics_interface
std::shared_ptr< rclcpp::node_interfaces::NodeTopicsInterface > get_node_topics_interface(NodeType &&node)
Get the NodeTopicsInterface as a shared pointer from a pointer to a "Node like" object.
Definition: get_node_topics_interface.hpp:72
std::weak_ptr
rclcpp::detail::resolve_enable_topic_statistics
bool resolve_enable_topic_statistics(const OptionsT &options, const NodeBaseT &node_base)
Return whether or not topic statistics is enabled, resolving "NodeDefault" if needed.
Definition: resolve_enable_topic_statistics.hpp:30
subscription_factory.hpp
subscription_options.hpp
rclcpp::detail::create_subscription
std::shared_ptr< SubscriptionT > create_subscription(NodeParametersT &node_parameters, NodeTopicsT &node_topics, 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()))
Definition: create_subscription.hpp:56
rclcpp::message_memory_strategy::MessageMemoryStrategy
Default allocation strategy for messages received by subscriptions.
Definition: message_memory_strategy.hpp:41
rclcpp::create_subscription
std::shared_ptr< SubscriptionT > 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.
Definition: create_subscription.hpp:183
node_timers_interface.hpp
std::allocator
resolve_enable_topic_statistics.hpp
subscription_topic_statistics.hpp
qos_profiles.h
create_publisher.hpp