Skip to content

Commit

Permalink
Check that future is done, and always call rclpy.shutdown (ros2#273)
Browse files Browse the repository at this point in the history
* Assert the client call succeeded

Signed-off-by: Shane Loretz <sloretz@openrobotics.org>

* Shutdown rclpy when test throws exceptions

Signed-off-by: Shane Loretz <sloretz@openrobotics.org>
  • Loading branch information
sloretz authored Oct 13, 2021
1 parent 06a47b0 commit 4bfd998
Show file tree
Hide file tree
Showing 3 changed files with 20 additions and 12 deletions.
12 changes: 7 additions & 5 deletions launch_testing_ros/test/examples/check_msgs_launch_test.py
Original file line number Diff line number Diff line change
Expand Up @@ -51,11 +51,13 @@ class TestFixture(unittest.TestCase):

def test_check_if_msgs_published(self, proc_output):
rclpy.init()
node = MakeTestNode('test_node')
node.start_subscriber()
msgs_received_flag = node.msg_event_object.wait(timeout=5.0)
assert msgs_received_flag, 'Did not receive msgs !'
rclpy.shutdown()
try:
node = MakeTestNode('test_node')
node.start_subscriber()
msgs_received_flag = node.msg_event_object.wait(timeout=5.0)
assert msgs_received_flag, 'Did not receive msgs !'
finally:
rclpy.shutdown()


class MakeTestNode(Node):
Expand Down
8 changes: 5 additions & 3 deletions launch_testing_ros/test/examples/check_node_launch_test.py
Original file line number Diff line number Diff line change
Expand Up @@ -51,9 +51,11 @@ class TestFixture(unittest.TestCase):

def test_node_start(self, proc_output):
rclpy.init()
node = MakeTestNode('test_node')
assert node.wait_for_node('demo_node_1', 8.0), 'Node not found !'
rclpy.shutdown()
try:
node = MakeTestNode('test_node')
assert node.wait_for_node('demo_node_1', 8.0), 'Node not found !'
finally:
rclpy.shutdown()


class MakeTestNode(Node):
Expand Down
12 changes: 8 additions & 4 deletions launch_testing_ros/test/examples/set_param_launch_test.py
Original file line number Diff line number Diff line change
Expand Up @@ -47,10 +47,12 @@ class TestFixture(unittest.TestCase):

def test_set_parameter(self, proc_output):
rclpy.init()
node = MakeTestNode('test_node')
response = node.set_parameter(state=True)
assert response.successful, 'Could not set parameter!'
rclpy.shutdown()
try:
node = MakeTestNode('test_node')
response = node.set_parameter(state=True)
assert response.successful, 'Could not set parameter!'
finally:
rclpy.shutdown()


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

assert future.done(), 'Client request timed out'

response = future.result()
return response.results[0]

0 comments on commit 4bfd998

Please sign in to comment.