Skip to content

Commit ac0a979

Browse files
committed
Address feedback on test
Signed-off-by: Shane Loretz <[email protected]>
1 parent dbb4c14 commit ac0a979

File tree

1 file changed

+16
-33
lines changed

1 file changed

+16
-33
lines changed

rclpy/test/test_publisher.py

Lines changed: 16 additions & 33 deletions
Original file line numberDiff line numberDiff line change
@@ -16,6 +16,7 @@
1616
import unittest
1717

1818
import rclpy
19+
from rclpy.duration import Duration
1920

2021
from test_msgs.msg import BasicTypes
2122

@@ -76,26 +77,6 @@ def do_test_topic_name(cls, test_topics, node):
7677
assert publisher.topic_name == target_topic
7778
publisher.destroy()
7879

79-
@classmethod
80-
def do_test_wait_for_all_acked(cls, test_topic, node, pub_qos, sub_qos):
81-
pub = node.create_publisher(BasicTypes, test_topic, pub_qos)
82-
sub = node.create_subscription(BasicTypes, test_topic, lambda msg: print(msg), sub_qos)
83-
time.sleep(1)
84-
assert pub.get_subscription_count() == 1
85-
basic_types_msg = BasicTypes()
86-
try:
87-
pub.publish(basic_types_msg)
88-
except Exception:
89-
raise AssertionError('Publish data failed')
90-
91-
try:
92-
assert pub.wait_for_all_acked() is True
93-
except Exception:
94-
raise AssertionError('wait_for_all_acked raise exception')
95-
96-
pub.destroy()
97-
sub.destroy()
98-
9980
def test_topic_name(self):
10081
test_topics = [
10182
(TEST_TOPIC, '/' + TEST_TOPIC),
@@ -125,25 +106,27 @@ def test_topic_name_remapping(self):
125106
TestPublisher.do_test_topic_name(test_topics, self.node)
126107

127108
def test_wait_for_all_acked(self):
128-
pub_qos = rclpy.qos.QoSProfile(
109+
qos = rclpy.qos.QoSProfile(
129110
depth=1,
130111
reliability=rclpy.qos.QoSReliabilityPolicy.RELIABLE)
131-
sub_qos = pub_qos
132112

133-
# Publisher and subscription are all reliable
134-
TestPublisher.do_test_wait_for_all_acked(TEST_TOPIC, self.node, pub_qos, sub_qos)
113+
pub = self.node.create_publisher(BasicTypes, TEST_TOPIC, qos)
114+
sub = self.node.create_subscription(BasicTypes, TEST_TOPIC, lambda msg: print(msg), qos)
115+
116+
max_seconds_to_wait = 1
117+
end_time = time.time() + max_seconds_to_wait
118+
while pub.get_subscription_count() != 1:
119+
time.sleep(0.05)
120+
assert time.time() <= end_time # timeout waiting for pub/sub to discover each other
121+
assert pub.get_subscription_count() == 1
135122

136-
# Publisher and subscription are all best effort
137-
pub_qos.reliability = rclpy.qos.QoSReliabilityPolicy.BEST_EFFORT
138-
sub_qos.reliability = rclpy.qos.QoSReliabilityPolicy.BEST_EFFORT
139-
TestPublisher.do_test_wait_for_all_acked(TEST_TOPIC, self.node, pub_qos, sub_qos)
123+
basic_types_msg = BasicTypes()
124+
pub.publish(basic_types_msg)
140125

141-
# Publisher is reliable and subscription is best effort
142-
pub_qos.reliability = rclpy.qos.QoSReliabilityPolicy.RELIABLE
143-
TestPublisher.do_test_wait_for_all_acked(TEST_TOPIC, self.node, pub_qos, sub_qos)
126+
assert pub.wait_for_all_acked(Duration(seconds=max_seconds_to_wait))
144127

145-
# Publisher is best effort and subscription is reliable
146-
# Not work.
128+
pub.destroy()
129+
sub.destroy()
147130

148131

149132
if __name__ == '__main__':

0 commit comments

Comments
 (0)