Skip to content

Missing attribute self._tasks when running executor AutoScalingMultiThreadedExecutor.shutdown() in ROS 2 Jazy #197

@zmk5

Description

@zmk5

Bug description

Platform:

  • OS: Ubuntu Noble
  • ROS: Jazzy
  • proto2ros version: Not Sure

How to reproduce

I currently followed this Dockerfile to build spot_ros2 in jazzy. I went through the installation and it was successful. However, when attempting to run the spot_driver via the launch file (ros2 launch spot_driver spot_driver.launch.py) I noticed two nodes failing,spot_alerts and spot_ros2, with the same failure:

[spot_alerts-6] Traceback (most recent call last):
[spot_alerts-6]   File "/spot_ws/install/spot_driver/lib/spot_driver/spot_alerts", line 56, in <module>
[spot_alerts-6]     main()
[spot_alerts-6]   File "/spot_ws/install/synchros2/lib/python3.12/site-packages/synchros2/process.py", line 190, in __call__
[spot_alerts-6]     with scope.top(argv, global_=True, interruptible=self._interruptible, **scope_kwargs) as self._scope:
[spot_alerts-6]   File "/usr/lib/python3.12/contextlib.py", line 158, in __exit__
[spot_alerts-6]     self.gen.throw(value)
[spot_alerts-6]   File "/spot_ws/install/synchros2/lib/python3.12/site-packages/synchros2/scope.py", line 556, in top
[spot_alerts-6]     stack.close()
[spot_alerts-6]   File "/usr/lib/python3.12/contextlib.py", line 618, in close
[spot_alerts-6]     self.__exit__(None, None, None)
[spot_alerts-6]   File "/usr/lib/python3.12/contextlib.py", line 610, in __exit__
[spot_alerts-6]     raise exc_details[1]
[spot_alerts-6]   File "/usr/lib/python3.12/contextlib.py", line 595, in __exit__
[spot_alerts-6]     if cb(*exc_details):
[spot_alerts-6]        ^^^^^^^^^^^^^^^^
[spot_alerts-6]   File "/spot_ws/install/synchros2/lib/python3.12/site-packages/synchros2/scope.py", line 165, in __exit__
[spot_alerts-6]     self._stack.close()
[spot_alerts-6]   File "/usr/lib/python3.12/contextlib.py", line 618, in close
[spot_alerts-6]     self.__exit__(None, None, None)
[spot_alerts-6]   File "/usr/lib/python3.12/contextlib.py", line 610, in __exit__                                                                                                                                     [spot_alerts-6]     raise exc_details[1]
[spot_alerts-6]   File "/usr/lib/python3.12/contextlib.py", line 595, in __exit__
[spot_alerts-6]     if cb(*exc_details):
[spot_alerts-6]        ^^^^^^^^^^^^^^^^
[spot_alerts-6]   File "/usr/lib/python3.12/contextlib.py", line 144, in __exit__
[spot_alerts-6]     next(self.gen)
[spot_alerts-6]   File "/spot_ws/install/synchros2/lib/python3.12/site-packages/synchros2/executors.py", line 837, in foreground
[spot_alerts-6]     if not executor.shutdown(timeout_sec=5.0):
[spot_alerts-6]            ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
[spot_alerts-6]   File "/spot_ws/install/synchros2/lib/python3.12/site-packages/synchros2/executors.py", line 768, in shutdown
[spot_alerts-6]     AutoScalingMultiThreadedExecutor.Task(task, entity, node) for task, entity, node in self._tasks
[spot_alerts-6]                                                                                         ^^^^^^^^^^^
[spot_alerts-6] AttributeError: 'AutoScalingMultiThreadedExecutor' object has no attribute '_tasks'
[ERROR] [spot_alerts-6]: process has died [pid 1067, exit code 1, cmd '/spot_ws/install/spot_driver/lib/spot_driver/spot_alerts --ros-args -r __node:=spot_alerts -r __ns:=/ -p use_sim_time:=False'].

and

