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

Fix error when advertising duplicate service #683

Merged
merged 2 commits into from
Nov 29, 2021
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
Original file line number Diff line number Diff line change
Expand Up @@ -45,9 +45,10 @@ async def handle_request(self, req, res):
}
self.protocol.send(request_message)

res = await future
del self.request_futures[request_id]
return res
try:
return await future
finally:
del self.request_futures[request_id]

def handle_response(self, request_id, res):
"""
Expand Down Expand Up @@ -75,6 +76,8 @@ def graceful_shutdown(self):
f"Service {self.service_name} was unadvertised with a service call in progress, "
f"aborting service calls with request IDs {incomplete_ids}",
)
for future in self.request_futures.values():
future.set_exception(RuntimeError(f"Service {self.service_name} was unadvertised"))
self.protocol.node_handle.destroy_service(self.service_handle)


Expand Down Expand Up @@ -128,9 +131,7 @@ def advertise_service(self, message):
self.protocol.log(
"warn", "Duplicate service advertised. Overwriting %s." % service_name
)
self.protocol.external_service_list[service_name].service_handle.shutdown(
"Duplicate advertiser."
)
self.protocol.external_service_list[service_name].graceful_shutdown()
del self.protocol.external_service_list[service_name]

# setup and store the service information
Expand Down
3 changes: 2 additions & 1 deletion rosbridge_server/test/websocket/advertise_service.test.py
Original file line number Diff line number Diff line change
Expand Up @@ -19,7 +19,8 @@

class TestAdvertiseService(unittest.TestCase):
@websocket_test
async def test_two_concurrent_calls(self, node: Node, ws_client):
async def test_two_concurrent_calls(self, node: Node, make_client):
ws_client = await make_client()
ws_client.sendJson(
{
"op": "advertise_service",
Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,99 @@
import os
import sys
import unittest

from rclpy.node import Node
from std_srvs.srv import SetBool
from twisted.python import log

sys.path.append(os.path.dirname(__file__)) # enable importing from common.py in this directory

import common # noqa: E402
from common import expect_messages, sleep, websocket_test # noqa: E402

log.startLogging(sys.stderr)

generate_test_description = common.generate_test_description


class TestAdvertiseService(unittest.TestCase):
@websocket_test
async def test_double_advertise(self, node: Node, make_client):
ws_client1 = await make_client()
ws_client1.sendJson(
{
"op": "advertise_service",
"type": "std_srvs/SetBool",
"service": "/test_service",
}
)
client = node.create_client(SetBool, "/test_service")
client.wait_for_service()

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

client.call_async(SetBool.Request(data=True))

requests1 = await requests1_future
self.assertEqual(
requests1,
[
{
"op": "call_service",
"service": "/test_service",
"id": "service_request:/test_service:1",
"args": {"data": True},
}
],
)

ws_client1.sendClose()

ws_client2 = await make_client()
ws_client2.sendJson(
{
"op": "advertise_service",
"type": "std_srvs/SetBool",
"service": "/test_service",
}
)

# wait for the server to handle the new advertisement
await sleep(node, 1)

requests2_future, ws_client2.message_handler = expect_messages(
1, "WebSocket 2", node.get_logger()
)
requests2_future.add_done_callback(lambda _: node.executor.wake())

response2_future = client.call_async(SetBool.Request(data=False))

requests2 = await requests2_future
self.assertEqual(
requests2,
[
{
"op": "call_service",
"id": "service_request:/test_service:1",
"service": "/test_service",
"args": {"data": False},
}
],
)

ws_client2.sendJson(
{
"op": "service_response",
"service": "/test_service",
"values": {"success": True, "message": "Hello world 2"},
"id": "service_request:/test_service:1",
"result": True,
}
)

self.assertEqual(
await response2_future, SetBool.Response(success=True, message="Hello world 2")
)
3 changes: 2 additions & 1 deletion rosbridge_server/test/websocket/call_service.test.py
Original file line number Diff line number Diff line change
Expand Up @@ -19,7 +19,7 @@

class TestCallService(unittest.TestCase):
@websocket_test
async def test_one_call(self, node: Node, ws_client):
async def test_one_call(self, node: Node, make_client):
def service_cb(req, res):
self.assertTrue(req.data)
res.success = True
Expand All @@ -28,6 +28,7 @@ def service_cb(req, res):

service = node.create_service(SetBool, "/test_service", service_cb)

ws_client = await make_client()
responses_future, ws_client.message_handler = expect_messages(
1, "WebSocket", node.get_logger()
)
Expand Down
9 changes: 5 additions & 4 deletions rosbridge_server/test/websocket/common.py
Original file line number Diff line number Diff line change
Expand Up @@ -103,7 +103,8 @@ def connect():


def run_websocket_test(
node_name: str, test_fn: Callable[[Node, TestClientProtocol], Awaitable[None]]
node_name: str,
test_fn: Callable[[Node, Callable[[], Awaitable[TestClientProtocol]]], Awaitable[None]],
):
context = rclpy.Context()
rclpy.init(context=context)
Expand All @@ -112,8 +113,7 @@ def run_websocket_test(
executor.add_node(node)

async def task():
ws_client = await connect_to_server(node)
await test_fn(node, ws_client)
await test_fn(node, lambda: connect_to_server(node))
reactor.callFromThread(reactor.stop)

future = executor.create_task(task)
Expand Down Expand Up @@ -142,7 +142,8 @@ def callback():

def websocket_test(test_fn):
"""
Decorator for tests which use a ROS node and WebSocket server and client
Decorator for tests which use a ROS node and WebSocket server and client.
Multiple tests per file are not supported because the Twisted reactor cannot be run multiple times.
"""

@functools.wraps(test_fn)
Expand Down
3 changes: 2 additions & 1 deletion rosbridge_server/test/websocket/smoke.test.py
Original file line number Diff line number Diff line change
Expand Up @@ -19,7 +19,8 @@

class TestWebsocketSmoke(unittest.TestCase):
@websocket_test
async def test_smoke(self, node: Node, ws_client):
async def test_smoke(self, node: Node, make_client):
ws_client = await make_client()
# For consistency, the number of messages must not exceed the the protocol
# Subscriber queue_size.
NUM_MSGS = 10
Expand Down