rclpy icon indicating copy to clipboard operation
rclpy copied to clipboard

rclpy Context.on_shutdown callbacks are not called when Ctrl-C is pressed

Open tfoote opened this issue 5 years ago • 7 comments

The on_shutdown doesn't get triggered unless the user explicitly catches the Ctrl-C and then calls shutdown themselves.

#!/usr/bin/env python3
import rclpy

class TestShutdown():
    def on_shutdown_method(self):
        print("on shutdown method called")

def main(args=None):

    rclpy.init(args=args)

    ros_node = rclpy.create_node('test_node')

    test_class = TestShutdown()
    rclpy.get_default_context().on_shutdown(test_class.on_shutdown_method)

    rclpy.spin(ros_node)

    # Shutdown
    print("exiting")
    rclpy.shutdown()


if __name__ == '__main__':
    main()

If you put a try catch around the spin it will work. But otherwise you get no on_shutdown which could be useful for cleaning up a hardware driver etc.

test_shutdown.py 
^CTraceback (most recent call last):
  File "/home/tfoote/work/tdk/test_shutdown.py", line 25, in <module>
    main()
  File "/home/tfoote/work/tdk/test_shutdown.py", line 17, in main
    rclpy.spin(ros_node)
  File "/home/tfoote/work/workspaces/rclpy/install/rclpy/lib/python3.6/site-packages/rclpy/__init__.py", line 190, in spin
    executor.spin_once()
  File "/home/tfoote/work/workspaces/rclpy/install/rclpy/lib/python3.6/site-packages/rclpy/executors.py", line 676, in spin_once
    handler, entity, node = self.wait_for_ready_callbacks(timeout_sec=timeout_sec)
  File "/home/tfoote/work/workspaces/rclpy/install/rclpy/lib/python3.6/site-packages/rclpy/executors.py", line 662, in wait_for_ready_callbacks
    return next(self._cb_iter)
  File "/home/tfoote/work/workspaces/rclpy/install/rclpy/lib/python3.6/site-packages/rclpy/executors.py", line 560, in _wait_for_ready_callbacks
    _rclpy.rclpy_wait(wait_set, timeout_nsec)
KeyboardInterrupt

Letting the Ctrl-C bubble up is probably still correct, but the Context could use a ContextManager or other mechanism to make sure that the shutdown occurs for this and other unexpected exits otherwise the on_shutdown callback is not particularly useful.

The workaround in the short term is to simply put a try catch around the spin and catch the KeyboardInterrupt exception.

tfoote avatar Mar 31 '20 08:03 tfoote

According to the latest codes (77949d2c54b8104e48a94d0ea83c7049e18a8809), this problem also exists.

After receiving SIGINT/SIGTERM, this thread will be awaked and call rclpy::shutdown_contexts() which call rcl_shutdown.

https://github.com/ros2/rclpy/blob/77949d2c54b8104e48a94d0ea83c7049e18a8809/rclpy/src/rclpy/signal_handler.cpp#L137-L146

For user codes

   ...
    try:
        rclpy.spin(node)
    except KeyboardInterrupt:
        pass
    except ExternalShutdownException:
        sys.exit(1)
    finally:
        rclpy.try_shutdown()
        node.destroy_node()

It will call rclpy.try_shutdown(). Since rcl_shutdown has been called, self.__context.ok() is always false.
It leads shutdown callback never is called.

https://github.com/ros2/rclpy/blob/77949d2c54b8104e48a94d0ea83c7049e18a8809/rclpy/rclpy/context.py#L105-L113

Maybe we can use setting shutdown flag instead of calling rclpy::shutdown_contexts() in signal handling thread (signal_handler.cpp).
At line 591, check above shutdown flag. https://github.com/ros2/rclpy/blob/77949d2c54b8104e48a94d0ea83c7049e18a8809/rclpy/rclpy/executors.py#L588-L592 Of course, this may introduce new issues. @ivanpauno do you have any opinions ?

Barry-Xu-2018 avatar Nov 18 '21 07:11 Barry-Xu-2018

Maybe we can use setting shutdown flag instead of calling rclpy::shutdown_contexts() in signal handling thread (signal_handler.cpp).

I don't understand how that would work. Could you expand the idea?

Maybe rclpy::shutdown_contexts() should also call the shutdown callbacks, though that might not be simple to implement.

ivanpauno avatar Nov 18 '21 12:11 ivanpauno

Could you expand the idea?

My rough idea is

At context.cpp, add 2 functions.

void requst_shutdown()
{
   Set a global shutdown flag
}

bool check_shutdown_request()
{
   return global shutdown flag
}

At signal_handler.cpp

setup_deferred_signal_handler()
{
    ...
    rclpy::requst_shutdown()  // call new function 
    trigger_guard_conditions();
    // rclpy::shutdown_contexts(); // comment this line
}

At executors.py

def _wait_for_ready_callbacks()
     ...
     # Wait for something to become ready
     wait_set.wait(timeout_nsec)
     if self._is_shutdown:
         raise ShutdownException()
     if _rclpy.check_shutdown_request or not self._context.ok():  # Check if shutdown is requested.
         raise ExternalShutdownException()

User app take charge of calling shutdown.

   ...
    try:
        rclpy.spin(node)
    except KeyboardInterrupt:
        pass
    except ExternalShutdownException:
        pass
    finally:
        rclpy.try_shutdown()

Barry-Xu-2018 avatar Nov 19 '21 08:11 Barry-Xu-2018

That would only be effective if there's an executor spinning, if that's not the case shutdown() would never get called.

ivanpauno avatar Nov 19 '21 16:11 ivanpauno

That would only be effective if there's an executor spinning, if that's not the case shutdown() would never get called.

Yes. I missed this case.

Barry-Xu-2018 avatar Nov 20 '21 03:11 Barry-Xu-2018

As I read this issue to be only related to SIGINT (Ctrl+C) just the note for whoever is also wondering:

A callback registered via on_shutdown is never called if the program was closed/interrupted via a signal. I tested: SIGINT, SIGTERM, SIGQUIT

firesurfer avatar May 23 '24 06:05 firesurfer