Skip to content

Commit 4bfd998

Browse files
authored
Check that future is done, and always call rclpy.shutdown (#273)
* Assert the client call succeeded Signed-off-by: Shane Loretz <[email protected]> * Shutdown rclpy when test throws exceptions Signed-off-by: Shane Loretz <[email protected]>
1 parent 06a47b0 commit 4bfd998

File tree

3 files changed

+20
-12
lines changed

3 files changed

+20
-12
lines changed

launch_testing_ros/test/examples/check_msgs_launch_test.py

Lines changed: 7 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -51,11 +51,13 @@ class TestFixture(unittest.TestCase):
5151

5252
def test_check_if_msgs_published(self, proc_output):
5353
rclpy.init()
54-
node = MakeTestNode('test_node')
55-
node.start_subscriber()
56-
msgs_received_flag = node.msg_event_object.wait(timeout=5.0)
57-
assert msgs_received_flag, 'Did not receive msgs !'
58-
rclpy.shutdown()
54+
try:
55+
node = MakeTestNode('test_node')
56+
node.start_subscriber()
57+
msgs_received_flag = node.msg_event_object.wait(timeout=5.0)
58+
assert msgs_received_flag, 'Did not receive msgs !'
59+
finally:
60+
rclpy.shutdown()
5961

6062

6163
class MakeTestNode(Node):

launch_testing_ros/test/examples/check_node_launch_test.py

Lines changed: 5 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -51,9 +51,11 @@ class TestFixture(unittest.TestCase):
5151

5252
def test_node_start(self, proc_output):
5353
rclpy.init()
54-
node = MakeTestNode('test_node')
55-
assert node.wait_for_node('demo_node_1', 8.0), 'Node not found !'
56-
rclpy.shutdown()
54+
try:
55+
node = MakeTestNode('test_node')
56+
assert node.wait_for_node('demo_node_1', 8.0), 'Node not found !'
57+
finally:
58+
rclpy.shutdown()
5759

5860

5961
class MakeTestNode(Node):

launch_testing_ros/test/examples/set_param_launch_test.py

Lines changed: 8 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -47,10 +47,12 @@ class TestFixture(unittest.TestCase):
4747

4848
def test_set_parameter(self, proc_output):
4949
rclpy.init()
50-
node = MakeTestNode('test_node')
51-
response = node.set_parameter(state=True)
52-
assert response.successful, 'Could not set parameter!'
53-
rclpy.shutdown()
50+
try:
51+
node = MakeTestNode('test_node')
52+
response = node.set_parameter(state=True)
53+
assert response.successful, 'Could not set parameter!'
54+
finally:
55+
rclpy.shutdown()
5456

5557

5658
class MakeTestNode(Node):
@@ -71,5 +73,7 @@ def set_parameter(self, state=True, timeout=5.0):
7173
future = client.call_async(request)
7274
rclpy.spin_until_future_complete(self, future, timeout_sec=timeout)
7375

76+
assert future.done(), 'Client request timed out'
77+
7478
response = future.result()
7579
return response.results[0]

0 commit comments

Comments
 (0)