From 77670b783fcdd56a42e624b0d437cc1354dc1acf Mon Sep 17 00:00:00 2001 From: Kentaro Wada Date: Fri, 6 Nov 2015 07:10:28 +0900 Subject: [PATCH 1/4] Refactor: test_block.py as good example --- jsk_topic_tools/test/test_block.py | 70 +++++++++++++++--------------- 1 file changed, 36 insertions(+), 34 deletions(-) diff --git a/jsk_topic_tools/test/test_block.py b/jsk_topic_tools/test/test_block.py index e5f141cb0..07400790e 100755 --- a/jsk_topic_tools/test/test_block.py +++ b/jsk_topic_tools/test/test_block.py @@ -1,60 +1,62 @@ #!/usr/bin/env python -import os -import sys - import unittest -sys.path.insert(0, os.path.abspath(os.path.join(os.path.dirname(__file__), "..", - "scripts"))) - import rospy try: from std_msgs.msg import String except: - import roslib; roslib.load_manifest("jsk_topic_tools") + import roslib + roslib.load_manifest("jsk_topic_tools") from std_msgs.msg import String +PKG = 'jsk_topic_tools' +NAME = 'test_block' + + class TestBlock(unittest.TestCase): input_msg = None subscriber = None - def reset_subscribers(self): - global running + + def __init__(self, *args): + super(TestBlock, self).__init__(*args) + rospy.init_node(NAME) + self.output_original_pub = rospy.Publisher( + 'output_original', String, queue_size=1) + self.input_original_sub = rospy.Subscriber( + 'input_original', String, self.original_topic_cb) + + def original_topic_cb(self, msg): + self.running = True + self.output_original_pub.publish(msg) + + def reset_subscriber(self): if self.subscriber: self.subscriber.unregister() - seff.subscriber = None - self._input_msg = None - running = False + self.subscriber = None + self.input_msg = None + self.running = False + + def test_subscribe(self): + self.reset_subscriber() + self.subscriber = rospy.Subscriber("output", String, self.cb) + rospy.loginfo("wait 10 seconds...") + rospy.sleep(10) + self.assertFalse(self.input_msg is None) + def cb(self, msg): self.input_msg = msg - def test_no_(self): - global running + + def test_no_subscribe(self): + self.reset_subscriber() # do not subscribe - self.reset_subscribers() rospy.loginfo("wait 10 seconds...") rospy.sleep(10) - self.assertTrue(self.input_msg == None) - def test_sub(self): - global running - self.reset_subscribers() - self.subscribe = rospy.Subscriber("/output", String, self.cb) - rospy.loginfo("wait 10 seconds...") - rospy.sleep(10) - self.assertFalse(self.input_msg == None) + self.assertTrue(self.input_msg is None) -running = False -output_original_pub = None -def topic_cb(msg): - global running - running = True - output_original_pub.publish(msg) if __name__ == "__main__": import rostest - rospy.init_node("test_blocke") - output_original_pub = rospy.Publisher("/output_original", String) - s = rospy.Subscriber("/input_original", String, topic_cb) - rostest.rosrun("jsk_topic_tools", "test_block", TestBlock) - + rostest.rosrun(PKG, NAME, TestBlock) From fdc2cb875d23b8937337dc5488a20da13637ceed Mon Sep 17 00:00:00 2001 From: Kentaro Wada Date: Fri, 6 Nov 2015 07:13:41 +0900 Subject: [PATCH 2/4] Refactor test_connection.py as good example --- jsk_topic_tools/test/test_connection.py | 11 +++++++++-- 1 file changed, 9 insertions(+), 2 deletions(-) diff --git a/jsk_topic_tools/test/test_connection.py b/jsk_topic_tools/test/test_connection.py index 7a3619b24..fa7ab5a4d 100755 --- a/jsk_topic_tools/test/test_connection.py +++ b/jsk_topic_tools/test/test_connection.py @@ -11,8 +11,16 @@ import roslib +PKG = 'jsk_topic_tools' +NAME = 'test_connection' + + class TestConnection(unittest.TestCase): + def __init__(self, *args): + super(TestConnection, self).__init__(*args) + rospy.init_node(NAME) + def test_no_subscribers(self): check_connected_topics = rospy.get_param('~check_connected_topics') master = rosgraph.Master('/test_connection') @@ -51,5 +59,4 @@ def _cb_test_subscriber_appears(self, msg): if __name__ == "__main__": import rostest - rospy.init_node('test_connection') - rostest.rosrun("jsk_topic_tools", "test_connection", TestConnection) + rostest.rosrun(PKG, NAME, TestConnection) From ab9c354ffcbbaa489ef5f9cf1dfa72796dc68b83 Mon Sep 17 00:00:00 2001 From: Kentaro Wada Date: Fri, 6 Nov 2015 07:18:52 +0900 Subject: [PATCH 3/4] Refactor test_hz_measure.py as good example --- jsk_topic_tools/test/test_hz_measure.py | 45 +++++++++++++------------ 1 file changed, 24 insertions(+), 21 deletions(-) diff --git a/jsk_topic_tools/test/test_hz_measure.py b/jsk_topic_tools/test/test_hz_measure.py index d9939a69f..bd491f2d6 100755 --- a/jsk_topic_tools/test/test_hz_measure.py +++ b/jsk_topic_tools/test/test_hz_measure.py @@ -1,54 +1,57 @@ #!/usr/bin/env python -import os -import sys +# -*- coding: utf-8 -*- import unittest -sys.path.insert(0, os.path.abspath(os.path.join(os.path.dirname(__file__), "..", - "scripts"))) -from topic_compare import ROSTopicCompare import rospy -import time import numpy as np try: from std_msgs.msg import Float32 except: - import roslib; roslib.load_manifest("jsk_topic_tools") + import roslib + roslib.load_manifest("jsk_topic_tools") from std_msgs.msg import Float32 + +PKG = 'jsk_topic_tools' +NAME = 'test_hz_measure' + + def eps_equal(a, b, err=0.001): return abs(a - b) < err -hz_msg = None -def topic_cb(msg): - global hz_msg - hz_msg = msg +class TestHzMeasure(unittest.TestCase): + def __init__(self, *args): + super(TestHzMeasure, self).__init__(*args) + self.hz_msg = None + rospy.init_node(NAME) + rospy.Subscriber('/hz/output', Float32, self.topic_cb) + + def topic_cb(self, msg): + self.hz_msg = msg -class TestHzMeasure(unittest.TestCase): def test_hz(self): - global hz_msg - while hz_msg == None: + while self.hz_msg is None: rospy.loginfo('wait for msg...') if not rospy.is_shutdown(): - rospy.sleep(5.0) #wait for 5 sec + rospy.sleep(5.0) # wait for 5 sec # should be 30Hz msgs = [] while len(msgs) < 30: - msgs.append(hz_msg.data) + msgs.append(self.hz_msg.data) # rospy.loginfo('hz of msg %s'%hz_msg.data) rospy.sleep(0.1) hz = np.median(msgs) - rospy.loginfo('average hz of msg %s'%np.mean(msgs)) - rospy.loginfo('median hz of msg %s'%hz) + rospy.loginfo('average hz of msg %s' % np.mean(msgs)) + rospy.loginfo('median hz of msg %s' % hz) self.assertTrue(eps_equal(hz, 30, 1)) + if __name__ == "__main__": import rostest - rospy.init_node("test_hz_measure") - s = rospy.Subscriber("/hz/output", Float32, topic_cb) - rostest.rosrun("jsk_topic_tools", "test_hz_measure", TestHzMeasure) + rostest.rosrun(PKG, NAME, TestHzMeasure) From d79d5f08b4f36ec84be087ca0bff86227cb78d24 Mon Sep 17 00:00:00 2001 From: Kentaro Wada Date: Fri, 6 Nov 2015 13:48:19 +0900 Subject: [PATCH 4/4] [jsk_topic_tools] Use retry for tag --- jsk_topic_tools/test/test_hz_measure.py | 4 +--- jsk_topic_tools/test/test_topic_compare.py | 16 ++++++++++------ jsk_topic_tools/test/test_topic_compare.test | 3 ++- 3 files changed, 13 insertions(+), 10 deletions(-) diff --git a/jsk_topic_tools/test/test_hz_measure.py b/jsk_topic_tools/test/test_hz_measure.py index bd491f2d6..a66a5ed34 100755 --- a/jsk_topic_tools/test/test_hz_measure.py +++ b/jsk_topic_tools/test/test_hz_measure.py @@ -3,11 +3,9 @@ import unittest - -import rospy - import numpy as np +import rospy try: from std_msgs.msg import Float32 except: diff --git a/jsk_topic_tools/test/test_topic_compare.py b/jsk_topic_tools/test/test_topic_compare.py index 44a67ceee..9decd5e24 100755 --- a/jsk_topic_tools/test/test_topic_compare.py +++ b/jsk_topic_tools/test/test_topic_compare.py @@ -11,20 +11,25 @@ import rospy import time + def eps_equal(a, b, err=0.001): return abs(a - b) < err -# subscribing three topics -# * /origin -# * /origin (the same topic) -# * /half + class TestTopicCompare(unittest.TestCase): + """Subscribing three topics + * /origin + * /origin (the same topic) + * /half + """ + def test_same_topic(self): while not tc.isAllTopicAvailable(20): rospy.sleep(1) print tc.getTotalBytes(0) / (tc.getEndTime(0) - tc.getStartTime(0)) print tc.getTotalBytes(1) / (tc.getEndTime(1) - tc.getStartTime(1)) self.assertTrue(eps_equal(tc.getBandwidth(0), tc.getBandwidth(1), 20)) + def test_half_topic(self): while not tc.isAllTopicAvailable(20): rospy.sleep(1) @@ -32,6 +37,7 @@ def test_half_topic(self): print tc.getTotalBytes(2) / (tc.getEndTime(2) - tc.getStartTime(2)) self.assertTrue(eps_equal(tc.getBandwidth(0), 2 * tc.getBandwidth(2), 20)) + if __name__ == "__main__": import rostest rospy.init_node("test_topic_compare") @@ -40,5 +46,3 @@ def test_half_topic(self): tc.registerTopic("/origin") tc.registerTopic("/half") rostest.rosrun("jsk_topic_tools", "test_topic_compare", TestTopicCompare) - - diff --git a/jsk_topic_tools/test/test_topic_compare.test b/jsk_topic_tools/test/test_topic_compare.test index 455a1438f..70b355b58 100644 --- a/jsk_topic_tools/test/test_topic_compare.test +++ b/jsk_topic_tools/test/test_topic_compare.test @@ -9,5 +9,6 @@ args="/origin 1 2 /half" /> + name="test_topic_compare" + retry="3" />