Skip to content

Commit e97c41b

Browse files
authored
Add an optional timeout_sec input to Client.call() to fix issue #1181 (#1188)
Signed-off-by: KKSTB <[email protected]>
1 parent f909278 commit e97c41b

File tree

2 files changed

+70
-4
lines changed

2 files changed

+70
-4
lines changed

rclpy/rclpy/client.py

Lines changed: 11 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -69,14 +69,19 @@ def __init__(
6969

7070
self._lock = threading.Lock()
7171

72-
def call(self, request: SrvTypeRequest) -> SrvTypeResponse:
72+
def call(
73+
self,
74+
request: SrvTypeRequest,
75+
timeout_sec: Optional[float] = None
76+
) -> Optional[SrvTypeResponse]:
7377
"""
7478
Make a service request and wait for the result.
7579
76-
.. warning:: Do not call this method in a callback or a deadlock may occur.
80+
.. warning:: Do not call this method in a callback, or a deadlock or timeout may occur.
7781
7882
:param request: The service request.
79-
:return: The service response.
83+
:param timeout_sec: Seconds to wait. If ``None``, then wait forever.
84+
:return: The service response, or None if timed out.
8085
:raises: TypeError if the type of the passed request isn't an instance
8186
of the Request type of the provided service when the client was
8287
constructed.
@@ -97,7 +102,9 @@ def unblock(future):
97102
# The callback might have been added after the future is completed,
98103
# resulting in the event never being set.
99104
if not future.done():
100-
event.wait()
105+
if not event.wait(timeout_sec):
106+
# Timed out. remove_pending_request() to free resources
107+
self.remove_pending_request(future)
101108
if future.exception() is not None:
102109
raise future.exception()
103110
return future.result()

rclpy/test/test_client.py

Lines changed: 59 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -13,12 +13,15 @@
1313
# limitations under the License.
1414

1515
import platform
16+
import threading
1617
import time
18+
import traceback
1719
import unittest
1820

1921
from rcl_interfaces.srv import GetParameters
2022
import rclpy
2123
import rclpy.executors
24+
import rclpy.node
2225
from rclpy.utilities import get_rmw_implementation_identifier
2326
from test_msgs.srv import Empty
2427

@@ -56,6 +59,21 @@ def do_test_service_name(cls, test_service_name_list):
5659
client.destroy()
5760
node.destroy_node()
5861

62+
@staticmethod
63+
def _spin_rclpy_node(
64+
rclpy_node: rclpy.node.Node,
65+
rclpy_executor: rclpy.executors.SingleThreadedExecutor
66+
) -> None:
67+
try:
68+
rclpy_executor.spin()
69+
except rclpy.executors.ExternalShutdownException:
70+
pass
71+
except Exception as err:
72+
traceback.print_exc()
73+
print(rclpy_node.get_name() + ': ' + str(err))
74+
print(rclpy_node.get_name() + ': rclpy_node exit')
75+
# rclpy_node.destroy_node()
76+
5977
def test_wait_for_service_5sec(self):
6078
cli = self.node.create_client(GetParameters, 'get/parameters')
6179
try:
@@ -183,6 +201,47 @@ def test_get_service_name_after_remapping(self):
183201
]
184202
TestClient.do_test_service_name(test_service_name_list)
185203

204+
def test_sync_call(self):
205+
def _service(request, response):
206+
return response
207+
cli = self.node.create_client(GetParameters, 'get/parameters')
208+
srv = self.node.create_service(GetParameters, 'get/parameters', _service)
209+
try:
210+
self.assertTrue(cli.wait_for_service(timeout_sec=20))
211+
executor = rclpy.executors.SingleThreadedExecutor(context=self.context)
212+
executor.add_node(self.node)
213+
executor_thread = threading.Thread(
214+
target=TestClient._spin_rclpy_node, args=(self.node, executor))
215+
executor_thread.start()
216+
result = cli.call(GetParameters.Request(), 0.5)
217+
self.assertTrue(result is not None)
218+
executor.shutdown()
219+
executor_thread.join()
220+
finally:
221+
self.node.destroy_client(cli)
222+
self.node.destroy_service(srv)
223+
224+
def test_sync_call_timeout(self):
225+
def _service(request, response):
226+
time.sleep(1)
227+
return response
228+
cli = self.node.create_client(GetParameters, 'get/parameters')
229+
srv = self.node.create_service(GetParameters, 'get/parameters', _service)
230+
try:
231+
self.assertTrue(cli.wait_for_service(timeout_sec=20))
232+
executor = rclpy.executors.SingleThreadedExecutor(context=self.context)
233+
executor.add_node(self.node)
234+
executor_thread = threading.Thread(
235+
target=TestClient._spin_rclpy_node, args=(self.node, executor))
236+
executor_thread.start()
237+
result = cli.call(GetParameters.Request(), 0.5)
238+
self.assertTrue(result is None)
239+
executor.shutdown()
240+
executor_thread.join()
241+
finally:
242+
self.node.destroy_client(cli)
243+
self.node.destroy_service(srv)
244+
186245

187246
if __name__ == '__main__':
188247
unittest.main()

0 commit comments

Comments
 (0)