Skip to content

Commit

Permalink
New async rosapi params module implementation (#1001)
Browse files Browse the repository at this point in the history
* 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
  • Loading branch information
bjsowa authored Feb 17, 2025
1 parent 28d80f6 commit 52d39c1
Show file tree
Hide file tree
Showing 7 changed files with 295 additions and 127 deletions.
6 changes: 0 additions & 6 deletions rosapi/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -24,14 +24,8 @@
<exec_depend>rcl_interfaces</exec_depend>
<exec_depend>rosbridge_library</exec_depend>
<exec_depend>ros2node</exec_depend>
<exec_depend>ros2param</exec_depend>
<exec_depend>ros2pkg</exec_depend>
<exec_depend>ros2service</exec_depend>
<exec_depend>ros2topic</exec_depend>
<!--
<exec_depend>rosnode</exec_depend>
<exec_depend>rosgraph</exec_depend>
-->

<test_depend>ament_cmake_mypy</test_depend>
<test_depend>ament_cmake_pytest</test_depend>
Expand Down
112 changes: 90 additions & 22 deletions rosapi/scripts/rosapi_node
Original file line number Diff line number Diff line change
Expand Up @@ -33,10 +33,13 @@

import os
import sys
from json import dumps, loads

import rclpy
from rclpy.callback_groups import ReentrantCallbackGroup
from rclpy.clock import Clock, ClockType
from rclpy.node import Node
from rclpy.qos import qos_profile_parameters

from rosapi import glob_helper, objectutils, params, proxy
from rosapi_msgs.msg import TypeDef
Expand Down Expand Up @@ -85,13 +88,9 @@ class Rosapi(Node):
# Initialises the ROS node
def register_services(self):
proxy.init(self)
if self.get_namespace() == "/":
full_name = self.get_namespace() + self.get_name()
else:
full_name = self.get_namespace() + "/" + self.get_name()

timeout_sec = self.get_parameter("params_timeout").value
params.init(full_name, timeout_sec)
params.init(self, timeout_sec)

self.create_service(Topics, "~/topics", self.get_topics)
self.create_service(Interfaces, "~/interfaces", self.get_interfaces)
Expand Down Expand Up @@ -131,11 +130,41 @@ class Rosapi(Node):
"~/service_response_details",
self.get_service_response_details,
)
self.create_service(SetParam, "~/set_param", self.set_param)
self.create_service(GetParam, "~/get_param", self.get_param)
self.create_service(HasParam, "~/has_param", self.has_param)
self.create_service(DeleteParam, "~/delete_param", self.delete_param)
self.create_service(GetParamNames, "~/get_param_names", self.get_param_names)
self.create_service(
SetParam,
"~/set_param",
self.set_param,
callback_group=ReentrantCallbackGroup(),
qos_profile=qos_profile_parameters,
)
self.create_service(
GetParam,
"~/get_param",
self.get_param,
callback_group=ReentrantCallbackGroup(),
qos_profile=qos_profile_parameters,
)
self.create_service(
HasParam,
"~/has_param",
self.has_param,
callback_group=ReentrantCallbackGroup(),
qos_profile=qos_profile_parameters,
)
self.create_service(
DeleteParam,
"~/delete_param",
self.delete_param,
callback_group=ReentrantCallbackGroup(),
qos_profile=qos_profile_parameters,
)
self.create_service(
GetParamNames,
"~/get_param_names",
self.get_param_names,
callback_group=ReentrantCallbackGroup(),
qos_profile=qos_profile_parameters,
)
self.create_service(GetTime, "~/get_time", self.get_time)
self.create_service(GetROSVersion, "~/get_ros_version", self.get_ros_version)

Expand Down Expand Up @@ -262,38 +291,77 @@ class Rosapi(Node):
]
return response

def set_param(self, request, response):
async def set_param(self, request, response):
try:
node_name, param_name = self._get_node_and_param_name(request.name)
params.set_param(node_name, param_name, request.value, self.globs.params)
except ValueError:
self._print_malformed_param_name_warning(request.name)

try:
await params.set_param(node_name, param_name, request.value, self.globs.params)
except Exception as e:
response.successful = False
response.reason = str(e)
else:
response.successful = True

return response

def get_param(self, request, response):
async def get_param(self, request, response):
try:
node_name, param_name = self._get_node_and_param_name(request.name)
response.value = params.get_param(
node_name, param_name, request.default_value, self.globs.params
)
except ValueError:
self._print_malformed_param_name_warning(request.name)

try:
response.value = await params.get_param(node_name, param_name, self.globs.params)
except Exception as e:
response.successful = False
response.reason = str(e)

default = ""
if request.default_value != "":
try:
default = loads(request.default_value)
except ValueError:
self.get_logger().error(
"Failed to parse default value: {}".format(request.default_value)
)

response.value = dumps(default)
else:
response.successful = True

return response

def has_param(self, request, response):
async def has_param(self, request, response):
try:
node_name, param_name = self._get_node_and_param_name(request.name)
response.exists = params.has_param(node_name, param_name, self.globs.params)
except ValueError:
self._print_malformed_param_name_warning(request.name)

response.exists = await params.has_param(node_name, param_name, self.globs.params)

return response

def delete_param(self, request, response):
params.delete_param(request.node_name, request.name, self.globs.params)
async def delete_param(self, request, response):
try:
node_name, param_name = self._get_node_and_param_name(request.name)
except ValueError:
self._print_malformed_param_name_warning(request.name)

try:
await params.delete_param(node_name, param_name, self.globs.params)
except Exception as e:
response.successful = False
response.reason = str(e)
else:
response.successful = True

return response

def get_param_names(self, request, response):
response.names = params.get_param_names(self.globs.params)
async def get_param_names(self, request, response):
response.names = await params.get_param_names(self.globs.params)
return response

def get_time(self, request, response):
Expand Down
71 changes: 71 additions & 0 deletions rosapi/src/rosapi/async_helper.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,71 @@
# Software License Agreement (BSD License)
#
# Copyright (c) 2025, Fictionlab sp. z o.o.
# All rights reserved.
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
# are met:
#
# * Redistributions of source code must retain the above copyright
# notice, this list of conditions and the following disclaimer.
# * Redistributions in binary form must reproduce the above
# copyright notice, this list of conditions and the following
# disclaimer in the documentation and/or other materials provided
# with the distribution.
# * Neither the name of Willow Garage, Inc. nor the names of its
# contributors may be used to endorse or promote products derived
# from this software without specific prior written permission.
#
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
# LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
# CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# POSSIBILITY OF SUCH DAMAGE.

from rclpy.node import Node
from rclpy.task import Future


async def futures_wait_for(node: Node, futures: list[Future], timeout_sec: float):
"""Await a list of futures with a timeout."""
first_done_future: Future = Future()

def timeout_callback():
first_done_future.set_result(None)

timer = node.create_timer(timeout_sec, timeout_callback)

def future_done_callback(arg):
if all(future.done() for future in futures):
first_done_future.set_result(None)

for future in futures:
future.add_done_callback(future_done_callback)

await first_done_future

timer.cancel()
timer.destroy()


async def async_sleep(node: Node, delay_sec: float):
"""Block the coroutine for a given time."""
sleep_future: Future = Future()

def timeout_callback():
sleep_future.set_result(None)

timer = node.create_timer(delay_sec, timeout_callback)

await sleep_future

timer.cancel()
timer.destroy()
Loading

0 comments on commit 52d39c1

Please sign in to comment.