Skip to content

Commit

Permalink
Make launch_testing_ros examples more robust. (#394)
Browse files Browse the repository at this point in the history
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 <[email protected]>
  • Loading branch information
clalancette authored Mar 8, 2024
1 parent d71c7a9 commit 862520d
Show file tree
Hide file tree
Showing 5 changed files with 61 additions and 68 deletions.
45 changes: 24 additions & 21 deletions launch_testing_ros/test/examples/check_msgs_launch_test.py
Original file line number Diff line number Diff line change
Expand Up @@ -27,7 +27,6 @@
import launch_testing.markers
import pytest
import rclpy
from rclpy.node import Node
from std_msgs.msg import String


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

class TestFixture(unittest.TestCase):

def test_check_if_msgs_published(self, proc_output: ActiveIoHandler):
rclpy.init()
def subscription_callback(self, data: String):
self.msg_event_object.set()

def spin(self):
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 !'
while rclpy.ok() and not self.spinning.is_set():
rclpy.spin_once(self.node, timeout_sec=0.1)
finally:
rclpy.shutdown()


class MakeTestNode(Node):
return

def __init__(self, name: str = 'test_node'):
super().__init__(name)
def setUp(self):
rclpy.init()
self.node = rclpy.create_node('test_node')
self.spinning = Event()
self.msg_event_object = Event()

def start_subscriber(self):
# Create a subscriber
self.subscription = self.create_subscription(
self.subscription = self.node.create_subscription(
String,
'chatter',
self.subscriber_callback,
self.subscription_callback,
10
)

# Add a spin thread
self.ros_spin_thread = Thread(target=lambda node: rclpy.spin(node), args=(self,))
self.ros_spin_thread = Thread(target=self.spin)
self.ros_spin_thread.start()

def subscriber_callback(self, data: String):
self.msg_event_object.set()
def tearDown(self):
self.spinning.set()
self.ros_spin_thread.join()
self.node.destroy_subscription(self.subscription)
self.node.destroy_node()
rclpy.shutdown()

def test_check_if_msgs_published(self, proc_output: ActiveIoHandler):
msgs_received_flag = self.msg_event_object.wait(timeout=15.0)
assert msgs_received_flag, 'Did not receive msgs !'
32 changes: 14 additions & 18 deletions launch_testing_ros/test/examples/check_node_launch_test.py
Original file line number Diff line number Diff line change
Expand Up @@ -25,7 +25,6 @@
import launch_testing.markers
import pytest
import rclpy
from rclpy.node import Node


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

class TestFixture(unittest.TestCase):

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


class MakeTestNode(Node):
self.node = rclpy.create_node('test_node')

def __init__(self, name: str = 'test_node'):
super().__init__(name)
def tearDown(self):
self.node.destroy_node()
rclpy.shutdown()

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

return flag
assert found, 'Node not found!'
46 changes: 20 additions & 26 deletions launch_testing_ros/test/examples/set_param_launch_test.py
Original file line number Diff line number Diff line change
Expand Up @@ -25,7 +25,6 @@
import pytest
from rcl_interfaces.srv import SetParameters
import rclpy
from rclpy.node import Node


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

class TestFixture(unittest.TestCase):

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

self.node = rclpy.create_node('test_node')

class MakeTestNode(Node):
def tearDown(self):
self.node.destroy_node()
rclpy.shutdown()

def __init__(self, name: str = 'test_node'):
super().__init__(name)

def set_parameter(self, state: bool = True, timeout: float = 5.0):
parameters = [rclpy.Parameter('demo_parameter_1', value=state).to_parameter_msg()]
def test_set_parameter(self, proc_output: ActiveIoHandler):
parameters = [rclpy.Parameter('demo_parameter_1', value=True).to_parameter_msg()]

client = self.create_client(SetParameters, 'demo_node_1/set_parameters')
ready = client.wait_for_service(timeout_sec=timeout)
if not ready:
raise RuntimeError('Wait for service timed out')
client = self.node.create_client(SetParameters, 'demo_node_1/set_parameters')
try:
ready = client.wait_for_service(timeout_sec=15.0)
if not ready:
raise RuntimeError('Wait for service timed out')

request = SetParameters.Request()
request.parameters = parameters
future = client.call_async(request)
rclpy.spin_until_future_complete(self, future, timeout_sec=timeout)
request = SetParameters.Request()
request.parameters = parameters
future = client.call_async(request)
rclpy.spin_until_future_complete(self.node, future, timeout_sec=15.0)

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

response = future.result()
return response.results[0]
assert future.result().results[0].successful, 'Could not set parameter!'
finally:
self.node.destroy_client(client)
Original file line number Diff line number Diff line change
Expand Up @@ -140,7 +140,7 @@ def test_listener_receives(self,
success = proc_output.waitFor(
expected_output=msg.data,
process=listener,
timeout=1.0,
timeout=15.0,
)
if success:
break
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -64,7 +64,7 @@ def test_topics_successful(self, count: int):

# Method 1 : Using the magic methods and 'with' keyword
with WaitForTopics(
topic_list, timeout=10.0, messages_received_buffer_length=10
topic_list, timeout=15.0, messages_received_buffer_length=10
) as wait_for_node_object_1:
assert wait_for_node_object_1.topics_received() == expected_topics
assert wait_for_node_object_1.topics_not_received() == set()
Expand All @@ -76,7 +76,7 @@ def test_topics_successful(self, count: int):
# Multiple instances of WaitForNode() can be created safely as
# their internal nodes spin in separate contexts
# Method 2 : Manually calling wait() and shutdown()
wait_for_node_object_2 = WaitForTopics(topic_list, timeout=10.0)
wait_for_node_object_2 = WaitForTopics(topic_list, timeout=15.0)
assert wait_for_node_object_2.wait()
assert wait_for_node_object_2.topics_received() == expected_topics
assert wait_for_node_object_2.topics_not_received() == set()
Expand Down

0 comments on commit 862520d

Please sign in to comment.