ROS 2 rclcpp + rcl - humble  humble
ROS 2 C++ Client Library with ROS Client Library
subscription.c
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 #ifdef __cplusplus
16 extern "C"
17 {
18 #endif
19 
20 #include "rcl/subscription.h"
21 
22 #include <stdio.h>
23 
24 #include "rcl/error_handling.h"
25 #include "rcl/node.h"
26 #include "rcutils/env.h"
27 #include "rcutils/logging_macros.h"
28 #include "rcutils/strdup.h"
29 #include "rcutils/types/string_array.h"
30 #include "rmw/error_handling.h"
31 #include "rmw/subscription_content_filter_options.h"
32 #include "rmw/validate_full_topic_name.h"
33 #include "tracetools/tracetools.h"
34 
35 #include "./common.h"
36 #include "./subscription_impl.h"
37 
38 
41 {
42  static rcl_subscription_t null_subscription = {0};
43  return null_subscription;
44 }
45 
48  rcl_subscription_t * subscription,
49  const rcl_node_t * node,
50  const rosidl_message_type_support_t * type_support,
51  const char * topic_name,
52  const rcl_subscription_options_t * options
53 )
54 {
55  rcl_ret_t fail_ret = RCL_RET_ERROR;
56 
57  // Check options and allocator first, so the allocator can be used in errors.
58  RCL_CHECK_ARGUMENT_FOR_NULL(options, RCL_RET_INVALID_ARGUMENT);
59  rcl_allocator_t * allocator = (rcl_allocator_t *)&options->allocator;
60  RCL_CHECK_ALLOCATOR_WITH_MSG(allocator, "invalid allocator", return RCL_RET_INVALID_ARGUMENT);
61  RCL_CHECK_ARGUMENT_FOR_NULL(subscription, RCL_RET_INVALID_ARGUMENT);
62  if (!rcl_node_is_valid(node)) {
63  return RCL_RET_NODE_INVALID; // error already set
64  }
65  RCL_CHECK_ARGUMENT_FOR_NULL(type_support, RCL_RET_INVALID_ARGUMENT);
66  RCL_CHECK_ARGUMENT_FOR_NULL(topic_name, RCL_RET_INVALID_ARGUMENT);
67  RCUTILS_LOG_DEBUG_NAMED(
68  ROS_PACKAGE_NAME, "Initializing subscription for topic name '%s'", topic_name);
69  if (subscription->impl) {
70  RCL_SET_ERROR_MSG("subscription already initialized, or memory was uninitialized");
71  return RCL_RET_ALREADY_INIT;
72  }
73 
74  // Expand and remap the given topic name.
75  char * remapped_topic_name = NULL;
77  node,
78  topic_name,
79  *allocator,
80  false,
81  false,
82  &remapped_topic_name);
83  if (ret != RCL_RET_OK) {
86  } else if (ret != RCL_RET_BAD_ALLOC) {
87  ret = RCL_RET_ERROR;
88  }
89  goto cleanup;
90  }
91  RCUTILS_LOG_DEBUG_NAMED(
92  ROS_PACKAGE_NAME, "Expanded and remapped topic name '%s'", remapped_topic_name);
93 
94  // Allocate memory for the implementation struct.
95  subscription->impl = (rcl_subscription_impl_t *)allocator->zero_allocate(
96  1, sizeof(rcl_subscription_impl_t), allocator->state);
97  RCL_CHECK_FOR_NULL_WITH_MSG(
98  subscription->impl, "allocating memory failed", ret = RCL_RET_BAD_ALLOC; goto cleanup);
99  // Fill out the implemenation struct.
100  // rmw_handle
101  // TODO(wjwwood): pass allocator once supported in rmw api.
102  subscription->impl->rmw_handle = rmw_create_subscription(
104  type_support,
105  remapped_topic_name,
106  &(options->qos),
107  &(options->rmw_subscription_options));
108  if (!subscription->impl->rmw_handle) {
109  RCL_SET_ERROR_MSG(rmw_get_error_string().str);
110  goto fail;
111  }
112  // get actual qos, and store it
113  rmw_ret_t rmw_ret = rmw_subscription_get_actual_qos(
114  subscription->impl->rmw_handle,
115  &subscription->impl->actual_qos);
116  if (RMW_RET_OK != rmw_ret) {
117  RCL_SET_ERROR_MSG(rmw_get_error_string().str);
118  goto fail;
119  }
120  subscription->impl->actual_qos.avoid_ros_namespace_conventions =
121  options->qos.avoid_ros_namespace_conventions;
122  // options
123  subscription->impl->options = *options;
124  RCUTILS_LOG_DEBUG_NAMED(ROS_PACKAGE_NAME, "Subscription initialized");
125  ret = RCL_RET_OK;
126  TRACEPOINT(
128  (const void *)subscription,
129  (const void *)node,
130  (const void *)subscription->impl->rmw_handle,
131  remapped_topic_name,
132  options->qos.depth);
133  goto cleanup;
134 fail:
135  if (subscription->impl) {
136  if (subscription->impl->rmw_handle) {
137  rmw_ret_t rmw_fail_ret = rmw_destroy_subscription(
138  rcl_node_get_rmw_handle(node), subscription->impl->rmw_handle);
139  if (RMW_RET_OK != rmw_fail_ret) {
140  RCUTILS_SAFE_FWRITE_TO_STDERR(rmw_get_error_string().str);
141  RCUTILS_SAFE_FWRITE_TO_STDERR("\n");
142  }
143  }
144 
145  ret = rcl_subscription_options_fini(&subscription->impl->options);
146  if (RCL_RET_OK != ret) {
147  RCUTILS_SAFE_FWRITE_TO_STDERR(rmw_get_error_string().str);
148  RCUTILS_SAFE_FWRITE_TO_STDERR("\n");
149  }
150 
151  allocator->deallocate(subscription->impl, allocator->state);
152  subscription->impl = NULL;
153  }
154  ret = fail_ret;
155  // Fall through to cleanup
156 cleanup:
157  allocator->deallocate(remapped_topic_name, allocator->state);
158  return ret;
159 }
160 
161 rcl_ret_t
163 {
164  RCUTILS_CAN_RETURN_WITH_ERROR_OF(RCL_RET_SUBSCRIPTION_INVALID);
165  RCUTILS_CAN_RETURN_WITH_ERROR_OF(RCL_RET_NODE_INVALID);
166  RCUTILS_CAN_RETURN_WITH_ERROR_OF(RCL_RET_INVALID_ARGUMENT);
167  RCUTILS_CAN_RETURN_WITH_ERROR_OF(RCL_RET_ERROR);
168 
169  RCUTILS_LOG_DEBUG_NAMED(ROS_PACKAGE_NAME, "Finalizing subscription");
170  rcl_ret_t result = RCL_RET_OK;
171  RCL_CHECK_ARGUMENT_FOR_NULL(subscription, RCL_RET_SUBSCRIPTION_INVALID);
173  return RCL_RET_NODE_INVALID; // error already set
174  }
175  if (subscription->impl) {
176  rcl_allocator_t allocator = subscription->impl->options.allocator;
177  rmw_node_t * rmw_node = rcl_node_get_rmw_handle(node);
178  if (!rmw_node) {
180  }
181  rmw_ret_t ret =
182  rmw_destroy_subscription(rmw_node, subscription->impl->rmw_handle);
183  if (ret != RMW_RET_OK) {
184  RCL_SET_ERROR_MSG(rmw_get_error_string().str);
185  result = RCL_RET_ERROR;
186  }
187  rcl_ret_t rcl_ret = rcl_subscription_options_fini(&subscription->impl->options);
188  if (RCL_RET_OK != rcl_ret) {
189  RCUTILS_SAFE_FWRITE_TO_STDERR(rcl_get_error_string().str);
190  RCUTILS_SAFE_FWRITE_TO_STDERR("\n");
191  result = RCL_RET_ERROR;
192  }
193 
194  allocator.deallocate(subscription->impl, allocator.state);
195  subscription->impl = NULL;
196  }
197  RCUTILS_LOG_DEBUG_NAMED(ROS_PACKAGE_NAME, "Subscription finalized");
198  return result;
199 }
200 
203 {
204  // !!! MAKE SURE THAT CHANGES TO THESE DEFAULTS ARE REFLECTED IN THE HEADER DOC STRING
205  static rcl_subscription_options_t default_options;
206  // Must set these after declaration because they are not a compile time constants.
207  default_options.qos = rmw_qos_profile_default;
208  default_options.allocator = rcl_get_default_allocator();
209  default_options.rmw_subscription_options = rmw_get_default_subscription_options();
210  return default_options;
211 }
212 
213 rcl_ret_t
215 {
216  RCL_CHECK_ARGUMENT_FOR_NULL(option, RCL_RET_INVALID_ARGUMENT);
217  // fini rmw_subscription_options_t
218  const rcl_allocator_t * allocator = &option->allocator;
219  RCL_CHECK_ALLOCATOR_WITH_MSG(allocator, "invalid allocator", return RCL_RET_INVALID_ARGUMENT);
220 
221  if (option->rmw_subscription_options.content_filter_options) {
222  rmw_ret_t ret = rmw_subscription_content_filter_options_fini(
223  option->rmw_subscription_options.content_filter_options, allocator);
224  if (RCUTILS_RET_OK != ret) {
225  RCUTILS_SAFE_FWRITE_TO_STDERR("Failed to fini content filter options.\n");
226  return rcl_convert_rmw_ret_to_rcl_ret(ret);
227  }
228  allocator->deallocate(
229  option->rmw_subscription_options.content_filter_options, allocator->state);
230  option->rmw_subscription_options.content_filter_options = NULL;
231  }
232  return RCL_RET_OK;
233 }
234 
235 rcl_ret_t
237  const char * filter_expression,
238  size_t expression_parameters_argc,
239  const char * expression_parameter_argv[],
240  rcl_subscription_options_t * options)
241 {
242  RCL_CHECK_ARGUMENT_FOR_NULL(filter_expression, RCL_RET_INVALID_ARGUMENT);
243  if (expression_parameters_argc > 100) {
244  RCL_SET_ERROR_MSG("The maximum of expression parameters argument number is 100");
246  }
247  RCL_CHECK_ARGUMENT_FOR_NULL(options, RCL_RET_INVALID_ARGUMENT);
248  const rcl_allocator_t * allocator = &options->allocator;
249  RCL_CHECK_ALLOCATOR_WITH_MSG(allocator, "invalid allocator", return RCL_RET_INVALID_ARGUMENT);
250 
251  rcl_ret_t ret;
252  rmw_ret_t rmw_ret;
253  rmw_subscription_content_filter_options_t * original_content_filter_options =
254  options->rmw_subscription_options.content_filter_options;
255  rmw_subscription_content_filter_options_t content_filter_options_backup =
256  rmw_get_zero_initialized_content_filter_options();
257 
258  if (original_content_filter_options) {
259  // make a backup, restore the data if failure happened
260  rmw_ret = rmw_subscription_content_filter_options_copy(
261  original_content_filter_options,
262  allocator,
263  &content_filter_options_backup
264  );
265  if (rmw_ret != RMW_RET_OK) {
266  return rcl_convert_rmw_ret_to_rcl_ret(rmw_ret);
267  }
268  } else {
269  options->rmw_subscription_options.content_filter_options =
270  allocator->allocate(
271  sizeof(rmw_subscription_content_filter_options_t), allocator->state);
272  if (!options->rmw_subscription_options.content_filter_options) {
273  RCL_SET_ERROR_MSG("failed to allocate memory");
274  return RCL_RET_BAD_ALLOC;
275  }
276  *options->rmw_subscription_options.content_filter_options =
277  rmw_get_zero_initialized_content_filter_options();
278  }
279 
280  rmw_ret = rmw_subscription_content_filter_options_set(
281  filter_expression,
282  expression_parameters_argc,
283  expression_parameter_argv,
284  allocator,
285  options->rmw_subscription_options.content_filter_options
286  );
287 
288  if (rmw_ret != RMW_RET_OK) {
289  ret = rcl_convert_rmw_ret_to_rcl_ret(rmw_ret);
290  goto failed;
291  }
292 
293  rmw_ret = rmw_subscription_content_filter_options_fini(
294  &content_filter_options_backup,
295  allocator
296  );
297  if (rmw_ret != RMW_RET_OK) {
298  return rcl_convert_rmw_ret_to_rcl_ret(rmw_ret);
299  }
300 
301  return RMW_RET_OK;
302 
303 failed:
304 
305  if (original_content_filter_options == NULL) {
306  if (options->rmw_subscription_options.content_filter_options) {
307  rmw_ret = rmw_subscription_content_filter_options_fini(
308  options->rmw_subscription_options.content_filter_options,
309  allocator
310  );
311 
312  if (rmw_ret != RMW_RET_OK) {
313  return rcl_convert_rmw_ret_to_rcl_ret(rmw_ret);
314  }
315 
316  allocator->deallocate(
317  options->rmw_subscription_options.content_filter_options, allocator->state);
318  options->rmw_subscription_options.content_filter_options = NULL;
319  }
320  } else {
321  rmw_ret = rmw_subscription_content_filter_options_copy(
322  &content_filter_options_backup,
323  allocator,
324  options->rmw_subscription_options.content_filter_options
325  );
326  if (rmw_ret != RMW_RET_OK) {
327  return rcl_convert_rmw_ret_to_rcl_ret(rmw_ret);
328  }
329 
330  rmw_ret = rmw_subscription_content_filter_options_fini(
331  &content_filter_options_backup,
332  allocator
333  );
334  if (rmw_ret != RMW_RET_OK) {
335  return rcl_convert_rmw_ret_to_rcl_ret(rmw_ret);
336  }
337  }
338 
339  return ret;
340 }
341 
344 {
346  .rmw_subscription_content_filter_options =
347  rmw_get_zero_initialized_content_filter_options()
348  }; // NOLINT(readability/braces): false positive
349 }
350 
351 rcl_ret_t
353  const rcl_subscription_t * subscription,
354  const char * filter_expression,
355  size_t expression_parameters_argc,
356  const char * expression_parameter_argv[],
358 {
359  if (!rcl_subscription_is_valid(subscription)) {
361  }
362  RCL_CHECK_ARGUMENT_FOR_NULL(options, RCL_RET_INVALID_ARGUMENT);
363  const rcl_allocator_t * allocator = &subscription->impl->options.allocator;
364  RCL_CHECK_ALLOCATOR_WITH_MSG(allocator, "invalid allocator", return RCL_RET_INVALID_ARGUMENT);
365  if (expression_parameters_argc > 100) {
366  RCL_SET_ERROR_MSG("The maximum of expression parameters argument number is 100");
368  }
369 
370  rmw_ret_t rmw_ret = rmw_subscription_content_filter_options_init(
371  filter_expression,
372  expression_parameters_argc,
373  expression_parameter_argv,
374  allocator,
375  &options->rmw_subscription_content_filter_options
376  );
377 
378  return rcl_convert_rmw_ret_to_rcl_ret(rmw_ret);
379 }
380 
381 rcl_ret_t
383  const rcl_subscription_t * subscription,
384  const char * filter_expression,
385  size_t expression_parameters_argc,
386  const char * expression_parameter_argv[],
388 {
389  if (!rcl_subscription_is_valid(subscription)) {
391  }
392  if (expression_parameters_argc > 100) {
393  RCL_SET_ERROR_MSG("The maximum of expression parameters argument number is 100");
395  }
396  RCL_CHECK_ARGUMENT_FOR_NULL(options, RCL_RET_INVALID_ARGUMENT);
397  const rcl_allocator_t * allocator = &subscription->impl->options.allocator;
398  RCL_CHECK_ALLOCATOR_WITH_MSG(allocator, "invalid allocator", return RCL_RET_INVALID_ARGUMENT);
399 
400  rmw_ret_t ret = rmw_subscription_content_filter_options_set(
401  filter_expression,
402  expression_parameters_argc,
403  expression_parameter_argv,
404  allocator,
405  &options->rmw_subscription_content_filter_options
406  );
407  return rcl_convert_rmw_ret_to_rcl_ret(ret);
408 }
409 
410 rcl_ret_t
412  const rcl_subscription_t * subscription,
414 {
415  if (!rcl_subscription_is_valid(subscription)) {
417  }
418  RCL_CHECK_ARGUMENT_FOR_NULL(options, RCL_RET_INVALID_ARGUMENT);
419  const rcl_allocator_t * allocator = &subscription->impl->options.allocator;
420  RCL_CHECK_ALLOCATOR_WITH_MSG(allocator, "invalid allocator", return RCL_RET_INVALID_ARGUMENT);
421 
422  rmw_ret_t ret = rmw_subscription_content_filter_options_fini(
423  &options->rmw_subscription_content_filter_options,
424  allocator
425  );
426 
427  return rcl_convert_rmw_ret_to_rcl_ret(ret);
428 }
429 
430 bool
432 {
433  if (!rcl_subscription_is_valid(subscription)) {
434  return false;
435  }
436  return subscription->impl->rmw_handle->is_cft_enabled;
437 }
438 
439 rcl_ret_t
441  const rcl_subscription_t * subscription,
443 )
444 {
445  RCUTILS_CAN_RETURN_WITH_ERROR_OF(RCL_RET_SUBSCRIPTION_INVALID);
446  RCUTILS_CAN_RETURN_WITH_ERROR_OF(RCL_RET_INVALID_ARGUMENT);
447 
448  if (!rcl_subscription_is_valid(subscription)) {
450  }
451 
452  RCL_CHECK_ARGUMENT_FOR_NULL(options, RCL_RET_INVALID_ARGUMENT);
453  rmw_ret_t ret = rmw_subscription_set_content_filter(
454  subscription->impl->rmw_handle,
455  &options->rmw_subscription_content_filter_options);
456 
457  if (ret != RMW_RET_OK) {
458  RCL_SET_ERROR_MSG(rmw_get_error_string().str);
459  return rcl_convert_rmw_ret_to_rcl_ret(ret);
460  }
461 
462  // copy options into subscription_options
463  const rmw_subscription_content_filter_options_t * content_filter_options =
464  &options->rmw_subscription_content_filter_options;
466  content_filter_options->filter_expression,
467  content_filter_options->expression_parameters.size,
468  (const char **)content_filter_options->expression_parameters.data,
469  &subscription->impl->options
470  );
471 }
472 
473 rcl_ret_t
475  const rcl_subscription_t * subscription,
477 )
478 {
479  RCUTILS_CAN_RETURN_WITH_ERROR_OF(RCL_RET_SUBSCRIPTION_INVALID);
480  RCUTILS_CAN_RETURN_WITH_ERROR_OF(RCL_RET_INVALID_ARGUMENT);
481 
482  if (!rcl_subscription_is_valid(subscription)) {
484  }
485  RCL_CHECK_ARGUMENT_FOR_NULL(options, RCL_RET_INVALID_ARGUMENT);
486  rcl_allocator_t * allocator = &subscription->impl->options.allocator;
487  RCL_CHECK_ALLOCATOR_WITH_MSG(allocator, "invalid allocator", return RCL_RET_INVALID_ARGUMENT);
488 
489  rmw_ret_t rmw_ret = rmw_subscription_get_content_filter(
490  subscription->impl->rmw_handle,
491  allocator,
492  &options->rmw_subscription_content_filter_options);
493 
494  return rcl_convert_rmw_ret_to_rcl_ret(rmw_ret);
495 }
496 
497 rcl_ret_t
499  const rcl_subscription_t * subscription,
500  void * ros_message,
501  rmw_message_info_t * message_info,
502  rmw_subscription_allocation_t * allocation
503 )
504 {
505  RCUTILS_LOG_DEBUG_NAMED(ROS_PACKAGE_NAME, "Subscription taking message");
506  if (!rcl_subscription_is_valid(subscription)) {
507  return RCL_RET_SUBSCRIPTION_INVALID; // error message already set
508  }
509  RCL_CHECK_ARGUMENT_FOR_NULL(ros_message, RCL_RET_INVALID_ARGUMENT);
510 
511  // If message_info is NULL, use a place holder which can be discarded.
512  rmw_message_info_t dummy_message_info;
513  rmw_message_info_t * message_info_local = message_info ? message_info : &dummy_message_info;
514  *message_info_local = rmw_get_zero_initialized_message_info();
515  // Call rmw_take_with_info.
516  bool taken = false;
517  rmw_ret_t ret = rmw_take_with_info(
518  subscription->impl->rmw_handle, ros_message, &taken, message_info_local, allocation);
519  if (ret != RMW_RET_OK) {
520  RCL_SET_ERROR_MSG(rmw_get_error_string().str);
521  return rcl_convert_rmw_ret_to_rcl_ret(ret);
522  }
523  RCUTILS_LOG_DEBUG_NAMED(
524  ROS_PACKAGE_NAME, "Subscription take succeeded: %s", taken ? "true" : "false");
525  TRACEPOINT(rcl_take, (const void *)ros_message);
526  if (!taken) {
528  }
529  return RCL_RET_OK;
530 }
531 
532 rcl_ret_t
534  const rcl_subscription_t * subscription,
535  size_t count,
536  rmw_message_sequence_t * message_sequence,
537  rmw_message_info_sequence_t * message_info_sequence,
538  rmw_subscription_allocation_t * allocation
539 )
540 {
541  RCUTILS_LOG_DEBUG_NAMED(ROS_PACKAGE_NAME, "Subscription taking %zu messages", count);
542  if (!rcl_subscription_is_valid(subscription)) {
543  return RCL_RET_SUBSCRIPTION_INVALID; // error message already set
544  }
545  RCL_CHECK_ARGUMENT_FOR_NULL(message_sequence, RCL_RET_INVALID_ARGUMENT);
546  RCL_CHECK_ARGUMENT_FOR_NULL(message_info_sequence, RCL_RET_INVALID_ARGUMENT);
547 
548  if (message_sequence->capacity < count) {
549  RCL_SET_ERROR_MSG("Insufficient message sequence capacity for requested count");
551  }
552 
553  if (message_info_sequence->capacity < count) {
554  RCL_SET_ERROR_MSG("Insufficient message info sequence capacity for requested count");
556  }
557 
558  // Set the sizes to zero to indicate that there are no valid messages
559  message_sequence->size = 0u;
560  message_info_sequence->size = 0u;
561 
562  size_t taken = 0u;
563  rmw_ret_t ret = rmw_take_sequence(
564  subscription->impl->rmw_handle, count, message_sequence, message_info_sequence, &taken,
565  allocation);
566  if (ret != RMW_RET_OK) {
567  RCL_SET_ERROR_MSG(rmw_get_error_string().str);
568  return rcl_convert_rmw_ret_to_rcl_ret(ret);
569  }
570  RCUTILS_LOG_DEBUG_NAMED(
571  ROS_PACKAGE_NAME, "Subscription took %zu messages", taken);
572  if (0u == taken) {
574  }
575  return RCL_RET_OK;
576 }
577 
578 rcl_ret_t
580  const rcl_subscription_t * subscription,
581  rcl_serialized_message_t * serialized_message,
582  rmw_message_info_t * message_info,
583  rmw_subscription_allocation_t * allocation
584 )
585 {
586  RCUTILS_LOG_DEBUG_NAMED(ROS_PACKAGE_NAME, "Subscription taking serialized message");
587  if (!rcl_subscription_is_valid(subscription)) {
588  return RCL_RET_SUBSCRIPTION_INVALID; // error already set
589  }
590  RCL_CHECK_ARGUMENT_FOR_NULL(serialized_message, RCL_RET_INVALID_ARGUMENT);
591  // If message_info is NULL, use a place holder which can be discarded.
592  rmw_message_info_t dummy_message_info;
593  rmw_message_info_t * message_info_local = message_info ? message_info : &dummy_message_info;
594  *message_info_local = rmw_get_zero_initialized_message_info();
595  // Call rmw_take_with_info.
596  bool taken = false;
597  rmw_ret_t ret = rmw_take_serialized_message_with_info(
598  subscription->impl->rmw_handle, serialized_message, &taken, message_info_local, allocation);
599  if (ret != RMW_RET_OK) {
600  RCL_SET_ERROR_MSG(rmw_get_error_string().str);
601  return rcl_convert_rmw_ret_to_rcl_ret(ret);
602  }
603  RCUTILS_LOG_DEBUG_NAMED(
604  ROS_PACKAGE_NAME, "Subscription serialized take succeeded: %s", taken ? "true" : "false");
605  if (!taken) {
607  }
608  return RCL_RET_OK;
609 }
610 
611 rcl_ret_t
613  const rcl_subscription_t * subscription,
614  void ** loaned_message,
615  rmw_message_info_t * message_info,
616  rmw_subscription_allocation_t * allocation)
617 {
618  RCUTILS_LOG_DEBUG_NAMED(ROS_PACKAGE_NAME, "Subscription taking loaned message");
619  if (!rcl_subscription_is_valid(subscription)) {
620  return RCL_RET_SUBSCRIPTION_INVALID; // error already set
621  }
622  RCL_CHECK_ARGUMENT_FOR_NULL(loaned_message, RCL_RET_INVALID_ARGUMENT);
623  if (*loaned_message) {
624  RCL_SET_ERROR_MSG("loaned message is already initialized");
626  }
627  // If message_info is NULL, use a place holder which can be discarded.
628  rmw_message_info_t dummy_message_info;
629  rmw_message_info_t * message_info_local = message_info ? message_info : &dummy_message_info;
630  *message_info_local = rmw_get_zero_initialized_message_info();
631  // Call rmw_take_with_info.
632  bool taken = false;
633  rmw_ret_t ret = rmw_take_loaned_message_with_info(
634  subscription->impl->rmw_handle, loaned_message, &taken, message_info_local, allocation);
635  if (ret != RMW_RET_OK) {
636  RCL_SET_ERROR_MSG(rmw_get_error_string().str);
637  return rcl_convert_rmw_ret_to_rcl_ret(ret);
638  }
639  RCUTILS_LOG_DEBUG_NAMED(
640  ROS_PACKAGE_NAME, "Subscription loaned take succeeded: %s", taken ? "true" : "false");
641  if (!taken) {
643  }
644  return RCL_RET_OK;
645 }
646 
647 rcl_ret_t
649  const rcl_subscription_t * subscription,
650  void * loaned_message)
651 {
652  RCUTILS_LOG_DEBUG_NAMED(ROS_PACKAGE_NAME, "Subscription releasing loaned message");
653  if (!rcl_subscription_is_valid(subscription)) {
654  return RCL_RET_SUBSCRIPTION_INVALID; // error already set
655  }
656  RCL_CHECK_ARGUMENT_FOR_NULL(loaned_message, RCL_RET_INVALID_ARGUMENT);
657  return rcl_convert_rmw_ret_to_rcl_ret(
658  rmw_return_loaned_message_from_subscription(
659  subscription->impl->rmw_handle, loaned_message));
660 }
661 
662 const char *
664 {
665  if (!rcl_subscription_is_valid(subscription)) {
666  return NULL; // error already set
667  }
668  return subscription->impl->rmw_handle->topic_name;
669 }
670 
671 #define _subscription_get_options(subscription) & subscription->impl->options
672 
675 {
676  if (!rcl_subscription_is_valid(subscription)) {
677  return NULL; // error already set
678  }
679  return _subscription_get_options(subscription);
680 }
681 
682 rmw_subscription_t *
684 {
685  if (!rcl_subscription_is_valid(subscription)) {
686  return NULL; // error already set
687  }
688  return subscription->impl->rmw_handle;
689 }
690 
691 bool
693 {
694  RCL_CHECK_FOR_NULL_WITH_MSG(subscription, "subscription pointer is invalid", return false);
695  RCL_CHECK_FOR_NULL_WITH_MSG(
696  subscription->impl, "subscription's implementation is invalid", return false);
697  RCL_CHECK_FOR_NULL_WITH_MSG(
698  subscription->impl->rmw_handle, "subscription's rmw handle is invalid", return false);
699  return true;
700 }
701 
702 rmw_ret_t
704  const rcl_subscription_t * subscription,
705  size_t * publisher_count)
706 {
707  RCUTILS_CAN_RETURN_WITH_ERROR_OF(RCL_RET_SUBSCRIPTION_INVALID);
708  RCUTILS_CAN_RETURN_WITH_ERROR_OF(RCL_RET_INVALID_ARGUMENT);
709 
710  if (!rcl_subscription_is_valid(subscription)) {
712  }
713  RCL_CHECK_ARGUMENT_FOR_NULL(publisher_count, RCL_RET_INVALID_ARGUMENT);
714  rmw_ret_t ret = rmw_subscription_count_matched_publishers(
715  subscription->impl->rmw_handle, publisher_count);
716 
717  if (ret != RMW_RET_OK) {
718  RCL_SET_ERROR_MSG(rmw_get_error_string().str);
719  return rcl_convert_rmw_ret_to_rcl_ret(ret);
720  }
721  return RCL_RET_OK;
722 }
723 
724 const rmw_qos_profile_t *
726 {
727  if (!rcl_subscription_is_valid(subscription)) {
728  return NULL;
729  }
730  return &subscription->impl->actual_qos;
731 }
732 
733 bool
735 {
736  if (!rcl_subscription_is_valid(subscription)) {
737  return false; // error message already set
738  }
739 
740  // Load disable flag to LoanedMessage via environmental variable.
741  // TODO(clalancette): This is kind of a copy of rcl_get_disable_loaned_message(), but we need
742  // more information than that function provides.
743  bool disable_loaned_message = true;
744 
745  const char * env_val = NULL;
746  const char * env_error_str = rcutils_get_env(RCL_DISABLE_LOANED_MESSAGES_ENV_VAR, &env_val);
747  if (NULL != env_error_str) {
748  RCUTILS_SAFE_FWRITE_TO_STDERR("Failed to get disable_loaned_message: ");
749  RCUTILS_SAFE_FWRITE_TO_STDERR_WITH_FORMAT_STRING(
750  "Error getting env var: '" RCUTILS_STRINGIFY(RCL_DISABLE_LOANED_MESSAGES_ENV_VAR) "': %s\n",
751  env_error_str);
752  return RCL_RET_ERROR;
753  } else {
754  disable_loaned_message = !(strcmp(env_val, "0") == 0);
755  }
756 
757  if (disable_loaned_message) {
758  return false;
759  }
760 
761  return subscription->impl->rmw_handle->can_loan_messages;
762 }
763 
764 rcl_ret_t
766  const rcl_subscription_t * subscription,
767  rcl_event_callback_t callback,
768  const void * user_data)
769 {
770  if (!rcl_subscription_is_valid(subscription)) {
771  // error state already set
773  }
774 
775  return rmw_subscription_set_on_new_message_callback(
776  subscription->impl->rmw_handle,
777  callback,
778  user_data);
779 }
780 
781 #ifdef __cplusplus
782 }
783 #endif
#define rcl_get_default_allocator
Return a properly initialized rcl_allocator_t with default values.
Definition: allocator.h:37
#define RCL_CHECK_ALLOCATOR_WITH_MSG(allocator, msg, fail_statement)
Check that the given allocator is initialized, or fail with a message.
Definition: allocator.h:56
rcutils_allocator_t rcl_allocator_t
Encapsulation of an allocator.
Definition: allocator.h:31
RCL_PUBLIC bool rcl_node_is_valid(const rcl_node_t *node)
Return true if the node is valid, else false.
Definition: node.c:421
RCL_PUBLIC RCL_WARN_UNUSED rmw_node_t * rcl_node_get_rmw_handle(const rcl_node_t *node)
Return the rmw node handle.
Definition: node.c:485
RCL_PUBLIC RCL_WARN_UNUSED rcl_ret_t rcl_node_resolve_name(const rcl_node_t *node, const char *input_name, rcl_allocator_t allocator, bool is_service, bool only_expand, char **output_name)
Expand a given name into a fully-qualified topic name and apply remapping rules.
RCL_PUBLIC bool rcl_node_is_valid_except_context(const rcl_node_t *node)
Return true if node is valid, except for the context being valid.
Definition: node.c:411
Structure which encapsulates a ROS Node.
Definition: node.h:42
Options available for a rcl subscription.
Definition: subscription.h:46
rcl_allocator_t allocator
Custom allocator for the subscription, used for incidental allocations.
Definition: subscription.h:51
rmw_qos_profile_t qos
Middleware quality of service settings for the subscription.
Definition: subscription.h:48
rmw_subscription_options_t rmw_subscription_options
rmw specific subscription options, e.g. the rmw implementation specific payload.
Definition: subscription.h:53
Structure which encapsulates a ROS Subscription.
Definition: subscription.h:39
rcl_subscription_impl_t * impl
Pointer to the subscription implementation.
Definition: subscription.h:41
RCL_PUBLIC RCL_WARN_UNUSED rcl_subscription_options_t rcl_subscription_get_default_options(void)
Return the default subscription options in a rcl_subscription_options_t.
Definition: subscription.c:202
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_options_fini(rcl_subscription_options_t *option)
Reclaim resources held inside rcl_subscription_options_t structure.
Definition: subscription.c:214
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 rcl_ret_t rcl_take_sequence(const rcl_subscription_t *subscription, size_t count, rmw_message_sequence_t *message_sequence, rmw_message_info_sequence_t *message_info_sequence, rmw_subscription_allocation_t *allocation)
Take a sequence of messages from a topic using a rcl subscription.
Definition: subscription.c:533
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 rmw_subscription_t * rcl_subscription_get_rmw_handle(const rcl_subscription_t *subscription)
Return the rmw subscription handle.
Definition: subscription.c:683
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_subscription_options_set_content_filter_options(const char *filter_expression, size_t expression_parameters_argc, const char *expression_parameter_argv[], rcl_subscription_options_t *options)
Set the content filter options for the given subscription options.
Definition: subscription.c:236
RCL_PUBLIC bool rcl_subscription_is_valid(const rcl_subscription_t *subscription)
Check that the subscription is valid.
Definition: subscription.c:692
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_ret_t rcl_take_loaned_message(const rcl_subscription_t *subscription, void **loaned_message, rmw_message_info_t *message_info, rmw_subscription_allocation_t *allocation)
Take a loaned message from a topic using a rcl subscription.
Definition: subscription.c:612
RCL_PUBLIC RCL_WARN_UNUSED rcl_ret_t rcl_subscription_content_filter_options_set(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)
Set the content filter options for the given subscription options.
Definition: subscription.c:382
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
RCL_PUBLIC RCL_WARN_UNUSED rcl_ret_t rcl_return_loaned_message_from_subscription(const rcl_subscription_t *subscription, void *loaned_message)
Return a loaned message from a topic using a rcl subscription.
Definition: subscription.c:648
RCL_PUBLIC RCL_WARN_UNUSED const rcl_subscription_options_t * rcl_subscription_get_options(const rcl_subscription_t *subscription)
Return the rcl subscription options.
Definition: subscription.c:674
#define RCL_RET_UNKNOWN_SUBSTITUTION
Topic name substitution is unknown.
Definition: types.h:50
#define RCL_RET_ALREADY_INIT
rcl_init() already called return code.
Definition: types.h:40
#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_BAD_ALLOC
Failed to allocate memory return code.
Definition: types.h:32
#define RCL_RET_INVALID_ARGUMENT
Invalid argument return code.
Definition: types.h:34
#define RCL_RET_ERROR
Unspecified error return code.
Definition: types.h:28
rmw_serialized_message_t rcl_serialized_message_t
typedef for rmw_serialized_message_t;
Definition: types.h:127
#define RCL_RET_NODE_INVALID
Invalid rcl_node_t given return code.
Definition: types.h:56
#define RCL_RET_TOPIC_NAME_INVALID
Topic name does not pass validation.
Definition: types.h:46
#define RCL_RET_SUBSCRIPTION_INVALID
Invalid rcl_subscription_t given return code.
Definition: types.h:70
rmw_ret_t rcl_ret_t
The type that holds an rcl return code.
Definition: types.h:23