rclpy icon indicating copy to clipboard operation
rclpy copied to clipboard

MultiThreadedExecutor.shutdown does not shut down underlying threadpool

Open apockill opened this issue 2 years ago • 4 comments

Preface: Thanks for this wonderful library. Below is what might be considered a bug. I'm happy to make a PR with fixes+tests if a fix is agreed upon.

Bug report

Required Info:

  • Operating System:
    • Ubuntu 20.04
  • Installation type:
    • Binaries, from apt repo, within a Ubuntu 20.04 docker container
  • Version or commit hash:
    • Foxy
  • DDS implementation:
    • I'm not confident I know enough about ROS to answer this. I'm not doing anything that's not default for this.
  • Client library (if applicable):
    • rclpy

Steps to reproduce issue

import threading

import rclpy
from rclpy.executors import MultiThreadedExecutor
from rclpy.node import Node


class CoolNode(Node):
    def __init__(self):
        super().__init__(node_name="nodes_live_lonely_lives")
        # Create a timer to give the executor something to do
        self.create_timer(0., callback=lambda: None)

rclpy.init()
executor = MultiThreadedExecutor()
node = CoolNode()


# Spin once to give the executor some work to do (creating threads)
rclpy.spin_once(node, executor=executor)

print("Shutting down")
rclpy.shutdown()
node.destroy_node()
executor.shutdown()

print(f"Leftover Threads: {threading.enumerate()}")

Expected behavior

This is up to for discussion. I would argue that after executor.shutdown() there should be no leftover threads. In this case, the log would be:

Leftover Threads: [<_MainThread(MainThread, started 139683413362496)>]

Actual behavior

There are leftover threads from the executor.

Leftover Threads: [<_MainThread(MainThread, started 139683413362496)>, <Thread(ThreadPoolExecutor-0_0, started daemon 139683303745280)>]

Suggested Fix

Inside of MultiThreadedExuctor.shutdown call self._executor.shutdown() after calling super().shutdown().

Here's a suggested API:

class MultiThreadedExecutor(Executor):
    ...

    def shutdown(
        self, timeout_sec: float = None, wait_for_threads: bool = True
    ) -> bool:
        success = super().shutdown(timeout_sec)
        self._executor.shutdown(wait=wait_for_threads)
        return success

This will help ensure that there are no side effects after calling shutdown(wait_for_threads=True). My personal use case is it will ensure that unit tests are isolated from eachother after full teardowns.

apockill avatar Feb 08 '22 23:02 apockill

i think this is a bug and your suggested fix seems reasonable to me. if you are willing to address the fix and test, i am happy to do the review! appreciate for being supportive!

fujitatomoya avatar Feb 18 '22 23:02 fujitatomoya

@fujitatomoya Great! Can you take a look at my PR and see if it looks good? Cheers

apockill avatar Feb 19 '22 21:02 apockill

here are some possible workarounds for this issue (credit @sloretz):

  • you can call executor.shutdown() followed by executor._executor.shutdown() in whatever code is creating the MultiThreadedExecutor
  • Alternatively, the thread should get shut down when the executor is garbage collected. Releasing any references to the multi threaded executor and calling gc.collect() should get rid of the threadpool executor threads

scpeters avatar Jun 26 '24 21:06 scpeters

@scpeters i revived this with https://github.com/ros2/rclpy/pull/1309, if you can review that would be appreciated.

fujitatomoya avatar Jun 28 '24 20:06 fujitatomoya