Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Switch to using a context manager for the python examples. #700

Merged
merged 1 commit into from
Jul 9, 2024
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
10 changes: 5 additions & 5 deletions examples_tf2_py/examples_tf2_py/async_waits_for_transform.py
Original file line number Diff line number Diff line change
Expand Up @@ -13,6 +13,7 @@
# limitations under the License.

import rclpy
from rclpy.executors import ExternalShutdownException
from rclpy.node import Node
import rclpy.time
from tf2_ros import LookupException
Expand Down Expand Up @@ -62,10 +63,9 @@ async def on_timer(self):


def main():
rclpy.init()
node = AsyncWaitsForTransform()
try:
rclpy.spin(node)
except KeyboardInterrupt:
with rclpy.init():
node = AsyncWaitsForTransform()
rclpy.spin(node)
except (KeyboardInterrupt, ExternalShutdownException):
pass
rclpy.shutdown()
19 changes: 8 additions & 11 deletions examples_tf2_py/examples_tf2_py/blocking_waits_for_transform.py
Original file line number Diff line number Diff line change
Expand Up @@ -14,6 +14,7 @@

import rclpy
from rclpy.duration import Duration
from rclpy.executors import ExternalShutdownException, MultiThreadedExecutor
from rclpy.node import Node
import rclpy.time
from tf2_ros import LookupException
Expand Down Expand Up @@ -55,16 +56,12 @@ def on_timer(self):


def main():
from rclpy.executors import MultiThreadedExecutor

rclpy.init()
node = BlockingWaitsForTransform()
# this node blocks in a callback, so a MultiThreadedExecutor is required
executor = MultiThreadedExecutor()
executor.add_node(node)
try:
executor.spin()
except KeyboardInterrupt:
with rclpy.init():
node = BlockingWaitsForTransform()
# this node blocks in a callback, so a MultiThreadedExecutor is required
executor = MultiThreadedExecutor()
executor.add_node(node)
executor.spin()
except (KeyboardInterrupt, ExternalShutdownException):
pass
executor.shutdown()
rclpy.shutdown()
25 changes: 11 additions & 14 deletions examples_tf2_py/examples_tf2_py/dynamic_broadcaster.py
Original file line number Diff line number Diff line change
Expand Up @@ -16,6 +16,7 @@

from geometry_msgs.msg import TransformStamped
import rclpy
from rclpy.executors import ExternalShutdownException, SingleThreadedExecutor
from rclpy.node import Node
from rclpy.qos import QoSProfile
from sensor_msgs.msg import JointState
Expand Down Expand Up @@ -87,20 +88,16 @@ def on_timer(self):


def main():
rclpy.init()
nodes = []
nodes.append(DynamicFramePublisher())
nodes.append(FakeJointStatePublisher())
try:
with rclpy.init():
nodes = []
nodes.append(DynamicFramePublisher())
nodes.append(FakeJointStatePublisher())

from rclpy.executors import SingleThreadedExecutor
executor = SingleThreadedExecutor()
for node in nodes:
executor.add_node(node)
executor = SingleThreadedExecutor()
for node in nodes:
executor.add_node(node)

try:
executor.spin()
except KeyboardInterrupt:
executor.spin()
except (KeyboardInterrupt, ExternalShutdownException):
pass

executor.shutdown()
rclpy.shutdown()
11 changes: 5 additions & 6 deletions examples_tf2_py/examples_tf2_py/frame_dumper.py
Original file line number Diff line number Diff line change
Expand Up @@ -13,6 +13,7 @@
# limitations under the License.

import rclpy
from rclpy.executors import ExternalShutdownException
from rclpy.node import Node
from tf2_ros.buffer import Buffer
from tf2_ros.transform_listener import TransformListener
Expand All @@ -34,11 +35,9 @@ def on_timer(self):


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

rclpy.shutdown()
11 changes: 5 additions & 6 deletions examples_tf2_py/examples_tf2_py/static_broadcaster.py
Original file line number Diff line number Diff line change
Expand Up @@ -16,6 +16,7 @@

from geometry_msgs.msg import TransformStamped
import rclpy
from rclpy.executors import ExternalShutdownException
from rclpy.node import Node
from tf2_ros.static_transform_broadcaster import StaticTransformBroadcaster

Expand Down Expand Up @@ -109,11 +110,9 @@ def make_transforms(self):


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

rclpy.shutdown()
10 changes: 5 additions & 5 deletions examples_tf2_py/examples_tf2_py/waits_for_transform.py
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,7 @@
import threading

import rclpy
from rclpy.executors import ExternalShutdownException
from rclpy.node import Node
import rclpy.time
from tf2_ros import LookupException
Expand Down Expand Up @@ -73,10 +74,9 @@ def on_timer(self):


def main():
rclpy.init()
node = WaitsForTransform()
try:
rclpy.spin(node)
except KeyboardInterrupt:
with rclpy.init():
node = WaitsForTransform()
rclpy.spin(node)
except (KeyboardInterrupt, ExternalShutdownException):
pass
rclpy.shutdown()
3 changes: 3 additions & 0 deletions test_tf2/test/test_buffer_client.py
Original file line number Diff line number Diff line change
Expand Up @@ -59,6 +59,9 @@ def setUpClass(cls):

@classmethod
def tearDownClass(cls):
cls.executor.remove_node(cls.node)
cls.node.destroy_node()
cls.executor.shutdown()
rclpy.shutdown(context=cls.context)

def setUp(self):
Expand Down
2 changes: 2 additions & 0 deletions tf2_ros_py/test/test_buffer_client.py
Original file line number Diff line number Diff line change
Expand Up @@ -112,6 +112,8 @@ def setup_class(cls):

@classmethod
def teardown_class(cls):
cls.executor.remove_node(cls.node)
cls.executor.shutdown()
cls.mock_action_server.destroy()
cls.node.destroy_node()
rclpy.shutdown(context=cls.context)
Expand Down
1 change: 1 addition & 0 deletions tf2_ros_py/test/test_listener_and_broadcaster.py
Original file line number Diff line number Diff line change
Expand Up @@ -73,6 +73,7 @@ def setup_class(cls):

@classmethod
def teardown_class(cls):
cls.executor.remove_node(cls.node)
cls.node.destroy_node()
rclpy.shutdown()

Expand Down