15 #include "rclcpp/subscription_base.hpp"
20 #include <unordered_map>
23 #include "rcpputils/scope_exit.hpp"
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"
32 #include "rmw/error_handling.h"
37 SubscriptionBase::SubscriptionBase(
39 const rosidl_message_type_support_t & type_support_handle,
40 const std::string & topic_name,
43 : node_base_(node_base),
44 node_handle_(node_base_->get_shared_rcl_node_handle()),
46 use_intra_process_(false),
47 intra_process_subscription_id_(0),
48 type_support_(type_support_handle),
49 is_serialized_(is_serialized)
51 auto custom_deletor = [node_handle = this->node_handle_](
rcl_subscription_t * rcl_subs)
56 "Error in destruction of rcl subscription handle: %s",
57 rcl_get_error_string().str);
63 subscription_handle_ = std::shared_ptr<rcl_subscription_t>(
68 subscription_handle_.get(),
72 &subscription_options);
75 auto rcl_node_handle = node_handle_.get();
84 rclcpp::exceptions::throw_from_rcl_error(ret,
"could not create subscription");
92 for (
const auto & pair : event_handlers_) {
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_);
117 std::shared_ptr<rcl_subscription_t>
118 SubscriptionBase::get_subscription_handle()
120 return subscription_handle_;
123 std::shared_ptr<const rcl_subscription_t>
124 SubscriptionBase::get_subscription_handle()
const
126 return subscription_handle_;
130 std::unordered_map<rcl_subscription_event_type_t, std::shared_ptr<rclcpp::QOSEventHandlerBase>> &
133 return event_handlers_;
141 auto msg = std::string(
"failed to get qos settings: ") + rcl_get_error_string().str;
143 throw std::runtime_error(msg);
153 this->get_subscription_handle().get(),
158 TRACEPOINT(rclcpp_take,
static_cast<const void *
>(message_out));
162 rclcpp::exceptions::throw_from_rcl_error(ret);
180 this->get_subscription_handle().get(),
187 rclcpp::exceptions::throw_from_rcl_error(ret);
192 const rosidl_message_type_support_t &
193 SubscriptionBase::get_message_type_support_handle()
const
195 return type_support_;
201 return is_serialized_;
207 size_t inter_process_publisher_count = 0;
210 subscription_handle_.get(),
211 &inter_process_publisher_count);
214 rclcpp::exceptions::throw_from_rcl_error(status,
"failed to get get publisher count");
216 return inter_process_publisher_count;
221 uint64_t intra_process_subscription_id,
222 IntraProcessManagerWeakPtr weak_ipm)
224 intra_process_subscription_id_ = intra_process_subscription_id;
225 weak_ipm_ = weak_ipm;
226 use_intra_process_ =
true;
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).");
248 rclcpp::Waitable::SharedPtr
252 if (!use_intra_process_) {
256 auto ipm = weak_ipm_.lock();
258 throw std::runtime_error(
259 "SubscriptionBase::get_intra_process_waitable() called "
260 "after destruction of intra process manager");
264 return ipm->get_subscription_intra_process(intra_process_subscription_id_);
268 SubscriptionBase::default_incompatible_qos_callback(
269 rclcpp::QOSRequestedIncompatibleQoSInfo & event)
const
271 std::string policy_name = qos_policy_name_from_kind(event.last_policy_kind);
274 "New publisher discovered on topic '%s', offering incompatible QoS. "
275 "No messages will be sent to it. "
276 "Last incompatible policy: %s",
278 policy_name.c_str());
282 SubscriptionBase::matches_any_intra_process_publishers(
const rmw_gid_t * sender_gid)
const
284 if (!use_intra_process_) {
287 auto ipm = weak_ipm_.lock();
289 throw std::runtime_error(
290 "intra process publisher check called "
291 "after destruction of intra process manager");
293 return ipm->matches_any_publishers(sender_gid);
298 void * pointer_to_subscription_part,
301 if (
nullptr == pointer_to_subscription_part) {
302 throw std::invalid_argument(
"pointer_to_subscription_part is unexpectedly nullptr");
304 if (
this == pointer_to_subscription_part) {
305 return subscription_in_use_by_wait_set_.exchange(in_use_state);
308 return intra_process_subscription_waitable_in_use_by_wait_set_.exchange(in_use_state);
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);
316 throw std::runtime_error(
"given pointer_to_subscription_part does not match any part");
319 std::vector<rclcpp::NetworkFlowEndpoint>
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);
328 auto error_msg = std::string(
"Error obtaining network flows of subscription: ") +
329 rcl_get_error_string().str;
332 rcl_network_flow_endpoint_array_fini(&network_flow_endpoint_array))
334 error_msg += std::string(
". Also error cleaning up network flow array: ") +
335 rcl_get_error_string().str;
338 rclcpp::exceptions::throw_from_rcl_error(ret, error_msg);
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]));
349 ret = rcl_network_flow_endpoint_array_fini(&network_flow_endpoint_array);
351 rclcpp::exceptions::throw_from_rcl_error(ret,
"error cleaning up network flow array");
354 return network_flow_endpoint_vector;
359 rcl_event_callback_t callback,
360 const void * user_data)
363 subscription_handle_.get(),
368 using rclcpp::exceptions::throw_from_rcl_error;
369 throw_from_rcl_error(ret,
"failed to set the on new message callback for subscription");
381 const std::string & filter_expression,
382 const std::vector<std::string> & expression_parameters)
387 std::vector<const char *> cstrings =
390 subscription_handle_.get(),
396 rclcpp::exceptions::throw_from_rcl_error(
397 ret,
"failed to init subscription content_filtered_topic option");
399 RCPPUTILS_SCOPE_EXIT(
402 subscription_handle_.get(), &options);
406 "Failed to fini subscription content_filtered_topic option: %s",
407 rcl_get_error_string().str);
413 subscription_handle_.get(),
417 rclcpp::exceptions::throw_from_rcl_error(ret,
"failed to set cft expression parameters");
429 subscription_handle_.get(),
433 rclcpp::exceptions::throw_from_rcl_error(ret,
"failed to get cft expression parameters");
436 RCPPUTILS_SCOPE_EXIT(
439 subscription_handle_.get(), &options);
443 "Failed to fini subscription content_filtered_topic option: %s",
444 rcl_get_error_string().str);
449 rmw_subscription_content_filter_options_t & content_filter_options =
450 options.rmw_subscription_content_filter_options;
453 for (
size_t i = 0; i < content_filter_options.expression_parameters.size; ++i) {
455 content_filter_options.expression_parameters.data[i]);
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 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.
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.
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.