Skip to content

Commit 0d96ae5

Browse files
MehsiasbjsowaMatthias Rathauscher (LWN)FlorianLebecque
authored
Prevent parameter retrieval crashes (#978)
* fix(params): prevent parameter retrieval crashes in ROS2 - Add check for node's fully qualified name to prevent deadlocks - Add 2.0s timeout to spin_until_future_complete - Fix crashes when retrieving parameters via Roslibjs Fixes #972 * added parameter for timeout * Add new service to retrieve the different interfaces in the ROS Network (#988) * Fix rosbridge_websocket symlink * Don't fail on nodes without parameter services * Remove added empty line --------- Co-authored-by: Błażej Sowa <bsowa123@gmail.com> Co-authored-by: Matthias Rathauscher (LWN) <matthias.rathauscher@liebherr.com> Co-authored-by: Lebecque Florian <Florianlebecque@hotmail.com>
1 parent 528b21f commit 0d96ae5

File tree

3 files changed

+21
-9
lines changed

3 files changed

+21
-9
lines changed

rosapi/scripts/rosapi_node

Lines changed: 4 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -78,6 +78,7 @@ class Rosapi(Node):
7878
self.declare_parameter("topics_glob", "[*]")
7979
self.declare_parameter("services_glob", "[*]")
8080
self.declare_parameter("params_glob", "[*]")
81+
self.declare_parameter("params_timeout", 5.0)
8182
self.globs = self.get_globs()
8283
self.register_services()
8384

@@ -88,7 +89,9 @@ class Rosapi(Node):
8889
full_name = self.get_namespace() + self.get_name()
8990
else:
9091
full_name = self.get_namespace() + "/" + self.get_name()
91-
params.init(full_name)
92+
93+
timeout_sec = self.get_parameter("params_timeout").value
94+
params.init(full_name, timeout_sec)
9295

9396
self.create_service(Topics, "~/topics", self.get_topics)
9497
self.create_service(Interfaces, "~/interfaces", self.get_interfaces)

rosapi/src/rosapi/params.py

Lines changed: 15 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -45,10 +45,14 @@
4545
""" Methods to interact with the param server. Values have to be passed
4646
as JSON in order to facilitate dynamically typed SRV messages """
4747

48+
# Constants
49+
DEFAULT_PARAM_TIMEOUT_SEC = 5.0
50+
4851
# Ensure thread safety for setting / getting parameters.
4952
param_server_lock = threading.RLock()
5053
_node = None
5154
_parent_node_name = ""
55+
_timeout_sec = DEFAULT_PARAM_TIMEOUT_SEC
5256

5357
_parameter_type_mapping = [
5458
"",
@@ -64,12 +68,12 @@
6468
]
6569

6670

67-
def init(parent_node_name):
71+
def init(parent_node_name, timeout_sec=DEFAULT_PARAM_TIMEOUT_SEC):
6872
"""
6973
Initializes params module with a rclpy.node.Node for further use.
7074
This function has to be called before any other for the module to work.
7175
"""
72-
global _node, _parent_node_name
76+
global _node, _parent_node_name, _timeout_sec
7377
# TODO(@jubeira): remove this node; use rosapi node with MultiThreadedExecutor or
7478
# async / await to prevent the service calls from blocking.
7579
parent_node_basename = parent_node_name.split("/")[-1]
@@ -81,6 +85,10 @@ def init(parent_node_name):
8185
)
8286
_parent_node_name = get_absolute_node_name(parent_node_name)
8387

88+
if not isinstance(timeout_sec, (int, float)) or timeout_sec <= 0:
89+
raise ValueError("Parameter timeout must be a positive number")
90+
_timeout_sec = timeout_sec
91+
8492

8593
def set_param(node_name, name, value, params_glob):
8694
"""Sets a parameter in a given node"""
@@ -226,21 +234,20 @@ def _get_param_names(node_name):
226234
# This method is called in a service callback; calling a service of the same node
227235
# will cause a deadlock.
228236
global _parent_node_name
229-
if node_name == _parent_node_name:
237+
if node_name == _parent_node_name or node_name == _node.get_fully_qualified_name():
230238
return []
231239

232240
client = _node.create_client(ListParameters, f"{node_name}/list_parameters")
233241

234-
ready = client.wait_for_service(timeout_sec=5.0)
235-
if not ready:
236-
raise RuntimeError("Wait for list_parameters service timed out")
242+
if not client.service_is_ready():
243+
return []
237244

238245
request = ListParameters.Request()
239246
future = client.call_async(request)
240247
if _node.executor:
241-
_node.executor.spin_until_future_complete(future)
248+
_node.executor.spin_until_future_complete(future, timeout_sec=_timeout_sec)
242249
else:
243-
rclpy.spin_until_future_complete(_node, future)
250+
rclpy.spin_until_future_complete(_node, future, timeout_sec=_timeout_sec)
244251
response = future.result()
245252

246253
if response is not None:

rosbridge_server/launch/rosbridge_websocket_launch.xml

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -23,6 +23,7 @@
2323
<arg name="topics_glob" default="" />
2424
<arg name="services_glob" default="" />
2525
<arg name="params_glob" default="" />
26+
<arg name="params_timeout" default="5.0" />
2627
<arg name="bson_only_mode" default="false" />
2728

2829
<arg name="respawn" default="false"/>
@@ -78,5 +79,6 @@
7879
<param name="topics_glob" value="$(var topics_glob)"/>
7980
<param name="services_glob" value="$(var services_glob)"/>
8081
<param name="params_glob" value="$(var params_glob)"/>
82+
<param name="params_timeout" value="$(var params_timeout)"/>
8183
</node>
8284
</launch>

0 commit comments

Comments
 (0)