Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Fixed multiple subscriber on transient_local topic #723

Merged
merged 2 commits into from
Apr 22, 2022
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
38 changes: 21 additions & 17 deletions rosbridge_library/src/rosbridge_library/internal/subscribers.py
Original file line number Diff line number Diff line change
Expand Up @@ -101,33 +101,34 @@ def __init__(self, topic, client_id, callback, node_handle, msg_type=None, raw=F
if topic_type is not None and topic_type != msg_type_string:
raise TypeConflictException(topic, topic_type, msg_type_string)

# Create the subscriber and associated member variables
# Subscriptions is initialized with the current client to start with.
self.subscriptions = {client_id: callback}
self.lock = Lock()
self.topic = topic
self.msg_class = msg_class
self.node_handle = node_handle

qos = QoSProfile(
depth=10,
durability=DurabilityPolicy.VOLATILE,
reliability=ReliabilityPolicy.RELIABLE,
)
infos = node_handle.get_publishers_info_by_topic(topic)

# Certain combinations of publisher and subscriber QoS parameters are
# 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:
# - https://docs.ros.org/en/rolling/Concepts/About-Quality-of-Service-Settings.html
# - https://github.com/RobotWebTools/rosbridge_suite/issues/551
qos = QoSProfile(
depth=10,
durability=DurabilityPolicy.VOLATILE,
reliability=ReliabilityPolicy.RELIABLE,
)

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
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.
self.subscriptions = {client_id: callback}
self.lock = Lock()
self.msg_class = msg_class
self.node_handle = node_handle
self.topic = topic
self.qos = qos

self.subscriber = node_handle.create_subscription(
msg_class, topic, self.callback, qos, raw=raw
)
Expand Down Expand Up @@ -171,7 +172,7 @@ def subscribe(self, client_id, callback):
self.new_subscriptions.update({client_id: callback})
if self.new_subscriber is None:
self.new_subscriber = self.node_handle.create_subscription(
self.msg_class, self.topic, self._new_sub_callback, 10
self.msg_class, self.topic, self._new_sub_callback, self.qos
)

def unsubscribe(self, client_id):
Expand All @@ -182,7 +183,10 @@ def unsubscribe(self, client_id):

"""
with self.lock:
del self.subscriptions[client_id]
if client_id in self.new_subscriptions:
del self.new_subscriptions[client_id]
else:
del self.subscriptions[client_id]

def has_subscribers(self):
"""Return true if there are subscribers"""
Expand Down
37 changes: 19 additions & 18 deletions rosbridge_server/test/websocket/transient_local_publisher.test.py
Original file line number Diff line number Diff line change
Expand Up @@ -33,23 +33,24 @@ async def test_transient_local_publisher(self, node: Node, make_client):

await sleep(node, 1)

ws_client1 = await make_client()
ws_client1.sendJson(
{
"op": "subscribe",
"topic": "/a_topic",
"type": "std_msgs/String",
}
)

ws1_completed_future, ws_client1.message_handler = expect_messages(
1, "WebSocket 1", node.get_logger()
)
ws1_completed_future.add_done_callback(lambda _: node.executor.wake())

self.assertEqual(
await ws1_completed_future,
[{"op": "publish", "topic": "/a_topic", "msg": {"data": "hello"}}],
)
for num in range(3):
ws_client = await make_client()
ws_client.sendJson(
{
"op": "subscribe",
"topic": "/a_topic",
"type": "std_msgs/String",
}
)

ws_completed_future, ws_client.message_handler = expect_messages(
1, "WebSocket " + str(num), node.get_logger()
)
ws_completed_future.add_done_callback(lambda _: node.executor.wake())

self.assertEqual(
await ws_completed_future,
[{"op": "publish", "topic": "/a_topic", "msg": {"data": "hello"}}],
)

node.destroy_publisher(pub_a)