|
34 | 34 | from __future__ import annotations |
35 | 35 |
|
36 | 36 | import argparse |
| 37 | +import asyncio |
| 38 | +import signal |
37 | 39 | import sys |
| 40 | +import threading |
38 | 41 | import time |
39 | 42 | from typing import TYPE_CHECKING, cast |
40 | 43 |
|
41 | 44 | import rclpy |
42 | 45 | from rcl_interfaces.msg import ParameterDescriptor |
| 46 | +from rclpy.executors import SingleThreadedExecutor |
43 | 47 | from rclpy.node import Node |
44 | 48 | from rclpy.utilities import remove_ros_args |
45 | 49 | from tornado.httpserver import HTTPServer |
46 | | -from tornado.ioloop import IOLoop, PeriodicCallback |
47 | 50 | from tornado.netutil import bind_sockets |
48 | 51 | from tornado.web import Application |
49 | 52 |
|
|
53 | 56 | from tornado.routing import _RuleList |
54 | 57 |
|
55 | 58 |
|
56 | | -def start_hook() -> None: |
57 | | - IOLoop.instance().start() |
58 | | - |
59 | | - |
60 | | -def shutdown_hook() -> None: |
61 | | - IOLoop.instance().stop() |
62 | | - |
63 | | - |
64 | 59 | SERVER_PARAMETERS = ( |
65 | 60 | # Server parameters |
66 | 61 | ("port", int, 9090, "Port to listen on for WebSocket connections."), |
@@ -132,6 +127,7 @@ def __init__(self) -> None: |
132 | 127 |
|
133 | 128 | RosbridgeWebSocket.node_handle = self |
134 | 129 | RosbridgeWebSocket.client_manager = ClientManager(self) |
| 130 | + RosbridgeWebSocket.event_loop = asyncio.get_event_loop() |
135 | 131 |
|
136 | 132 | self._handle_parameters() |
137 | 133 | self._check_deprecated_parameters() |
@@ -256,30 +252,42 @@ def _check_deprecated_parameters(self) -> None: |
256 | 252 | ) |
257 | 253 |
|
258 | 254 |
|
259 | | -def main() -> None: |
260 | | - rclpy.init() |
| 255 | +async def async_main() -> None: |
| 256 | + rclpy.init(args=sys.argv, signal_handler_options=rclpy.signals.SignalHandlerOptions.NO) |
| 257 | + |
261 | 258 | node = RosbridgeWebsocketNode() |
262 | 259 |
|
263 | | - executor = rclpy.executors.SingleThreadedExecutor() |
| 260 | + executor = SingleThreadedExecutor() |
264 | 261 | executor.add_node(node) |
265 | 262 |
|
266 | | - def spin_ros() -> None: |
267 | | - if not rclpy.ok(): |
268 | | - shutdown_hook() |
| 263 | + spin_thread = threading.Thread(target=executor.spin) |
| 264 | + spin_thread.start() |
| 265 | + |
| 266 | + loop = asyncio.get_running_loop() |
| 267 | + stop_event = asyncio.Event() |
| 268 | + signal_handled = False |
| 269 | + |
| 270 | + def handle_signal() -> None: |
| 271 | + nonlocal signal_handled |
| 272 | + if signal_handled: |
269 | 273 | return |
270 | | - executor.spin_once(timeout_sec=0.01) |
271 | | - |
272 | | - spin_callback = PeriodicCallback(spin_ros, 1) |
273 | | - spin_callback.start() |
274 | | - try: |
275 | | - start_hook() |
276 | | - node.destroy_node() |
277 | | - rclpy.shutdown() |
278 | | - except KeyboardInterrupt: |
279 | 274 | print("Exiting due to SIGINT") |
280 | | - finally: |
281 | | - spin_callback.stop() |
282 | | - shutdown_hook() # shutdown hook to stop the server |
| 275 | + stop_event.set() |
| 276 | + executor.shutdown() |
| 277 | + signal_handled = True |
| 278 | + |
| 279 | + for sig in (signal.SIGINT, signal.SIGTERM): |
| 280 | + loop.add_signal_handler(sig, handle_signal) |
| 281 | + |
| 282 | + await stop_event.wait() |
| 283 | + spin_thread.join() |
| 284 | + |
| 285 | + node.destroy_node() |
| 286 | + rclpy.shutdown() |
| 287 | + |
| 288 | + |
| 289 | +def main() -> None: |
| 290 | + asyncio.run(async_main()) |
283 | 291 |
|
284 | 292 |
|
285 | 293 | if __name__ == "__main__": |
|
0 commit comments