24 #include "rcl/error_handling.h"
26 #include "rcl/node_type_cache.h"
27 #include "rcutils/env.h"
28 #include "rcutils/logging_macros.h"
29 #include "rcutils/strdup.h"
30 #include "rcutils/types/string_array.h"
31 #include "rmw/error_handling.h"
32 #include "rmw/dynamic_message_type_support.h"
33 #include "rmw/subscription_content_filter_options.h"
34 #include "rmw/validate_full_topic_name.h"
35 #include "rosidl_dynamic_typesupport/identifier.h"
36 #include "tracetools/tracetools.h"
39 #include "./subscription_impl.h"
47 return null_subscription;
54 const rosidl_message_type_support_t * type_support,
55 const char * topic_name,
71 RCUTILS_LOG_DEBUG_NAMED(
72 ROS_PACKAGE_NAME,
"Initializing subscription for topic name '%s'", topic_name);
73 if (subscription->
impl) {
74 RCL_SET_ERROR_MSG(
"subscription already initialized, or memory was uninitialized");
79 char * remapped_topic_name = NULL;
86 &remapped_topic_name);
95 RCUTILS_LOG_DEBUG_NAMED(
96 ROS_PACKAGE_NAME,
"Expanded and remapped topic name '%s'", remapped_topic_name);
101 RCL_CHECK_FOR_NULL_WITH_MSG(
105 subscription->
impl->options = *options;
109 subscription->
impl->rmw_handle = rmw_create_subscription(
115 if (!subscription->
impl->rmw_handle) {
116 RCL_SET_ERROR_MSG(rmw_get_error_string().str);
120 rmw_ret_t rmw_ret = rmw_subscription_get_actual_qos(
121 subscription->
impl->rmw_handle,
122 &subscription->
impl->actual_qos);
123 if (RMW_RET_OK != rmw_ret) {
124 RCL_SET_ERROR_MSG(rmw_get_error_string().str);
127 subscription->
impl->actual_qos.avoid_ros_namespace_conventions =
128 options->
qos.avoid_ros_namespace_conventions;
130 if (
RCL_RET_OK != rcl_node_type_cache_register_type(
131 node, type_support->get_type_hash_func(type_support),
132 type_support->get_type_description_func(type_support),
133 type_support->get_type_description_sources_func(type_support)))
135 rcutils_reset_error();
136 RCL_SET_ERROR_MSG(
"Failed to register type for subscription");
139 subscription->
impl->type_hash = *type_support->get_type_hash_func(type_support);
141 RCUTILS_LOG_DEBUG_NAMED(ROS_PACKAGE_NAME,
"Subscription initialized");
143 TRACETOOLS_TRACEPOINT(
145 (
const void *)subscription,
147 (
const void *)subscription->
impl->rmw_handle,
153 if (subscription->
impl) {
154 if (subscription->
impl->rmw_handle) {
155 rmw_ret_t rmw_fail_ret = rmw_destroy_subscription(
157 if (RMW_RET_OK != rmw_fail_ret) {
158 RCUTILS_SAFE_FWRITE_TO_STDERR(rmw_get_error_string().str);
159 RCUTILS_SAFE_FWRITE_TO_STDERR(
"\n");
165 RCUTILS_SAFE_FWRITE_TO_STDERR(rmw_get_error_string().str);
166 RCUTILS_SAFE_FWRITE_TO_STDERR(
"\n");
169 allocator->deallocate(subscription->
impl, allocator->state);
170 subscription->
impl = NULL;
175 allocator->deallocate(remapped_topic_name, allocator->state);
187 RCUTILS_LOG_DEBUG_NAMED(ROS_PACKAGE_NAME,
"Finalizing subscription");
193 if (subscription->
impl) {
200 rmw_destroy_subscription(rmw_node, subscription->
impl->rmw_handle);
201 if (ret != RMW_RET_OK) {
202 RCL_SET_ERROR_MSG(rmw_get_error_string().str);
207 RCUTILS_SAFE_FWRITE_TO_STDERR(rcl_get_error_string().str);
208 RCUTILS_SAFE_FWRITE_TO_STDERR(
"\n");
213 ROSIDL_TYPE_HASH_VERSION_UNSET != subscription->
impl->type_hash.version &&
214 RCL_RET_OK != rcl_node_type_cache_unregister_type(node, &subscription->
impl->type_hash))
216 RCUTILS_SAFE_FWRITE_TO_STDERR(rcl_get_error_string().str);
217 RCUTILS_SAFE_FWRITE_TO_STDERR(
"\n");
221 allocator.deallocate(subscription->
impl, allocator.state);
222 subscription->
impl = NULL;
224 RCUTILS_LOG_DEBUG_NAMED(ROS_PACKAGE_NAME,
"Subscription finalized");
234 default_options.
qos = rmw_qos_profile_default;
243 const char * env_val = NULL;
244 const char * env_error_str = rcutils_get_env(RCL_DISABLE_LOANED_MESSAGES_ENV_VAR, &env_val);
245 if (NULL != env_error_str) {
246 RCUTILS_SAFE_FWRITE_TO_STDERR(
"Failed to get disable_loaned_message: ");
247 RCUTILS_SAFE_FWRITE_TO_STDERR_WITH_FORMAT_STRING(
248 "Error getting env var: '" RCUTILS_STRINGIFY(RCL_DISABLE_LOANED_MESSAGES_ENV_VAR)
"': %s\n",
254 return default_options;
266 rmw_ret_t ret = rmw_subscription_content_filter_options_fini(
268 if (RCUTILS_RET_OK != ret) {
269 RCUTILS_SAFE_FWRITE_TO_STDERR(
"Failed to fini content filter options.\n");
270 return rcl_convert_rmw_ret_to_rcl_ret(ret);
272 allocator->deallocate(
281 const char * filter_expression,
282 size_t expression_parameters_argc,
283 const char * expression_parameter_argv[],
287 if (expression_parameters_argc > 100) {
288 RCL_SET_ERROR_MSG(
"The maximum of expression parameters argument number is 100");
297 rmw_subscription_content_filter_options_t * original_content_filter_options =
299 rmw_subscription_content_filter_options_t content_filter_options_backup =
300 rmw_get_zero_initialized_content_filter_options();
302 if (original_content_filter_options) {
304 rmw_ret = rmw_subscription_content_filter_options_copy(
305 original_content_filter_options,
307 &content_filter_options_backup
309 if (rmw_ret != RMW_RET_OK) {
310 return rcl_convert_rmw_ret_to_rcl_ret(rmw_ret);
315 sizeof(rmw_subscription_content_filter_options_t), allocator->state);
317 RCL_SET_ERROR_MSG(
"failed to allocate memory");
321 rmw_get_zero_initialized_content_filter_options();
324 rmw_ret = rmw_subscription_content_filter_options_set(
326 expression_parameters_argc,
327 expression_parameter_argv,
332 if (rmw_ret != RMW_RET_OK) {
333 ret = rcl_convert_rmw_ret_to_rcl_ret(rmw_ret);
337 rmw_ret = rmw_subscription_content_filter_options_fini(
338 &content_filter_options_backup,
341 if (rmw_ret != RMW_RET_OK) {
342 return rcl_convert_rmw_ret_to_rcl_ret(rmw_ret);
349 if (original_content_filter_options == NULL) {
351 rmw_ret = rmw_subscription_content_filter_options_fini(
356 if (rmw_ret != RMW_RET_OK) {
357 return rcl_convert_rmw_ret_to_rcl_ret(rmw_ret);
360 allocator->deallocate(
365 rmw_ret = rmw_subscription_content_filter_options_copy(
366 &content_filter_options_backup,
370 if (rmw_ret != RMW_RET_OK) {
371 return rcl_convert_rmw_ret_to_rcl_ret(rmw_ret);
374 rmw_ret = rmw_subscription_content_filter_options_fini(
375 &content_filter_options_backup,
378 if (rmw_ret != RMW_RET_OK) {
379 return rcl_convert_rmw_ret_to_rcl_ret(rmw_ret);
390 .rmw_subscription_content_filter_options =
391 rmw_get_zero_initialized_content_filter_options()
398 const char * filter_expression,
399 size_t expression_parameters_argc,
400 const char * expression_parameter_argv[],
409 if (expression_parameters_argc > 100) {
410 RCL_SET_ERROR_MSG(
"The maximum of expression parameters argument number is 100");
414 rmw_ret_t rmw_ret = rmw_subscription_content_filter_options_init(
416 expression_parameters_argc,
417 expression_parameter_argv,
419 &options->rmw_subscription_content_filter_options
422 return rcl_convert_rmw_ret_to_rcl_ret(rmw_ret);
428 const char * filter_expression,
429 size_t expression_parameters_argc,
430 const char * expression_parameter_argv[],
436 if (expression_parameters_argc > 100) {
437 RCL_SET_ERROR_MSG(
"The maximum of expression parameters argument number is 100");
444 rmw_ret_t ret = rmw_subscription_content_filter_options_set(
446 expression_parameters_argc,
447 expression_parameter_argv,
449 &options->rmw_subscription_content_filter_options
451 return rcl_convert_rmw_ret_to_rcl_ret(ret);
466 rmw_ret_t ret = rmw_subscription_content_filter_options_fini(
467 &options->rmw_subscription_content_filter_options,
471 return rcl_convert_rmw_ret_to_rcl_ret(ret);
480 return subscription->
impl->rmw_handle->is_cft_enabled;
497 rmw_ret_t ret = rmw_subscription_set_content_filter(
498 subscription->
impl->rmw_handle,
499 &options->rmw_subscription_content_filter_options);
501 if (ret != RMW_RET_OK) {
502 RCL_SET_ERROR_MSG(rmw_get_error_string().str);
503 return rcl_convert_rmw_ret_to_rcl_ret(ret);
507 const rmw_subscription_content_filter_options_t * content_filter_options =
508 &options->rmw_subscription_content_filter_options;
510 content_filter_options->filter_expression,
511 content_filter_options->expression_parameters.size,
512 (
const char **)content_filter_options->expression_parameters.data,
513 &subscription->
impl->options
533 rmw_ret_t rmw_ret = rmw_subscription_get_content_filter(
534 subscription->
impl->rmw_handle,
536 &options->rmw_subscription_content_filter_options);
538 return rcl_convert_rmw_ret_to_rcl_ret(rmw_ret);
545 rmw_message_info_t * message_info,
546 rmw_subscription_allocation_t * allocation
549 RCUTILS_LOG_DEBUG_NAMED(ROS_PACKAGE_NAME,
"Subscription taking message");
556 rmw_message_info_t dummy_message_info;
557 rmw_message_info_t * message_info_local = message_info ? message_info : &dummy_message_info;
558 *message_info_local = rmw_get_zero_initialized_message_info();
561 rmw_ret_t ret = rmw_take_with_info(
562 subscription->
impl->rmw_handle, ros_message, &taken, message_info_local, allocation);
563 if (ret != RMW_RET_OK) {
564 RCL_SET_ERROR_MSG(rmw_get_error_string().str);
565 return rcl_convert_rmw_ret_to_rcl_ret(ret);
567 RCUTILS_LOG_DEBUG_NAMED(
568 ROS_PACKAGE_NAME,
"Subscription take succeeded: %s", taken ?
"true" :
"false");
569 TRACETOOLS_TRACEPOINT(
rcl_take, (
const void *)ros_message);
580 rmw_message_sequence_t * message_sequence,
581 rmw_message_info_sequence_t * message_info_sequence,
582 rmw_subscription_allocation_t * allocation
585 RCUTILS_LOG_DEBUG_NAMED(ROS_PACKAGE_NAME,
"Subscription taking %zu messages", count);
592 if (message_sequence->capacity < count) {
593 RCL_SET_ERROR_MSG(
"Insufficient message sequence capacity for requested count");
597 if (message_info_sequence->capacity < count) {
598 RCL_SET_ERROR_MSG(
"Insufficient message info sequence capacity for requested count");
603 message_sequence->size = 0u;
604 message_info_sequence->size = 0u;
607 rmw_ret_t ret = rmw_take_sequence(
608 subscription->
impl->rmw_handle, count, message_sequence, message_info_sequence, &taken,
610 if (ret != RMW_RET_OK) {
611 RCL_SET_ERROR_MSG(rmw_get_error_string().str);
612 return rcl_convert_rmw_ret_to_rcl_ret(ret);
614 RCUTILS_LOG_DEBUG_NAMED(
615 ROS_PACKAGE_NAME,
"Subscription took %zu messages", taken);
626 rmw_message_info_t * message_info,
627 rmw_subscription_allocation_t * allocation
630 RCUTILS_LOG_DEBUG_NAMED(ROS_PACKAGE_NAME,
"Subscription taking serialized message");
636 rmw_message_info_t dummy_message_info;
637 rmw_message_info_t * message_info_local = message_info ? message_info : &dummy_message_info;
638 *message_info_local = rmw_get_zero_initialized_message_info();
641 rmw_ret_t ret = rmw_take_serialized_message_with_info(
642 subscription->
impl->rmw_handle, serialized_message, &taken, message_info_local, allocation);
643 if (ret != RMW_RET_OK) {
644 RCL_SET_ERROR_MSG(rmw_get_error_string().str);
645 return rcl_convert_rmw_ret_to_rcl_ret(ret);
647 RCUTILS_LOG_DEBUG_NAMED(
648 ROS_PACKAGE_NAME,
"Subscription serialized take succeeded: %s", taken ?
"true" :
"false");
649 TRACETOOLS_TRACEPOINT(
rcl_take, (
const void *)serialized_message);
659 rosidl_dynamic_typesupport_dynamic_data_t * dynamic_message,
660 rmw_message_info_t * message_info,
661 rmw_subscription_allocation_t * allocation)
663 RCUTILS_LOG_DEBUG_NAMED(ROS_PACKAGE_NAME,
"Subscription taking dynamic message");
669 rmw_message_info_t dummy_message_info;
670 rmw_message_info_t * message_info_local = message_info ? message_info : &dummy_message_info;
671 *message_info_local = rmw_get_zero_initialized_message_info();
674 rmw_ret_t ret = rmw_take_dynamic_message_with_info(
675 subscription->
impl->rmw_handle, dynamic_message, &taken, message_info_local, allocation);
676 if (ret != RMW_RET_OK) {
677 RCL_SET_ERROR_MSG(rmw_get_error_string().str);
678 return rcl_convert_rmw_ret_to_rcl_ret(ret);
680 RCUTILS_LOG_DEBUG_NAMED(
681 ROS_PACKAGE_NAME,
"Subscription dynamic take succeeded: %s", taken ?
"true" :
"false");
691 void ** loaned_message,
692 rmw_message_info_t * message_info,
693 rmw_subscription_allocation_t * allocation)
695 RCUTILS_LOG_DEBUG_NAMED(ROS_PACKAGE_NAME,
"Subscription taking loaned message");
700 if (*loaned_message) {
701 RCL_SET_ERROR_MSG(
"loaned message is already initialized");
705 rmw_message_info_t dummy_message_info;
706 rmw_message_info_t * message_info_local = message_info ? message_info : &dummy_message_info;
707 *message_info_local = rmw_get_zero_initialized_message_info();
710 rmw_ret_t ret = rmw_take_loaned_message_with_info(
711 subscription->
impl->rmw_handle, loaned_message, &taken, message_info_local, allocation);
712 if (ret != RMW_RET_OK) {
713 RCL_SET_ERROR_MSG(rmw_get_error_string().str);
714 return rcl_convert_rmw_ret_to_rcl_ret(ret);
716 RCUTILS_LOG_DEBUG_NAMED(
717 ROS_PACKAGE_NAME,
"Subscription loaned take succeeded: %s", taken ?
"true" :
"false");
727 void * loaned_message)
729 RCUTILS_LOG_DEBUG_NAMED(ROS_PACKAGE_NAME,
"Subscription releasing loaned message");
734 return rcl_convert_rmw_ret_to_rcl_ret(
735 rmw_return_loaned_message_from_subscription(
736 subscription->
impl->rmw_handle, loaned_message));
745 return subscription->
impl->rmw_handle->topic_name;
754 return &subscription->
impl->options;
763 return subscription->
impl->rmw_handle;
769 RCL_CHECK_FOR_NULL_WITH_MSG(subscription,
"subscription pointer is invalid",
return false);
770 RCL_CHECK_FOR_NULL_WITH_MSG(
771 subscription->
impl,
"subscription's implementation is invalid",
return false);
772 RCL_CHECK_FOR_NULL_WITH_MSG(
773 subscription->
impl->rmw_handle,
"subscription's rmw handle is invalid",
return false);
780 size_t * publisher_count)
789 rmw_ret_t ret = rmw_subscription_count_matched_publishers(
790 subscription->
impl->rmw_handle, publisher_count);
792 if (ret != RMW_RET_OK) {
793 RCL_SET_ERROR_MSG(rmw_get_error_string().str);
794 return rcl_convert_rmw_ret_to_rcl_ret(ret);
799 const rmw_qos_profile_t *
805 return &subscription->
impl->actual_qos;
819 return subscription->
impl->rmw_handle->can_loan_messages;
825 rcl_event_callback_t callback,
826 const void * user_data)
833 return rmw_subscription_set_on_new_message_callback(
834 subscription->
impl->rmw_handle,
#define rcl_get_default_allocator
Return a properly initialized rcl_allocator_t with default values.
#define RCL_CHECK_ALLOCATOR_WITH_MSG(allocator, msg, fail_statement)
Check that the given allocator is initialized, or fail with a message.
rcutils_allocator_t rcl_allocator_t
Encapsulation of an allocator.
RCL_PUBLIC bool rcl_node_is_valid(const rcl_node_t *node)
Return true if the node is valid, else false.
RCL_PUBLIC RCL_WARN_UNUSED rmw_node_t * rcl_node_get_rmw_handle(const rcl_node_t *node)
Return the rmw node handle.
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.
Structure which encapsulates a ROS Node.
Options available for a rcl subscription.
rcl_allocator_t allocator
Custom allocator for the subscription, used for incidental allocations.
rmw_qos_profile_t qos
Middleware quality of service settings for the subscription.
rmw_subscription_options_t rmw_subscription_options
rmw specific subscription options, e.g. the rmw implementation specific payload.
bool disable_loaned_message
Disable flag to LoanedMessage, initialized via environmental variable.
Structure which encapsulates a ROS Subscription.
rcl_subscription_impl_t * impl
Pointer to the subscription implementation.
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.
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.
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.
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.
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.
RCL_PUBLIC RCL_WARN_UNUSED const char * rcl_subscription_get_topic_name(const rcl_subscription_t *subscription)
Get the topic name for the subscription.
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.
RCL_PUBLIC bool rcl_subscription_can_loan_messages(const rcl_subscription_t *subscription)
Check if subscription instance can loan messages.
RCL_PUBLIC RCL_WARN_UNUSED rmw_subscription_t * rcl_subscription_get_rmw_handle(const rcl_subscription_t *subscription)
Return the rmw subscription handle.
RCL_PUBLIC RCL_WARN_UNUSED rcl_ret_t rcl_subscription_fini(rcl_subscription_t *subscription, rcl_node_t *node)
Finalize a rcl_subscription_t.
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.
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.
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.
RCL_PUBLIC bool rcl_subscription_is_valid(const rcl_subscription_t *subscription)
Check that the subscription is valid.
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.
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.
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.
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.
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.
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.
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.
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.
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.
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.
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.
RCL_PUBLIC RCL_WARN_UNUSED rcl_ret_t rcl_take_dynamic_message(const rcl_subscription_t *subscription, rosidl_dynamic_typesupport_dynamic_data_t *dynamic_message, rmw_message_info_t *message_info, rmw_subscription_allocation_t *allocation)
Take a dynamic type message from a topic using a rcl subscription.
RCL_PUBLIC RCL_WARN_UNUSED const rcl_subscription_options_t * rcl_subscription_get_options(const rcl_subscription_t *subscription)
Return the rcl subscription options.
#define RCL_RET_UNKNOWN_SUBSTITUTION
Topic name substitution is unknown.
#define RCL_RET_ALREADY_INIT
rcl_init() already called return code.
#define RCL_RET_SUBSCRIPTION_TAKE_FAILED
Failed to take a message from the subscription return code.
#define RCL_RET_OK
Success return code.
#define RCL_RET_BAD_ALLOC
Failed to allocate memory return code.
#define RCL_RET_INVALID_ARGUMENT
Invalid argument return code.
#define RCL_RET_ERROR
Unspecified error return code.
rmw_serialized_message_t rcl_serialized_message_t
typedef for rmw_serialized_message_t;
#define RCL_RET_NODE_INVALID
Invalid rcl_node_t given return code.
#define RCL_RET_TOPIC_NAME_INVALID
Topic name does not pass validation.
#define RCL_RET_SUBSCRIPTION_INVALID
Invalid rcl_subscription_t given return code.
rmw_ret_t rcl_ret_t
The type that holds an rcl return code.