[spot_ros2-1] [INFO] [1771893748.237147771] [spot_ros2]: Hi from spot_driver.
[spot_ros2-1] [INFO] [1771893748.273824298] [spot_ros2]: Starting ROS driver for Spot
[spot_ros2-1] [INFO] [1771893748.899415629] [spot_ros2]: Found estop!
[spot_ros2-1] [INFO] [1771893748.901132830] [spot_ros2]: Shutting down ROS driver for Spot
[spot_ros2-1] Traceback (most recent call last):
[spot_ros2-1]   File "/spot_ws/install/spot_driver/lib/spot_driver/spot_ros2", line 3182, in <module>
[spot_ros2-1]     main()
[spot_ros2-1]   File "/spot_ws/install/synchros2/lib/python3.12/site-packages/synchros2/process.py", line 190, in __call__
[spot_ros2-1]     with scope.top(argv, global_=True, interruptible=self._interruptible, **scope_kwargs) as self._scope:
[spot_ros2-1]   File "/usr/lib/python3.12/contextlib.py", line 158, in __exit__
[spot_ros2-1]     self.gen.throw(value)
[spot_ros2-1]   File "/spot_ws/install/synchros2/lib/python3.12/site-packages/synchros2/scope.py", line 556, in top
[spot_ros2-1]     stack.close()
[spot_ros2-1]   File "/usr/lib/python3.12/contextlib.py", line 618, in close
[spot_ros2-1]     self.__exit__(None, None, None)
[spot_ros2-1]   File "/usr/lib/python3.12/contextlib.py", line 610, in __exit__                                                                                                                                       [spot_ros2-1]     raise exc_details[1]
[spot_ros2-1]   File "/usr/lib/python3.12/contextlib.py", line 595, in __exit__
[spot_ros2-1]     if cb(*exc_details):
[spot_ros2-1]        ^^^^^^^^^^^^^^^^
[spot_ros2-1]   File "/spot_ws/install/synchros2/lib/python3.12/site-packages/synchros2/scope.py", line 165, in __exit__
[spot_ros2-1]     self._stack.close()
[spot_ros2-1]   File "/usr/lib/python3.12/contextlib.py", line 618, in close
[spot_ros2-1]     self.__exit__(None, None, None)
[spot_ros2-1]   File "/usr/lib/python3.12/contextlib.py", line 610, in __exit__
[spot_ros2-1]     raise exc_details[1]
[spot_ros2-1]   File "/usr/lib/python3.12/contextlib.py", line 595, in __exit__
[spot_ros2-1]     if cb(*exc_details):
[spot_ros2-1]        ^^^^^^^^^^^^^^^^
[spot_ros2-1]   File "/usr/lib/python3.12/contextlib.py", line 144, in __exit__
[spot_ros2-1]     next(self.gen)
[spot_ros2-1]   File "/spot_ws/install/synchros2/lib/python3.12/site-packages/synchros2/executors.py", line 837, in foreground
[spot_ros2-1]     if not executor.shutdown(timeout_sec=5.0):
[spot_ros2-1]            ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
[spot_ros2-1]   File "/spot_ws/install/synchros2/lib/python3.12/site-packages/synchros2/executors.py", line 768, in shutdown
[spot_ros2-1]     AutoScalingMultiThreadedExecutor.Task(task, entity, node) for task, entity, node in self._tasks
[spot_ros2-1]                                                                                         ^^^^^^^^^^^
[spot_ros2-1] AttributeError: 'AutoScalingMultiThreadedExecutor' object has no attribute '_tasks'
[ERROR] [spot_ros2-1]: process has died [pid 1062, exit code 1, cmd '/spot_ws/install/spot_driver/lib/spot_driver/spot_ros2 --ros-args -r __node:=spot_ros2 -r __ns:=/ -p use_sim_time:=False --params-file /tmp/launc
h_params_0kk870_l --params-file /tmp/launch_params_9zs_k23z'].

Upon investigating the failure, I noticed that AutoScalingMultiThreadedExecutor's shutdown method in synchros2/executors.py file attempts to access the self._tasks attribute inherited from rclpy.executors.Executor.

If you look into the Executor's source code, jazzy and beyond implementations remove the self._tasks attribute and replace it with self._ready_tasks which is a different type.

The remainder of the spot_driver code seems fine except for this issue, and I'm not sure if there is a similar workaround that would be backward compatible between ROS 2 Humble and ROS 2 Jazzy. I'll keep looking at the code to see if there may be a work around and provide a patch.

Metadata

Metadata

Assignees

No one assigned

    Labels

    bugSomething isn't working

    Type

    No type

    Projects

    No projects

    Milestone

    No milestone

    Relationships

    None yet

    Development

    No branches or pull requests

    Issue actions