rclcpp  master
C++ ROS Client Library API
subscription_base.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_BASE_HPP_
16 #define RCLCPP__SUBSCRIPTION_BASE_HPP_
17 
18 #include <atomic>
19 #include <memory>
20 #include <string>
21 #include <unordered_map>
22 #include <vector>
23 #include <utility>
24 
25 #include "rcl/subscription.h"
26 
27 #include "rmw/rmw.h"
28 
32 #include "rclcpp/macros.hpp"
33 #include "rclcpp/message_info.hpp"
34 #include "rclcpp/qos.hpp"
35 #include "rclcpp/qos_event.hpp"
39 
40 namespace rclcpp
41 {
42 
43 namespace node_interfaces
44 {
45 class NodeBaseInterface;
46 } // namespace node_interfaces
47 
48 namespace experimental
49 {
54 class IntraProcessManager;
55 } // namespace experimental
56 
59 class SubscriptionBase : public std::enable_shared_from_this<SubscriptionBase>
60 {
61 public:
63 
64 
65 
75  const rosidl_message_type_support_t & type_support_handle,
76  const std::string & topic_name,
77  const rcl_subscription_options_t & subscription_options,
78  bool is_serialized = false);
79 
82  virtual ~SubscriptionBase();
83 
86  const char *
87  get_topic_name() const;
88 
92 
96 
98 
101  get_event_handlers() const;
102 
104 
117  get_actual_qos() const;
118 
120 
137  bool
138  take_type_erased(void * message_out, rclcpp::MessageInfo & message_info_out);
139 
141 
155  bool
156  take_serialized(rclcpp::SerializedMessage & message_out, rclcpp::MessageInfo & message_info_out);
157 
159 
161  virtual
163  create_message() = 0;
164 
166 
168  virtual
171 
173 
178  virtual
179  void
180  handle_message(std::shared_ptr<void> & message, const rclcpp::MessageInfo & message_info) = 0;
181 
183  virtual
184  void
185  handle_loaned_message(void * loaned_message, const rclcpp::MessageInfo & message_info) = 0;
186 
188 
190  virtual
191  void
192  return_message(std::shared_ptr<void> & message) = 0;
193 
195 
197  virtual
198  void
200 
202  const rosidl_message_type_support_t &
204 
206 
210  bool
211  is_serialized() const;
212 
214 
216  size_t
217  get_publisher_count() const;
218 
220 
227  bool
228  can_loan_messages() const;
229 
232 
235  void
237  uint64_t intra_process_subscription_id,
238  IntraProcessManagerWeakPtr weak_ipm);
239 
241 
246  rclcpp::Waitable::SharedPtr
248 
250 
263  bool
264  exchange_in_use_by_wait_set_state(void * pointer_to_subscription_part, bool in_use_state);
265 
266 protected:
267  template<typename EventCallbackT>
268  void
270  const EventCallbackT & callback,
271  const rcl_subscription_event_type_t event_type)
272  {
273  auto handler = std::make_shared<QOSEventHandler<EventCallbackT,
275  callback,
276  rcl_subscription_event_init,
278  event_type);
279  qos_events_in_use_by_wait_set_.insert(std::make_pair(handler.get(), false));
280  event_handlers_.emplace_back(handler);
281  }
282 
285 
287  bool
288  matches_any_intra_process_publishers(const rmw_gid_t * sender_gid) const;
289 
291 
295 
297 
301 
302 private:
304 
305  rosidl_message_type_support_t type_support_;
306  bool is_serialized_;
307 
308  std::atomic<bool> subscription_in_use_by_wait_set_{false};
309  std::atomic<bool> intra_process_subscription_waitable_in_use_by_wait_set_{false};
311  std::atomic<bool>> qos_events_in_use_by_wait_set_;
312 };
313 
314 } // namespace rclcpp
315 
316 #endif // RCLCPP__SUBSCRIPTION_BASE_HPP_
rclcpp::SubscriptionBase::get_event_handlers
const std::vector< std::shared_ptr< rclcpp::QOSEventHandlerBase > > & get_event_handlers() const
Get all the QoS event handlers associated with this subscription.
rclcpp::SubscriptionBase::handle_loaned_message
virtual void handle_loaned_message(void *loaned_message, const rclcpp::MessageInfo &message_info)=0
rclcpp::SubscriptionBase::setup_intra_process
void setup_intra_process(uint64_t intra_process_subscription_id, IntraProcessManagerWeakPtr weak_ipm)
Implemenation detail.
rclcpp::SubscriptionBase::intra_process_subscription_handle_
std::shared_ptr< rcl_subscription_t > intra_process_subscription_handle_
Definition: subscription_base.hpp:294
rclcpp::SubscriptionBase::get_message_type_support_handle
const rosidl_message_type_support_t & get_message_type_support_handle() const
rclcpp::SubscriptionBase::node_base_
rclcpp::node_interfaces::NodeBaseInterface *const node_base_
Definition: subscription_base.hpp:290
std::string
std::shared_ptr< rcl_subscription_t >
rclcpp::SubscriptionBase::use_intra_process_
bool use_intra_process_
Definition: subscription_base.hpp:298
message_info.hpp
RCLCPP_DISABLE_COPY
#define RCLCPP_DISABLE_COPY(...)
Definition: macros.hpp:26
rmw.h
rclcpp::SubscriptionBase::return_message
virtual void return_message(std::shared_ptr< void > &message)=0
Return the message borrowed in create_message.
rclcpp::SubscriptionBase::weak_ipm_
IntraProcessManagerWeakPtr weak_ipm_
Definition: subscription_base.hpp:299
std::make_shared
T make_shared(T... args)
std::vector
rclcpp::SubscriptionBase::event_handlers_
std::vector< std::shared_ptr< rclcpp::QOSEventHandlerBase > > event_handlers_
Definition: subscription_base.hpp:296
rclcpp::SubscriptionBase::can_loan_messages
bool can_loan_messages() const
Check if subscription instance can loan messages.
rclcpp::SubscriptionBase::get_subscription_handle
std::shared_ptr< rcl_subscription_t > get_subscription_handle()
rclcpp::SubscriptionBase
Definition: subscription_base.hpp:59
rclcpp::SubscriptionBase::get_publisher_count
size_t get_publisher_count() const
Get matching publisher count.
rclcpp::SubscriptionBase::intra_process_subscription_id_
uint64_t intra_process_subscription_id_
Definition: subscription_base.hpp:300
rclcpp::SubscriptionBase::subscription_handle_
std::shared_ptr< rcl_subscription_t > subscription_handle_
Definition: subscription_base.hpp:293
rclcpp::SubscriptionBase::default_incompatible_qos_callback
void default_incompatible_qos_callback(QOSRequestedIncompatibleQoSInfo &info) const
rclcpp::SubscriptionBase::create_serialized_message
virtual std::shared_ptr< rclcpp::SerializedMessage > create_serialized_message()=0
Borrow a new serialized message.
rclcpp::SubscriptionBase::SubscriptionBase
SubscriptionBase(rclcpp::node_interfaces::NodeBaseInterface *node_base, const rosidl_message_type_support_t &type_support_handle, const std::string &topic_name, const rcl_subscription_options_t &subscription_options, bool is_serialized=false)
Default constructor.
serialized_message.hpp
rclcpp
This header provides the get_node_base_interface() template function.
Definition: allocator_common.hpp:24
subscription_intra_process_base.hpp
qos.hpp
RCLCPP_PUBLIC
#define RCLCPP_PUBLIC
Definition: visibility_control.hpp:50
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:59
macros.hpp
rclcpp::SubscriptionBase::is_serialized
bool is_serialized() const
Return if the subscription is serialized.
rclcpp::SubscriptionBase::get_topic_name
const char * get_topic_name() const
Get the topic that this subscription is subscribed on.
rclcpp::SubscriptionBase::take_serialized
bool take_serialized(rclcpp::SerializedMessage &message_out, rclcpp::MessageInfo &message_info_out)
Take the next inter-process message, in its serialized form, from the subscription.
rclcpp::SubscriptionBase::handle_message
virtual void handle_message(std::shared_ptr< void > &message, const rclcpp::MessageInfo &message_info)=0
Check if we need to handle the message, and execute the callback if we do.
rclcpp::SubscriptionBase::create_message
virtual std::shared_ptr< void > create_message()=0
Borrow a new message.
std::enable_shared_from_this
std::atomic< bool >
intra_process_manager.hpp
any_subscription_callback.hpp
rcl_subscription_options_t
std::weak_ptr< rclcpp::experimental::IntraProcessManager >
rclcpp::SubscriptionBase::take_type_erased
bool take_type_erased(void *message_out, rclcpp::MessageInfo &message_info_out)
Take the next inter-process message from the subscription as a type erased pointer.
std::vector::emplace_back
T emplace_back(T... args)
rclcpp::MessageInfo
Additional meta data about messages taken from subscriptions.
Definition: message_info.hpp:26
rmw_gid_t
rclcpp::SubscriptionBase::return_serialized_message
virtual void return_serialized_message(std::shared_ptr< rclcpp::SerializedMessage > &message)=0
Return the message borrowed in create_serialized_message.
type_support_decl.hpp
visibility_control.hpp
std::unordered_map::insert
T insert(T... args)
rmw_qos_incompatible_event_status_t
rclcpp::SerializedMessage
Object oriented version of rcl_serialized_message_t with destructor to avoid memory leaks.
Definition: serialized_message.hpp:27
rclcpp::SubscriptionBase::get_intra_process_waitable
rclcpp::Waitable::SharedPtr get_intra_process_waitable() const
Return the waitable for intra-process.
RCLCPP_SMART_PTR_DEFINITIONS_NOT_COPYABLE
#define RCLCPP_SMART_PTR_DEFINITIONS_NOT_COPYABLE(...)
Definition: macros.hpp:51
rclcpp::SubscriptionBase::~SubscriptionBase
virtual ~SubscriptionBase()
Default destructor.
rclcpp::SubscriptionBase::matches_any_intra_process_publishers
bool matches_any_intra_process_publishers(const rmw_gid_t *sender_gid) const
std::make_pair
T make_pair(T... args)
rclcpp::SubscriptionBase::exchange_in_use_by_wait_set_state
bool exchange_in_use_by_wait_set_state(void *pointer_to_subscription_part, bool in_use_state)
Exchange state of whether or not a part of the subscription is used by a wait set.
rclcpp::SubscriptionBase::node_handle_
std::shared_ptr< rcl_node_t > node_handle_
Definition: subscription_base.hpp:292
rclcpp::QOSEventHandlerBase
Definition: qos_event.hpp:79
rclcpp::QOSEventHandler
Definition: qos_event.hpp:106
std::unordered_map
rclcpp::SubscriptionBase::add_event_handler
void add_event_handler(const EventCallbackT &callback, const rcl_subscription_event_type_t event_type)
Definition: subscription_base.hpp:269
qos_event.hpp
rclcpp::SubscriptionBase::get_actual_qos
rclcpp::QoS get_actual_qos() const
Get the actual QoS settings, after the defaults have been determined.