Skip to content

Commit 7e07d22

Browse files
Cleanup the launch_testing_examples. (#374)
* Cleanup the launch_testing_examples. This is to make them more robust when run in parallel with other tests. In particular, we make sure that the tests cleanup after themselves, and we also increase the timeouts to 15 seconds. Signed-off-by: Chris Lalancette <[email protected]> Co-authored-by: Tomoya Fujita <[email protected]>
1 parent c370d7e commit 7e07d22

File tree

5 files changed

+34
-35
lines changed

5 files changed

+34
-35
lines changed

launch_testing/launch_testing_examples/README.md

Lines changed: 4 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -14,8 +14,9 @@ launch_test launch_testing_examples/check_node_launch_test.py
1414
```
1515

1616
There might be situations where nodes, once launched, take some time to actually start and we need to wait for the node to start to perform some action.
17-
We can simulate this using ``launch.actions.TimerAction``. This example shows one way to detect when a node has been launched.
18-
We delay the launch by 5 seconds, and wait for the node to start with a timeout of 8 seconds.
17+
We can simulate this using ``launch.actions.TimerAction``.
18+
This example shows one way to detect when a node has been launched.
19+
We delay the launch by 5 seconds, and wait for the node to start with a timeout of 20 seconds.
1920

2021
### `check_multiple_nodes_launch_test.py`
2122

@@ -64,7 +65,7 @@ Usage:
6465
launch_test launch_testing_examples/hello_world_launch_test.py
6566
```
6667

67-
This test is a simple example on how to use the ``launch_testing``.
68+
This test is a simple example on how to use the ``launch_testing``.
6869

6970
It launches a process and asserts that it prints "hello_world" to ``stdout`` using ``proc_output.assertWaitFor()``.
7071
Finally, it checks if the process exits normally (zero exit code).

launch_testing/launch_testing_examples/launch_testing_examples/check_msgs_launch_test.py

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -40,5 +40,5 @@ def generate_test_description():
4040
class TestFixture(unittest.TestCase):
4141

4242
def test_check_if_msgs_published(self):
43-
with WaitForTopics([('chatter', String)], timeout=5.0):
43+
with WaitForTopics([('chatter', String)], timeout=15.0):
4444
print('Topic received messages !')

launch_testing/launch_testing_examples/launch_testing_examples/check_node_launch_test.py

Lines changed: 12 additions & 13 deletions
Original file line numberDiff line numberDiff line change
@@ -44,19 +44,18 @@ def generate_test_description():
4444

4545
class TestFixture(unittest.TestCase):
4646

47-
def test_node_start(self, proc_output):
47+
def setUp(self):
4848
rclpy.init()
49-
node = Node('test_node')
50-
assert wait_for_node(node, 'demo_node_1', 8.0), 'Node not found !'
51-
rclpy.shutdown()
52-
49+
self.node = Node('test_node')
5350

54-
def wait_for_node(dummy_node, node_name, timeout=8.0):
55-
start = time.time()
56-
flag = False
57-
print('Waiting for node...')
58-
while time.time() - start < timeout and not flag:
59-
flag = node_name in dummy_node.get_node_names()
60-
time.sleep(0.1)
51+
def tearDown(self):
52+
self.node.destroy_node()
53+
rclpy.shutdown()
6154

62-
return flag
55+
def test_node_start(self, proc_output):
56+
start = time.time()
57+
found = False
58+
while time.time() - start < 20.0 and not found:
59+
found = 'demo_node_1' in self.node.get_node_names()
60+
time.sleep(0.1)
61+
assert found, 'Node not found !'

launch_testing/launch_testing_examples/launch_testing_examples/set_param_launch_test.py

Lines changed: 17 additions & 17 deletions
Original file line numberDiff line numberDiff line change
@@ -43,26 +43,26 @@ def generate_test_description():
4343
if os.name != 'nt':
4444
class TestFixture(unittest.TestCase):
4545

46-
def test_set_parameter(self, proc_output):
46+
def setUp(self):
4747
rclpy.init()
48-
node = Node('test_node')
49-
response = set_parameter(node, value=True)
50-
assert response.successful, 'Could not set parameter!'
51-
rclpy.shutdown()
48+
self.node = Node('test_node')
5249

50+
def tearDown(self):
51+
self.node.destroy_node()
52+
rclpy.shutdown()
5353

54-
def set_parameter(dummy_node, value=True, timeout=5.0):
55-
parameters = [rclpy.Parameter('demo_parameter_1', value=value).to_parameter_msg()]
54+
def test_set_parameter(self, proc_output):
55+
parameters = [rclpy.Parameter('demo_parameter_1', value=True).to_parameter_msg()]
5656

57-
client = dummy_node.create_client(SetParameters, 'demo_node_1/set_parameters')
58-
ready = client.wait_for_service(timeout_sec=timeout)
59-
if not ready:
60-
raise RuntimeError('Wait for service timed out')
57+
client = self.node.create_client(SetParameters, 'demo_node_1/set_parameters')
58+
ready = client.wait_for_service(timeout_sec=15.0)
59+
if not ready:
60+
raise RuntimeError('Wait for service timed out')
6161

62-
request = SetParameters.Request()
63-
request.parameters = parameters
64-
future = client.call_async(request)
65-
rclpy.spin_until_future_complete(dummy_node, future, timeout_sec=timeout)
62+
request = SetParameters.Request()
63+
request.parameters = parameters
64+
future = client.call_async(request)
65+
rclpy.spin_until_future_complete(self.node, future, timeout_sec=15.0)
6666

67-
response = future.result()
68-
return response.results[0]
67+
response = future.result()
68+
assert response.results[0].successful, 'Could not set parameter!'

launch_testing/launch_testing_examples/package.xml

Lines changed: 0 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -22,7 +22,6 @@
2222
<exec_depend>rclpy</exec_depend>
2323
<exec_depend>rcl_interfaces</exec_depend>
2424
<exec_depend>ros2bag</exec_depend>
25-
<exec_depend>rosbag2_transport</exec_depend>
2625
<exec_depend>std_msgs</exec_depend>
2726

2827
<test_depend>ament_copyright</test_depend>

0 commit comments

Comments
 (0)