$search
00001 #! /usr/bin/env python 00002 00003 import sys 00004 import time 00005 import subprocess 00006 import unittest 00007 import math 00008 00009 import roslib; roslib.load_manifest('network_monitor_udp') 00010 import rospy 00011 import rostest 00012 00013 from network_monitor_udp.linktest import MetricLog 00014 from network_monitor_udp.linktest import UdpmonsourceHandle 00015 from network_monitor_udp.linktest import LinkTest 00016 from network_monitor_udp.msg import LinktestGoal 00017 00018 class MetricLogTest(unittest.TestCase): 00019 def __init__(self, *args): 00020 super(MetricLogTest, self).__init__(*args) 00021 00022 def setUp(self): 00023 pass 00024 00025 def test_basic_stats(self): 00026 testlog = MetricLog() 00027 00028 for i in range(1, 101): 00029 testlog.record(float(i), rospy.Time(float(i))) 00030 00031 self.assertEqual(testlog.curr(), 100.0, 00032 "Curr val should be (%.2f) and was instead (%.2f)"% 00033 (100.0, testlog.curr())) 00034 00035 self.assertEqual(testlog.min(), 1.0, 00036 "Min val should be (%.2f) and was instead (%.2f)"% 00037 (1.0, testlog.min())) 00038 00039 self.assertEqual(testlog.max(), 100.0, 00040 "Max val should be (%.2f) and was instead (%.2f)"% 00041 (100.0, testlog.max())) 00042 00043 self.assertEqual(testlog.avg(), 50.5, 00044 "Avg val should be (%.2f) and was instead (%.2f)"% 00045 (50.5, testlog.avg())) 00046 00047 self.assertEqual(testlog.count(), 100, 00048 "Count should be (%d) and was instead (%d)"% 00049 (100, testlog.count())) 00050 00051 self.assertAlmostEqual(testlog.stdev(), 29.0115, 3, 00052 "Stdev should be (%.2f) and was instead (%.2f)"% 00053 (29.0115, testlog.stdev())) 00054 00055 for i in range(101, 201): 00056 testlog.record(-float(i), rospy.Time(float(i))) 00057 00058 self.assertEqual(testlog.curr(), -200.0, 00059 "Curr val should be (%.2f) and was instead (%.2f)"% 00060 (-200.0, testlog.curr())) 00061 00062 self.assertEqual(testlog.min(), -200.0, 00063 "Min val should be (%.2f) and was instead (%.2f)"% 00064 (1.0, testlog.min())) 00065 00066 self.assertEqual(testlog.max(), 100.0, 00067 "Max val should be (%.2f) and was instead (%.2f)"% 00068 (100.0, testlog.max())) 00069 00070 self.assertEqual(testlog.avg(), -50.0, 00071 "Avg val should be (%.2f) and was instead (%.2f)"% 00072 (-50.0, testlog.avg())) 00073 00074 self.assertEqual(testlog.count(), 200, 00075 "Count should be (%d) and was instead (%d)"% 00076 (200, testlog.count())) 00077 00078 self.assertAlmostEqual(testlog.stdev(), 104.8258, 3, 00079 "Stdev should be (%.2f) and was instead (%.2f)"% 00080 (104.8258, testlog.stdev())) 00081 00082 def test_moving_stats(self): 00083 testlog = MetricLog() 00084 00085 for i in range(1, 98, 4): 00086 testlog.record(float(i), rospy.Time(float(i))) 00087 00088 self.assertEqual(testlog.movavg(), 79.0, 00089 "Moving avg should be (%.2f) and was instead (%.2f)"% 00090 (79.0, testlog.movavg())) 00091 00092 self.assertAlmostEqual(testlog.movstdev(), 12.1106, 3, 00093 "Stdev should be (%.2f) and was instead (%.2f)"% 00094 (12.1106, testlog.movstdev())) 00095 00096 self.assertAlmostEqual(testlog.expavg(), 63.8716, 3, 00097 "Expavg should be (%.2f) and was instead (%.2f)"% 00098 (63.8716, testlog.expavg())) 00099 00100 def test_time_and_duration(self): 00101 testlog = MetricLog() 00102 00103 testlog.min_time() 00104 00105 self.assertEqual(testlog.min_time(), 0.0) 00106 self.assertEqual(testlog.max_time(), 0.0) 00107 self.assertEqual(testlog.duration(), 0.0, 00108 "Duration should be (%.2f) and was instead (%.2f)"% 00109 (0.0, testlog.duration())) 00110 00111 testlog.record(1.0, 5.0) 00112 testlog.record(2.0, 1000.0) 00113 testlog.record(3.0, 1330.0) 00114 00115 self.assertEqual(testlog.min_time(), 5.0, 00116 "Min recorded time should be (%.2f) and was instead (%.2f)"% 00117 (5.0, testlog.min_time())) 00118 self.assertEqual(testlog.max_time(), 1330.0, 00119 "Min recorded time should be (%.2f) and was instead (%.2f)"% 00120 (1330.0, testlog.max_time())) 00121 self.assertEqual(testlog.duration(), 1325.0, 00122 "Duration should be (%.2f) and was instead (%.2f)"% 00123 (1325.0, testlog.duration())) 00124 00125 testlog.reset_all() 00126 00127 start_time = time.time() 00128 testlog.record(1.0) 00129 time.sleep(0.5) 00130 testlog.record(2.0) 00131 time.sleep(0.5) 00132 testlog.record(3.0) 00133 end_time = time.time() 00134 00135 self.assertTrue(math.fabs(end_time - testlog.max_time()) < 0.1, 00136 "Max time should be (%.2f) and was instead (%.2f)"% 00137 (end_time, testlog.max_time())) 00138 00139 self.assertTrue(math.fabs(end_time - testlog.max_time()) < 0.1, 00140 "Min time should be (%.2f) and was instead (%.2f)"% 00141 (end_time, testlog.min_time())) 00142 00143 self.assertTrue(math.fabs((end_time - start_time) - testlog.duration()) < 0.15, 00144 "Duration should be (%.2f) and was instead (%.2f)"% 00145 ((end_time - start_time), testlog.duration())) 00146 00147 if __name__ == '__main__': 00148 try: 00149 rostest.run('network_monitor_udp', 'blahblah', MetricLogTest) 00150 except KeyboardInterrupt, e: 00151 pass