Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

fix(params): prevent parameter retrieval crashes in ROS2 #978

Open
wants to merge 6 commits into
base: ros2
Choose a base branch
from

Conversation

Mehsias
Copy link

@Mehsias Mehsias commented Dec 5, 2024

Public API Changes
None

Description

  • Add check for node's fully qualified name to prevent deadlocks
  • Add 2.0s timeout to spin_until_future_complete to avoid endless loop
  • Fix crashes when retrieving parameters via Roslibjs

Fixes #972

Mehsias and others added 2 commits December 5, 2024 09:57
- 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 RobotWebTools#972
@Mehsias Mehsias force-pushed the fix/issue-972-parameter-retrieval branch from 237d668 to fbed931 Compare January 13, 2025 14:45
@Mehsias Mehsias requested a review from sea-bass January 17, 2025 06:34
@Mehsias
Copy link
Author

Mehsias commented Jan 17, 2025

@sea-bass I don't know what I did to break the whole CI. I force pushed a squashed commit because the linter check was failing, and now everything is failing.

@bjsowa
Copy link
Collaborator

bjsowa commented Jan 17, 2025

You somehow broke the rosbridge_websocket symlink. I can fix it if you want.

Comment on lines +242 to 244
ready = client.wait_for_service(timeout_sec=_timeout_sec)
if not ready:
raise RuntimeError("Wait for list_parameters service timed out")
Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

This function can crash if the wait_for_service call fails as the RuntimeError is not catched anywhere. The easiest way to make this call fail is to have a node which doesn't start it's parameter services. Here's an example:

import rclpy
rclpy.init();
node = rclpy.create_node('rosapi_test_node', start_parameter_services=False)
rclpy.spin(node)

As this is still related to the issue you are trying to fix (crashes during parameter retrieval), could you also fix that?

IMO we shouldn't wait 5 seconds for service to become available as this will greatly increase the response time when we are running nodes without parameter servers. If we assume the rosapi node has enough time to spin and gather information about the ROS graph, we should be good with just returning an empty list if the list_parameters service is not available right away:

Suggested change
ready = client.wait_for_service(timeout_sec=_timeout_sec)
if not ready:
raise RuntimeError("Wait for list_parameters service timed out")
if not client.service_is_ready():
return []

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

Successfully merging this pull request may close these issues.

ROS2 humble getParams
4 participants