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

Exception occurs when iterating waitables in rclpy executors #1385

Open
eska007 opened this issue Dec 4, 2024 · 1 comment
Open

Exception occurs when iterating waitables in rclpy executors #1385

eska007 opened this issue Dec 4, 2024 · 1 comment
Labels
more-information-needed Further information is required

Comments

@eska007
Copy link

eska007 commented Dec 4, 2024

Bug report

Required Info:

  • Operating System:
    • Ubuntu 22.04
  • Installation type:
    • binaries/source (both)
  • Version or commit hash:
    • humble
  • DDS implementation:
    • CycloneDDS
  • Client library (if applicable):
    • rclpy (5.3.8)

Steps to reproduce issue

The task of controlling the actual robot is implemented to create and destroy various service and action client objects at runtime based on the behavior tree. If the client object is repeatedly operated, the following error occurs. Since it is difficult to share the entire code of the related server and client, it can be reproduced by making the client side operate for a certain period of time in multi-threading based on the action and service type server/client sample code and then destroying it.

Expected behavior

When creating or destroying action and service client objects in multi-threads, an exception should not occur in the RCL layer.

Actual behavior

CASE 1. rclpy spin: Invalid pointer in action_client, rclpy._rclpy_pybind11.RCLError occurs

File "/opt/ros/humble/lib/python3.8/site-packages/rclpy/__init__.py", line 222, in spin
executor.spin_once()
"/opt/ros/humble/lib/python3.8/site-packages/rclpy/executors.py", line 739, in spin_once
self._spin_once_impl(timeout_sec)
"/opt/ros/humble/lib/python3.8/site-packages/rclpy/executors.py", line 728, in _spin_once_impl
handler, entity, node = self.wait_for_ready_callbacks(timeout_sec=timeout_sec)
"/opt/ros/humble/lib/python3.8/site-packages/rclpy/executors.py", line 711, in wait_for_ready_callbacks
return next(self._cb_iter)
"/opt/ros/humble/lib/python3.8/site-packages/rclpy/executors.py", line 605, in _wait_for_ready_callbacks
waitable.add_to_wait_set(wait_set)
"/opt/ros/humble/lib/python3.8/site-packages/rclpy/action/client.py", line 361, in add_to_wait_set
self._client_handle.add_to_waitset(wait_set)
rclpy._rclpy_pybind11.RCLError: Failed to add 'rcl_action_client_t' to wait set: action client pointer is invalid, at /home/hyundai/test/ros2_ws/src/rcl-5.3.8/rcl_action/src/rcl_action/action_client.c:470 

CASE 2. InvalidHandle occurs in qos_event when spinning rclpy

File "/opt/ros/humble/lib/python3.8/site-packages/rclpy/__init__.py", line 222, in spin
    executor.spin_once()
File "/opt/ros/humble/lib/python3.8/site-packages/rclpy/executors.py", line 739, in spin_once
    self._spin_once_impl(timeout_sec)
File "/opt/ros/humble/lib/python3.8/site-packages/rclpy/executors.py", line 728, in _spin_once_impl
    handler, entity, node = self.wait_for_ready_callbacks(timeout_sec=timeout_sec)
File "/opt/ros/humble/lib/python3.8/site-packages/rclpy/executors.py", line 711, in wait_for_ready_callbacks
    return next(self._cb_iter)
File "/opt/ros/humble/lib/python3.8/site-packages/rclpy/executors.py", line 605, in _wait_for_ready_callbacks
    waitable.add_to_wait_set(wait_set)  
File "/opt/ros/humble/lib/python3.8/site-packages/rclpy/qos_event.py", line 114, in add_to_wait_set
    with self.__event:
rclpy._rclpy_pybind11.InvalidHandle: cannot use Destroyable because destruction was requested

Additional information

It appears to be caused by a similar issue as below:
#1284

https://github.com/ros2/rclpy/blob/humble/rclpy/rclpy/executors.py#L605

(AS-IS)

for waitable in waitables:
    waitable.add_to_wait_set(wait_set)

(TO-BE)

#import rclpy
from rclpy._rclpy_pybind11 import RCLError

for waitable in waitables:
   try:
      waitable.add_to_wait_set(wait_set)
   except (RCLError, InvalidHandle) as e:
       pass
       #rclpy.logging.get_logger('executor').error(f'{e}')

After applying the patch, the ros2-based node Linux service catches the RCL Exception and maintains the PID normally.

@eska007 eska007 changed the title Exception occurs when iterating witables in rclpy executors Exception occurs when iterating waitables in rclpy executors Dec 4, 2024
@sloretz
Copy link
Contributor

sloretz commented Dec 13, 2024

humble

Do you see the same behavior in ROS Rolling?

except (RCLError, InvalidHandle) as e:

Ignoring InvalidHandle seems reasonable. Ignoring RCLError is probably not a good idea. That part of the bug we should get to the root cause on.

@sloretz sloretz added the more-information-needed Further information is required label Dec 13, 2024
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
more-information-needed Further information is required
Projects
None yet
Development

No branches or pull requests

2 participants