Open emersonknapp opened 2 years ago
As another pointer, there's another implementation of this in domain_bridge
(inspired by the rosbag2
logic).
Here are other threads discussing this feature:
I think it makes sense to have two functions in rcl
(and maybe implemented inrmw
): one for getting the best possible QoS for a given publisher and a second function for a given subscription. We can then provide rclcpp
and rclpy
wrappers for the rcl
functions.
@emersonknapp I think these functions could easily satisfy your second and third behavioral considerations: get the highest possible QoS and account for multiple entities with different QoS. However, doing something like re-adapting to new pub/subs on the graph sounds difficult.
We considered re-adapting QoS during runtime for the domain_bridge
, but it is not clear how to achieve this without recreating the publisher or subscription in question. If we recreate a subscription, then it becomes difficult to deal with messages that may be lost (or duplicated) during the transition. I'd like to hear from others about how this kind of feature might best be achieved. IMO, it seems like it is not worth the effort.
@jacobperron
However, doing something like re-adapting to new pub/subs on the graph sounds difficult. but it is not clear how to achieve this without recreating the publisher or subscription in question.
I think we do need to have new RMW interface to reset the QoS for publisher and subscriber at runtime to achieve this re-adapting QoS
? if i am not mistaken, it can be done with DDS. CC: @MiguelCompany @eboasson
You're opening a can of worms here ... the very short answer is that in DDS it is impossible to make a data reader that will "reliably" get data from all writers for the same topic without getting duplicates:
Furthermore, some of the QoS settings that do this problematic request-offered (RxO) matching and that are supported by ROS 2 cannot be changed: reliability, durability and liveliness are fixed at creation time of a reader/writer. If you really want to go ahead with this, I'd suggest recreating the publisher/subscription, make sure that the new one is discovered before deleting the old one and deal with any double arrivals separately.
The only alternative would be DDS spec changes or vendor-specific extensions to implement different matching rules, which could be done in such a way that there'd be no need to adapt anything. Sadly, vendor-specific will get messy if interoperability is desired and the spec changes more slowly than a glacier melts in an ice age ...
@eboasson appreciate for your quick and informative comments.
I'd suggest recreating the publisher/subscription, make sure that the new one is discovered before deleting the old one and deal with any double arrivals separately.
i see. at least i do not have any other ways to achieve this. and it seems like it is not worth the effort...
@jacobperron (and others) I think it makes sense to provide the utilities to adapt a subscription to a known set of publisher qos profiles. We could skip re-adapting to newly discovered publishers, in the requirements for this particular ticket - and revisit that as its own feature, if desired, later.
With the assumption that publishers exist at subscription creation time and not adapt to new publishers, listing here a couple of approaches to this. My thought was to add the detection logic in rcl
and update/add wrapper to the subscription initialization interface rcl_subscription_init()
to use this and adapt to the publisher QoS.
rmw_qos_profile_t
(eg. rmw_qos_profile_autodetect
) to rmw/qos_profiles.h
; this would be used to trigger the publisher QoS lookup logic (which would in turn use rcl_get_publishers_info_by_topic()
) while using rcl_subscription_init()
. rcl
(for logic), auto detect profile addition to rmw
(qos_profiles.h
) and corresponding updates to rclcpp
(qos.hpp
), rclpy
(qos.py
) ; enabling users to call rcl_subscription_init()
using exiting methods even while invoking this additional autodetection feature.
rmw_qos_profile_t
seems like an overkill for something that can be accomplished by passing just a boolean flag (to trigger QoS detection logic).rcl_adaptive_qos_subscription_init()
, which would essentially be a wrapper around rcl_subscription_init()
, that does not need the subscription options.rcl_subscription_init()
.rclcpp
, rclpy
to be able to make use of this new method.After some iteration, I've proposed adding new policy enum values at the RMW layer for selecting the 'best available' policy (ie. the policy that will match the most endpoints while maintaining the highest level of service). Feedback is welcome: https://github.com/ros2/rmw/pull/320
This delegates to the middleware for how to implement the matching logic. For DDS implementations, we provide a common implementation that will query discovered endpoints at the time of creating a subscription/publisher and use that information to adapt the QoS policies: https://github.com/ros2/rmw_dds_common/pull/60
Feature request
Feature description
Provide the ability for a subscription to automatically choose a QoS based on detected QoS of publishers in the graph. Most times for the business logic of robot applications, we want to explicitly specify QoS policies to clearly lay out communication behavior requirements.
However, some tooling and infrastructure by design does not care about the exact behavior and just wants to match with publishers no matter what, at as high a level of fidelity/service as possible. Three use cases come to mind up front:
ros2 topic echo
in my view should always start printing messages, if there is a publisher providing them, regardless of QoS mismatchrelay
,throttle
andmux
generally want to receive messages from publishers and imitate those publisher's behaviors, with modificationsThis feature API might be:
AdaptiveQoSSubscription
that provides this behaviorSubscriptionOptions
value that turns this onAdaptiveSubscriptionQoSProfile
that acts as a flag to enable the behaviorBehavior considerations:
Implementation considerations
Will need this in both
rclpy
andrclcpp
. Python is necessary to expose to ros2cli and some topic_tools. Given that, maybe this feature belongs inrcl
or maybe even in some RMW utility package.There are two current implementations that I know of for this feature, in
rosbag2
and intopic_tools
. Using those as a starting point for a "core" implementation makes sense to me.See https://github.com/ros2/rosbag2/blob/master/rosbag2_transport/src/rosbag2_transport/qos.cpp for rosbag2 logic - those tools used around https://github.com/ros2/rosbag2/blob/master/rosbag2_transport/src/rosbag2_transport/recorder.cpp#L238