From b26d2a8b7cbdddf874f9d2d45f2eca5a551bb2ba Mon Sep 17 00:00:00 2001 From: Roald Schaum <178021507+Roald-Schaum@users.noreply.github.com> Date: Sat, 7 Feb 2026 01:27:08 -0600 Subject: [PATCH 1/6] Added QOS support for subscribers and publishers --- .../capabilities/advertise.py | 17 +++++++++-- .../capabilities/subscribe.py | 16 ++++++++++ .../rosbridge_library/internal/publishers.py | 22 +++++++++----- .../rosbridge_library/internal/subscribers.py | 30 ++++++++++--------- 4 files changed, 62 insertions(+), 23 deletions(-) diff --git a/rosbridge_library/src/rosbridge_library/capabilities/advertise.py b/rosbridge_library/src/rosbridge_library/capabilities/advertise.py index 9397809de..bcf8b69b7 100644 --- a/rosbridge_library/src/rosbridge_library/capabilities/advertise.py +++ b/rosbridge_library/src/rosbridge_library/capabilities/advertise.py @@ -39,6 +39,8 @@ from rosbridge_library.capability import Capability from rosbridge_library.internal.publishers import manager +from rclpy.qos import QoSProfile, ReliabilityPolicy, DurabilityPolicy, HistoryPolicy, LivelinessPolicy + if TYPE_CHECKING: from rclpy.node import Node @@ -67,7 +69,7 @@ def unregister(self) -> None: manager.unregister(self.client_id, self.topic) def register_advertisement( - self, msg_type: str, adv_id: str | None = None, latch: bool = False, queue_size: int = 100 + self, msg_type: str, adv_id: str | None = None, latch: bool = False, queue_size: int = 100, qos: QoSProfile | None = None ) -> None: # Register with the publisher manager, propagating any exception manager.register( @@ -77,6 +79,7 @@ def register_advertisement( msg_type=msg_type, latch=latch, queue_size=queue_size, + qos=qos, ) if adv_id is not None: @@ -122,6 +125,16 @@ def advertise(self, message: dict[str, Any]) -> None: msg_type: str = message["type"] latch: bool = message.get("latch", False) queue_size: int = message.get("queue_size", 100) + qos: QoSProfile | None = QoSProfile( + depth=message.get("qos_depth", 10), + durability=message.get("durability_policy", DurabilityPolicy.SYSTEM_DEFAULT), + reliability=message.get("reliability_policy", ReliabilityPolicy.SYSTEM_DEFAULT), + history=message.get("history_policy", HistoryPolicy.SYSTEM_DEFAULT), + liveliness=message.get("liveliness_policy", LivelinessPolicy.SYSTEM_DEFAULT), + ) + + if message["durability_policy"] is None or message["history_policy"] is None or message["liveliness_policy"] is None or message["reliability_policy"] is None: + qos = None if self.topics_glob is not None: self.protocol.log("debug", "Topic security glob enabled, checking topic: " + topic) @@ -149,7 +162,7 @@ def advertise(self, message: dict[str, Any]) -> None: self._registrations[topic] = Registration(client_id, topic, self.protocol.node_handle) # Register, propagating any exceptions - self._registrations[topic].register_advertisement(msg_type, aid, latch, queue_size) + self._registrations[topic].register_advertisement(msg_type=msg_type, adv_id=aid, latch=latch, queue_size=queue_size, qos=qos) def unadvertise(self, message: dict[str, Any]) -> None: # Pull out the ID diff --git a/rosbridge_library/src/rosbridge_library/capabilities/subscribe.py b/rosbridge_library/src/rosbridge_library/capabilities/subscribe.py index 518fbfbf7..6e154e4d8 100644 --- a/rosbridge_library/src/rosbridge_library/capabilities/subscribe.py +++ b/rosbridge_library/src/rosbridge_library/capabilities/subscribe.py @@ -43,6 +43,8 @@ from rosbridge_library.internal.subscription_modifiers import MessageHandler from rosbridge_library.internal.type_support import ROSMessageT +from rclpy.qos import QoSProfile, ReliabilityPolicy, DurabilityPolicy, HistoryPolicy, LivelinessPolicy + if TYPE_CHECKING: from collections.abc import Callable @@ -116,6 +118,7 @@ def subscribe( queue_length: int = 0, fragment_size: int | None = None, compression: str = "none", + qos: QoSProfile | None = None, ) -> None: """ Add another client's subscription request. @@ -156,6 +159,7 @@ def subscribe( self.node_handle, msg_type=msg_type, raw=raw, + qos=qos, ) def unsubscribe(self, sid: str | None = None) -> None: @@ -245,6 +249,7 @@ class Subscribe(Capability): (False, "fragment_size", int), (False, "queue_length", int), (False, "compression", str), + (False, "qos", QoSProfile) ) unsubscribe_msg_fields = ((True, "topic", str),) @@ -307,6 +312,17 @@ def subscribe(self, msg: dict[str, Any]) -> None: "fragment_size": msg.get("fragment_size"), "queue_length": msg.get("queue_length", 0), "compression": msg.get("compression", "none"), + "qos": ( + QoSProfile( + depth=msg.get("qos_depth", 10), + durability=msg.get("durability_policy", DurabilityPolicy.SYSTEM_DEFAULT), + reliability=msg.get("reliability_policy", ReliabilityPolicy.SYSTEM_DEFAULT), + history=msg.get("history_policy", HistoryPolicy.SYSTEM_DEFAULT), + liveliness=msg.get("liveliness_policy", LivelinessPolicy.SYSTEM_DEFAULT), + ) + if "qos" in msg + else None + ) } self._subscriptions[topic].subscribe(**subscribe_args) diff --git a/rosbridge_library/src/rosbridge_library/internal/publishers.py b/rosbridge_library/src/rosbridge_library/internal/publishers.py index 6901fe642..4b6c20716 100644 --- a/rosbridge_library/src/rosbridge_library/internal/publishers.py +++ b/rosbridge_library/src/rosbridge_library/internal/publishers.py @@ -67,6 +67,7 @@ def __init__( msg_type: str | None = None, latched_client_id: str | None = None, queue_size: int = 100, + qos : QoSProfile | None = None, ) -> None: """ Register a publisher on the specified topic. @@ -119,23 +120,28 @@ def __init__( self.topic = topic self.node_handle = node_handle self.msg_class = msg_class + self.publisher_qos: QoSProfile = None + # Adding a lifespan solves the problem of late-joining subscribers # without the need of a custom message publisher implementation. - publisher_qos = QoSProfile( - depth=queue_size, - durability=DurabilityPolicy.TRANSIENT_LOCAL, - ) + if qos is None: + self.publisher_qos = QoSProfile( + depth=queue_size, + durability=DurabilityPolicy.TRANSIENT_LOCAL, + ) + else: + self.publisher_qos = qos; # For latched clients, no lifespan has to be specified (i.e. latch forever). # Otherwise we want to keep the messages for a second to prevent late-joining subscribers from # missing messages. if latched_client_id is None: - publisher_qos.lifespan = Duration(seconds=1) + self.publisher_qos.lifespan = Duration(seconds=1) else: - publisher_qos.depth = 1 + self.publisher_qos.depth = 1 self.publisher: Publisher[ROSMessageT] = node_handle.create_publisher( - msg_class, topic, qos_profile=publisher_qos + msg_class, topic, qos_profile=self.publisher_qos ) def unregister(self) -> None: @@ -222,6 +228,7 @@ def register( msg_type: str | None = None, latch: bool = False, queue_size: int = 100, + qos: QoSProfile | None = None, ) -> None: """ Register a publisher on the specified topic. @@ -247,6 +254,7 @@ def register( msg_type=msg_type, latched_client_id=latched_client_id, queue_size=queue_size, + qos=qos, ) elif latch and self._publishers[topic].latched_client_id != client_id: node_handle.get_logger().warning( diff --git a/rosbridge_library/src/rosbridge_library/internal/subscribers.py b/rosbridge_library/src/rosbridge_library/internal/subscribers.py index 083bec684..101c2b19c 100644 --- a/rosbridge_library/src/rosbridge_library/internal/subscribers.py +++ b/rosbridge_library/src/rosbridge_library/internal/subscribers.py @@ -38,7 +38,7 @@ from typing import TYPE_CHECKING, Generic, cast from rclpy.callback_groups import MutuallyExclusiveCallbackGroup -from rclpy.qos import DurabilityPolicy, QoSProfile, ReliabilityPolicy +from rclpy.qos import QoSProfile, ReliabilityPolicy, DurabilityPolicy, HistoryPolicy, LivelinessPolicy from rosbridge_library.internal import ros_loader from rosbridge_library.internal.message_conversion import msg_class_type_repr @@ -77,6 +77,7 @@ def __init__( node_handle: Node, msg_type: str | None = None, raw: bool = False, + qos: QoSProfile | None = None, ) -> None: """ Register a subscriber on the specified topic. @@ -134,21 +135,22 @@ def __init__( # - 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.BEST_EFFORT, - ) + if qos is None: + qos = QoSProfile( + depth=10, + durability=DurabilityPolicy.VOLATILE, + reliability=ReliabilityPolicy.BEST_EFFORT, + ) - infos = node_handle.get_publishers_info_by_topic(topic) + infos = node_handle.get_publishers_info_by_topic(topic) - 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): - qos.reliability = ReliabilityPolicy.BEST_EFFORT + 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): + qos.reliability = ReliabilityPolicy.BEST_EFFORT # Create the subscriber and associated member variables # Subscriptions is initialized with the current client to start with. From c1fa069b01ac6e1eb54475bbc3e94efac50465db Mon Sep 17 00:00:00 2001 From: Roald Schaum <178021507+Roald-Schaum@users.noreply.github.com> Date: Sat, 7 Feb 2026 02:56:51 -0600 Subject: [PATCH 2/6] FIX: Add qos argument to manager.subscribe --- rosbridge_library/src/rosbridge_library/internal/subscribers.py | 1 + 1 file changed, 1 insertion(+) diff --git a/rosbridge_library/src/rosbridge_library/internal/subscribers.py b/rosbridge_library/src/rosbridge_library/internal/subscribers.py index 101c2b19c..c817f5feb 100644 --- a/rosbridge_library/src/rosbridge_library/internal/subscribers.py +++ b/rosbridge_library/src/rosbridge_library/internal/subscribers.py @@ -306,6 +306,7 @@ def subscribe( node_handle: Node, msg_type: str | None = None, raw: bool = False, + qos: QoSProfile | None = None, ) -> None: """ Subscribe to a topic. From 83a766a694be7d0e2d17ec1edc5748a4aa8de2c3 Mon Sep 17 00:00:00 2001 From: Roald Schaum <178021507+Roald-Schaum@users.noreply.github.com> Date: Tue, 17 Feb 2026 21:03:03 -0600 Subject: [PATCH 3/6] Fixed QOS setting existence check --- .../src/rosbridge_library/capabilities/advertise.py | 10 ++++++++-- .../src/rosbridge_library/capabilities/subscribe.py | 8 +++++++- .../src/rosbridge_library/internal/subscribers.py | 8 ++++++-- 3 files changed, 21 insertions(+), 5 deletions(-) diff --git a/rosbridge_library/src/rosbridge_library/capabilities/advertise.py b/rosbridge_library/src/rosbridge_library/capabilities/advertise.py index bcf8b69b7..35db5acc4 100644 --- a/rosbridge_library/src/rosbridge_library/capabilities/advertise.py +++ b/rosbridge_library/src/rosbridge_library/capabilities/advertise.py @@ -39,7 +39,13 @@ from rosbridge_library.capability import Capability from rosbridge_library.internal.publishers import manager -from rclpy.qos import QoSProfile, ReliabilityPolicy, DurabilityPolicy, HistoryPolicy, LivelinessPolicy +from rclpy.qos import ( + QoSProfile, + ReliabilityPolicy, + DurabilityPolicy, + HistoryPolicy, + LivelinessPolicy, +) if TYPE_CHECKING: from rclpy.node import Node @@ -133,7 +139,7 @@ def advertise(self, message: dict[str, Any]) -> None: liveliness=message.get("liveliness_policy", LivelinessPolicy.SYSTEM_DEFAULT), ) - if message["durability_policy"] is None or message["history_policy"] is None or message["liveliness_policy"] is None or message["reliability_policy"] is None: + if message.keys() & {'durability_policy', 'history_policy', 'liveliness_policy', 'reliability_policy'}: qos = None if self.topics_glob is not None: diff --git a/rosbridge_library/src/rosbridge_library/capabilities/subscribe.py b/rosbridge_library/src/rosbridge_library/capabilities/subscribe.py index 6e154e4d8..11ed2f9fc 100644 --- a/rosbridge_library/src/rosbridge_library/capabilities/subscribe.py +++ b/rosbridge_library/src/rosbridge_library/capabilities/subscribe.py @@ -43,7 +43,13 @@ from rosbridge_library.internal.subscription_modifiers import MessageHandler from rosbridge_library.internal.type_support import ROSMessageT -from rclpy.qos import QoSProfile, ReliabilityPolicy, DurabilityPolicy, HistoryPolicy, LivelinessPolicy +from rclpy.qos import ( + QoSProfile, + ReliabilityPolicy, + DurabilityPolicy, + HistoryPolicy, + LivelinessPolicy, +) if TYPE_CHECKING: from collections.abc import Callable diff --git a/rosbridge_library/src/rosbridge_library/internal/subscribers.py b/rosbridge_library/src/rosbridge_library/internal/subscribers.py index c817f5feb..dc9d24d9e 100644 --- a/rosbridge_library/src/rosbridge_library/internal/subscribers.py +++ b/rosbridge_library/src/rosbridge_library/internal/subscribers.py @@ -38,7 +38,11 @@ from typing import TYPE_CHECKING, Generic, cast from rclpy.callback_groups import MutuallyExclusiveCallbackGroup -from rclpy.qos import QoSProfile, ReliabilityPolicy, DurabilityPolicy, HistoryPolicy, LivelinessPolicy +from rclpy.qos import ( + QoSProfile, + ReliabilityPolicy, + DurabilityPolicy, +) from rosbridge_library.internal import ros_loader from rosbridge_library.internal.message_conversion import msg_class_type_repr @@ -319,7 +323,7 @@ def subscribe( with self._lock: if topic not in self._subscribers: self._subscribers[topic] = MultiSubscriber( - topic, client_id, callback, node_handle, msg_type=msg_type, raw=raw + topic, client_id, callback, node_handle, msg_type=msg_type, raw=raw, qos=qos ) else: self._subscribers[topic].subscribe(client_id, callback) From 69d65a25f9d3fbb4d298af60a5056fa6d228b21c Mon Sep 17 00:00:00 2001 From: Roald Schaum <178021507+Roald-Schaum@users.noreply.github.com> Date: Tue, 17 Feb 2026 21:27:16 -0600 Subject: [PATCH 4/6] Fixed formatting, missing None type potential in multipublisher __init__ --- .../rosbridge_library/capabilities/advertise.py | 12 ++++++------ .../rosbridge_library/capabilities/subscribe.py | 16 ++++++++-------- .../src/rosbridge_library/internal/publishers.py | 4 ++-- .../rosbridge_library/internal/subscribers.py | 2 +- 4 files changed, 17 insertions(+), 17 deletions(-) diff --git a/rosbridge_library/src/rosbridge_library/capabilities/advertise.py b/rosbridge_library/src/rosbridge_library/capabilities/advertise.py index 35db5acc4..7a5e8ed53 100644 --- a/rosbridge_library/src/rosbridge_library/capabilities/advertise.py +++ b/rosbridge_library/src/rosbridge_library/capabilities/advertise.py @@ -36,17 +36,17 @@ import fnmatch from typing import TYPE_CHECKING, Any -from rosbridge_library.capability import Capability -from rosbridge_library.internal.publishers import manager - from rclpy.qos import ( - QoSProfile, - ReliabilityPolicy, DurabilityPolicy, HistoryPolicy, LivelinessPolicy, + QoSProfile, + ReliabilityPolicy, ) +from rosbridge_library.capability import Capability +from rosbridge_library.internal.publishers import manager + if TYPE_CHECKING: from rclpy.node import Node @@ -139,7 +139,7 @@ def advertise(self, message: dict[str, Any]) -> None: liveliness=message.get("liveliness_policy", LivelinessPolicy.SYSTEM_DEFAULT), ) - if message.keys() & {'durability_policy', 'history_policy', 'liveliness_policy', 'reliability_policy'}: + if message.keys() & {"durability_policy", "history_policy", "liveliness_policy", "reliability_policy"}: qos = None if self.topics_glob is not None: diff --git a/rosbridge_library/src/rosbridge_library/capabilities/subscribe.py b/rosbridge_library/src/rosbridge_library/capabilities/subscribe.py index 11ed2f9fc..87fe4d241 100644 --- a/rosbridge_library/src/rosbridge_library/capabilities/subscribe.py +++ b/rosbridge_library/src/rosbridge_library/capabilities/subscribe.py @@ -37,20 +37,20 @@ from threading import Lock from typing import TYPE_CHECKING, Any, Generic -from rosbridge_library.capability import Capability -from rosbridge_library.internal.pngcompression import encode as encode_png -from rosbridge_library.internal.subscribers import manager -from rosbridge_library.internal.subscription_modifiers import MessageHandler -from rosbridge_library.internal.type_support import ROSMessageT - from rclpy.qos import ( - QoSProfile, - ReliabilityPolicy, DurabilityPolicy, HistoryPolicy, LivelinessPolicy, + QoSProfile, + ReliabilityPolicy, ) +from rosbridge_library.capability import Capability +from rosbridge_library.internal.pngcompression import encode as encode_png +from rosbridge_library.internal.subscribers import manager +from rosbridge_library.internal.subscription_modifiers import MessageHandler +from rosbridge_library.internal.type_support import ROSMessageT + if TYPE_CHECKING: from collections.abc import Callable diff --git a/rosbridge_library/src/rosbridge_library/internal/publishers.py b/rosbridge_library/src/rosbridge_library/internal/publishers.py index 4b6c20716..d2b59426d 100644 --- a/rosbridge_library/src/rosbridge_library/internal/publishers.py +++ b/rosbridge_library/src/rosbridge_library/internal/publishers.py @@ -120,7 +120,7 @@ def __init__( self.topic = topic self.node_handle = node_handle self.msg_class = msg_class - self.publisher_qos: QoSProfile = None + self.publisher_qos: QoSProfile | None = None # Adding a lifespan solves the problem of late-joining subscribers # without the need of a custom message publisher implementation. @@ -130,7 +130,7 @@ def __init__( durability=DurabilityPolicy.TRANSIENT_LOCAL, ) else: - self.publisher_qos = qos; + self.publisher_qos = qos # For latched clients, no lifespan has to be specified (i.e. latch forever). # Otherwise we want to keep the messages for a second to prevent late-joining subscribers from diff --git a/rosbridge_library/src/rosbridge_library/internal/subscribers.py b/rosbridge_library/src/rosbridge_library/internal/subscribers.py index dc9d24d9e..80d359241 100644 --- a/rosbridge_library/src/rosbridge_library/internal/subscribers.py +++ b/rosbridge_library/src/rosbridge_library/internal/subscribers.py @@ -39,9 +39,9 @@ from rclpy.callback_groups import MutuallyExclusiveCallbackGroup from rclpy.qos import ( + DurabilityPolicy, QoSProfile, ReliabilityPolicy, - DurabilityPolicy, ) from rosbridge_library.internal import ros_loader From b2a5c99feccb7d31966393f0aa7d7d1bb8387c1c Mon Sep 17 00:00:00 2001 From: Roald Schaum <178021507+Roald-Schaum@users.noreply.github.com> Date: Tue, 17 Feb 2026 21:37:28 -0600 Subject: [PATCH 5/6] Fixed formatting (again) --- .../capabilities/advertise.py | 18 +++++++++++++++--- .../capabilities/subscribe.py | 2 +- .../rosbridge_library/internal/publishers.py | 2 +- 3 files changed, 17 insertions(+), 5 deletions(-) diff --git a/rosbridge_library/src/rosbridge_library/capabilities/advertise.py b/rosbridge_library/src/rosbridge_library/capabilities/advertise.py index 7a5e8ed53..1194a7788 100644 --- a/rosbridge_library/src/rosbridge_library/capabilities/advertise.py +++ b/rosbridge_library/src/rosbridge_library/capabilities/advertise.py @@ -75,7 +75,12 @@ def unregister(self) -> None: manager.unregister(self.client_id, self.topic) def register_advertisement( - self, msg_type: str, adv_id: str | None = None, latch: bool = False, queue_size: int = 100, qos: QoSProfile | None = None + self, + msg_type: str, + adv_id: str | None = None, + latch: bool = False, + queue_size: int = 100, + qos: QoSProfile | None = None ) -> None: # Register with the publisher manager, propagating any exception manager.register( @@ -139,7 +144,12 @@ def advertise(self, message: dict[str, Any]) -> None: liveliness=message.get("liveliness_policy", LivelinessPolicy.SYSTEM_DEFAULT), ) - if message.keys() & {"durability_policy", "history_policy", "liveliness_policy", "reliability_policy"}: + if message.keys() & { + "durability_policy", + "history_policy", + "liveliness_policy", + "reliability_policy" + }: qos = None if self.topics_glob is not None: @@ -168,7 +178,9 @@ def advertise(self, message: dict[str, Any]) -> None: self._registrations[topic] = Registration(client_id, topic, self.protocol.node_handle) # Register, propagating any exceptions - self._registrations[topic].register_advertisement(msg_type=msg_type, adv_id=aid, latch=latch, queue_size=queue_size, qos=qos) + self._registrations[topic].register_advertisement( + msg_type=msg_type, adv_id=aid, latch=latch, queue_size=queue_size, qos=qos + ) def unadvertise(self, message: dict[str, Any]) -> None: # Pull out the ID diff --git a/rosbridge_library/src/rosbridge_library/capabilities/subscribe.py b/rosbridge_library/src/rosbridge_library/capabilities/subscribe.py index 87fe4d241..db62d0fe1 100644 --- a/rosbridge_library/src/rosbridge_library/capabilities/subscribe.py +++ b/rosbridge_library/src/rosbridge_library/capabilities/subscribe.py @@ -255,7 +255,7 @@ class Subscribe(Capability): (False, "fragment_size", int), (False, "queue_length", int), (False, "compression", str), - (False, "qos", QoSProfile) + (False, "qos", QoSProfile), ) unsubscribe_msg_fields = ((True, "topic", str),) diff --git a/rosbridge_library/src/rosbridge_library/internal/publishers.py b/rosbridge_library/src/rosbridge_library/internal/publishers.py index d2b59426d..f7a5133fd 100644 --- a/rosbridge_library/src/rosbridge_library/internal/publishers.py +++ b/rosbridge_library/src/rosbridge_library/internal/publishers.py @@ -67,7 +67,7 @@ def __init__( msg_type: str | None = None, latched_client_id: str | None = None, queue_size: int = 100, - qos : QoSProfile | None = None, + qos: QoSProfile | None = None, ) -> None: """ Register a publisher on the specified topic. From 6b384776126d6c7d05b2400532ab08360ff134ee Mon Sep 17 00:00:00 2001 From: Roald Schaum <178021507+Roald-Schaum@users.noreply.github.com> Date: Tue, 17 Feb 2026 21:39:44 -0600 Subject: [PATCH 6/6] More formatting fixes --- .../src/rosbridge_library/capabilities/advertise.py | 4 ++-- .../src/rosbridge_library/capabilities/subscribe.py | 2 +- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/rosbridge_library/src/rosbridge_library/capabilities/advertise.py b/rosbridge_library/src/rosbridge_library/capabilities/advertise.py index 1194a7788..046ddd921 100644 --- a/rosbridge_library/src/rosbridge_library/capabilities/advertise.py +++ b/rosbridge_library/src/rosbridge_library/capabilities/advertise.py @@ -80,7 +80,7 @@ def register_advertisement( adv_id: str | None = None, latch: bool = False, queue_size: int = 100, - qos: QoSProfile | None = None + qos: QoSProfile | None = None, ) -> None: # Register with the publisher manager, propagating any exception manager.register( @@ -148,7 +148,7 @@ def advertise(self, message: dict[str, Any]) -> None: "durability_policy", "history_policy", "liveliness_policy", - "reliability_policy" + "reliability_policy", }: qos = None diff --git a/rosbridge_library/src/rosbridge_library/capabilities/subscribe.py b/rosbridge_library/src/rosbridge_library/capabilities/subscribe.py index db62d0fe1..c11cf5a65 100644 --- a/rosbridge_library/src/rosbridge_library/capabilities/subscribe.py +++ b/rosbridge_library/src/rosbridge_library/capabilities/subscribe.py @@ -328,7 +328,7 @@ def subscribe(self, msg: dict[str, Any]) -> None: ) if "qos" in msg else None - ) + ), } self._subscriptions[topic].subscribe(**subscribe_args)