From ef8f1000cd7d072399769bac9d929a4988d339b7 Mon Sep 17 00:00:00 2001 From: "mergify[bot]" <37929162+mergify[bot]@users.noreply.github.com> Date: Fri, 6 Dec 2024 10:39:25 +0100 Subject: [PATCH] Don't call shutdown() after an exception (#1400) (#1411) --- .../publisher_forward_position_controller.py | 6 +----- .../publisher_joint_trajectory_controller.py | 6 +----- 2 files changed, 2 insertions(+), 10 deletions(-) diff --git a/ros2_controllers_test_nodes/ros2_controllers_test_nodes/publisher_forward_position_controller.py b/ros2_controllers_test_nodes/ros2_controllers_test_nodes/publisher_forward_position_controller.py index 9c5fc90a2d..7ea201386c 100644 --- a/ros2_controllers_test_nodes/ros2_controllers_test_nodes/publisher_forward_position_controller.py +++ b/ros2_controllers_test_nodes/ros2_controllers_test_nodes/publisher_forward_position_controller.py @@ -72,14 +72,10 @@ def main(args=None): try: rclpy.spin(publisher_forward_position) - except KeyboardInterrupt: + except (KeyboardInterrupt, rclpy.executors.ExternalShutdownException): print("Keyboard interrupt received. Shutting down node.") except Exception as e: print(f"Unhandled exception: {e}") - finally: - if rclpy.ok(): - publisher_forward_position.destroy_node() - rclpy.shutdown() if __name__ == "__main__": diff --git a/ros2_controllers_test_nodes/ros2_controllers_test_nodes/publisher_joint_trajectory_controller.py b/ros2_controllers_test_nodes/ros2_controllers_test_nodes/publisher_joint_trajectory_controller.py index 01f4642585..c2a38fe4d6 100644 --- a/ros2_controllers_test_nodes/ros2_controllers_test_nodes/publisher_joint_trajectory_controller.py +++ b/ros2_controllers_test_nodes/ros2_controllers_test_nodes/publisher_joint_trajectory_controller.py @@ -212,14 +212,10 @@ def main(args=None): try: rclpy.spin(publisher_joint_trajectory) - except KeyboardInterrupt: + except (KeyboardInterrupt, rclpy.executors.ExternalShutdownException): print("Keyboard interrupt received. Shutting down node.") except Exception as e: print(f"Unhandled exception: {e}") - finally: - if rclpy.ok(): - publisher_joint_trajectory.destroy_node() - rclpy.shutdown() if __name__ == "__main__":