You signed in with another tab or window. Reload to refresh your session.You signed out in another tab or window. Reload to refresh your session.You switched accounts on another tab or window. Reload to refresh your session.Dismiss alert
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
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.
The text was updated successfully, but these errors were encountered:
eska007
changed the title
Exception occurs when iterating witables in rclpy executors
Exception occurs when iterating waitables in rclpy executors
Dec 4, 2024
Bug report
Required Info:
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
CASE 2. InvalidHandle occurs in qos_event when spinning rclpy
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)
(TO-BE)
After applying the patch, the ros2-based node Linux service catches the RCL Exception and maintains the PID normally.
The text was updated successfully, but these errors were encountered: