11 from threading
import Lock
20 def __init__(self, scale="KB", captureSize=100):
31 self.topicSizesArray.append([])
32 self.topicTimesArray.append([])
35 topic_num = _topic_num
50 sub = rospy.Subscriber(topic_name, rospy.AnyMsg, self.
_gen_callback())
51 self.subscriberArray.append(sub)
52 print "subscribed as %d: %s" % (len(self.
subscriberArray)-1, topic_name)
71 current_time = time.time()
78 row_format =
"{:>" + str(longest_topic_len + 1) +
"}" +
"{:>11}" * 5
80 print row_format.format(
"Name",
"avg/sec",
"avg/msg",
81 "min/msg",
"max/msg",
"quant")
87 bytes_per_sec = 1.0 * total_bytes / (current_time - start_time)
88 bytes_per_msg = total_bytes / n
91 res = [bytes_per_sec, bytes_per_msg, min_size, max_size]
94 bps, bpm, ms, Ms = [
"%.2fB" % v
for v
in res]
96 bps, bpm, ms, Ms = [
"%.2fKB" % (v/1000)
for v
in res]
98 bps, bpm, ms, Ms = [
"%.2fMB" % (v/1000000)
for v
in res]
100 raise "error: invalid scale type" 102 print row_format.format(self.
subscriberArray[i].name, bps, bpm, ms, Ms, n)
108 print "subscribed topic:" 109 for sub
in tc.subscriberArray:
110 print "%d: %s" % (i, sub.name)
114 print "[Usage] rosrun jsk_topic_tools topic_compare.py [Option] <topic_name_1>..<topic_name_n>" 116 print "-h: full usage" 117 print "-b: show value as bytes" 118 print "-m: show value as megabytes" 120 if __name__ ==
'__main__':
122 if len(sys.argv) < 2:
123 print "[Usage] rosrun jsk_topic_tools topic_compare.py <topic_name_1>..<topic_name_n>" 126 rospy.init_node(
"topic_compare")
132 elif "-b" in sys.argv:
134 elif "-m" in sys.argv:
139 for name
in sys.argv[1:]:
142 tc.registerTopic(name)
144 rospy.on_shutdown(onShutdown)
146 while not rospy.is_shutdown():
147 rospy.rostime.wallsleep(1.0)
def __init__(self, scale="KB", captureSize=100)
def getStartTime(self, i)
def registerTopic(self, topic_name)
def getBandwidth(self, i)
def getTotalBytes(self, i)
def isAllTopicAvailable(self, size)
def getMessageNum(self, i)