Skip to content

Commit 2cceb34

Browse files
committed
Add timeout options to call_service messages
1 parent 460d202 commit 2cceb34

File tree

4 files changed

+39
-7
lines changed

4 files changed

+39
-7
lines changed

ROSBRIDGE_PROTOCOL.md

+3-1
Original file line numberDiff line numberDiff line change
@@ -436,7 +436,8 @@ Calls a ROS service.
436436
"service": <string>,
437437
(optional) "args": <list<json>>,
438438
(optional) "fragment_size": <int>,
439-
(optional) "compression": <string>
439+
(optional) "compression": <string>,
440+
(optional) "timeout": <float>
440441
}
441442
```
442443

@@ -449,6 +450,7 @@ Calls a ROS service.
449450
before it is fragmented
450451
* **compression** – an optional string to specify the compression scheme to be
451452
used on messages. Valid values are "none" and "png"
453+
* **timeout** – the time, in seconds, to wait for a response from the server
452454

453455

454456
Stops advertising an external ROS service server

rosbridge_library/src/rosbridge_library/capabilities/call_service.py

+9-1
Original file line numberDiff line numberDiff line change
@@ -81,6 +81,7 @@ def call_service(self, message):
8181
fragment_size = message.get("fragment_size", None)
8282
compression = message.get("compression", "none")
8383
args = message.get("args", [])
84+
timeout = message.get("timeout", 5.0)
8485

8586
if CallService.services_glob is not None and CallService.services_glob:
8687
self.protocol.log(
@@ -112,7 +113,14 @@ def call_service(self, message):
112113
e_cb = partial(self._failure, cid, service)
113114

114115
# Run service caller in the same thread.
115-
ServiceCaller(trim_servicename(service), args, s_cb, e_cb, self.protocol.node_handle).run()
116+
ServiceCaller(
117+
trim_servicename(service),
118+
args,
119+
timeout,
120+
s_cb,
121+
e_cb,
122+
self.protocol.node_handle,
123+
).run()
116124

117125
def _success(self, cid, service, fragment_size, compression, message):
118126
outgoing_message = {

rosbridge_library/src/rosbridge_library/internal/services.py

+25-5
Original file line numberDiff line numberDiff line change
@@ -58,6 +58,7 @@ def __init__(
5858
self,
5959
service: str,
6060
args: dict,
61+
timeout: float,
6162
success_callback: Callable[[str, str, int, bool, Any], None],
6263
error_callback: Callable[[str, str, Exception], None],
6364
node_handle: Node,
@@ -71,6 +72,7 @@ def __init__(
7172
ordered list, or a dict of name-value pairs. Anything else will be
7273
treated as though no arguments were provided (which is still valid for
7374
some kinds of service)
75+
timeout -- the time, in seconds, to wait for a response from the server
7476
success_callback -- a callback to call with the JSON result of the
7577
service call
7678
error_callback -- a callback to call if an error occurs. The
@@ -81,14 +83,22 @@ def __init__(
8183
self.daemon = True
8284
self.service = service
8385
self.args = args
86+
self.timeout = timeout
8487
self.success = success_callback
8588
self.error = error_callback
8689
self.node_handle = node_handle
8790

8891
def run(self) -> None:
8992
try:
9093
# Call the service and pass the result to the success handler
91-
self.success(call_service(self.node_handle, self.service, args=self.args))
94+
self.success(
95+
call_service(
96+
self.node_handle,
97+
self.service,
98+
args=self.args,
99+
server_response_timeout=self.timeout,
100+
)
101+
)
92102
except Exception as e:
93103
# On error, just pass the exception to the error handler
94104
self.error(e)
@@ -114,7 +124,8 @@ def call_service(
114124
node_handle: Node,
115125
service: str,
116126
args: Optional[dict] = None,
117-
server_timeout_time: float = 1.0,
127+
server_ready_timeout: float = 1.0,
128+
server_response_timeout: float = 5.0,
118129
sleep_time: float = 0.001,
119130
) -> dict:
120131
# Given the service name, fetch the type and class of the service,
@@ -141,20 +152,29 @@ def call_service(
141152
service_class, service, callback_group=ReentrantCallbackGroup()
142153
)
143154

144-
if not client.wait_for_service(server_timeout_time):
155+
if not client.wait_for_service(server_ready_timeout):
145156
node_handle.destroy_client(client)
146157
raise InvalidServiceException(service)
147158

148159
future = client.call_async(inst)
149-
while rclpy.ok() and not future.done():
160+
start_time = time.monotonic()
161+
while (
162+
rclpy.ok() and not future.done() and time.monotonic() - start_time < server_response_timeout
163+
):
150164
time.sleep(sleep_time)
165+
166+
if not future.done():
167+
future.cancel()
168+
node_handle.destroy_client(client)
169+
raise Exception("Timeout exceeded while waiting for service response")
170+
151171
result = future.result()
152172

153173
node_handle.destroy_client(client)
154174
if result is not None:
155175
# Turn the response into JSON and pass to the callback
156176
json_response = extract_values(result)
157177
else:
158-
raise Exception(result)
178+
raise Exception("Service call returned None")
159179

160180
return json_response

rosbridge_library/test/internal/services/test_services.py

+2
Original file line numberDiff line numberDiff line change
@@ -52,6 +52,7 @@ def start(self):
5252
thread = services.ServiceCaller(
5353
self.name,
5454
gen,
55+
5.0,
5556
self.success,
5657
self.error,
5758
self.node,
@@ -201,6 +202,7 @@ def error():
201202
services.ServiceCaller(
202203
self.node.get_name() + "/list_parameters",
203204
None,
205+
5.0,
204206
success,
205207
error,
206208
self.node,

0 commit comments

Comments
 (0)