Skip to content

Commit 862520d

Browse files
authored
Make launch_testing_ros examples more robust. (ros2#394)
The original goal here was to expand the timeouts on the launch_testing_ros examples so that they are more robust. I did that, and in most cases these tests now wait at least 15 seconds for things to happen. Along the way, I also somewhat rewrote some of these tests so they properly clean up after themselves. Signed-off-by: Chris Lalancette <clalancette@gmail.com>
1 parent d71c7a9 commit 862520d

File tree

5 files changed

+61
-68
lines changed

5 files changed

+61
-68
lines changed

‎launch_testing_ros/test/examples/check_msgs_launch_test.py‎

Lines changed: 24 additions & 21 deletions
Original file line numberDiff line numberDiff line change
@@ -27,7 +27,6 @@
2727
import launch_testing.markers
2828
import pytest
2929
import rclpy
30-
from rclpy.node import Node
3130
from std_msgs.msg import String
3231

3332

@@ -50,35 +49,39 @@ def generate_test_description():
5049

5150
class TestFixture(unittest.TestCase):
5251

53-
def test_check_if_msgs_published(self, proc_output: ActiveIoHandler):
54-
rclpy.init()
52+
def subscription_callback(self, data: String):
53+
self.msg_event_object.set()
54+
55+
def spin(self):
5556
try:
56-
node = MakeTestNode('test_node')
57-
node.start_subscriber()
58-
msgs_received_flag = node.msg_event_object.wait(timeout=5.0)
59-
assert msgs_received_flag, 'Did not receive msgs !'
57+
while rclpy.ok() and not self.spinning.is_set():
58+
rclpy.spin_once(self.node, timeout_sec=0.1)
6059
finally:
61-
rclpy.shutdown()
62-
63-
64-
class MakeTestNode(Node):
60+
return
6561

66-
def __init__(self, name: str = 'test_node'):
67-
super().__init__(name)
62+
def setUp(self):
63+
rclpy.init()
64+
self.node = rclpy.create_node('test_node')
65+
self.spinning = Event()
6866
self.msg_event_object = Event()
69-
70-
def start_subscriber(self):
71-
# Create a subscriber
72-
self.subscription = self.create_subscription(
67+
self.subscription = self.node.create_subscription(
7368
String,
7469
'chatter',
75-
self.subscriber_callback,
70+
self.subscription_callback,
7671
10
7772
)
7873

7974
# Add a spin thread
80-
self.ros_spin_thread = Thread(target=lambda node: rclpy.spin(node), args=(self,))
75+
self.ros_spin_thread = Thread(target=self.spin)
8176
self.ros_spin_thread.start()
8277

83-
def subscriber_callback(self, data: String):
84-
self.msg_event_object.set()
78+
def tearDown(self):
79+
self.spinning.set()
80+
self.ros_spin_thread.join()
81+
self.node.destroy_subscription(self.subscription)
82+
self.node.destroy_node()
83+
rclpy.shutdown()
84+
85+
def test_check_if_msgs_published(self, proc_output: ActiveIoHandler):
86+
msgs_received_flag = self.msg_event_object.wait(timeout=15.0)
87+
assert msgs_received_flag, 'Did not receive msgs !'

‎launch_testing_ros/test/examples/check_node_launch_test.py‎

Lines changed: 14 additions & 18 deletions
Original file line numberDiff line numberDiff line change
@@ -25,7 +25,6 @@
2525
import launch_testing.markers
2626
import pytest
2727
import rclpy
28-
from rclpy.node import Node
2928

3029

3130
@pytest.mark.launch_test
@@ -50,26 +49,23 @@ def generate_test_description():
5049

5150
class TestFixture(unittest.TestCase):
5251

53-
def test_node_start(self, proc_output: ActiveIoHandler):
52+
def setUp(self):
5453
rclpy.init()
55-
try:
56-
node = MakeTestNode('test_node')
57-
assert node.wait_for_node('demo_node_1', 8.0), 'Node not found !'
58-
finally:
59-
rclpy.shutdown()
60-
61-
62-
class MakeTestNode(Node):
54+
self.node = rclpy.create_node('test_node')
6355

64-
def __init__(self, name: str = 'test_node'):
65-
super().__init__(name)
56+
def tearDown(self):
57+
self.node.destroy_node()
58+
rclpy.shutdown()
6659

67-
def wait_for_node(self, node_name: str, timeout: float = 8.0):
68-
start = time.time()
69-
flag = False
60+
def test_node_start(self, proc_output: ActiveIoHandler):
61+
found = False
7062
print('Waiting for node...')
71-
while time.time() - start < timeout and not flag:
72-
flag = node_name in self.get_node_names()
63+
# demo_node_1 won't start for at least 5 seconds after this test
64+
# is launched, so we wait for a total of up to 20 seconds for it
65+
# to appear.
66+
start = time.time()
67+
while time.time() - start < 20.0 and not found:
68+
found = 'demo_node_1' in self.node.get_node_names()
7369
time.sleep(0.1)
7470

75-
return flag
71+
assert found, 'Node not found!'

‎launch_testing_ros/test/examples/set_param_launch_test.py‎

Lines changed: 20 additions & 26 deletions
Original file line numberDiff line numberDiff line change
@@ -25,7 +25,6 @@
2525
import pytest
2626
from rcl_interfaces.srv import SetParameters
2727
import rclpy
28-
from rclpy.node import Node
2928

3029

3130
@pytest.mark.launch_test
@@ -46,35 +45,30 @@ def generate_test_description():
4645

4746
class TestFixture(unittest.TestCase):
4847

49-
def test_set_parameter(self, proc_output: ActiveIoHandler):
48+
def setUp(self):
5049
rclpy.init()
51-
try:
52-
node = MakeTestNode('test_node')
53-
response = node.set_parameter(state=True)
54-
assert response.successful, 'Could not set parameter!'
55-
finally:
56-
rclpy.shutdown()
57-
50+
self.node = rclpy.create_node('test_node')
5851

59-
class MakeTestNode(Node):
52+
def tearDown(self):
53+
self.node.destroy_node()
54+
rclpy.shutdown()
6055

61-
def __init__(self, name: str = 'test_node'):
62-
super().__init__(name)
63-
64-
def set_parameter(self, state: bool = True, timeout: float = 5.0):
65-
parameters = [rclpy.Parameter('demo_parameter_1', value=state).to_parameter_msg()]
56+
def test_set_parameter(self, proc_output: ActiveIoHandler):
57+
parameters = [rclpy.Parameter('demo_parameter_1', value=True).to_parameter_msg()]
6658

67-
client = self.create_client(SetParameters, 'demo_node_1/set_parameters')
68-
ready = client.wait_for_service(timeout_sec=timeout)
69-
if not ready:
70-
raise RuntimeError('Wait for service timed out')
59+
client = self.node.create_client(SetParameters, 'demo_node_1/set_parameters')
60+
try:
61+
ready = client.wait_for_service(timeout_sec=15.0)
62+
if not ready:
63+
raise RuntimeError('Wait for service timed out')
7164

72-
request = SetParameters.Request()
73-
request.parameters = parameters
74-
future = client.call_async(request)
75-
rclpy.spin_until_future_complete(self, future, timeout_sec=timeout)
65+
request = SetParameters.Request()
66+
request.parameters = parameters
67+
future = client.call_async(request)
68+
rclpy.spin_until_future_complete(self.node, future, timeout_sec=15.0)
7669

77-
assert future.done(), 'Client request timed out'
70+
assert future.done(), 'Client request timed out'
7871

79-
response = future.result()
80-
return response.results[0]
72+
assert future.result().results[0].successful, 'Could not set parameter!'
73+
finally:
74+
self.node.destroy_client(client)

‎launch_testing_ros/test/examples/talker_listener_launch_test.py‎

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -140,7 +140,7 @@ def test_listener_receives(self,
140140
success = proc_output.waitFor(
141141
expected_output=msg.data,
142142
process=listener,
143-
timeout=1.0,
143+
timeout=15.0,
144144
)
145145
if success:
146146
break

‎launch_testing_ros/test/examples/wait_for_topic_launch_test.py‎

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -64,7 +64,7 @@ def test_topics_successful(self, count: int):
6464

6565
# Method 1 : Using the magic methods and 'with' keyword
6666
with WaitForTopics(
67-
topic_list, timeout=10.0, messages_received_buffer_length=10
67+
topic_list, timeout=15.0, messages_received_buffer_length=10
6868
) as wait_for_node_object_1:
6969
assert wait_for_node_object_1.topics_received() == expected_topics
7070
assert wait_for_node_object_1.topics_not_received() == set()
@@ -76,7 +76,7 @@ def test_topics_successful(self, count: int):
7676
# Multiple instances of WaitForNode() can be created safely as
7777
# their internal nodes spin in separate contexts
7878
# Method 2 : Manually calling wait() and shutdown()
79-
wait_for_node_object_2 = WaitForTopics(topic_list, timeout=10.0)
79+
wait_for_node_object_2 = WaitForTopics(topic_list, timeout=15.0)
8080
assert wait_for_node_object_2.wait()
8181
assert wait_for_node_object_2.topics_received() == expected_topics
8282
assert wait_for_node_object_2.topics_not_received() == set()

0 commit comments

Comments
 (0)