|
33 | 33 |
|
34 | 34 | import os |
35 | 35 | import sys |
| 36 | +from json import dumps, loads |
36 | 37 |
|
37 | 38 | import rclpy |
| 39 | +from rclpy.callback_groups import ReentrantCallbackGroup |
38 | 40 | from rclpy.clock import Clock, ClockType |
39 | 41 | from rclpy.node import Node |
| 42 | +from rclpy.qos import qos_profile_parameters |
40 | 43 |
|
41 | 44 | from rosapi import glob_helper, objectutils, params, proxy |
42 | 45 | from rosapi_msgs.msg import TypeDef |
@@ -85,13 +88,9 @@ class Rosapi(Node): |
85 | 88 | # Initialises the ROS node |
86 | 89 | def register_services(self): |
87 | 90 | proxy.init(self) |
88 | | - if self.get_namespace() == "/": |
89 | | - full_name = self.get_namespace() + self.get_name() |
90 | | - else: |
91 | | - full_name = self.get_namespace() + "/" + self.get_name() |
92 | 91 |
|
93 | 92 | timeout_sec = self.get_parameter("params_timeout").value |
94 | | - params.init(full_name, timeout_sec) |
| 93 | + params.init(self, timeout_sec) |
95 | 94 |
|
96 | 95 | self.create_service(Topics, "~/topics", self.get_topics) |
97 | 96 | self.create_service(Interfaces, "~/interfaces", self.get_interfaces) |
@@ -131,11 +130,41 @@ class Rosapi(Node): |
131 | 130 | "~/service_response_details", |
132 | 131 | self.get_service_response_details, |
133 | 132 | ) |
134 | | - self.create_service(SetParam, "~/set_param", self.set_param) |
135 | | - self.create_service(GetParam, "~/get_param", self.get_param) |
136 | | - self.create_service(HasParam, "~/has_param", self.has_param) |
137 | | - self.create_service(DeleteParam, "~/delete_param", self.delete_param) |
138 | | - self.create_service(GetParamNames, "~/get_param_names", self.get_param_names) |
| 133 | + self.create_service( |
| 134 | + SetParam, |
| 135 | + "~/set_param", |
| 136 | + self.set_param, |
| 137 | + callback_group=ReentrantCallbackGroup(), |
| 138 | + qos_profile=qos_profile_parameters, |
| 139 | + ) |
| 140 | + self.create_service( |
| 141 | + GetParam, |
| 142 | + "~/get_param", |
| 143 | + self.get_param, |
| 144 | + callback_group=ReentrantCallbackGroup(), |
| 145 | + qos_profile=qos_profile_parameters, |
| 146 | + ) |
| 147 | + self.create_service( |
| 148 | + HasParam, |
| 149 | + "~/has_param", |
| 150 | + self.has_param, |
| 151 | + callback_group=ReentrantCallbackGroup(), |
| 152 | + qos_profile=qos_profile_parameters, |
| 153 | + ) |
| 154 | + self.create_service( |
| 155 | + DeleteParam, |
| 156 | + "~/delete_param", |
| 157 | + self.delete_param, |
| 158 | + callback_group=ReentrantCallbackGroup(), |
| 159 | + qos_profile=qos_profile_parameters, |
| 160 | + ) |
| 161 | + self.create_service( |
| 162 | + GetParamNames, |
| 163 | + "~/get_param_names", |
| 164 | + self.get_param_names, |
| 165 | + callback_group=ReentrantCallbackGroup(), |
| 166 | + qos_profile=qos_profile_parameters, |
| 167 | + ) |
139 | 168 | self.create_service(GetTime, "~/get_time", self.get_time) |
140 | 169 | self.create_service(GetROSVersion, "~/get_ros_version", self.get_ros_version) |
141 | 170 |
|
@@ -262,38 +291,77 @@ class Rosapi(Node): |
262 | 291 | ] |
263 | 292 | return response |
264 | 293 |
|
265 | | - def set_param(self, request, response): |
| 294 | + async def set_param(self, request, response): |
266 | 295 | try: |
267 | 296 | node_name, param_name = self._get_node_and_param_name(request.name) |
268 | | - params.set_param(node_name, param_name, request.value, self.globs.params) |
269 | 297 | except ValueError: |
270 | 298 | self._print_malformed_param_name_warning(request.name) |
| 299 | + |
| 300 | + try: |
| 301 | + await params.set_param(node_name, param_name, request.value, self.globs.params) |
| 302 | + except Exception as e: |
| 303 | + response.successful = False |
| 304 | + response.reason = str(e) |
| 305 | + else: |
| 306 | + response.successful = True |
| 307 | + |
271 | 308 | return response |
272 | 309 |
|
273 | | - def get_param(self, request, response): |
| 310 | + async def get_param(self, request, response): |
274 | 311 | try: |
275 | 312 | node_name, param_name = self._get_node_and_param_name(request.name) |
276 | | - response.value = params.get_param( |
277 | | - node_name, param_name, request.default_value, self.globs.params |
278 | | - ) |
279 | 313 | except ValueError: |
280 | 314 | self._print_malformed_param_name_warning(request.name) |
| 315 | + |
| 316 | + try: |
| 317 | + response.value = await params.get_param(node_name, param_name, self.globs.params) |
| 318 | + except Exception as e: |
| 319 | + response.successful = False |
| 320 | + response.reason = str(e) |
| 321 | + |
| 322 | + default = "" |
| 323 | + if request.default_value != "": |
| 324 | + try: |
| 325 | + default = loads(request.default_value) |
| 326 | + except ValueError: |
| 327 | + self.get_logger().error( |
| 328 | + "Failed to parse default value: {}".format(request.default_value) |
| 329 | + ) |
| 330 | + |
| 331 | + response.value = dumps(default) |
| 332 | + else: |
| 333 | + response.successful = True |
| 334 | + |
281 | 335 | return response |
282 | 336 |
|
283 | | - def has_param(self, request, response): |
| 337 | + async def has_param(self, request, response): |
284 | 338 | try: |
285 | 339 | node_name, param_name = self._get_node_and_param_name(request.name) |
286 | | - response.exists = params.has_param(node_name, param_name, self.globs.params) |
287 | 340 | except ValueError: |
288 | 341 | self._print_malformed_param_name_warning(request.name) |
| 342 | + |
| 343 | + response.exists = await params.has_param(node_name, param_name, self.globs.params) |
| 344 | + |
289 | 345 | return response |
290 | 346 |
|
291 | | - def delete_param(self, request, response): |
292 | | - params.delete_param(request.node_name, request.name, self.globs.params) |
| 347 | + async def delete_param(self, request, response): |
| 348 | + try: |
| 349 | + node_name, param_name = self._get_node_and_param_name(request.name) |
| 350 | + except ValueError: |
| 351 | + self._print_malformed_param_name_warning(request.name) |
| 352 | + |
| 353 | + try: |
| 354 | + await params.delete_param(node_name, param_name, self.globs.params) |
| 355 | + except Exception as e: |
| 356 | + response.successful = False |
| 357 | + response.reason = str(e) |
| 358 | + else: |
| 359 | + response.successful = True |
| 360 | + |
293 | 361 | return response |
294 | 362 |
|
295 | | - def get_param_names(self, request, response): |
296 | | - response.names = params.get_param_names(self.globs.params) |
| 363 | + async def get_param_names(self, request, response): |
| 364 | + response.names = await params.get_param_names(self.globs.params) |
297 | 365 | return response |
298 | 366 |
|
299 | 367 | def get_time(self, request, response): |
|
0 commit comments