rclcpp  master
C++ ROS Client Library API
subscription_factory.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__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 
30 #include "rclcpp/qos.hpp"
31 #include "rclcpp/subscription.hpp"
36 
37 namespace rclcpp
38 {
39 
41 
55 {
56  // Creates a Subscription<MessageT> object and returns it as a SubscriptionBase.
58  rclcpp::SubscriptionBase::SharedPtr(
60  const std::string & topic_name,
61  const rclcpp::QoS & qos)>;
62 
64 };
65 
67 
73 template<
74  typename MessageT,
75  typename CallbackT,
76  typename AllocatorT,
77  typename CallbackMessageT =
80  typename MessageMemoryStrategyT = rclcpp::message_memory_strategy::MessageMemoryStrategy<
81  CallbackMessageT,
82  AllocatorT
83  >>
86  CallbackT && callback,
88  typename MessageMemoryStrategyT::SharedPtr msg_mem_strat,
90  subscription_topic_stats = nullptr
91 )
92 {
93  auto allocator = options.get_allocator();
94 
96  AnySubscriptionCallback<CallbackMessageT, AllocatorT> any_subscription_callback(*allocator);
97  any_subscription_callback.set(std::forward<CallbackT>(callback));
98 
99  SubscriptionFactory factory {
100  // factory function that creates a MessageT specific SubscriptionT
101  [options, msg_mem_strat, any_subscription_callback, subscription_topic_stats](
103  const std::string & topic_name,
104  const rclcpp::QoS & qos
105  ) -> rclcpp::SubscriptionBase::SharedPtr
106  {
107  using rclcpp::Subscription;
109 
111  node_base,
112  *rosidl_typesupport_cpp::get_message_type_support_handle<MessageT>(),
113  topic_name,
114  qos,
115  any_subscription_callback,
116  options,
117  msg_mem_strat,
118  subscription_topic_stats);
119  // This is used for setting up things like intra process comms which
120  // require this->shared_from_this() which cannot be called from
121  // the constructor.
122  sub->post_init_setup(node_base, qos, options);
123  auto sub_base_ptr = std::dynamic_pointer_cast<SubscriptionBase>(sub);
124  return sub_base_ptr;
125  }
126  };
127 
128  // return the factory now that it is populated
129  return factory;
130 }
131 
132 } // namespace rclcpp
133 
134 #endif // RCLCPP__SUBSCRIPTION_FACTORY_HPP_
rclcpp::topic_statistics::SubscriptionTopicStatistics
Definition: subscription_topic_statistics.hpp:55
std::string
std::shared_ptr
rclcpp::create_subscription_factory
SubscriptionFactory create_subscription_factory(CallbackT &&callback, const rclcpp::SubscriptionOptionsWithAllocator< AllocatorT > &options, typename MessageMemoryStrategyT::SharedPtr msg_mem_strat, std::shared_ptr< rclcpp::topic_statistics::SubscriptionTopicStatistics< CallbackMessageT >> subscription_topic_stats=nullptr)
Return a SubscriptionFactory setup to create a SubscriptionT<MessageT, AllocatorT>.
Definition: subscription_factory.hpp:85
rclcpp::SubscriptionOptionsWithAllocator
Structure containing optional configuration for Subscriptions.
Definition: subscription_options.hpp:87
rclcpp::SubscriptionBase
Definition: subscription_base.hpp:60
std::function
subscription.h
rclcpp::SubscriptionOptionsWithAllocator::get_allocator
std::shared_ptr< Allocator > get_allocator() const
Get the allocator, creating one if needed.
Definition: subscription_options.hpp:129
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
rclcpp::AnySubscriptionCallback::set
AnySubscriptionCallback< MessageT, AllocatorT > set(CallbackT callback)
Generic function for setting the callback.
Definition: any_subscription_callback.hpp:158
qos.hpp
rclcpp::Subscription
Subscription implementation, templated on the type of message this subscription receives.
Definition: subscription.hpp:69
rclcpp::node_interfaces::NodeBaseInterface
Pure virtual interface class for the NodeBase part of the Node API.
Definition: node_base_interface.hpp:36
rclcpp::QoS
Encapsulation of Quality of Service settings.
Definition: qos.hpp:110
intra_process_buffer_type.hpp
subscription_traits.hpp
node_base_interface.hpp
rclcpp::AnySubscriptionCallback
Definition: any_subscription_callback.hpp:101
any_subscription_callback.hpp
subscription_options.hpp
rclcpp::SubscriptionFactory::create_typed_subscription
const SubscriptionFactoryFunction create_typed_subscription
Definition: subscription_factory.hpp:63
visibility_control.hpp
rclcpp::SubscriptionFactory
Factory containing a function used to create a Subscription<MessageT>.
Definition: subscription_factory.hpp:54
rclcpp::message_memory_strategy::MessageMemoryStrategy
Default allocation strategy for messages received by subscriptions.
Definition: message_memory_strategy.hpp:41
subscription_topic_statistics.hpp
subscription.hpp