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 <memory>
19 #include <string>
20 #include <utility>
21 
24 #include "rmw/qos_profiles.h"
25 
26 namespace rclcpp
27 {
28 
29 template<typename MessageT, typename CallbackT, typename AllocatorT, typename SubscriptionT>
33  const std::string & topic_name,
34  CallbackT && callback,
35  const rmw_qos_profile_t & qos_profile,
36  rclcpp::callback_group::CallbackGroup::SharedPtr group,
37  bool ignore_local_publications,
38  bool use_intra_process_comms,
40  msg_mem_strat,
41  typename std::shared_ptr<AllocatorT> allocator)
42 {
43  auto subscription_options = rcl_subscription_get_default_options();
44  subscription_options.qos = qos_profile;
45  subscription_options.ignore_local_publications = ignore_local_publications;
46 
47  auto factory =
48  rclcpp::create_subscription_factory<MessageT, CallbackT, AllocatorT, SubscriptionT>(
49  std::forward<CallbackT>(callback), msg_mem_strat, allocator);
50 
51  auto sub = node_topics->create_subscription(
52  topic_name,
53  factory,
54  subscription_options,
55  use_intra_process_comms);
56  node_topics->add_subscription(sub, group);
57  return std::dynamic_pointer_cast<SubscriptionT>(sub);
58 }
59 
60 } // namespace rclcpp
61 
62 #endif // RCLCPP__CREATE_SUBSCRIPTION_HPP_
Default allocation strategy for messages received by subscriptions.
Definition: message_memory_strategy.hpp:33
Subscription implementation, templated on the type of message this subscription receives.
Definition: subscription.hpp:124
Definition: allocator_common.hpp:24
virtual rclcpp::subscription::SubscriptionBase::SharedPtr create_subscription(const std::string &topic_name, const rclcpp::SubscriptionFactory &subscription_factory, rcl_subscription_options_t &subscription_options, bool use_intra_process)=0
rcl_subscription_options_t rcl_subscription_get_default_options(void)
virtual void add_subscription(rclcpp::subscription::SubscriptionBase::SharedPtr subscription, rclcpp::callback_group::CallbackGroup::SharedPtr callback_group)=0
rclcpp::subscription::Subscription< MessageT, AllocatorT >::SharedPtr create_subscription(rclcpp::node_interfaces::NodeTopicsInterface *node_topics, const std::string &topic_name, CallbackT &&callback, const rmw_qos_profile_t &qos_profile, rclcpp::callback_group::CallbackGroup::SharedPtr group, bool ignore_local_publications, bool use_intra_process_comms, typename rclcpp::message_memory_strategy::MessageMemoryStrategy< MessageT, AllocatorT >::SharedPtr msg_mem_strat, typename std::shared_ptr< AllocatorT > allocator)
Definition: create_subscription.hpp:31
Pure virtual interface class for the NodeTopics part of the Node API.
Definition: node_topics_interface.hpp:38