rclcpp  master
C++ ROS Client Library API
subscription_options.hpp
Go to the documentation of this file.
1 // Copyright 2019 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_OPTIONS_HPP_
16 #define RCLCPP__SUBSCRIPTION_OPTIONS_HPP_
17 
18 #include <memory>
19 #include <string>
20 #include <vector>
21 
24 #include "rclcpp/qos.hpp"
25 #include "rclcpp/qos_event.hpp"
27 
28 namespace rclcpp
29 {
30 
33 {
39  rclcpp::callback_group::CallbackGroup::SharedPtr callback_group = nullptr;
42 };
43 
45 template<typename Allocator>
47 {
49  std::shared_ptr<Allocator> allocator = nullptr;
50 
52 
55  const SubscriptionOptionsBase & subscription_options_base)
56  : SubscriptionOptionsBase(subscription_options_base)
57  {}
58 
60  template<typename MessageT>
63  {
65  using AllocatorTraits = std::allocator_traits<Allocator>;
66  using MessageAllocatorT = typename AllocatorTraits::template rebind_alloc<MessageT>;
67  auto message_alloc = std::make_shared<MessageAllocatorT>(*allocator.get());
68  result.allocator = allocator::get_rcl_allocator<MessageT>(*message_alloc);
70  result.qos = qos.get_rmw_qos_profile();
71  return result;
72  }
73 };
74 
76 
77 } // namespace rclcpp
78 
79 #endif // RCLCPP__SUBSCRIPTION_OPTIONS_HPP_
Non-template base class for subscription options.
Definition: subscription_options.hpp:32
Encapsulation of Quality of Service settings.
Definition: qos.hpp:55
SubscriptionEventCallbacks event_callbacks
Callbacks for events related to this subscription.
Definition: subscription_options.hpp:35
IntraProcessSetting
Used as argument in create_publisher and create_subscriber.
Definition: intra_process_setting.hpp:22
rmw_qos_profile_t & get_rmw_qos_profile()
Return the rmw qos profile.
This header provides the get_node_topics_interface() template function.
Definition: allocator_common.hpp:24
rmw_qos_profile_t qos
T get(T... args)
Structure containing optional configuration for Subscriptions.
Definition: subscription_options.hpp:46
rcl_subscription_options_t to_rcl_subscription_options(const rclcpp::QoS &qos) const
Convert this class, with a rclcpp::QoS, into an rcl_subscription_options_t.
Definition: subscription_options.hpp:62
rclcpp::callback_group::CallbackGroup::SharedPtr callback_group
The callback group for this subscription. NULL to use the default callback group. ...
Definition: subscription_options.hpp:39
IntraProcessSetting use_intra_process_comm
Setting to explicitly set intraprocess communications.
Definition: subscription_options.hpp:41
rcl_allocator_t allocator
Contains callbacks for non-message events that a Subscription can receive from the middleware...
Definition: qos_event.hpp:49
SubscriptionOptionsWithAllocator(const SubscriptionOptionsBase &subscription_options_base)
Constructor using base class as input.
Definition: subscription_options.hpp:54
Take intraprocess configuration from the node.
bool ignore_local_publications
True to ignore local publications.
Definition: subscription_options.hpp:37