Skip to content

Commit caaf81a

Browse files
committed
feat: use executor for spinning
1 parent e276f93 commit caaf81a

File tree

1 file changed

+6
-3
lines changed

1 file changed

+6
-3
lines changed

tests/messages/test_transport.py

Lines changed: 6 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -20,6 +20,7 @@
2020
import numpy as np
2121
import pytest
2222
import rclpy
23+
from rclpy.executors import SingleThreadedExecutor
2324
from rclpy.node import Node
2425
from rclpy.qos import QoSPresetProfiles, QoSProfile
2526
from sensor_msgs.msg import Image
@@ -90,7 +91,9 @@ def test_transport(qos_profile: str):
9091
if not rclpy.ok():
9192
rclpy.init()
9293
publisher = TestPublisher(QoSPresetProfiles.get_from_short_key(qos_profile))
93-
thread = threading.Thread(target=rclpy.spin, args=(publisher,))
94+
executor = SingleThreadedExecutor()
95+
executor.add_node(publisher)
96+
thread = threading.Thread(target=executor.spin)
9497
thread.start()
9598

9699
rai_base_node = RaiBaseNode(
@@ -102,7 +105,7 @@ def test_transport(qos_profile: str):
102105
output = rai_base_node.get_raw_message_from_topic(topic, timeout_sec=5.0)
103106
assert not isinstance(output, Exception), f"Exception: {output}"
104107
finally:
105-
# TODO: Fix errors regarding node destruction in thread
108+
executor.shutdown()
106109
publisher.destroy_node()
107110
rclpy.shutdown()
108-
thread.join()
111+
thread.join(timeout=1.0)

0 commit comments

Comments
 (0)