@@ -58,6 +58,7 @@ def __init__(
58
58
self ,
59
59
service : str ,
60
60
args : dict ,
61
+ timeout : float ,
61
62
success_callback : Callable [[str , str , int , bool , Any ], None ],
62
63
error_callback : Callable [[str , str , Exception ], None ],
63
64
node_handle : Node ,
@@ -71,6 +72,7 @@ def __init__(
71
72
ordered list, or a dict of name-value pairs. Anything else will be
72
73
treated as though no arguments were provided (which is still valid for
73
74
some kinds of service)
75
+ timeout -- the time, in seconds, to wait for a response from the server
74
76
success_callback -- a callback to call with the JSON result of the
75
77
service call
76
78
error_callback -- a callback to call if an error occurs. The
@@ -81,14 +83,22 @@ def __init__(
81
83
self .daemon = True
82
84
self .service = service
83
85
self .args = args
86
+ self .timeout = timeout
84
87
self .success = success_callback
85
88
self .error = error_callback
86
89
self .node_handle = node_handle
87
90
88
91
def run (self ) -> None :
89
92
try :
90
93
# 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
+ )
92
102
except Exception as e :
93
103
# On error, just pass the exception to the error handler
94
104
self .error (e )
@@ -114,7 +124,8 @@ def call_service(
114
124
node_handle : Node ,
115
125
service : str ,
116
126
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 ,
118
129
sleep_time : float = 0.001 ,
119
130
) -> dict :
120
131
# Given the service name, fetch the type and class of the service,
@@ -141,20 +152,29 @@ def call_service(
141
152
service_class , service , callback_group = ReentrantCallbackGroup ()
142
153
)
143
154
144
- if not client .wait_for_service (server_timeout_time ):
155
+ if not client .wait_for_service (server_ready_timeout ):
145
156
node_handle .destroy_client (client )
146
157
raise InvalidServiceException (service )
147
158
148
159
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
+ ):
150
164
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
+
151
171
result = future .result ()
152
172
153
173
node_handle .destroy_client (client )
154
174
if result is not None :
155
175
# Turn the response into JSON and pass to the callback
156
176
json_response = extract_values (result )
157
177
else :
158
- raise Exception (result )
178
+ raise Exception ("Service call returned None" )
159
179
160
180
return json_response
0 commit comments