Skip to content

Commit 52d39c1

Browse files
authored
New async rosapi params module implementation (#1001)
* New async rosapi params module implementation * Fail set_param if service not available * add missing endline * Don't use f-strings without placeholders * Fix bandit warning * Fix ament_mypy errors * Fix get_param when service not available * Return empty JSON string as value when get_param fails * Use ReentrantCallbackGroup for parameter services * Destroy parameter service clients * Add async_sleep helper coroutine * Use parameters QoS for param services * Add missing type annotation * Remove ros2param and ros2pkg dependencies * Use fully qualified instead of relative import * Add default_value field to GetParam interface
1 parent 28d80f6 commit 52d39c1

File tree

7 files changed

+295
-127
lines changed

7 files changed

+295
-127
lines changed

rosapi/package.xml

Lines changed: 0 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -24,14 +24,8 @@
2424
<exec_depend>rcl_interfaces</exec_depend>
2525
<exec_depend>rosbridge_library</exec_depend>
2626
<exec_depend>ros2node</exec_depend>
27-
<exec_depend>ros2param</exec_depend>
28-
<exec_depend>ros2pkg</exec_depend>
2927
<exec_depend>ros2service</exec_depend>
3028
<exec_depend>ros2topic</exec_depend>
31-
<!--
32-
<exec_depend>rosnode</exec_depend>
33-
<exec_depend>rosgraph</exec_depend>
34-
-->
3529

3630
<test_depend>ament_cmake_mypy</test_depend>
3731
<test_depend>ament_cmake_pytest</test_depend>

rosapi/scripts/rosapi_node

Lines changed: 90 additions & 22 deletions
Original file line numberDiff line numberDiff line change
@@ -33,10 +33,13 @@
3333

3434
import os
3535
import sys
36+
from json import dumps, loads
3637

3738
import rclpy
39+
from rclpy.callback_groups import ReentrantCallbackGroup
3840
from rclpy.clock import Clock, ClockType
3941
from rclpy.node import Node
42+
from rclpy.qos import qos_profile_parameters
4043

4144
from rosapi import glob_helper, objectutils, params, proxy
4245
from rosapi_msgs.msg import TypeDef
@@ -85,13 +88,9 @@ class Rosapi(Node):
8588
# Initialises the ROS node
8689
def register_services(self):
8790
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()
9291

9392
timeout_sec = self.get_parameter("params_timeout").value
94-
params.init(full_name, timeout_sec)
93+
params.init(self, timeout_sec)
9594

9695
self.create_service(Topics, "~/topics", self.get_topics)
9796
self.create_service(Interfaces, "~/interfaces", self.get_interfaces)
@@ -131,11 +130,41 @@ class Rosapi(Node):
131130
"~/service_response_details",
132131
self.get_service_response_details,
133132
)
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+
)
139168
self.create_service(GetTime, "~/get_time", self.get_time)
140169
self.create_service(GetROSVersion, "~/get_ros_version", self.get_ros_version)
141170

@@ -262,38 +291,77 @@ class Rosapi(Node):
262291
]
263292
return response
264293

265-
def set_param(self, request, response):
294+
async def set_param(self, request, response):
266295
try:
267296
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)
269297
except ValueError:
270298
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+
271308
return response
272309

273-
def get_param(self, request, response):
310+
async def get_param(self, request, response):
274311
try:
275312
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-
)
279313
except ValueError:
280314
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+
281335
return response
282336

283-
def has_param(self, request, response):
337+
async def has_param(self, request, response):
284338
try:
285339
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)
287340
except ValueError:
288341
self._print_malformed_param_name_warning(request.name)
342+
343+
response.exists = await params.has_param(node_name, param_name, self.globs.params)
344+
289345
return response
290346

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+
293361
return response
294362

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)
297365
return response
298366

299367
def get_time(self, request, response):

rosapi/src/rosapi/async_helper.py

Lines changed: 71 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,71 @@
1+
# Software License Agreement (BSD License)
2+
#
3+
# Copyright (c) 2025, Fictionlab sp. z o.o.
4+
# All rights reserved.
5+
#
6+
# Redistribution and use in source and binary forms, with or without
7+
# modification, are permitted provided that the following conditions
8+
# are met:
9+
#
10+
# * Redistributions of source code must retain the above copyright
11+
# notice, this list of conditions and the following disclaimer.
12+
# * Redistributions in binary form must reproduce the above
13+
# copyright notice, this list of conditions and the following
14+
# disclaimer in the documentation and/or other materials provided
15+
# with the distribution.
16+
# * Neither the name of Willow Garage, Inc. nor the names of its
17+
# contributors may be used to endorse or promote products derived
18+
# from this software without specific prior written permission.
19+
#
20+
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
21+
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
22+
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
23+
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
24+
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
25+
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
26+
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
27+
# LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
28+
# CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
29+
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
30+
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
31+
# POSSIBILITY OF SUCH DAMAGE.
32+
33+
from rclpy.node import Node
34+
from rclpy.task import Future
35+
36+
37+
async def futures_wait_for(node: Node, futures: list[Future], timeout_sec: float):
38+
"""Await a list of futures with a timeout."""
39+
first_done_future: Future = Future()
40+
41+
def timeout_callback():
42+
first_done_future.set_result(None)
43+
44+
timer = node.create_timer(timeout_sec, timeout_callback)
45+
46+
def future_done_callback(arg):
47+
if all(future.done() for future in futures):
48+
first_done_future.set_result(None)
49+
50+
for future in futures:
51+
future.add_done_callback(future_done_callback)
52+
53+
await first_done_future
54+
55+
timer.cancel()
56+
timer.destroy()
57+
58+
59+
async def async_sleep(node: Node, delay_sec: float):
60+
"""Block the coroutine for a given time."""
61+
sleep_future: Future = Future()
62+
63+
def timeout_callback():
64+
sleep_future.set_result(None)
65+
66+
timer = node.create_timer(delay_sec, timeout_callback)
67+
68+
await sleep_future
69+
70+
timer.cancel()
71+
timer.destroy()

0 commit comments

Comments
 (0)