File tree Expand file tree Collapse file tree 1 file changed +6
-3
lines changed Expand file tree Collapse file tree 1 file changed +6
-3
lines changed Original file line number Diff line number Diff line change 20
20
import numpy as np
21
21
import pytest
22
22
import rclpy
23
+ from rclpy .executors import SingleThreadedExecutor
23
24
from rclpy .node import Node
24
25
from rclpy .qos import QoSPresetProfiles , QoSProfile
25
26
from sensor_msgs .msg import Image
@@ -90,7 +91,9 @@ def test_transport(qos_profile: str):
90
91
if not rclpy .ok ():
91
92
rclpy .init ()
92
93
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 )
94
97
thread .start ()
95
98
96
99
rai_base_node = RaiBaseNode (
@@ -102,7 +105,7 @@ def test_transport(qos_profile: str):
102
105
output = rai_base_node .get_raw_message_from_topic (topic , timeout_sec = 5.0 )
103
106
assert not isinstance (output , Exception ), f"Exception: { output } "
104
107
finally :
105
- # TODO: Fix errors regarding node destruction in thread
108
+ executor . shutdown ()
106
109
publisher .destroy_node ()
107
110
rclpy .shutdown ()
108
- thread .join ()
111
+ thread .join (timeout = 1.0 )
You can’t perform that action at this time.
0 commit comments