Skip to content

Commit 7c1b1ba

Browse files
committed
fix: Failing service and subscription tests (backport #1147)
* Add error logging when service is unadvertised during in-flight request * Fix service destruction method in AdvertisedServiceHandler * Fix unadvertise service test * Try to fix failing topic subscription assertions by adding a timeout * Remove redundant sleeps * Remove extra call to destroy service after graceful shutdown * Re-raise original exception in handle_request
1 parent 1741cee commit 7c1b1ba

File tree

5 files changed

+124
-73
lines changed

5 files changed

+124
-73
lines changed

rosbridge_library/src/rosbridge_library/capabilities/advertise_service.py

Lines changed: 7 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -62,6 +62,12 @@ async def handle_request(
6262
result = await future
6363
assert result is not None, "Service response cannot be None"
6464
return result
65+
except Exception as e:
66+
self.protocol.log(
67+
"error",
68+
f"Error while waiting for response to service request with id {request_id}: {e}",
69+
)
70+
raise
6571
finally:
6672
del self.request_futures[request_id]
6773

@@ -96,7 +102,7 @@ def graceful_shutdown(self) -> None:
96102
for future_id in self.request_futures:
97103
future = self.request_futures[future_id]
98104
future.set_exception(RuntimeError(f"Service {self.service_name} was unadvertised"))
99-
self.service_handle.destroy()
105+
self.protocol.node_handle.destroy_service(self.service_handle)
100106

101107

102108
class AdvertiseService(Capability):

rosbridge_library/src/rosbridge_library/capabilities/unadvertise_service.py

Lines changed: 0 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -59,7 +59,6 @@ def unadvertise_service(self, message: dict[str, Any]) -> None:
5959
# unregister service in ROS
6060
if service_name in self.protocol.external_service_list:
6161
self.protocol.external_service_list[service_name].graceful_shutdown()
62-
self.protocol.external_service_list[service_name].service_handle.destroy()
6362
del self.protocol.external_service_list[service_name]
6463
self.protocol.log("info", f"Unadvertised service {service_name}")
6564
else:

rosbridge_library/test/capabilities/test_service_capabilities.py

Lines changed: 50 additions & 10 deletions
Original file line numberDiff line numberDiff line change
@@ -27,7 +27,7 @@ def setUp(self) -> None:
2727

2828
protocol_parameters = {
2929
"call_services_in_new_thread": False,
30-
"default_call_service_timeout": 5.0,
30+
"default_call_service_timeout": 0.5,
3131
"send_action_goals_in_new_thread": False,
3232
}
3333

@@ -257,20 +257,60 @@ def test_unadvertise_with_live_request(self) -> None:
257257
self.assertTrue("id" in self.received_message)
258258

259259
# Now unadvertise the service
260-
# TODO: This raises an exception, likely because of the following rclpy issue:
261-
# https://github.com/ros2/rclpy/issues/1098
262260
unadvertise_msg = loads(dumps({"op": "unadvertise_service", "service": service_path}))
263261
self.received_message = None
264262
self.unadvertise.unadvertise_service(unadvertise_msg)
265263

266-
with self.assertRaises(RuntimeError) as context:
267-
start_time = time.monotonic()
268-
while self.received_message is None:
269-
rclpy.spin_once(self.node, timeout_sec=0.1)
270-
if time.monotonic() - start_time > 0.3:
271-
self.fail("Timed out waiting for unadvertise service message.")
264+
# The in-flight request should time out and return a service_response (result False)
265+
# TODO: Ideally, the in-flight request should be cancelled immediately and return a
266+
# response indicating the service was unadvertised. Right now, the service handler from
267+
# advertise_service does not differentiate between internal and remote service calls and
268+
# rclpy does not provide a way to cancel an in-flight service request, so we just let the
269+
# request time out on the client side and return a timeout response.
270+
self.received_message = None
271+
start_time = time.monotonic()
272+
while self.received_message is None:
273+
rclpy.spin_once(self.node, timeout_sec=0.1)
274+
if time.monotonic() - start_time > 1.0:
275+
self.fail(
276+
"Timed out waiting for service_response after unadvertise (expected timeout response)."
277+
)
278+
279+
self.assertEqual(self.received_message["op"], "service_response")
280+
self.assertFalse(self.received_message["result"])
281+
self.assertEqual(
282+
self.received_message["values"],
283+
"Timeout exceeded while waiting for service response",
284+
)
272285

273-
self.assertTrue(f"Service {service_path} was unadvertised" in context.exception)
286+
# Subsequent calls should be rejected immediately
287+
self.received_message = None
288+
call_msg2 = loads(
289+
dumps(
290+
{
291+
"op": "call_service",
292+
"id": "bar",
293+
"service": service_path,
294+
"args": {"data": False},
295+
}
296+
)
297+
)
298+
Thread(target=self.call_service.call_service, args=(call_msg2,)).start()
299+
300+
start_time = time.monotonic()
301+
while self.received_message is None:
302+
rclpy.spin_once(self.node, timeout_sec=0.1)
303+
if time.monotonic() - start_time > 0.5:
304+
self.fail(
305+
"Timed out waiting for immediate rejection of call to unadvertised service."
306+
)
307+
308+
self.assertEqual(self.received_message["op"], "service_response")
309+
self.assertFalse(self.received_message["result"])
310+
self.assertEqual(
311+
self.received_message["values"],
312+
f"Service {service_path} does not exist",
313+
)
274314

275315

276316
if __name__ == "__main__":

rosbridge_library/test/internal/subscribers/test_multi_subscriber.py

Lines changed: 22 additions & 13 deletions
Original file line numberDiff line numberDiff line change
@@ -37,30 +37,41 @@ def tearDown(self) -> None:
3737
self.executor.shutdown()
3838
rclpy.shutdown()
3939

40+
def assertTopicSubscribed(self, topic: str, timeout: float = 1.0) -> None:
41+
start_time = time.monotonic()
42+
while not is_topic_subscribed(self.node, topic):
43+
time.sleep(0.05)
44+
if time.monotonic() - start_time > timeout:
45+
self.fail(f"Timed out waiting for topic '{topic}' to be subscribed.")
46+
47+
def assertTopicNotSubscribed(self, topic: str, timeout: float = 1.0) -> None:
48+
start_time = time.monotonic()
49+
while is_topic_subscribed(self.node, topic):
50+
time.sleep(0.05)
51+
if time.monotonic() - start_time > timeout:
52+
self.fail(f"Timed out waiting for topic '{topic}' to be unsubscribed.")
53+
4054
def test_register_multisubscriber(self) -> None:
4155
"""Register a subscriber on a clean topic with a good msg type."""
4256
topic = "/test_register_multisubscriber"
4357
msg_type = "std_msgs/String"
4458

45-
self.assertFalse(is_topic_subscribed(self.node, topic))
59+
self.assertTopicNotSubscribed(topic)
4660
MultiSubscriber(topic, self.client_id, lambda *_args: None, self.node, msg_type=msg_type)
47-
time.sleep(0.05)
48-
self.assertTrue(is_topic_subscribed(self.node, topic))
61+
self.assertTopicSubscribed(topic)
4962

5063
def test_unregister_multisubscriber(self) -> None:
5164
"""Register and unregister a subscriber on a clean topic with a good msg type."""
5265
topic = "/test_unregister_multisubscriber"
5366
msg_type = "std_msgs/String"
5467

55-
self.assertFalse(is_topic_subscribed(self.node, topic))
68+
self.assertTopicNotSubscribed(topic)
5669
multi: MultiSubscriber[String] = MultiSubscriber(
5770
topic, self.client_id, lambda *_args: None, self.node, msg_type=msg_type
5871
)
59-
time.sleep(0.05)
60-
self.assertTrue(is_topic_subscribed(self.node, topic))
72+
self.assertTopicSubscribed(topic)
6173
multi.unregister()
62-
time.sleep(0.05)
63-
self.assertFalse(is_topic_subscribed(self.node, topic))
74+
self.assertTopicNotSubscribed(topic)
6475

6576
def test_verify_type(self) -> None:
6677
topic = "/test_verify_type"
@@ -90,12 +101,11 @@ def test_subscribe_unsubscribe(self) -> None:
90101
topic = "/test_subscribe_unsubscribe"
91102
msg_type = "std_msgs/String"
92103

93-
self.assertFalse(is_topic_subscribed(self.node, topic))
104+
self.assertTopicNotSubscribed(topic)
94105
multi: MultiSubscriber[String] = MultiSubscriber(
95106
topic, self.client_id, lambda *_args: None, self.node, msg_type=msg_type
96107
)
97-
time.sleep(0.05)
98-
self.assertTrue(is_topic_subscribed(self.node, topic))
108+
self.assertTopicSubscribed(topic)
99109
self.assertEqual(len(multi.new_subscriptions), 0)
100110

101111
multi.subscribe(self.client_id, lambda _: None)
@@ -105,8 +115,7 @@ def test_subscribe_unsubscribe(self) -> None:
105115
self.assertEqual(len(multi.new_subscriptions), 0)
106116

107117
multi.unregister()
108-
time.sleep(0.1)
109-
self.assertFalse(is_topic_subscribed(self.node, topic))
118+
self.assertTopicNotSubscribed(topic)
110119

111120
def test_subscribe_receive_json(self) -> None:
112121
topic = "/test_subscribe_receive_json"

rosbridge_library/test/internal/subscribers/test_subscriber_manager.py

Lines changed: 45 additions & 48 deletions
Original file line numberDiff line numberDiff line change
@@ -38,23 +38,35 @@ def tearDown(self) -> None:
3838
self.executor.shutdown()
3939
rclpy.shutdown()
4040

41+
def assertTopicSubscribed(self, topic: str, timeout: float = 1.0) -> None:
42+
start_time = time.monotonic()
43+
while not is_topic_subscribed(self.node, topic):
44+
time.sleep(0.05)
45+
if time.monotonic() - start_time > timeout:
46+
self.fail(f"Timed out waiting for topic '{topic}' to be subscribed.")
47+
48+
def assertTopicNotSubscribed(self, topic: str, timeout: float = 1.0) -> None:
49+
start_time = time.monotonic()
50+
while is_topic_subscribed(self.node, topic):
51+
time.sleep(0.05)
52+
if time.monotonic() - start_time > timeout:
53+
self.fail(f"Timed out waiting for topic '{topic}' to be unsubscribed.")
54+
4155
def test_subscribe(self) -> None:
4256
"""Register a publisher on a clean topic with a good msg type."""
4357
topic = "/test_subscribe"
4458
msg_type = "std_msgs/String"
4559
client = "client_test_subscribe"
4660

4761
self.assertFalse(topic in manager._subscribers)
48-
self.assertFalse(is_topic_subscribed(self.node, topic))
62+
self.assertTopicNotSubscribed(topic)
4963
manager.subscribe(client, topic, lambda _: None, self.node, msg_type)
50-
time.sleep(0.05)
5164
self.assertTrue(topic in manager._subscribers)
52-
self.assertTrue(is_topic_subscribed(self.node, topic))
65+
self.assertTopicSubscribed(topic)
5366

5467
manager.unsubscribe(client, topic)
55-
time.sleep(0.05)
5668
self.assertFalse(topic in manager._subscribers)
57-
self.assertFalse(is_topic_subscribed(self.node, topic))
69+
self.assertTopicNotSubscribed(topic)
5870

5971
def test_register_subscriber_multiclient(self) -> None:
6072
topic = "/test_register_subscriber_multiclient"
@@ -63,26 +75,22 @@ def test_register_subscriber_multiclient(self) -> None:
6375
client2 = "client_test_register_subscriber_multiclient_2"
6476

6577
self.assertFalse(topic in manager._subscribers)
66-
self.assertFalse(is_topic_subscribed(self.node, topic))
78+
self.assertTopicNotSubscribed(topic)
6779
manager.subscribe(client1, topic, lambda _: None, self.node, msg_type)
68-
time.sleep(0.05)
6980
self.assertTrue(topic in manager._subscribers)
70-
self.assertTrue(is_topic_subscribed(self.node, topic))
81+
self.assertTopicSubscribed(topic)
7182

7283
manager.subscribe(client2, topic, lambda _: None, self.node, msg_type)
73-
time.sleep(0.05)
7484
self.assertTrue(topic in manager._subscribers)
75-
self.assertTrue(is_topic_subscribed(self.node, topic))
85+
self.assertTopicSubscribed(topic)
7686

7787
manager.unsubscribe(client1, topic)
78-
time.sleep(0.05)
7988
self.assertTrue(topic in manager._subscribers)
80-
self.assertTrue(is_topic_subscribed(self.node, topic))
89+
self.assertTopicSubscribed(topic)
8190

8291
manager.unsubscribe(client2, topic)
83-
time.sleep(0.05)
8492
self.assertFalse(topic in manager._subscribers)
85-
self.assertFalse(is_topic_subscribed(self.node, topic))
93+
self.assertTopicNotSubscribed(topic)
8694

8795
def test_register_publisher_conflicting_types(self) -> None:
8896
topic = "/test_register_publisher_conflicting_types"
@@ -91,11 +99,10 @@ def test_register_publisher_conflicting_types(self) -> None:
9199
client = "client_test_register_publisher_conflicting_types"
92100

93101
self.assertFalse(topic in manager._subscribers)
94-
self.assertFalse(is_topic_subscribed(self.node, topic))
102+
self.assertTopicNotSubscribed(topic)
95103
manager.subscribe(client, topic, lambda _: None, self.node, msg_type)
96-
time.sleep(0.05)
97104
self.assertTrue(topic in manager._subscribers)
98-
self.assertTrue(is_topic_subscribed(self.node, topic))
105+
self.assertTopicSubscribed(topic)
99106

100107
self.assertRaises(
101108
TypeConflictException,
@@ -115,43 +122,39 @@ def test_register_multiple_publishers(self) -> None:
115122

116123
self.assertFalse(topic1 in manager._subscribers)
117124
self.assertFalse(topic2 in manager._subscribers)
118-
self.assertFalse(is_topic_subscribed(self.node, topic1))
119-
self.assertFalse(is_topic_subscribed(self.node, topic2))
125+
self.assertTopicNotSubscribed(topic1)
126+
self.assertTopicNotSubscribed(topic2)
120127

121128
manager.subscribe(client, topic1, lambda _: None, self.node, msg_type)
122-
time.sleep(0.05)
123129
self.assertTrue(topic1 in manager._subscribers)
124-
self.assertTrue(is_topic_subscribed(self.node, topic1))
130+
self.assertTopicSubscribed(topic1)
125131
self.assertFalse(topic2 in manager._subscribers)
126-
self.assertFalse(is_topic_subscribed(self.node, topic2))
132+
self.assertTopicNotSubscribed(topic2)
127133

128134
manager.subscribe(client, topic2, lambda _: None, self.node, msg_type)
129-
time.sleep(0.05)
130135
self.assertTrue(topic1 in manager._subscribers)
131-
self.assertTrue(is_topic_subscribed(self.node, topic1))
136+
self.assertTopicSubscribed(topic1)
132137
self.assertTrue(topic2 in manager._subscribers)
133-
self.assertTrue(is_topic_subscribed(self.node, topic2))
138+
self.assertTopicSubscribed(topic2)
134139

135140
manager.unsubscribe(client, topic1)
136-
time.sleep(0.05)
137141
self.assertFalse(topic1 in manager._subscribers)
138-
self.assertFalse(is_topic_subscribed(self.node, topic1))
142+
self.assertTopicNotSubscribed(topic1)
139143
self.assertTrue(topic2 in manager._subscribers)
140-
self.assertTrue(is_topic_subscribed(self.node, topic2))
144+
self.assertTopicSubscribed(topic2)
141145

142146
manager.unsubscribe(client, topic2)
143-
time.sleep(0.05)
144147
self.assertFalse(topic1 in manager._subscribers)
145-
self.assertFalse(is_topic_subscribed(self.node, topic1))
148+
self.assertTopicNotSubscribed(topic1)
146149
self.assertFalse(topic2 in manager._subscribers)
147-
self.assertFalse(is_topic_subscribed(self.node, topic2))
150+
self.assertTopicNotSubscribed(topic2)
148151

149152
def test_register_no_msgtype(self) -> None:
150153
topic = "/test_register_no_msgtype"
151154
client = "client_test_register_no_msgtype"
152155

153156
self.assertFalse(topic in manager._subscribers)
154-
self.assertFalse(is_topic_subscribed(self.node, topic))
157+
self.assertTopicNotSubscribed(topic)
155158
self.assertRaises(
156159
TopicNotEstablishedException, manager.subscribe, client, topic, None, self.node
157160
)
@@ -160,26 +163,24 @@ def test_register_infer_topictype(self) -> None:
160163
topic = "/test_register_infer_topictype"
161164
client = "client_test_register_infer_topictype"
162165

163-
self.assertFalse(is_topic_subscribed(self.node, topic))
166+
self.assertTopicNotSubscribed(topic)
164167

165168
subscriber_qos = QoSProfile(
166169
depth=10,
167170
durability=DurabilityPolicy.TRANSIENT_LOCAL,
168171
)
169172
self.node.create_subscription(String, topic, lambda *_args: None, subscriber_qos)
170173

171-
self.assertTrue(is_topic_subscribed(self.node, topic))
174+
self.assertTopicSubscribed(topic)
172175
self.assertFalse(topic in manager._subscribers)
173176

174177
manager.subscribe(client, topic, lambda _: None, self.node)
175-
time.sleep(0.05)
176178
self.assertTrue(topic in manager._subscribers)
177-
self.assertTrue(is_topic_subscribed(self.node, topic))
179+
self.assertTopicSubscribed(topic)
178180

179181
manager.unsubscribe(client, topic)
180-
time.sleep(0.05)
181182
self.assertFalse(topic in manager._subscribers)
182-
self.assertTrue(is_topic_subscribed(self.node, topic))
183+
self.assertTopicSubscribed(topic)
183184

184185
def test_register_multiple_notopictype(self) -> None:
185186
topic = "/test_register_multiple_notopictype"
@@ -188,34 +189,30 @@ def test_register_multiple_notopictype(self) -> None:
188189
client2 = "client_test_register_multiple_notopictype_2"
189190

190191
self.assertFalse(topic in manager._subscribers)
191-
self.assertFalse(is_topic_subscribed(self.node, topic))
192+
self.assertTopicNotSubscribed(topic)
192193

193194
manager.subscribe(client1, topic, lambda _: None, self.node, msg_type)
194-
time.sleep(0.05)
195195
self.assertTrue(topic in manager._subscribers)
196-
self.assertTrue(is_topic_subscribed(self.node, topic))
196+
self.assertTopicSubscribed(topic)
197197

198198
manager.subscribe(client2, topic, lambda _: None, self.node)
199-
time.sleep(0.05)
200199
self.assertTrue(topic in manager._subscribers)
201-
self.assertTrue(is_topic_subscribed(self.node, topic))
200+
self.assertTopicSubscribed(topic)
202201

203202
manager.unsubscribe(client1, topic)
204-
time.sleep(0.05)
205203
self.assertTrue(topic in manager._subscribers)
206-
self.assertTrue(is_topic_subscribed(self.node, topic))
204+
self.assertTopicSubscribed(topic)
207205

208206
manager.unsubscribe(client2, topic)
209-
time.sleep(0.05)
210207
self.assertFalse(topic in manager._subscribers)
211-
self.assertFalse(is_topic_subscribed(self.node, topic))
208+
self.assertTopicNotSubscribed(topic)
212209

213210
def test_subscribe_not_registered(self) -> None:
214211
topic = "/test_subscribe_not_registered"
215212
client = "client_test_subscribe_not_registered"
216213

217214
self.assertFalse(topic in manager._subscribers)
218-
self.assertFalse(is_topic_subscribed(self.node, topic))
215+
self.assertTopicNotSubscribed(topic)
219216
self.assertRaises(
220217
TopicNotEstablishedException, manager.subscribe, client, topic, None, self.node
221218
)

0 commit comments

Comments
 (0)