Go to the documentation of this file.00001
00002
00003
00004 import imp
00005 import roslib
00006 import roslib.message
00007 import rospy
00008 import os, sys
00009 import time
00010 import traceback
00011 from threading import Lock
00012
00013 class ROSTopicCompare(object):
00014 subscriberArray = []
00015 topicSizesArray = []
00016 topicTimesArray = []
00017 scaleType = 0
00018 captureSize = 100
00019 lock = Lock()
00020 def __init__(self, scale="KB", captureSize=100):
00021 if scale == "B":
00022 self.scaleType = 1
00023 elif scale == "KB":
00024 self.scaleType = 2
00025 elif scale == "MB":
00026 self.scaleType = 3
00027
00028 self.captureSize = captureSize
00029
00030 def _gen_callback(self):
00031 self.topicSizesArray.append([])
00032 self.topicTimesArray.append([])
00033 _topic_num = len(self.subscriberArray)
00034 def _callback(msg):
00035 topic_num = _topic_num
00036 try:
00037 t = time.time()
00038 with self.lock:
00039 self.topicTimesArray[topic_num].append(t)
00040 self.topicSizesArray[topic_num].append(len(msg._buff))
00041 assert(len(self.topicTimesArray[topic_num]) == len(self.topicSizesArray[topic_num]))
00042 if len(self.topicTimesArray[topic_num]) > self.captureSize:
00043 self.topicTimesArray[topic_num].pop(0)
00044 self.topicSizesArray[topic_num].pop(0)
00045 except:
00046 traceback.print_exc()
00047 return _callback
00048
00049 def registerTopic(self, topic_name):
00050 sub = rospy.Subscriber(topic_name, rospy.AnyMsg, self._gen_callback())
00051 self.subscriberArray.append(sub)
00052 print "subscribed as %d: %s" % (len(self.subscriberArray)-1, topic_name)
00053 def isAllTopicAvailable(self, size):
00054 with self.lock:
00055 return all([len(t) > size for t in self.topicTimesArray])
00056 def getTotalBytes(self, i):
00057 return sum(self.topicSizesArray[i])
00058 def getMaxByte(self, i):
00059 return max(self.topicSizesArray[i])
00060 def getMinByte(self, i):
00061 return min(self.topicSizesArray[i])
00062 def getMessageNum(self, i):
00063 return len(self.topicTimesArray[i])
00064 def getStartTime(self, i):
00065 return self.topicTimesArray[i][0]
00066 def getEndTime(self, i):
00067 return self.topicTimesArray[i][-1]
00068 def getBandwidth(self, i):
00069 return self.getTotalBytes(i) / (self.getEndTime(i) - self.getStartTime(i))
00070 def printBandWidth(self):
00071 current_time = time.time()
00072
00073
00074 longest_topic_len = 0
00075 for i in range(len(self.subscriberArray)):
00076 if len(self.subscriberArray[i].name) > longest_topic_len:
00077 longest_topic_len = len(self.subscriberArray[i].name)
00078 row_format = "{:>" + str(longest_topic_len + 1) + "}" + "{:>11}" * 5
00079 print ""
00080 print row_format.format("Name", "avg/sec", "avg/msg",
00081 "min/msg", "max/msg", "quant")
00082 for i in range(len(self.subscriberArray)):
00083 try:
00084 n = self.getMessageNum(i)
00085 start_time = self.getStartTime(i)
00086 total_bytes = self.getTotalBytes(i)
00087 bytes_per_sec = 1.0 * total_bytes / (current_time - start_time)
00088 bytes_per_msg = total_bytes / n
00089 max_size = self.getMaxByte(i)
00090 min_size = self.getMinByte(i)
00091 res = [bytes_per_sec, bytes_per_msg, min_size, max_size]
00092
00093 if self.scaleType == 1:
00094 bps, bpm, ms, Ms = ["%.2fB" % v for v in res]
00095 elif self.scaleType == 2:
00096 bps, bpm, ms, Ms = ["%.2fKB" % (v/1000) for v in res]
00097 elif self.scaleType == 3:
00098 bps, bpm, ms, Ms = ["%.2fMB" % (v/1000000) for v in res]
00099 else:
00100 raise "error: invalid scale type"
00101 quit()
00102 print row_format.format(self.subscriberArray[i].name, bps, bpm, ms, Ms, n)
00103 except:
00104 pass
00105
00106 def onShutdown():
00107 i = 0
00108 print "subscribed topic:"
00109 for sub in tc.subscriberArray:
00110 print "%d: %s" % (i, sub.name)
00111 i += 1
00112
00113 def fullUsage():
00114 print "[Usage] rosrun jsk_topic_tools topic_compare.py [Option] <topic_name_1>..<topic_name_n>"
00115 print "[Option]"
00116 print "-h: full usage"
00117 print "-b: show value as bytes"
00118 print "-m: show value as megabytes"
00119
00120 if __name__ == '__main__':
00121
00122 if len(sys.argv) < 2:
00123 print "[Usage] rosrun jsk_topic_tools topic_compare.py <topic_name_1>..<topic_name_n>"
00124 quit()
00125
00126 rospy.init_node("topic_compare")
00127
00128
00129 if "-h" in sys.argv:
00130 fullUsage()
00131 quit()
00132 elif "-b" in sys.argv:
00133 tc = ROSTopicCompare("B")
00134 elif "-m" in sys.argv:
00135 tc = ROSTopicCompare("MB")
00136 else:
00137 tc = ROSTopicCompare()
00138
00139 for name in sys.argv[1:]:
00140 if name[0] != "/":
00141 continue
00142 tc.registerTopic(name)
00143
00144 rospy.on_shutdown(onShutdown)
00145
00146 while not rospy.is_shutdown():
00147 rospy.rostime.wallsleep(1.0)
00148 tc.printBandWidth()