From 3ec6026beab85c2d4585560b63a919abb0a1d62a Mon Sep 17 00:00:00 2001 From: ewak Date: Thu, 27 Feb 2025 06:33:29 +1100 Subject: [PATCH 1/2] Default subscriber QOS to BestEffort, account for TRANSIENT_LOCAL (#991) * use permissive QoS to ensure compatibilty with publishers * use RELIABLE qos if publisher found to be TRANSIENT_LOCAL --------- Co-authored-by: William Wedler Co-authored-by: Mike Wake --- .../src/rosbridge_library/internal/subscribers.py | 9 +++++++-- 1 file changed, 7 insertions(+), 2 deletions(-) diff --git a/rosbridge_library/src/rosbridge_library/internal/subscribers.py b/rosbridge_library/src/rosbridge_library/internal/subscribers.py index a64c90b7f..597563cd7 100644 --- a/rosbridge_library/src/rosbridge_library/internal/subscribers.py +++ b/rosbridge_library/src/rosbridge_library/internal/subscribers.py @@ -106,18 +106,23 @@ def __init__(self, topic, client_id, callback, node_handle, msg_type=None, raw=F # incompatible. Here we make a "best effort" attempt to match existing # publishers for the requested topic. This is not perfect because more # publishers may come online after our subscriber is set up, but we try - # to provide sane defaults. For more information, see: + # to provide sane defaults. + # For this reason we use volatile durability and best effort reliability + # to prioritize topic compatibility when the publisher policy is not known. + # For more information, see: # - https://docs.ros.org/en/rolling/Concepts/About-Quality-of-Service-Settings.html # - https://github.com/RobotWebTools/rosbridge_suite/issues/551 + # - https://github.com/RobotWebTools/rosbridge_suite/issues/769 qos = QoSProfile( depth=10, durability=DurabilityPolicy.VOLATILE, - reliability=ReliabilityPolicy.RELIABLE, + reliability=ReliabilityPolicy.BEST_EFFORT, ) infos = node_handle.get_publishers_info_by_topic(topic) if any(pub.qos_profile.durability == DurabilityPolicy.TRANSIENT_LOCAL for pub in infos): qos.durability = DurabilityPolicy.TRANSIENT_LOCAL + qos.reliability = ReliabilityPolicy.RELIABLE if any(pub.qos_profile.reliability == ReliabilityPolicy.BEST_EFFORT for pub in infos): qos.reliability = ReliabilityPolicy.BEST_EFFORT From cc74edc4406c96a123961393d77da20255e34d65 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Talha=20I=C5=9F=C4=B1k?= <55973034+Egoless41@users.noreply.github.com> Date: Mon, 14 Apr 2025 18:41:35 +0300 Subject: [PATCH 2/2] Don't subscribe with Transient local QoS when there are volatile publishers (#1023) * fix: incompatible QoS settings for subs for reliability, if any subscribed topic has a non-reliable policy, we set reliability to best effort. for durability, if if any subscribed topic has a non-transient-local policy, we set durability to volatile. * fix: define variables * fix: lint and remove default publisher qos durability setting * fix: default durability policy for tests * fix: code fixed according to recommendation * fix: lint * fix: added recommended changes * fix: reverted test changes * fix: check if there are any publisher. * fix: lint * fix: qos settings * fix: requested changes --- .../src/rosbridge_library/internal/subscribers.py | 11 +++++++++-- 1 file changed, 9 insertions(+), 2 deletions(-) diff --git a/rosbridge_library/src/rosbridge_library/internal/subscribers.py b/rosbridge_library/src/rosbridge_library/internal/subscribers.py index 597563cd7..3ebdbcd0c 100644 --- a/rosbridge_library/src/rosbridge_library/internal/subscribers.py +++ b/rosbridge_library/src/rosbridge_library/internal/subscribers.py @@ -120,7 +120,10 @@ def __init__(self, topic, client_id, callback, node_handle, msg_type=None, raw=F ) infos = node_handle.get_publishers_info_by_topic(topic) - if any(pub.qos_profile.durability == DurabilityPolicy.TRANSIENT_LOCAL for pub in infos): + + if len(infos) > 0 and all( + pub.qos_profile.durability == DurabilityPolicy.TRANSIENT_LOCAL for pub in infos + ): qos.durability = DurabilityPolicy.TRANSIENT_LOCAL qos.reliability = ReliabilityPolicy.RELIABLE if any(pub.qos_profile.reliability == ReliabilityPolicy.BEST_EFFORT for pub in infos): @@ -182,10 +185,14 @@ def subscribe(self, client_id, callback): # which adds the new callback to the subscriptions dictionary. self.new_subscriptions.update({client_id: callback}) infos = self.node_handle.get_publishers_info_by_topic(self.topic) - if any(pub.qos_profile.durability == DurabilityPolicy.TRANSIENT_LOCAL for pub in infos): + + if len(infos) > 0 and all( + pub.qos_profile.durability == DurabilityPolicy.TRANSIENT_LOCAL for pub in infos + ): self.qos.durability = DurabilityPolicy.TRANSIENT_LOCAL if any(pub.qos_profile.reliability == ReliabilityPolicy.BEST_EFFORT for pub in infos): self.qos.reliability = ReliabilityPolicy.BEST_EFFORT + if self.new_subscriber is None: self.new_subscriber = self.node_handle.create_subscription( self.msg_class,