26
26
)
27
27
28
28
import rclpy
29
+ import yaml
30
+ from rcl_interfaces .msg import Parameter
29
31
32
+ # @note: The versions conditioning is added here to support the source-compatibility with Humble
33
+ # The `get_parameter_value` function is moved to `rclpy.parameter` module from `ros2param.api` module from version 3.6.0
34
+ try :
35
+ from rclpy .parameter import get_parameter_value
36
+ except ImportError :
37
+ from ros2param .api import get_parameter_value
38
+ from ros2param .api import call_set_parameters
30
39
31
- def service_caller (node , service_name , service_type , request , service_timeout = 10.0 ):
40
+
41
+ # from https://stackoverflow.com/a/287944
42
+ class bcolors :
43
+ MAGENTA = "\033 [95m"
44
+ OKBLUE = "\033 [94m"
45
+ OKCYAN = "\033 [96m"
46
+ OKGREEN = "\033 [92m"
47
+ WARNING = "\033 [93m"
48
+ FAIL = "\033 [91m"
49
+ ENDC = "\033 [0m"
50
+ BOLD = "\033 [1m"
51
+ UNDERLINE = "\033 [4m"
52
+
53
+
54
+ class ServiceNotFoundError (Exception ):
55
+ pass
56
+
57
+
58
+ def service_caller (
59
+ node ,
60
+ service_name ,
61
+ service_type ,
62
+ request ,
63
+ service_timeout = 0.0 ,
64
+ call_timeout = 10.0 ,
65
+ max_attempts = 3 ,
66
+ ):
67
+ """
68
+ Abstraction of a service call.
69
+
70
+ Has an optional timeout to find the service, receive the answer to a call
71
+ and a mechanism to retry a call of no response is received.
72
+
73
+ @param node Node object to be associated with
74
+ @type rclpy.node.Node
75
+ @param service_name Service URL
76
+ @type str
77
+ @param request The request to be sent
78
+ @type service request type
79
+ @param service_timeout Timeout (in seconds) to wait until the service is available. 0 means
80
+ waiting forever, retrying every 10 seconds.
81
+ @type float
82
+ @param call_timeout Timeout (in seconds) for getting a response
83
+ @type float
84
+ @param max_attempts Number of attempts until a valid response is received. With some
85
+ middlewares it can happen, that the service response doesn't reach the client leaving it in
86
+ a waiting state forever.
87
+ @type int
88
+ @return The service response
89
+
90
+ """
32
91
cli = node .create_client (service_type , service_name )
33
92
34
- if not cli .service_is_ready ():
35
- node .get_logger ().debug (
36
- f"waiting { service_timeout } seconds for service { service_name } to become available..."
37
- )
38
- if not cli .wait_for_service (service_timeout ):
39
- raise RuntimeError (f"Could not contact service { service_name } " )
93
+ while not cli .service_is_ready ():
94
+ node .get_logger ().info (f"waiting for service { service_name } to become available..." )
95
+ if service_timeout :
96
+ if not cli .wait_for_service (service_timeout ):
97
+ raise ServiceNotFoundError (f"Could not contact service { service_name } " )
98
+ elif not cli .wait_for_service (10.0 ):
99
+ node .get_logger ().warn (f"Could not contact service { service_name } " )
40
100
41
101
node .get_logger ().debug (f"requester: making request: { request } \n " )
42
- future = cli .call_async (request )
43
- rclpy .spin_until_future_complete (node , future )
44
- if future .result () is not None :
45
- return future .result ()
46
- else :
47
- raise RuntimeError (f"Exception while calling service: { future .exception ()} " )
102
+ future = None
103
+ for attempt in range (max_attempts ):
104
+ future = cli .call_async (request )
105
+ rclpy .spin_until_future_complete (node , future , timeout_sec = call_timeout )
106
+ if future .result () is None :
107
+ node .get_logger ().warning (
108
+ f"Failed getting a result from calling { service_name } in "
109
+ f"{ service_timeout } . (Attempt { attempt + 1 } of { max_attempts } .)"
110
+ )
111
+ else :
112
+ return future .result ()
113
+ raise RuntimeError (
114
+ f"Could not successfully call service { service_name } after { max_attempts } attempts."
115
+ )
48
116
49
117
50
- def configure_controller (node , controller_manager_name , controller_name , service_timeout = 10 .0 ):
118
+ def configure_controller (node , controller_manager_name , controller_name , service_timeout = 0 .0 ):
51
119
request = ConfigureController .Request ()
52
120
request .name = controller_name
53
121
return service_caller (
@@ -59,7 +127,7 @@ def configure_controller(node, controller_manager_name, controller_name, service
59
127
)
60
128
61
129
62
- def list_controllers (node , controller_manager_name , service_timeout = 10 .0 ):
130
+ def list_controllers (node , controller_manager_name , service_timeout = 0 .0 ):
63
131
request = ListControllers .Request ()
64
132
return service_caller (
65
133
node ,
@@ -70,7 +138,7 @@ def list_controllers(node, controller_manager_name, service_timeout=10.0):
70
138
)
71
139
72
140
73
- def list_controller_types (node , controller_manager_name , service_timeout = 10 .0 ):
141
+ def list_controller_types (node , controller_manager_name , service_timeout = 0 .0 ):
74
142
request = ListControllerTypes .Request ()
75
143
return service_caller (
76
144
node ,
@@ -81,7 +149,7 @@ def list_controller_types(node, controller_manager_name, service_timeout=10.0):
81
149
)
82
150
83
151
84
- def list_hardware_components (node , controller_manager_name , service_timeout = 10 .0 ):
152
+ def list_hardware_components (node , controller_manager_name , service_timeout = 0 .0 ):
85
153
request = ListHardwareComponents .Request ()
86
154
return service_caller (
87
155
node ,
@@ -92,7 +160,7 @@ def list_hardware_components(node, controller_manager_name, service_timeout=10.0
92
160
)
93
161
94
162
95
- def list_hardware_interfaces (node , controller_manager_name , service_timeout = 10 .0 ):
163
+ def list_hardware_interfaces (node , controller_manager_name , service_timeout = 0 .0 ):
96
164
request = ListHardwareInterfaces .Request ()
97
165
return service_caller (
98
166
node ,
@@ -103,7 +171,7 @@ def list_hardware_interfaces(node, controller_manager_name, service_timeout=10.0
103
171
)
104
172
105
173
106
- def load_controller (node , controller_manager_name , controller_name , service_timeout = 10 .0 ):
174
+ def load_controller (node , controller_manager_name , controller_name , service_timeout = 0 .0 ):
107
175
request = LoadController .Request ()
108
176
request .name = controller_name
109
177
return service_caller (
@@ -115,7 +183,7 @@ def load_controller(node, controller_manager_name, controller_name, service_time
115
183
)
116
184
117
185
118
- def reload_controller_libraries (node , controller_manager_name , force_kill , service_timeout = 10 .0 ):
186
+ def reload_controller_libraries (node , controller_manager_name , force_kill , service_timeout = 0 .0 ):
119
187
request = ReloadControllerLibraries .Request ()
120
188
request .force_kill = force_kill
121
189
return service_caller (
@@ -128,7 +196,7 @@ def reload_controller_libraries(node, controller_manager_name, force_kill, servi
128
196
129
197
130
198
def set_hardware_component_state (
131
- node , controller_manager_name , component_name , lifecyle_state , service_timeout = 10 .0
199
+ node , controller_manager_name , component_name , lifecyle_state , service_timeout = 0 .0
132
200
):
133
201
request = SetHardwareComponentState .Request ()
134
202
request .name = component_name
@@ -165,7 +233,7 @@ def switch_controllers(
165
233
)
166
234
167
235
168
- def unload_controller (node , controller_manager_name , controller_name , service_timeout = 10 .0 ):
236
+ def unload_controller (node , controller_manager_name , controller_name , service_timeout = 0 .0 ):
169
237
request = UnloadController .Request ()
170
238
request .name = controller_name
171
239
return service_caller (
@@ -175,3 +243,97 @@ def unload_controller(node, controller_manager_name, controller_name, service_ti
175
243
request ,
176
244
service_timeout ,
177
245
)
246
+
247
+
248
+ def get_parameter_from_param_file (controller_name , namespace , parameter_file , parameter_name ):
249
+ with open (parameter_file ) as f :
250
+ namespaced_controller = (
251
+ controller_name if namespace == "/" else f"{ namespace } /{ controller_name } "
252
+ )
253
+ parameters = yaml .safe_load (f )
254
+ if namespaced_controller in parameters :
255
+ value = parameters [namespaced_controller ]
256
+ if not isinstance (value , dict ) or "ros__parameters" not in value :
257
+ raise RuntimeError (
258
+ f"YAML file : { parameter_file } is not a valid ROS parameter file for controller : { namespaced_controller } "
259
+ )
260
+ if parameter_name in parameters [namespaced_controller ]["ros__parameters" ]:
261
+ return parameters [namespaced_controller ]["ros__parameters" ][parameter_name ]
262
+ else :
263
+ return None
264
+ else :
265
+ return None
266
+
267
+
268
+ def set_controller_parameters (
269
+ node , controller_manager_name , controller_name , parameter_name , parameter_value
270
+ ):
271
+ parameter = Parameter ()
272
+ parameter .name = controller_name + "." + parameter_name
273
+ parameter_string = str (parameter_value )
274
+ parameter .value = get_parameter_value (string_value = parameter_string )
275
+
276
+ response = call_set_parameters (
277
+ node = node , node_name = controller_manager_name , parameters = [parameter ]
278
+ )
279
+ assert len (response .results ) == 1
280
+ result = response .results [0 ]
281
+ if result .successful :
282
+ node .get_logger ().info (
283
+ bcolors .OKCYAN
284
+ + 'Setting controller param "'
285
+ + parameter_name
286
+ + '" to "'
287
+ + parameter_string
288
+ + '" for '
289
+ + bcolors .BOLD
290
+ + controller_name
291
+ + bcolors .ENDC
292
+ )
293
+ else :
294
+ node .get_logger ().fatal (
295
+ bcolors .FAIL
296
+ + 'Could not set controller param "'
297
+ + parameter_name
298
+ + '" to "'
299
+ + parameter_string
300
+ + '" for '
301
+ + bcolors .BOLD
302
+ + controller_name
303
+ + bcolors .ENDC
304
+ )
305
+ return False
306
+ return True
307
+
308
+
309
+ def set_controller_parameters_from_param_file (
310
+ node , controller_manager_name , controller_name , parameter_file , namespace = None
311
+ ):
312
+ if parameter_file :
313
+ spawner_namespace = namespace if namespace else node .get_namespace ()
314
+ set_controller_parameters (
315
+ node , controller_manager_name , controller_name , "params_file" , parameter_file
316
+ )
317
+
318
+ controller_type = get_parameter_from_param_file (
319
+ controller_name , spawner_namespace , parameter_file , "type"
320
+ )
321
+ if controller_type :
322
+ if not set_controller_parameters (
323
+ node , controller_manager_name , controller_name , "type" , controller_type
324
+ ):
325
+ return False
326
+
327
+ fallback_controllers = get_parameter_from_param_file (
328
+ controller_name , spawner_namespace , parameter_file , "fallback_controllers"
329
+ )
330
+ if fallback_controllers :
331
+ if not set_controller_parameters (
332
+ node ,
333
+ controller_manager_name ,
334
+ controller_name ,
335
+ "fallback_controllers" ,
336
+ fallback_controllers ,
337
+ ):
338
+ return False
339
+ return True
0 commit comments