Skip to content

Commit 367c39d

Browse files
authored
fix: Reduce idle CPU consumption of websocket server (backport #1040) (#1153)
1 parent 9a1b482 commit 367c39d

File tree

2 files changed

+45
-32
lines changed

2 files changed

+45
-32
lines changed

rosbridge_server/scripts/rosbridge_websocket.py

Lines changed: 35 additions & 27 deletions
Original file line numberDiff line numberDiff line change
@@ -34,16 +34,19 @@
3434
from __future__ import annotations
3535

3636
import argparse
37+
import asyncio
38+
import signal
3739
import sys
40+
import threading
3841
import time
3942
from typing import TYPE_CHECKING, cast
4043

4144
import rclpy
4245
from rcl_interfaces.msg import ParameterDescriptor
46+
from rclpy.executors import SingleThreadedExecutor
4347
from rclpy.node import Node
4448
from rclpy.utilities import remove_ros_args
4549
from tornado.httpserver import HTTPServer
46-
from tornado.ioloop import IOLoop, PeriodicCallback
4750
from tornado.netutil import bind_sockets
4851
from tornado.web import Application
4952

@@ -53,14 +56,6 @@
5356
from tornado.routing import _RuleList
5457

5558

56-
def start_hook() -> None:
57-
IOLoop.instance().start()
58-
59-
60-
def shutdown_hook() -> None:
61-
IOLoop.instance().stop()
62-
63-
6459
SERVER_PARAMETERS = (
6560
# Server parameters
6661
("port", int, 9090, "Port to listen on for WebSocket connections."),
@@ -132,6 +127,7 @@ def __init__(self) -> None:
132127

133128
RosbridgeWebSocket.node_handle = self
134129
RosbridgeWebSocket.client_manager = ClientManager(self)
130+
RosbridgeWebSocket.event_loop = asyncio.get_event_loop()
135131

136132
self._handle_parameters()
137133

@@ -230,30 +226,42 @@ def _start_server(self) -> None:
230226
time.sleep(self.retry_startup_delay)
231227

232228

233-
def main() -> None:
234-
rclpy.init()
229+
async def async_main() -> None:
230+
rclpy.init(args=sys.argv, signal_handler_options=rclpy.signals.SignalHandlerOptions.NO)
231+
235232
node = RosbridgeWebsocketNode()
236233

237-
executor = rclpy.executors.SingleThreadedExecutor()
234+
executor = SingleThreadedExecutor()
238235
executor.add_node(node)
239236

240-
def spin_ros() -> None:
241-
if not rclpy.ok():
242-
shutdown_hook()
237+
spin_thread = threading.Thread(target=executor.spin)
238+
spin_thread.start()
239+
240+
loop = asyncio.get_running_loop()
241+
stop_event = asyncio.Event()
242+
signal_handled = False
243+
244+
def handle_signal() -> None:
245+
nonlocal signal_handled
246+
if signal_handled:
243247
return
244-
executor.spin_once(timeout_sec=0.01)
245-
246-
spin_callback = PeriodicCallback(spin_ros, 1)
247-
spin_callback.start()
248-
try:
249-
start_hook()
250-
node.destroy_node()
251-
rclpy.shutdown()
252-
except KeyboardInterrupt:
253248
print("Exiting due to SIGINT")
254-
finally:
255-
spin_callback.stop()
256-
shutdown_hook() # shutdown hook to stop the server
249+
stop_event.set()
250+
executor.shutdown()
251+
signal_handled = True
252+
253+
for sig in (signal.SIGINT, signal.SIGTERM):
254+
loop.add_signal_handler(sig, handle_signal)
255+
256+
await stop_event.wait()
257+
spin_thread.join()
258+
259+
node.destroy_node()
260+
rclpy.shutdown()
261+
262+
263+
def main() -> None:
264+
asyncio.run(async_main())
257265

258266

259267
if __name__ == "__main__":

rosbridge_server/src/rosbridge_server/websocket_handler.py

Lines changed: 10 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -32,18 +32,19 @@
3232

3333
from __future__ import annotations
3434

35+
import asyncio
3536
import sys
3637
import threading
3738
import traceback
3839
import uuid
40+
from asyncio.events import AbstractEventLoop
3941
from collections import deque
40-
from functools import partial, wraps
42+
from functools import wraps
4143
from typing import TYPE_CHECKING, ClassVar, ParamSpec, TypeVar
4244

4345
from rclpy.node import Node
4446
from rosbridge_library.rosbridge_protocol import RosbridgeProtocol
4547
from rosbridge_library.util import bson
46-
from tornado.ioloop import IOLoop
4748
from tornado.iostream import StreamClosedError
4849
from tornado.websocket import WebSocketClosedError, WebSocketHandler
4950

@@ -52,8 +53,6 @@
5253

5354
from .client_manager import ClientManager
5455

55-
_io_loop = IOLoop.instance()
56-
5756

5857
def _log_exception() -> None:
5958
"""Log the most recent exception to ROS."""
@@ -132,6 +131,9 @@ class RosbridgeWebSocket(WebSocketHandler):
132131
# Class variable to manage connected clients
133132
client_manager: ClassVar[ClientManager | None] = None
134133

134+
# Event loop to run the coroutines on
135+
event_loop: ClassVar[AbstractEventLoop | None] = None
136+
135137
# Node handle to pass to RosbridgeProtocol when opening a connection
136138
node_handle: ClassVar[Node | None] = None
137139

@@ -189,12 +191,15 @@ def on_close(self) -> None:
189191
self.incoming_queue.finish()
190192

191193
def send_message(self, message: bson.BSON | bytearray | str, compression: str = "none") -> None:
194+
cls = self.__class__
195+
assert isinstance(cls.event_loop, AbstractEventLoop), "Event loop was not set"
196+
192197
if isinstance(message, bson.BSON) or compression in ["cbor", "cbor-raw"]:
193198
binary = True
194199
else:
195200
binary = False
196201

197-
_io_loop.add_callback(partial(self.prewrite_message, message, binary))
202+
asyncio.run_coroutine_threadsafe(self.prewrite_message(message, binary), cls.event_loop)
198203

199204
async def prewrite_message(self, message: bson.BSON | bytearray | str, binary: bool) -> None:
200205
cls = self.__class__

0 commit comments

Comments
 (0)