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 <chrono>
19 #include <memory>
20 #include <string>
21 #include <vector>
22 
27 #include "rclcpp/qos.hpp"
28 #include "rclcpp/qos_event.hpp"
32 
33 namespace rclcpp
34 {
35 
38 {
41 
43  bool use_default_callbacks = true;
44 
47 
52 
54  rclcpp::CallbackGroup::SharedPtr callback_group = nullptr;
55 
58 
61 
65 
66  // Options to configure topic statistics collector in the subscription.
68  {
69  // Enable and disable topic statistics calculation and publication. Defaults to disabled.
71 
72  // Topic to which topic statistics get published when enabled. Defaults to /statistics.
73  std::string publish_topic = "/statistics";
74 
75  // Topic statistics publication period in ms. Defaults to one second.
76  // Only values greater than zero are allowed.
78  };
79 
81 
83 };
84 
86 template<typename Allocator>
88 {
91 
93 
96  const SubscriptionOptionsBase & subscription_options_base)
97  : SubscriptionOptionsBase(subscription_options_base)
98  {}
99 
101 
105  template<typename MessageT>
108  {
110  using AllocatorTraits = std::allocator_traits<Allocator>;
111  using MessageAllocatorT = typename AllocatorTraits::template rebind_alloc<MessageT>;
112  auto message_alloc = std::make_shared<MessageAllocatorT>(*this->get_allocator().get());
113  result.allocator = allocator::get_rcl_allocator<MessageT>(*message_alloc);
114  result.qos = qos.get_rmw_qos_profile();
118 
119  // Apply payload to rcl_subscription_options if necessary.
120  if (rmw_implementation_payload && rmw_implementation_payload->has_been_customized()) {
121  rmw_implementation_payload->modify_rmw_subscription_options(result.rmw_subscription_options);
122  }
123 
124  return result;
125  }
126 
130  {
131  if (!this->allocator) {
132  return std::make_shared<Allocator>();
133  }
134  return this->allocator;
135  }
136 };
137 
139 } // namespace rclcpp
140 
141 #endif // RCLCPP__SUBSCRIPTION_OPTIONS_HPP_
rclcpp::SubscriptionOptionsBase::intra_process_buffer_type
IntraProcessBufferType intra_process_buffer_type
Setting the data-type stored in the intraprocess buffer.
Definition: subscription_options.hpp:60
rclcpp::SubscriptionOptionsBase::TopicStatisticsOptions::publish_topic
std::string publish_topic
Definition: subscription_options.hpp:73
rclcpp::SubscriptionOptionsBase::ignore_local_publications
bool ignore_local_publications
True to ignore local publications.
Definition: subscription_options.hpp:46
callback_group.hpp
rcl_subscription_options_t::allocator
rcl_allocator_t allocator
std::string
std::shared_ptr< rclcpp::detail::RMWImplementationSpecificSubscriptionPayload >
rcl_subscription_options_t::rmw_subscription_options
rmw_subscription_options_t rmw_subscription_options
rclcpp::IntraProcessSetting::NodeDefault
@ NodeDefault
Take intraprocess configuration from the node.
rclcpp::SubscriptionOptionsBase::rmw_implementation_payload
std::shared_ptr< rclcpp::detail::RMWImplementationSpecificSubscriptionPayload > rmw_implementation_payload
Optional RMW implementation specific payload to be used during creation of the subscription.
Definition: subscription_options.hpp:64
rclcpp::SubscriptionOptionsBase::TopicStatisticsOptions
Definition: subscription_options.hpp:67
rclcpp::QoS::get_rmw_qos_profile
rmw_qos_profile_t & get_rmw_qos_profile()
Return the rmw qos profile.
rmw_implementation_specific_subscription_payload.hpp
intra_process_setting.hpp
std::chrono::milliseconds
rclcpp::SubscriptionOptionsBase::TopicStatisticsOptions::state
TopicStatisticsState state
Definition: subscription_options.hpp:70
topic_statistics_state.hpp
rclcpp::SubscriptionOptionsWithAllocator
Structure containing optional configuration for Subscriptions.
Definition: subscription_options.hpp:87
rclcpp::SubscriptionOptionsWithAllocator::to_rcl_subscription_options
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:107
rclcpp::SubscriptionOptionsBase::require_unique_network_flow_endpoints
rmw_unique_network_flow_endpoints_requirement_t require_unique_network_flow_endpoints
Definition: subscription_options.hpp:50
rclcpp::SubscriptionOptionsWithAllocator::get_allocator
std::shared_ptr< Allocator > get_allocator() const
Get the allocator, creating one if needed.
Definition: subscription_options.hpp:129
std::allocator_traits
rclcpp
This header provides the get_node_base_interface() template function.
Definition: allocator_common.hpp:24
qos.hpp
rclcpp::SubscriptionOptionsBase::event_callbacks
SubscriptionEventCallbacks event_callbacks
Callbacks for events related to this subscription.
Definition: subscription_options.hpp:40
rclcpp::TopicStatisticsState
TopicStatisticsState
Definition: topic_statistics_state.hpp:23
rclcpp::SubscriptionOptionsBase::use_default_callbacks
bool use_default_callbacks
Whether or not to use default callbacks when user doesn't supply any in event_callbacks.
Definition: subscription_options.hpp:43
rclcpp::QosOverridingOptions
Options that are passed in subscription/publisher constructor to specify QoSConfigurability.
Definition: qos_overriding_options.hpp:89
rclcpp::QoS
Encapsulation of Quality of Service settings.
Definition: qos.hpp:110
rclcpp::TopicStatisticsState::NodeDefault
@ NodeDefault
Take topic statistics state from the node.
rcl_subscription_options_t::qos
rmw_qos_profile_t qos
intra_process_buffer_type.hpp
rclcpp::SubscriptionOptionsBase::TopicStatisticsOptions::publish_period
std::chrono::milliseconds publish_period
Definition: subscription_options.hpp:77
qos_overriding_options.hpp
rclcpp::SubscriptionOptionsBase::callback_group
rclcpp::CallbackGroup::SharedPtr callback_group
The callback group for this subscription. NULL to use the default callback group.
Definition: subscription_options.hpp:54
rclcpp::IntraProcessSetting
IntraProcessSetting
Used as argument in create_publisher and create_subscriber.
Definition: intra_process_setting.hpp:22
rcl_subscription_options_t
rclcpp::SubscriptionOptionsWithAllocator::SubscriptionOptionsWithAllocator
SubscriptionOptionsWithAllocator(const SubscriptionOptionsBase &subscription_options_base)
Constructor using base class as input.
Definition: subscription_options.hpp:95
rclcpp::IntraProcessBufferType::CallbackDefault
@ CallbackDefault
Set the data type used in the intra-process buffer as the same used in the callback.
rcl_subscription_get_default_options
rcl_subscription_options_t rcl_subscription_get_default_options(void)
visibility_control.hpp
rmw_subscription_options_t::ignore_local_publications
bool ignore_local_publications
rclcpp::SubscriptionOptionsBase::use_intra_process_comm
IntraProcessSetting use_intra_process_comm
Setting to explicitly set intraprocess communications.
Definition: subscription_options.hpp:57
rmw_unique_network_flow_endpoints_requirement_t
enum RMW_PUBLIC_TYPE rmw_unique_network_flow_endpoints_requirement_t rmw_unique_network_flow_endpoints_requirement_t
rclcpp::IntraProcessBufferType
IntraProcessBufferType
Definition: intra_process_buffer_type.hpp:23
rmw_subscription_options_t::require_unique_network_flow_endpoints
rmw_unique_network_flow_endpoints_requirement_t require_unique_network_flow_endpoints
rclcpp::SubscriptionOptionsWithAllocator::allocator
std::shared_ptr< Allocator > allocator
Optional custom allocator.
Definition: subscription_options.hpp:90
rclcpp::SubscriptionOptionsBase
Non-template base class for subscription options.
Definition: subscription_options.hpp:37
rclcpp::SubscriptionEventCallbacks
Contains callbacks for non-message events that a Subscription can receive from the middleware.
Definition: qos_event.hpp:61
RMW_UNIQUE_NETWORK_FLOW_ENDPOINTS_NOT_REQUIRED
RMW_UNIQUE_NETWORK_FLOW_ENDPOINTS_NOT_REQUIRED
qos_event.hpp
rclcpp::SubscriptionOptionsBase::qos_overriding_options
QosOverridingOptions qos_overriding_options
Definition: subscription_options.hpp:82
rclcpp::SubscriptionOptionsBase::topic_stats_options
TopicStatisticsOptions topic_stats_options
Definition: subscription_options.hpp:80