ROS 2 rclcpp + rcl - humble  humble
ROS 2 C++ Client Library with ROS Client Library
subscription_base.cpp
1 // Copyright 2015 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 #include "rclcpp/subscription_base.hpp"
16 
17 #include <cstdio>
18 #include <memory>
19 #include <string>
20 #include <unordered_map>
21 #include <vector>
22 
23 #include "rcpputils/scope_exit.hpp"
24 
25 #include "rclcpp/exceptions.hpp"
26 #include "rclcpp/expand_topic_or_service_name.hpp"
27 #include "rclcpp/experimental/intra_process_manager.hpp"
28 #include "rclcpp/logging.hpp"
29 #include "rclcpp/node_interfaces/node_base_interface.hpp"
30 #include "rclcpp/qos_event.hpp"
31 
32 #include "rmw/error_handling.h"
33 #include "rmw/rmw.h"
34 
36 
37 SubscriptionBase::SubscriptionBase(
39  const rosidl_message_type_support_t & type_support_handle,
40  const std::string & topic_name,
41  const rcl_subscription_options_t & subscription_options,
42  bool is_serialized)
43 : node_base_(node_base),
44  node_handle_(node_base_->get_shared_rcl_node_handle()),
45  node_logger_(rclcpp::get_node_logger(node_handle_.get())),
46  use_intra_process_(false),
47  intra_process_subscription_id_(0),
48  type_support_(type_support_handle),
49  is_serialized_(is_serialized)
50 {
51  auto custom_deletor = [node_handle = this->node_handle_](rcl_subscription_t * rcl_subs)
52  {
53  if (rcl_subscription_fini(rcl_subs, node_handle.get()) != RCL_RET_OK) {
54  RCLCPP_ERROR(
55  rclcpp::get_node_logger(node_handle.get()).get_child("rclcpp"),
56  "Error in destruction of rcl subscription handle: %s",
57  rcl_get_error_string().str);
58  rcl_reset_error();
59  }
60  delete rcl_subs;
61  };
62 
63  subscription_handle_ = std::shared_ptr<rcl_subscription_t>(
64  new rcl_subscription_t, custom_deletor);
65  *subscription_handle_.get() = rcl_get_zero_initialized_subscription();
66 
68  subscription_handle_.get(),
69  node_handle_.get(),
70  &type_support_handle,
71  topic_name.c_str(),
72  &subscription_options);
73  if (ret != RCL_RET_OK) {
74  if (ret == RCL_RET_TOPIC_NAME_INVALID) {
75  auto rcl_node_handle = node_handle_.get();
76  // this will throw on any validation problem
77  rcl_reset_error();
79  topic_name,
80  rcl_node_get_name(rcl_node_handle),
81  rcl_node_get_namespace(rcl_node_handle));
82  }
83 
84  rclcpp::exceptions::throw_from_rcl_error(ret, "could not create subscription");
85  }
86 }
87 
89 {
91 
92  for (const auto & pair : event_handlers_) {
93  rcl_subscription_event_type_t event_type = pair.first;
95  }
96 
97  if (!use_intra_process_) {
98  return;
99  }
100  auto ipm = weak_ipm_.lock();
101  if (!ipm) {
102  // TODO(ivanpauno): should this raise an error?
103  RCLCPP_WARN(
104  rclcpp::get_logger("rclcpp"),
105  "Intra process manager died before than a subscription.");
106  return;
107  }
108  ipm->remove_subscription(intra_process_subscription_id_);
109 }
110 
111 const char *
113 {
114  return rcl_subscription_get_topic_name(subscription_handle_.get());
115 }
116 
117 std::shared_ptr<rcl_subscription_t>
118 SubscriptionBase::get_subscription_handle()
119 {
120  return subscription_handle_;
121 }
122 
123 std::shared_ptr<const rcl_subscription_t>
124 SubscriptionBase::get_subscription_handle() const
125 {
126  return subscription_handle_;
127 }
128 
129 const
130 std::unordered_map<rcl_subscription_event_type_t, std::shared_ptr<rclcpp::QOSEventHandlerBase>> &
132 {
133  return event_handlers_;
134 }
135 
138 {
139  const rmw_qos_profile_t * qos = rcl_subscription_get_actual_qos(subscription_handle_.get());
140  if (!qos) {
141  auto msg = std::string("failed to get qos settings: ") + rcl_get_error_string().str;
142  rcl_reset_error();
143  throw std::runtime_error(msg);
144  }
145 
147 }
148 
149 bool
150 SubscriptionBase::take_type_erased(void * message_out, rclcpp::MessageInfo & message_info_out)
151 {
152  rcl_ret_t ret = rcl_take(
153  this->get_subscription_handle().get(),
154  message_out,
155  &message_info_out.get_rmw_message_info(),
156  nullptr // rmw_subscription_allocation_t is unused here
157  );
158  TRACEPOINT(rclcpp_take, static_cast<const void *>(message_out));
160  return false;
161  } else if (RCL_RET_OK != ret) {
162  rclcpp::exceptions::throw_from_rcl_error(ret);
163  }
164  if (
165  matches_any_intra_process_publishers(&message_info_out.get_rmw_message_info().publisher_gid))
166  {
167  // In this case, the message will be delivered via intra-process and
168  // we should ignore this copy of the message.
169  return false;
170  }
171  return true;
172 }
173 
174 bool
176  rclcpp::SerializedMessage & message_out,
177  rclcpp::MessageInfo & message_info_out)
178 {
180  this->get_subscription_handle().get(),
181  &message_out.get_rcl_serialized_message(),
182  &message_info_out.get_rmw_message_info(),
183  nullptr);
185  return false;
186  } else if (RCL_RET_OK != ret) {
187  rclcpp::exceptions::throw_from_rcl_error(ret);
188  }
189  return true;
190 }
191 
192 const rosidl_message_type_support_t &
193 SubscriptionBase::get_message_type_support_handle() const
194 {
195  return type_support_;
196 }
197 
198 bool
200 {
201  return is_serialized_;
202 }
203 
204 size_t
206 {
207  size_t inter_process_publisher_count = 0;
208 
209  rmw_ret_t status = rcl_subscription_get_publisher_count(
210  subscription_handle_.get(),
211  &inter_process_publisher_count);
212 
213  if (RCL_RET_OK != status) {
214  rclcpp::exceptions::throw_from_rcl_error(status, "failed to get get publisher count");
215  }
216  return inter_process_publisher_count;
217 }
218 
219 void
221  uint64_t intra_process_subscription_id,
222  IntraProcessManagerWeakPtr weak_ipm)
223 {
224  intra_process_subscription_id_ = intra_process_subscription_id;
225  weak_ipm_ = weak_ipm;
226  use_intra_process_ = true;
227 }
228 
229 bool
231 {
232  bool retval = rcl_subscription_can_loan_messages(subscription_handle_.get());
233  if (retval) {
234  // TODO(clalancette): The loaned message interface is currently not safe to use with
235  // shared_ptr callbacks. If a user takes a copy of the shared_ptr, it can get freed from
236  // underneath them via rcl_return_loaned_message_from_subscription(). The correct solution is
237  // to return the loaned message in a custom deleter, but that needs to be carefully handled
238  // with locking. Warn the user about this until we fix it.
239  RCLCPP_WARN_ONCE(
240  this->node_logger_,
241  "Loaned messages are only safe with const ref subscription callbacks. "
242  "If you are using any other kind of subscriptions, "
243  "set the ROS_DISABLE_LOANED_MESSAGES environment variable to 1 (the default).");
244  }
245  return retval;
246 }
247 
248 rclcpp::Waitable::SharedPtr
250 {
251  // If not using intra process, shortcut to nullptr.
252  if (!use_intra_process_) {
253  return nullptr;
254  }
255  // Get the intra process manager.
256  auto ipm = weak_ipm_.lock();
257  if (!ipm) {
258  throw std::runtime_error(
259  "SubscriptionBase::get_intra_process_waitable() called "
260  "after destruction of intra process manager");
261  }
262 
263  // Use the id to retrieve the subscription intra-process from the intra-process manager.
264  return ipm->get_subscription_intra_process(intra_process_subscription_id_);
265 }
266 
267 void
268 SubscriptionBase::default_incompatible_qos_callback(
269  rclcpp::QOSRequestedIncompatibleQoSInfo & event) const
270 {
271  std::string policy_name = qos_policy_name_from_kind(event.last_policy_kind);
272  RCLCPP_WARN(
273  rclcpp::get_logger(rcl_node_get_logger_name(node_handle_.get())),
274  "New publisher discovered on topic '%s', offering incompatible QoS. "
275  "No messages will be sent to it. "
276  "Last incompatible policy: %s",
277  get_topic_name(),
278  policy_name.c_str());
279 }
280 
281 bool
282 SubscriptionBase::matches_any_intra_process_publishers(const rmw_gid_t * sender_gid) const
283 {
284  if (!use_intra_process_) {
285  return false;
286  }
287  auto ipm = weak_ipm_.lock();
288  if (!ipm) {
289  throw std::runtime_error(
290  "intra process publisher check called "
291  "after destruction of intra process manager");
292  }
293  return ipm->matches_any_publishers(sender_gid);
294 }
295 
296 bool
298  void * pointer_to_subscription_part,
299  bool in_use_state)
300 {
301  if (nullptr == pointer_to_subscription_part) {
302  throw std::invalid_argument("pointer_to_subscription_part is unexpectedly nullptr");
303  }
304  if (this == pointer_to_subscription_part) {
305  return subscription_in_use_by_wait_set_.exchange(in_use_state);
306  }
307  if (get_intra_process_waitable().get() == pointer_to_subscription_part) {
308  return intra_process_subscription_waitable_in_use_by_wait_set_.exchange(in_use_state);
309  }
310  for (const auto & key_event_pair : event_handlers_) {
311  auto qos_event = key_event_pair.second;
312  if (qos_event.get() == pointer_to_subscription_part) {
313  return qos_events_in_use_by_wait_set_[qos_event.get()].exchange(in_use_state);
314  }
315  }
316  throw std::runtime_error("given pointer_to_subscription_part does not match any part");
317 }
318 
319 std::vector<rclcpp::NetworkFlowEndpoint>
321 {
322  rcutils_allocator_t allocator = rcutils_get_default_allocator();
323  rcl_network_flow_endpoint_array_t network_flow_endpoint_array =
324  rcl_get_zero_initialized_network_flow_endpoint_array();
325  rcl_ret_t ret = rcl_subscription_get_network_flow_endpoints(
326  subscription_handle_.get(), &allocator, &network_flow_endpoint_array);
327  if (RCL_RET_OK != ret) {
328  auto error_msg = std::string("Error obtaining network flows of subscription: ") +
329  rcl_get_error_string().str;
330  rcl_reset_error();
331  if (RCL_RET_OK !=
332  rcl_network_flow_endpoint_array_fini(&network_flow_endpoint_array))
333  {
334  error_msg += std::string(". Also error cleaning up network flow array: ") +
335  rcl_get_error_string().str;
336  rcl_reset_error();
337  }
338  rclcpp::exceptions::throw_from_rcl_error(ret, error_msg);
339  }
340 
341  std::vector<rclcpp::NetworkFlowEndpoint> network_flow_endpoint_vector;
342  for (size_t i = 0; i < network_flow_endpoint_array.size; ++i) {
343  network_flow_endpoint_vector.push_back(
345  network_flow_endpoint_array.
346  network_flow_endpoint[i]));
347  }
348 
349  ret = rcl_network_flow_endpoint_array_fini(&network_flow_endpoint_array);
350  if (RCL_RET_OK != ret) {
351  rclcpp::exceptions::throw_from_rcl_error(ret, "error cleaning up network flow array");
352  }
353 
354  return network_flow_endpoint_vector;
355 }
356 
357 void
359  rcl_event_callback_t callback,
360  const void * user_data)
361 {
363  subscription_handle_.get(),
364  callback,
365  user_data);
366 
367  if (RCL_RET_OK != ret) {
368  using rclcpp::exceptions::throw_from_rcl_error;
369  throw_from_rcl_error(ret, "failed to set the on new message callback for subscription");
370  }
371 }
372 
373 bool
375 {
376  return rcl_subscription_is_cft_enabled(subscription_handle_.get());
377 }
378 
379 void
381  const std::string & filter_expression,
382  const std::vector<std::string> & expression_parameters)
383 {
386 
387  std::vector<const char *> cstrings =
388  get_c_vector_string(expression_parameters);
390  subscription_handle_.get(),
391  get_c_string(filter_expression),
392  cstrings.size(),
393  cstrings.data(),
394  &options);
395  if (RCL_RET_OK != ret) {
396  rclcpp::exceptions::throw_from_rcl_error(
397  ret, "failed to init subscription content_filtered_topic option");
398  }
399  RCPPUTILS_SCOPE_EXIT(
400  {
402  subscription_handle_.get(), &options);
403  if (RCL_RET_OK != ret) {
404  RCLCPP_ERROR(
405  rclcpp::get_logger("rclcpp"),
406  "Failed to fini subscription content_filtered_topic option: %s",
407  rcl_get_error_string().str);
408  rcl_reset_error();
409  }
410  });
411 
413  subscription_handle_.get(),
414  &options);
415 
416  if (RCL_RET_OK != ret) {
417  rclcpp::exceptions::throw_from_rcl_error(ret, "failed to set cft expression parameters");
418  }
419 }
420 
423 {
424  rclcpp::ContentFilterOptions ret_options;
427 
429  subscription_handle_.get(),
430  &options);
431 
432  if (RCL_RET_OK != ret) {
433  rclcpp::exceptions::throw_from_rcl_error(ret, "failed to get cft expression parameters");
434  }
435 
436  RCPPUTILS_SCOPE_EXIT(
437  {
439  subscription_handle_.get(), &options);
440  if (RCL_RET_OK != ret) {
441  RCLCPP_ERROR(
442  rclcpp::get_logger("rclcpp"),
443  "Failed to fini subscription content_filtered_topic option: %s",
444  rcl_get_error_string().str);
445  rcl_reset_error();
446  }
447  });
448 
449  rmw_subscription_content_filter_options_t & content_filter_options =
450  options.rmw_subscription_content_filter_options;
451  ret_options.filter_expression = content_filter_options.filter_expression;
452 
453  for (size_t i = 0; i < content_filter_options.expression_parameters.size; ++i) {
454  ret_options.expression_parameters.push_back(
455  content_filter_options.expression_parameters.data[i]);
456  }
457 
458  return ret_options;
459 }
RCLCPP_PUBLIC Logger get_child(const std::string &suffix)
Return a logger that is a descendant of this logger.
Definition: logger.hpp:160
Additional meta data about messages taken from subscriptions.
const rmw_message_info_t & get_rmw_message_info() const
Return the message info as the underlying rmw message info type.
Encapsulation of Quality of Service settings.
Definition: qos.hpp:111
Object oriented version of rcl_serialized_message_t with destructor to avoid memory leaks.
rcl_serialized_message_t & get_rcl_serialized_message()
Get the underlying rcl_serialized_t handle.
RCLCPP_PUBLIC size_t get_publisher_count() const
Get matching publisher count.
RCLCPP_PUBLIC rclcpp::QoS get_actual_qos() const
Get the actual QoS settings, after the defaults have been determined.
RCLCPP_PUBLIC bool can_loan_messages() const
Check if subscription instance can loan messages.
void set_on_new_message_callback(std::function< void(size_t)> callback)
Set a callback to be called when each new message is received.
RCLCPP_PUBLIC rclcpp::Waitable::SharedPtr get_intra_process_waitable() const
Return the waitable for intra-process.
RCLCPP_PUBLIC const std::unordered_map< rcl_subscription_event_type_t, std::shared_ptr< rclcpp::QOSEventHandlerBase > > & get_event_handlers() const
Get all the QoS event handlers associated with this subscription.
RCLCPP_PUBLIC std::vector< rclcpp::NetworkFlowEndpoint > get_network_flow_endpoints() const
Get network flow endpoints.
RCLCPP_PUBLIC void setup_intra_process(uint64_t intra_process_subscription_id, IntraProcessManagerWeakPtr weak_ipm)
Implemenation detail.
void clear_on_new_message_callback()
Unset the callback registered for new messages, if any.
RCLCPP_PUBLIC 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_PUBLIC 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.
RCLCPP_PUBLIC 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.
void clear_on_new_qos_event_callback(rcl_subscription_event_type_t event_type)
Unset the callback registered for new qos events, if any.
RCLCPP_PUBLIC void set_content_filter(const std::string &filter_expression, const std::vector< std::string > &expression_parameters={})
Set the filter expression and expression parameters for the subscription.
virtual RCLCPP_PUBLIC ~SubscriptionBase()
Destructor.
RCLCPP_PUBLIC bool is_cft_enabled() const
Check if content filtered topic feature of the subscription instance is enabled.
RCLCPP_PUBLIC rclcpp::ContentFilterOptions get_content_filter() const
Get the filter expression and expression parameters for the subscription.
RCLCPP_PUBLIC bool is_serialized() const
Return if the subscription is serialized.
RCLCPP_PUBLIC const char * get_topic_name() const
Get the topic that this subscription is subscribed on.
Pure virtual interface class for the NodeBase part of the Node API.
enum rcl_subscription_event_type_e rcl_subscription_event_type_t
Enumeration of all of the subscription events that may fire.
Versions of rosidl_typesupport_cpp::get_message_type_support_handle that handle adapted types.
RCLCPP_PUBLIC std::string expand_topic_or_service_name(const std::string &name, const std::string &node_name, const std::string &namespace_, bool is_service=false)
Expand a topic or service name and throw if it is not valid.
RCLCPP_PUBLIC Logger get_node_logger(const rcl_node_t *node)
Return a named logger using an rcl_node_t.
Definition: logger.cpp:38
RCLCPP_PUBLIC std::vector< const char * > get_c_vector_string(const std::vector< std::string > &strings_in)
Return the std::vector of C string from the given std::vector<std::string>.
Definition: utilities.cpp:218
RCLCPP_PUBLIC const char * get_c_string(const char *string_in)
Return the given string.
Definition: utilities.cpp:206
RCLCPP_PUBLIC Logger get_logger(const std::string &name)
Return a named logger.
Definition: logger.cpp:27
RCL_PUBLIC RCL_WARN_UNUSED const char * rcl_node_get_name(const rcl_node_t *node)
Return the name of the node.
Definition: node.c:435
RCL_PUBLIC RCL_WARN_UNUSED const char * rcl_node_get_namespace(const rcl_node_t *node)
Return the namespace of the node.
Definition: node.c:444
RCL_PUBLIC RCL_WARN_UNUSED const char * rcl_node_get_logger_name(const rcl_node_t *node)
Return the logger name of the node.
Definition: node.c:512
Options available for a rcl subscription.
Definition: subscription.h:46
Structure which encapsulates a ROS Subscription.
Definition: subscription.h:39
Options to configure content filtered topic in the subscription.
std::string filter_expression
Filter expression is similar to the WHERE part of an SQL clause.
static QoSInitialization from_rmw(const rmw_qos_profile_t &rmw_qos)
Create a QoSInitialization from an existing rmw_qos_profile_t, using its history and depth.
Definition: qos.cpp:51
RCL_PUBLIC RCL_WARN_UNUSED rcl_ret_t rcl_subscription_content_filter_options_fini(const rcl_subscription_t *subscription, rcl_subscription_content_filter_options_t *options)
Reclaim rcl_subscription_content_filter_options_t structure.
Definition: subscription.c:411
RCL_PUBLIC RCL_WARN_UNUSED rcl_ret_t rcl_subscription_init(rcl_subscription_t *subscription, const rcl_node_t *node, const rosidl_message_type_support_t *type_support, const char *topic_name, const rcl_subscription_options_t *options)
Initialize a ROS subscription.
Definition: subscription.c:47
RCL_PUBLIC RCL_WARN_UNUSED const char * rcl_subscription_get_topic_name(const rcl_subscription_t *subscription)
Get the topic name for the subscription.
Definition: subscription.c:663
RCL_PUBLIC RCL_WARN_UNUSED rcl_ret_t rcl_subscription_set_on_new_message_callback(const rcl_subscription_t *subscription, rcl_event_callback_t callback, const void *user_data)
Set the on new message callback function for the subscription.
Definition: subscription.c:765
RCL_PUBLIC bool rcl_subscription_can_loan_messages(const rcl_subscription_t *subscription)
Check if subscription instance can loan messages.
Definition: subscription.c:734
RCL_PUBLIC RCL_WARN_UNUSED rcl_ret_t rcl_subscription_fini(rcl_subscription_t *subscription, rcl_node_t *node)
Finalize a rcl_subscription_t.
Definition: subscription.c:162
RCL_PUBLIC RCL_WARN_UNUSED rcl_ret_t rcl_take(const rcl_subscription_t *subscription, void *ros_message, rmw_message_info_t *message_info, rmw_subscription_allocation_t *allocation)
Take a ROS message from a topic using a rcl subscription.
Definition: subscription.c:498
RCL_PUBLIC RCL_WARN_UNUSED rmw_ret_t rcl_subscription_get_publisher_count(const rcl_subscription_t *subscription, size_t *publisher_count)
Get the number of publishers matched to a subscription.
Definition: subscription.c:703
RCL_PUBLIC RCL_WARN_UNUSED rcl_ret_t rcl_take_serialized_message(const rcl_subscription_t *subscription, rcl_serialized_message_t *serialized_message, rmw_message_info_t *message_info, rmw_subscription_allocation_t *allocation)
Take a serialized raw message from a topic using a rcl subscription.
Definition: subscription.c:579
RCL_PUBLIC RCL_WARN_UNUSED rcl_subscription_content_filter_options_t rcl_get_zero_initialized_subscription_content_filter_options(void)
Return the zero initialized subscription content filter options.
Definition: subscription.c:343
RCL_PUBLIC RCL_WARN_UNUSED bool rcl_subscription_is_cft_enabled(const rcl_subscription_t *subscription)
Check if the content filtered topic feature is enabled in the subscription.
Definition: subscription.c:431
RCL_PUBLIC RCL_WARN_UNUSED const rmw_qos_profile_t * rcl_subscription_get_actual_qos(const rcl_subscription_t *subscription)
Get the actual qos settings of the subscription.
Definition: subscription.c:725
RCL_PUBLIC RCL_WARN_UNUSED rcl_subscription_t rcl_get_zero_initialized_subscription(void)
Return a rcl_subscription_t struct with members set to NULL.
Definition: subscription.c:40
RCL_PUBLIC RCL_WARN_UNUSED rcl_ret_t rcl_subscription_get_content_filter(const rcl_subscription_t *subscription, rcl_subscription_content_filter_options_t *options)
Retrieve the filter expression of the subscription.
Definition: subscription.c:474
RCL_PUBLIC RCL_WARN_UNUSED rcl_ret_t rcl_subscription_set_content_filter(const rcl_subscription_t *subscription, const rcl_subscription_content_filter_options_t *options)
Set the filter expression and expression parameters for the subscription.
Definition: subscription.c:440
RCL_PUBLIC RCL_WARN_UNUSED rcl_ret_t rcl_subscription_content_filter_options_init(const rcl_subscription_t *subscription, const char *filter_expression, size_t expression_parameters_argc, const char *expression_parameter_argv[], rcl_subscription_content_filter_options_t *options)
Initialize the content filter options for the given subscription options.
Definition: subscription.c:352
#define RCL_RET_SUBSCRIPTION_TAKE_FAILED
Failed to take a message from the subscription return code.
Definition: types.h:72
#define RCL_RET_OK
Success return code.
Definition: types.h:26
#define RCL_RET_TOPIC_NAME_INVALID
Topic name does not pass validation.
Definition: types.h:46
rmw_ret_t rcl_ret_t
The type that holds an rcl return code.
Definition: types.h:23