40 from cStringIO
import StringIO
42 from io
import StringIO
44 from random_messages
import RandomMsgGen
56 nowtime = rospy.Time.now()
58 if self.
start is None:
63 self.input.append((topic, msg, nowtime.to_sec()))
69 rospy.init_node(
'random_sub', anonymous=
True)
74 self.assertTrue(len(sys.argv[1]) > 3)
76 seed = int(sys.argv[1])
77 topics = int(sys.argv[2])
78 length = float(sys.argv[3])
79 scale = float(sys.argv[4])
85 for (topic, msg_class)
in rmg.topics():
86 subscribers[topic] = rospy.Subscriber(topic, msg_class, self.
msg_cb_topic(topic))
88 bagpath = os.path.join(
'/tmp',
'test_rosbag_random_record_%d.bag'%seed)
89 cmd = [
'rosbag',
'play',
'-d', str(DELAY),
'-r', str(scale)]
91 rospy.loginfo(str(cmd))
94 cmd += [
'--clock',
'--hz',
'100']
99 f1 = subprocess.Popen(cmd)
102 while (len(self.
input) < rmg.message_count()):
106 if len(self.
input) == last_input_count:
109 self.assertEqual(rc, 0)
111 last_input_count = len(self.
input)
113 self.assertEqual(len(self.
input), rmg.message_count())
120 for (expect_topic, expect_msg, expect_time)
in rmg.messages():
126 expect_msg.serialize(buff)
127 expect_msg.deserialize(buff.getvalue())
131 for ind
in range(0,100):
132 (input_topic, input_msg, input_time) = self.
input[ind]
134 if (genpy.message.strify_message(expect_msg) == genpy.message.strify_message(input_msg)):
139 diff = input_time - expect_time
141 if (diff < max_early):
144 if (diff > max_late):
147 avg_off += diff / rmg.message_count()
149 power += (diff**2) / rmg.message_count()
154 self.assertTrue(input_time - expect_time > -.5)
155 self.assertTrue(abs(input_time - expect_time) < 5.0)
159 print(
"No match at time: %f" % expect_time)
161 self.assertTrue(msg_match)
163 print(
"%f %f %f %f"%(max_early, max_late, avg_off, power))
168 self.assertEqual(f1.returncode, 0)
170 if __name__ ==
'__main__':
171 rostest.rosrun(
'test_rosbag',
'random_record_play', RandomPlay, sys.argv)
def test_random_play(self)
def msg_cb_topic(self, topic)