diff --git a/rclpy/rclpy/client.py b/rclpy/rclpy/client.py index d4d7e5124..99bdce9b3 100644 --- a/rclpy/rclpy/client.py +++ b/rclpy/rclpy/client.py @@ -14,8 +14,10 @@ import threading import time +from types import TracebackType from typing import Dict from typing import Optional +from typing import Type from typing import TypeVar from rclpy.callback_groups import CallbackGroup @@ -224,3 +226,14 @@ def destroy(self): should call :meth:`.Node.destroy_client`. """ self.__client.destroy_when_not_in_use() + + def __enter__(self) -> 'Client': + return self + + def __exit__( + self, + exc_type: Optional[Type[BaseException]], + exc_val: Optional[BaseException], + exc_tb: Optional[TracebackType], + ) -> None: + self.destroy() diff --git a/rclpy/test/test_client.py b/rclpy/test/test_client.py index 556c32e2d..33f2d443e 100644 --- a/rclpy/test/test_client.py +++ b/rclpy/test/test_client.py @@ -242,6 +242,22 @@ def _service(request, response): self.node.destroy_client(cli) self.node.destroy_service(srv) + def test_sync_call_context_manager(self): + def _service(request, response): + return response + with self.node.create_client(GetParameters, 'get/parameters') as cli: + with self.node.create_service(GetParameters, 'get/parameters', _service): + self.assertTrue(cli.wait_for_service(timeout_sec=20)) + executor = rclpy.executors.SingleThreadedExecutor(context=self.context) + executor.add_node(self.node) + executor_thread = threading.Thread( + target=TestClient._spin_rclpy_node, args=(self.node, executor)) + executor_thread.start() + result = cli.call(GetParameters.Request(), 0.5) + self.assertTrue(result is not None) + executor.shutdown() + executor_thread.join() + if __name__ == '__main__': unittest.main()