Skip to content

Commit 600119f

Browse files
authored
Switch to using an rclpy context manager. (ros2#787)
This still manages the lifetime of rclpy, but uses less code to do so. Signed-off-by: Chris Lalancette <[email protected]>
1 parent c4c8033 commit 600119f

File tree

2 files changed

+6
-13
lines changed

2 files changed

+6
-13
lines changed

launch_pytest/test/launch_pytest/examples/check_node_msgs.py

Lines changed: 1 addition & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -46,14 +46,11 @@ def generate_test_description():
4646

4747
@pytest.mark.launch(fixture=generate_test_description)
4848
def test_check_if_msgs_published():
49-
rclpy.init()
50-
try:
49+
with rclpy.init():
5150
node = MakeTestNode('test_node')
5251
node.start_subscriber()
5352
msgs_received_flag = node.msg_event_object.wait(timeout=5.0)
5453
assert msgs_received_flag, 'Did not receive msgs !'
55-
finally:
56-
rclpy.shutdown()
5754

5855

5956
class MakeTestNode(Node):

launch_pytest/test/launch_pytest/examples/executables/talker.py

Lines changed: 5 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -13,6 +13,7 @@
1313
# limitations under the License.
1414

1515
import rclpy
16+
from rclpy.executors import ExternalShutdownException
1617
from rclpy.node import Node
1718

1819
from std_msgs.msg import String
@@ -34,17 +35,12 @@ def callback(self):
3435

3536

3637
def main(args=None):
37-
rclpy.init(args=args)
38-
39-
node = Talker()
40-
4138
try:
42-
rclpy.spin(node)
43-
except KeyboardInterrupt:
39+
with rclpy.init(args=args):
40+
node = Talker()
41+
rclpy.spin(node)
42+
except (KeyboardInterrupt, ExternalShutdownException):
4443
pass
45-
finally:
46-
node.destroy_node()
47-
rclpy.shutdown()
4844

4945

5046
if __name__ == '__main__':

0 commit comments

Comments
 (0)