Skip to content

Commit

Permalink
Switch to using a context manager for rclpy initialization.
Browse files Browse the repository at this point in the history
This ensures that everything will be properly cleaned up
when we leave the context manager.

Signed-off-by: Chris Lalancette <[email protected]>
  • Loading branch information
clalancette committed Jul 23, 2024
1 parent c63478d commit 79dbf8c
Show file tree
Hide file tree
Showing 6 changed files with 31 additions and 37 deletions.
11 changes: 5 additions & 6 deletions turtle_tf2_py/turtle_tf2_py/dynamic_frame_tf2_broadcaster.py
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,7 @@
from geometry_msgs.msg import TransformStamped

import rclpy
from rclpy.executors import ExternalShutdownException
from rclpy.node import Node

from tf2_ros import TransformBroadcaster
Expand Down Expand Up @@ -49,11 +50,9 @@ def broadcast_timer_callback(self):


def main():
rclpy.init()
node = DynamicFrameBroadcaster()
try:
rclpy.spin(node)
except KeyboardInterrupt:
with rclpy.init():
node = DynamicFrameBroadcaster()
rclpy.spin(node)
except (KeyboardInterrupt, ExternalShutdownException):
pass

rclpy.shutdown()
11 changes: 5 additions & 6 deletions turtle_tf2_py/turtle_tf2_py/fixed_frame_tf2_broadcaster.py
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,7 @@
from geometry_msgs.msg import TransformStamped

import rclpy
from rclpy.executors import ExternalShutdownException
from rclpy.node import Node

from tf2_ros import TransformBroadcaster
Expand Down Expand Up @@ -45,11 +46,9 @@ def broadcast_timer_callback(self):


def main():
rclpy.init()
node = FixedFrameBroadcaster()
try:
rclpy.spin(node)
except KeyboardInterrupt:
with rclpy.init():
node = FixedFrameBroadcaster()
rclpy.spin(node)
except (KeyboardInterrupt, ExternalShutdownException):
pass

rclpy.shutdown()
13 changes: 6 additions & 7 deletions turtle_tf2_py/turtle_tf2_py/static_turtle_tf2_broadcaster.py
Original file line number Diff line number Diff line change
Expand Up @@ -20,6 +20,7 @@
import numpy as np

import rclpy
from rclpy.executors import ExternalShutdownException
from rclpy.node import Node

from tf2_ros.static_transform_broadcaster import StaticTransformBroadcaster
Expand Down Expand Up @@ -104,12 +105,10 @@ def main():
logger.info('Your static turtle name cannot be "world"')
sys.exit(2)

# pass parameters and initialize node
rclpy.init()
node = StaticFramePublisher(sys.argv)
try:
rclpy.spin(node)
except KeyboardInterrupt:
with rclpy.init():
# pass parameters and initialize node
node = StaticFramePublisher(sys.argv)
rclpy.spin(node)
except (KeyboardInterrupt, ExternalShutdownException):
pass

rclpy.shutdown()
11 changes: 5 additions & 6 deletions turtle_tf2_py/turtle_tf2_py/turtle_tf2_broadcaster.py
Original file line number Diff line number Diff line change
Expand Up @@ -19,6 +19,7 @@
import numpy as np

import rclpy
from rclpy.executors import ExternalShutdownException
from rclpy.node import Node

from tf2_ros import TransformBroadcaster
Expand Down Expand Up @@ -104,11 +105,9 @@ def handle_turtle_pose(self, msg):


def main():
rclpy.init()
node = FramePublisher()
try:
rclpy.spin(node)
except KeyboardInterrupt:
with rclpy.init():
node = FramePublisher()
rclpy.spin(node)
except (KeyboardInterrupt, ExternalShutdownException):
pass

rclpy.shutdown()
11 changes: 5 additions & 6 deletions turtle_tf2_py/turtle_tf2_py/turtle_tf2_listener.py
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,7 @@
from geometry_msgs.msg import Twist

import rclpy
from rclpy.executors import ExternalShutdownException
from rclpy.node import Node

from tf2_ros import TransformException
Expand Down Expand Up @@ -109,11 +110,9 @@ def on_timer(self):


def main():
rclpy.init()
node = FrameListener()
try:
rclpy.spin(node)
except KeyboardInterrupt:
with rclpy.init():
node = FrameListener()
rclpy.spin(node)
except (KeyboardInterrupt, ExternalShutdownException):
pass

rclpy.shutdown()
11 changes: 5 additions & 6 deletions turtle_tf2_py/turtle_tf2_py/turtle_tf2_message_broadcaster.py
Original file line number Diff line number Diff line change
Expand Up @@ -16,6 +16,7 @@
from geometry_msgs.msg import Twist

import rclpy
from rclpy.executors import ExternalShutdownException
from rclpy.node import Node

from turtlesim_msgs.msg import Pose
Expand Down Expand Up @@ -87,11 +88,9 @@ def handle_turtle_pose(self, msg):


def main():
rclpy.init()
node = PointPublisher()
try:
rclpy.spin(node)
except KeyboardInterrupt:
with rclpy.init():
node = PointPublisher()
rclpy.spin(node)
except (KeyboardInterrupt, ExternalShutdownException):
pass

rclpy.shutdown()

0 comments on commit 79dbf8c

Please sign in to comment.