ROS 2 rclcpp + rcl - humble  humble
ROS 2 C++ Client Library with ROS Client Library
subscription_factory.hpp
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__SUBSCRIPTION_FACTORY_HPP_
16 #define RCLCPP__SUBSCRIPTION_FACTORY_HPP_
17 
18 #include <functional>
19 #include <memory>
20 #include <string>
21 #include <utility>
22 
23 #include "rcl/subscription.h"
24 
25 #include "rosidl_typesupport_cpp/message_type_support.hpp"
26 
27 #include "rclcpp/any_subscription_callback.hpp"
28 #include "rclcpp/get_message_type_support_handle.hpp"
29 #include "rclcpp/node_interfaces/node_base_interface.hpp"
30 #include "rclcpp/qos.hpp"
31 #include "rclcpp/subscription.hpp"
32 #include "rclcpp/subscription_options.hpp"
33 #include "rclcpp/subscription_traits.hpp"
34 #include "rclcpp/topic_statistics/subscription_topic_statistics.hpp"
35 #include "rclcpp/visibility_control.hpp"
36 
37 namespace rclcpp
38 {
39 
41 
55 {
56  // Creates a Subscription<MessageT> object and returns it as a SubscriptionBase.
57  using SubscriptionFactoryFunction = std::function<
58  rclcpp::SubscriptionBase::SharedPtr(
60  const std::string & topic_name,
61  const rclcpp::QoS & qos)>;
62 
63  const SubscriptionFactoryFunction create_typed_subscription;
64 };
65 
67 
73 template<
74  typename MessageT,
75  typename CallbackT,
76  typename AllocatorT,
77  typename SubscriptionT = rclcpp::Subscription<MessageT, AllocatorT>,
78  typename MessageMemoryStrategyT = typename SubscriptionT::MessageMemoryStrategyType,
79  typename ROSMessageType = typename SubscriptionT::ROSMessageType
80 >
83  CallbackT && callback,
85  typename MessageMemoryStrategyT::SharedPtr msg_mem_strat,
87  subscription_topic_stats = nullptr
88 )
89 {
90  auto allocator = options.get_allocator();
91 
93  AnySubscriptionCallback<MessageT, AllocatorT> any_subscription_callback(*allocator);
94  any_subscription_callback.set(std::forward<CallbackT>(callback));
95 
96  SubscriptionFactory factory {
97  // factory function that creates a MessageT specific SubscriptionT
98  [options, msg_mem_strat, any_subscription_callback, subscription_topic_stats](
100  const std::string & topic_name,
101  const rclcpp::QoS & qos
102  ) -> rclcpp::SubscriptionBase::SharedPtr
103  {
104  using rclcpp::Subscription;
106 
108  node_base,
109  rclcpp::get_message_type_support_handle<MessageT>(),
110  topic_name,
111  qos,
112  any_subscription_callback,
113  options,
114  msg_mem_strat,
115  subscription_topic_stats);
116  // This is used for setting up things like intra process comms which
117  // require this->shared_from_this() which cannot be called from
118  // the constructor.
119  sub->post_init_setup(node_base, qos, options);
120  auto sub_base_ptr = std::dynamic_pointer_cast<SubscriptionBase>(sub);
121  return sub_base_ptr;
122  }
123  };
124 
125  // return the factory now that it is populated
126  return factory;
127 }
128 
129 } // namespace rclcpp
130 
131 #endif // RCLCPP__SUBSCRIPTION_FACTORY_HPP_
AnySubscriptionCallback< MessageT, AllocatorT > set(CallbackT callback)
Generic function for setting the callback.
Encapsulation of Quality of Service settings.
Definition: qos.hpp:111
Subscription implementation, templated on the type of message this subscription receives.
Pure virtual interface class for the NodeBase part of the Node API.
Versions of rosidl_typesupport_cpp::get_message_type_support_handle that handle adapted types.
SubscriptionFactory create_subscription_factory(CallbackT &&callback, const rclcpp::SubscriptionOptionsWithAllocator< AllocatorT > &options, typename MessageMemoryStrategyT::SharedPtr msg_mem_strat, std::shared_ptr< rclcpp::topic_statistics::SubscriptionTopicStatistics< ROSMessageType >> subscription_topic_stats=nullptr)
Return a SubscriptionFactory setup to create a SubscriptionT<MessageT, AllocatorT>.
Factory containing a function used to create a Subscription<MessageT>.
Structure containing optional configuration for Subscriptions.