diff --git a/prover_rclpy/setup.py b/prover_rclpy/setup.py index a05a13d..aa9fa5d 100644 --- a/prover_rclpy/setup.py +++ b/prover_rclpy/setup.py @@ -75,6 +75,7 @@ 'rclpy_1163_sub = src.rclpy_1163_sub:main', 'rclpy_1199 = src.rclpy_1199:main', 'rclpy_1273 = src.rclpy_1273:main', + 'rclpy_1287 = src.rclpy_1287:main', 'ros2cli_818 = src.ros2cli_818:main', 'ros2cli_862 = src.ros2cli_862:main', 'ros2cli_885 = src.ros2cli_885:main', diff --git a/prover_rclpy/src/rclpy_1287.py b/prover_rclpy/src/rclpy_1287.py new file mode 100644 index 0000000..528eca3 --- /dev/null +++ b/prover_rclpy/src/rclpy_1287.py @@ -0,0 +1,43 @@ +#!/usr/bin/env python3 + +import signal +import sys + +import rclpy +import rclpy.node + +from rclpy.executors import ExternalShutdownException +from rclpy.signals import SignalHandlerOptions + +def shutdown_handler(): + print("exit") + +def main(args=None): + def signal_handler(sig, frame): + # this handler should be called before deferred signal handler + print("signal receive\n") + rclpy.shutdown() + #rclpy.try_shutdown() + signal.signal(signal.SIGINT, signal_handler) + + rclpy.init(args=args) + #rclpy.init(args=args, signal_handler_options=SignalHandlerOptions.NO) + + try: + node = rclpy.create_node("test_node") + + node.context.on_shutdown(shutdown_handler) + rclpy.get_default_context().on_shutdown(shutdown_handler) + + rclpy.spin(node) + except KeyboardInterrupt: + pass + except ExternalShutdownException: + sys.exit(1) + + #rclpy.shutdown() + rclpy.try_shutdown() + + +if __name__ == "__main__": + main()