15 #include "rclcpp/subscription_base.hpp"
20 #include <unordered_map>
23 #include "rcpputils/scope_exit.hpp"
25 #include "rclcpp/dynamic_typesupport/dynamic_message.hpp"
26 #include "rclcpp/exceptions.hpp"
27 #include "rclcpp/expand_topic_or_service_name.hpp"
28 #include "rclcpp/experimental/intra_process_manager.hpp"
29 #include "rclcpp/logging.hpp"
30 #include "rclcpp/node_interfaces/node_base_interface.hpp"
31 #include "rclcpp/event_handler.hpp"
33 #include "rmw/error_handling.h"
36 #include "rosidl_dynamic_typesupport/types.h"
40 SubscriptionBase::SubscriptionBase(
42 const rosidl_message_type_support_t & type_support_handle,
43 const std::string & topic_name,
46 bool use_default_callbacks,
48 : node_base_(node_base),
49 node_handle_(node_base_->get_shared_rcl_node_handle()),
51 use_intra_process_(false),
52 intra_process_subscription_id_(0),
53 event_callbacks_(event_callbacks),
54 type_support_(type_support_handle),
55 delivered_message_kind_(delivered_message_kind)
57 auto custom_deletor = [node_handle = this->node_handle_](
rcl_subscription_t * rcl_subs)
62 "Error in destruction of rcl subscription handle: %s",
63 rcl_get_error_string().str);
69 subscription_handle_ = std::shared_ptr<rcl_subscription_t>(
74 subscription_handle_.get(),
78 &subscription_options);
81 auto rcl_node_handle = node_handle_.get();
89 rclcpp::exceptions::throw_from_rcl_error(ret,
"could not create subscription");
97 if (!use_intra_process_) {
100 auto ipm = weak_ipm_.lock();
105 "Intra process manager died before than a subscription.");
108 ipm->remove_subscription(intra_process_subscription_id_);
115 if (event_callbacks.deadline_callback) {
116 this->add_event_handler(
117 event_callbacks.deadline_callback,
118 RCL_SUBSCRIPTION_REQUESTED_DEADLINE_MISSED);
121 if (event_callbacks.liveliness_callback) {
122 this->add_event_handler(
123 event_callbacks.liveliness_callback,
124 RCL_SUBSCRIPTION_LIVELINESS_CHANGED);
127 QOSRequestedIncompatibleQoSCallbackType incompatible_qos_cb;
128 if (event_callbacks.incompatible_qos_callback) {
129 incompatible_qos_cb = event_callbacks.incompatible_qos_callback;
130 }
else if (use_default_callbacks) {
132 incompatible_qos_cb = [
this](QOSRequestedIncompatibleQoSInfo & info) {
133 this->default_incompatible_qos_callback(info);
138 if (incompatible_qos_cb) {
139 this->add_event_handler(incompatible_qos_cb, RCL_SUBSCRIPTION_REQUESTED_INCOMPATIBLE_QOS);
145 IncompatibleTypeCallbackType incompatible_type_cb;
146 if (event_callbacks.incompatible_type_callback) {
147 incompatible_type_cb = event_callbacks.incompatible_type_callback;
148 }
else if (use_default_callbacks) {
150 incompatible_type_cb = [
this](IncompatibleTypeInfo & info) {
151 this->default_incompatible_type_callback(info);
155 if (incompatible_type_cb) {
156 this->add_event_handler(incompatible_type_cb, RCL_SUBSCRIPTION_INCOMPATIBLE_TYPE);
162 if (event_callbacks.message_lost_callback) {
163 this->add_event_handler(
164 event_callbacks.message_lost_callback,
165 RCL_SUBSCRIPTION_MESSAGE_LOST);
167 if (event_callbacks.matched_callback) {
168 this->add_event_handler(
169 event_callbacks.matched_callback,
170 RCL_SUBSCRIPTION_MATCHED);
180 std::shared_ptr<rcl_subscription_t>
181 SubscriptionBase::get_subscription_handle()
183 return subscription_handle_;
186 std::shared_ptr<const rcl_subscription_t>
187 SubscriptionBase::get_subscription_handle()
const
189 return subscription_handle_;
193 std::unordered_map<rcl_subscription_event_type_t, std::shared_ptr<rclcpp::EventHandlerBase>> &
196 return event_handlers_;
204 auto msg = std::string(
"failed to get qos settings: ") + rcl_get_error_string().str;
206 throw std::runtime_error(msg);
216 this->get_subscription_handle().get(),
221 TRACETOOLS_TRACEPOINT(rclcpp_take,
static_cast<const void *
>(message_out));
225 rclcpp::exceptions::throw_from_rcl_error(ret);
243 this->get_subscription_handle().get(),
247 TRACETOOLS_TRACEPOINT(
253 rclcpp::exceptions::throw_from_rcl_error(ret);
258 const rosidl_message_type_support_t &
259 SubscriptionBase::get_message_type_support_handle()
const
261 return type_support_;
267 return delivered_message_kind_ == rclcpp::DeliveredMessageKind::SERIALIZED_MESSAGE;
273 return delivered_message_kind_;
279 size_t inter_process_publisher_count = 0;
282 subscription_handle_.get(),
283 &inter_process_publisher_count);
286 rclcpp::exceptions::throw_from_rcl_error(status,
"failed to get get publisher count");
288 return inter_process_publisher_count;
293 uint64_t intra_process_subscription_id,
294 IntraProcessManagerWeakPtr weak_ipm)
296 intra_process_subscription_id_ = intra_process_subscription_id;
297 weak_ipm_ = weak_ipm;
298 use_intra_process_ =
true;
313 "Loaned messages are only safe with const ref subscription callbacks. "
314 "If you are using any other kind of subscriptions, "
315 "set the ROS_DISABLE_LOANED_MESSAGES environment variable to 1 (the default).");
320 rclcpp::Waitable::SharedPtr
324 if (!use_intra_process_) {
328 auto ipm = weak_ipm_.lock();
330 throw std::runtime_error(
331 "SubscriptionBase::get_intra_process_waitable() called "
332 "after destruction of intra process manager");
336 return ipm->get_subscription_intra_process(intra_process_subscription_id_);
340 SubscriptionBase::default_incompatible_qos_callback(
341 rclcpp::QOSRequestedIncompatibleQoSInfo & event)
const
343 std::string policy_name = qos_policy_name_from_kind(event.last_policy_kind);
346 "New publisher discovered on topic '%s', offering incompatible QoS. "
347 "No messages will be sent to it. "
348 "Last incompatible policy: %s",
350 policy_name.c_str());
354 SubscriptionBase::default_incompatible_type_callback(
355 rclcpp::IncompatibleTypeInfo & event)
const
361 "Incompatible type on topic '%s', no messages will be sent to it.",
get_topic_name());
365 SubscriptionBase::matches_any_intra_process_publishers(
const rmw_gid_t * sender_gid)
const
367 if (!use_intra_process_) {
370 auto ipm = weak_ipm_.lock();
372 throw std::runtime_error(
373 "intra process publisher check called "
374 "after destruction of intra process manager");
376 return ipm->matches_any_publishers(sender_gid);
381 void * pointer_to_subscription_part,
384 if (
nullptr == pointer_to_subscription_part) {
385 throw std::invalid_argument(
"pointer_to_subscription_part is unexpectedly nullptr");
387 if (
this == pointer_to_subscription_part) {
388 return subscription_in_use_by_wait_set_.exchange(in_use_state);
391 return intra_process_subscription_waitable_in_use_by_wait_set_.exchange(in_use_state);
393 for (
const auto & key_event_pair : event_handlers_) {
394 auto qos_event = key_event_pair.second;
395 if (qos_event.get() == pointer_to_subscription_part) {
396 return qos_events_in_use_by_wait_set_[qos_event.get()].exchange(in_use_state);
399 throw std::runtime_error(
"given pointer_to_subscription_part does not match any part");
402 std::vector<rclcpp::NetworkFlowEndpoint>
405 rcutils_allocator_t allocator = rcutils_get_default_allocator();
406 rcl_network_flow_endpoint_array_t network_flow_endpoint_array =
407 rcl_get_zero_initialized_network_flow_endpoint_array();
408 rcl_ret_t ret = rcl_subscription_get_network_flow_endpoints(
409 subscription_handle_.get(), &allocator, &network_flow_endpoint_array);
411 auto error_msg = std::string(
"Error obtaining network flows of subscription: ") +
412 rcl_get_error_string().str;
415 rcl_network_flow_endpoint_array_fini(&network_flow_endpoint_array))
417 error_msg += std::string(
". Also error cleaning up network flow array: ") +
418 rcl_get_error_string().str;
421 rclcpp::exceptions::throw_from_rcl_error(ret, error_msg);
424 std::vector<rclcpp::NetworkFlowEndpoint> network_flow_endpoint_vector;
425 for (
size_t i = 0; i < network_flow_endpoint_array.size; ++i) {
426 network_flow_endpoint_vector.push_back(
428 network_flow_endpoint_array.
429 network_flow_endpoint[i]));
432 ret = rcl_network_flow_endpoint_array_fini(&network_flow_endpoint_array);
434 rclcpp::exceptions::throw_from_rcl_error(ret,
"error cleaning up network flow array");
437 return network_flow_endpoint_vector;
442 rcl_event_callback_t callback,
443 const void * user_data)
446 subscription_handle_.get(),
451 using rclcpp::exceptions::throw_from_rcl_error;
452 throw_from_rcl_error(ret,
"failed to set the on new message callback for subscription");
464 const std::string & filter_expression,
465 const std::vector<std::string> & expression_parameters)
472 subscription_handle_.get(),
478 rclcpp::exceptions::throw_from_rcl_error(
479 ret,
"failed to init subscription content_filtered_topic option");
481 RCPPUTILS_SCOPE_EXIT(
484 subscription_handle_.get(), &options);
488 "Failed to fini subscription content_filtered_topic option: %s",
489 rcl_get_error_string().str);
495 subscription_handle_.get(),
499 rclcpp::exceptions::throw_from_rcl_error(ret,
"failed to set cft expression parameters");
511 subscription_handle_.get(),
515 rclcpp::exceptions::throw_from_rcl_error(ret,
"failed to get cft expression parameters");
518 RCPPUTILS_SCOPE_EXIT(
521 subscription_handle_.get(), &options);
525 "Failed to fini subscription content_filtered_topic option: %s",
526 rcl_get_error_string().str);
531 rmw_subscription_content_filter_options_t & content_filter_options =
532 options.rmw_subscription_content_filter_options;
535 for (
size_t i = 0; i < content_filter_options.expression_parameters.size; ++i) {
537 content_filter_options.expression_parameters.data[i]);
546 SubscriptionBase::take_dynamic_message(
550 throw std::runtime_error(
"Unimplemented");
RCLCPP_PUBLIC Logger get_child(const std::string &suffix)
Return a logger that is a descendant of this logger.
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.
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 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.
RCLCPP_PUBLIC DeliveredMessageKind get_delivered_message_kind() const
Return the delivered message kind.
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.
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 void bind_event_callbacks(const SubscriptionEventCallbacks &event_callbacks, bool use_default_callbacks)
Add event handlers for passed in event_callbacks.
RCLCPP_PUBLIC const std::unordered_map< rcl_subscription_event_type_t, std::shared_ptr< rclcpp::EventHandlerBase > > & get_event_handlers() const
Get all the QoS event handlers associated with this subscription.
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.
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.
DeliveredMessageKind
The kind of message that the subscription delivers in its callback, used by the executor.
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>.
RCLCPP_PUBLIC const char * get_c_string(const char *string_in)
Return the given string.
RCLCPP_PUBLIC Logger get_logger(const std::string &name)
Return a named logger.
RCL_PUBLIC RCL_WARN_UNUSED const char * rcl_node_get_name(const rcl_node_t *node)
Return the name of the node.
RCL_PUBLIC RCL_WARN_UNUSED const char * rcl_node_get_namespace(const rcl_node_t *node)
Return the namespace of the node.
RCL_PUBLIC RCL_WARN_UNUSED const char * rcl_node_get_logger_name(const rcl_node_t *node)
Return the logger name of the node.
Options available for a rcl subscription.
Structure which encapsulates a ROS Subscription.
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.
std::vector< std::string > expression_parameters
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.
Contains callbacks for non-message events that a Subscription can receive from the middleware.
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_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 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 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_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_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.
#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_TOPIC_NAME_INVALID
Topic name does not pass validation.
rmw_ret_t rcl_ret_t
The type that holds an rcl return code.