00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035 import roslib
00036 roslib.load_manifest('test_rosbag')
00037
00038 import unittest
00039 import rospy
00040 import rostest
00041 import sys
00042 from cStringIO import StringIO
00043 import time
00044 from random_messages import RandomMsgGen
00045 import subprocess
00046 import os
00047
00048 DELAY = 0.5
00049
00050 class RandomPlay(unittest.TestCase):
00051
00052 def msg_cb_topic(self, topic):
00053 def msg_cb(msg):
00054 nowtime = rospy.Time.now()
00055
00056 if self.start is None:
00057 self.start = nowtime
00058
00059 nowtime -= self.start
00060
00061 self.input.append((topic, msg, nowtime.to_sec()))
00062
00063 return msg_cb
00064
00065
00066 def test_random_play(self):
00067 rospy.init_node('random_sub', anonymous=True)
00068
00069 self.start = None
00070 self.input = []
00071
00072 self.assertTrue(len(sys.argv[1]) > 3)
00073
00074 seed = int(sys.argv[1])
00075 topics = int(sys.argv[2])
00076 length = float(sys.argv[3])
00077 scale = float(sys.argv[4])
00078 self.use_clock = bool(int(sys.argv[5]))
00079
00080 rmg = RandomMsgGen(int(seed), topics, length)
00081
00082 subscribers = {}
00083 for (topic, msg_class) in rmg.topics():
00084 subscribers[topic] = rospy.Subscriber(topic, msg_class, self.msg_cb_topic(topic))
00085
00086 bagpath = os.path.join('/tmp', 'test_rosbag_random_record_%d.bag'%seed)
00087 cmd = ['rosbag', 'play', '-d', str(DELAY), '-r', str(scale)]
00088
00089 rospy.loginfo(str(cmd))
00090
00091 if (self.use_clock):
00092 cmd += ['--clock', '--hz', '100']
00093
00094 cmd += [bagpath]
00095
00096 f1 = subprocess.Popen(cmd)
00097
00098 while (len(self.input) < rmg.message_count()):
00099
00100 time.sleep(.1)
00101
00102 self.assertEqual(len(self.input), rmg.message_count())
00103
00104 max_late = 0
00105 max_early = 0
00106 avg_off = 0
00107 power = 0
00108
00109 for (expect_topic, expect_msg, expect_time) in rmg.messages():
00110
00111 if (not self.use_clock):
00112 expect_time /= scale
00113
00114 buff = StringIO()
00115 expect_msg.serialize(buff)
00116 expect_msg.deserialize(buff.getvalue())
00117
00118 msg_match = False
00119
00120 for ind in xrange(0,100):
00121 (input_topic, input_msg, input_time) = self.input[ind]
00122
00123 if (roslib.message.strify_message(expect_msg) == roslib.message.strify_message(input_msg)):
00124 msg_match = True
00125 del self.input[ind]
00126
00127
00128 diff = input_time - expect_time
00129
00130 if (diff < max_early):
00131 max_early = diff
00132
00133 if (diff > max_late):
00134 max_late = diff
00135
00136 avg_off += diff / rmg.message_count()
00137
00138 power += (diff**2) / rmg.message_count()
00139
00140
00141
00142
00143 self.assertTrue(input_time - expect_time > -.5)
00144 self.assertTrue(abs(input_time - expect_time) < .5)
00145 break
00146
00147 if not msg_match:
00148 print "No match at time: %f"%expect_time
00149
00150 self.assertTrue(msg_match)
00151
00152 print "%f %f %f %f"%(max_early, max_late, avg_off, power)
00153
00154 (o1,e1) = f1.communicate()
00155 self.assertEqual(f1.returncode, 0)
00156
00157 if __name__ == '__main__':
00158 rostest.rosrun('test_rosbag', 'random_record_play', RandomPlay, sys.argv)