Skip to content

Commit

Permalink
Fix race condition in tests
Browse files Browse the repository at this point in the history
We need to publish scans repeatedly in case the filter chain runs and
processes the output scan before we finish subscribing to that topic.
  • Loading branch information
jonbinney committed Aug 20, 2024
1 parent e02d296 commit 5ea368f
Show file tree
Hide file tree
Showing 2 changed files with 18 additions and 10 deletions.
10 changes: 8 additions & 2 deletions test/test_polygon_filter.test.py
Original file line number Diff line number Diff line change
Expand Up @@ -37,8 +37,14 @@ def test_polygon_filter(self):
node.start_subscriber()
node.publish_laser_scan()

msgs_received_flag = node._msg_event_object.wait(timeout=10.0)
assert msgs_received_flag, "Did not receive msgs !"
publish_rate = node.create_rate(5)
for _ in range(10):
if node._msg_event_object.isSet():
break
node.publish_laser_scan()
publish_rate.sleep()

assert node._msg_event_object.isSet(), "Did not receive msgs !"
expected_scan_ranges = [1.0, 1.0, 1.0, 1.0, float("nan"), float("nan"), float("nan"), 1, 1, 1, 1]
for scan_range, expected_scan_range in zip(node._received_message.ranges, expected_scan_ranges):
if math.isnan(expected_scan_range) or math.isnan(scan_range):
Expand Down
18 changes: 10 additions & 8 deletions test/test_speckle_filter.test.py
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,6 @@
import pytest
import rclpy
from rclpy.node import Node
from rclpy.qos import QoSProfile, QoSDurabilityPolicy
from sensor_msgs.msg import LaserScan


Expand Down Expand Up @@ -50,12 +49,16 @@ def test_speckle_filter(self):
node = TestFixture()
self.assertTrue(node.wait_for_subscribers(10))
node.start_subscribers()
node.publish_laser_scan()

dist_msgs_received_flag = node.dist_msg_event_object.wait(timeout=10.0)
eucl_msgs_received_flag = node.eucl_msg_event_object.wait(timeout=10.0)
assert dist_msgs_received_flag, "Did not receive distance msgs !"
assert eucl_msgs_received_flag, "Did not receive euclidean msgs !"
publish_rate = node.create_rate(5)
for _ in range(10):
if node.dist_msg_event_object.isSet() and node.eucl_msg_event_object.isSet():
break
node.publish_laser_scan()
publish_rate.sleep()

assert node.dist_msg_event_object.isSet(), "Did not receive distance msgs !"
assert node.eucl_msg_event_object.isSet(), "Did not receive euclidean msgs !"

expected_scan_ranges = [1, 1, 1, 1, float("nan"), 1, 1, 1, 1, 1, 1]
for scan_range, expected_scan_range in zip(node.msg_dist.ranges, expected_scan_ranges):
Expand Down Expand Up @@ -92,8 +95,7 @@ def __init__(self):
super().__init__("test_speckle_filter_distance")
self.dist_msg_event_object = Event()
self.eucl_msg_event_object = Event()
qos = QoSProfile(depth=1, durability=QoSDurabilityPolicy.TRANSIENT_LOCAL)
self.publisher = self.create_publisher(LaserScan, "scan", qos_profile=qos)
self.publisher = self.create_publisher(LaserScan, "scan", 10)

def wait_for_subscribers(self, timeout):
timer_period = 0.1
Expand Down

0 comments on commit 5ea368f

Please sign in to comment.