topic_compare.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 # -*- coding: utf-8 -*-
3 
4 import imp
5 import roslib
6 import roslib.message
7 import rospy
8 import os, sys
9 import time
10 import traceback
11 from threading import Lock
12 
13 class ROSTopicCompare(object):
14  subscriberArray = []
15  topicSizesArray = []
16  topicTimesArray = []
17  scaleType = 0
18  captureSize = 100
19  lock = Lock()
20  def __init__(self, scale="KB", captureSize=100):
21  if scale == "B":
22  self.scaleType = 1
23  elif scale == "KB":
24  self.scaleType = 2
25  elif scale == "MB":
26  self.scaleType = 3
27 
28  self.captureSize = captureSize
29 
30  def _gen_callback(self):
31  self.topicSizesArray.append([])
32  self.topicTimesArray.append([])
33  _topic_num = len(self.subscriberArray)
34  def _callback(msg):
35  topic_num = _topic_num
36  try:
37  t = time.time()
38  with self.lock:
39  self.topicTimesArray[topic_num].append(t)
40  self.topicSizesArray[topic_num].append(len(msg._buff))
41  assert(len(self.topicTimesArray[topic_num]) == len(self.topicSizesArray[topic_num]))
42  if len(self.topicTimesArray[topic_num]) > self.captureSize:
43  self.topicTimesArray[topic_num].pop(0)
44  self.topicSizesArray[topic_num].pop(0)
45  except:
46  traceback.print_exc()
47  return _callback
48 
49  def registerTopic(self, topic_name):
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)
53  def isAllTopicAvailable(self, size):
54  with self.lock:
55  return all([len(t) > size for t in self.topicTimesArray])
56  def getTotalBytes(self, i):
57  return sum(self.topicSizesArray[i])
58  def getMaxByte(self, i):
59  return max(self.topicSizesArray[i])
60  def getMinByte(self, i):
61  return min(self.topicSizesArray[i])
62  def getMessageNum(self, i):
63  return len(self.topicTimesArray[i])
64  def getStartTime(self, i):
65  return self.topicTimesArray[i][0]
66  def getEndTime(self, i):
67  return self.topicTimesArray[i][-1]
68  def getBandwidth(self, i):
69  return self.getTotalBytes(i) / (self.getEndTime(i) - self.getStartTime(i))
70  def printBandWidth(self):
71  current_time = time.time()
72 
73  # first lookup the longest topic name
74  longest_topic_len = 0
75  for i in range(len(self.subscriberArray)):
76  if len(self.subscriberArray[i].name) > longest_topic_len:
77  longest_topic_len = len(self.subscriberArray[i].name)
78  row_format = "{:>" + str(longest_topic_len + 1) + "}" + "{:>11}" * 5
79  print ""
80  print row_format.format("Name", "avg/sec", "avg/msg",
81  "min/msg", "max/msg", "quant")
82  for i in range(len(self.subscriberArray)):
83  try:
84  n = self.getMessageNum(i)
85  start_time = self.getStartTime(i)
86  total_bytes = self.getTotalBytes(i)
87  bytes_per_sec = 1.0 * total_bytes / (current_time - start_time)
88  bytes_per_msg = total_bytes / n
89  max_size = self.getMaxByte(i)
90  min_size = self.getMinByte(i)
91  res = [bytes_per_sec, bytes_per_msg, min_size, max_size]
92 
93  if self.scaleType == 1: # B
94  bps, bpm, ms, Ms = ["%.2fB" % v for v in res]
95  elif self.scaleType == 2: # KB
96  bps, bpm, ms, Ms = ["%.2fKB" % (v/1000) for v in res]
97  elif self.scaleType == 3: # MB
98  bps, bpm, ms, Ms = ["%.2fMB" % (v/1000000) for v in res]
99  else:
100  raise "error: invalid scale type"
101  quit()
102  print row_format.format(self.subscriberArray[i].name, bps, bpm, ms, Ms, n)
103  except:
104  pass
105 
107  i = 0
108  print "subscribed topic:"
109  for sub in tc.subscriberArray:
110  print "%d: %s" % (i, sub.name)
111  i += 1
112 
113 def fullUsage():
114  print "[Usage] rosrun jsk_topic_tools topic_compare.py [Option] <topic_name_1>..<topic_name_n>"
115  print "[Option]"
116  print "-h: full usage"
117  print "-b: show value as bytes"
118  print "-m: show value as megabytes"
119 
120 if __name__ == '__main__':
121  # check if valid argument
122  if len(sys.argv) < 2:
123  print "[Usage] rosrun jsk_topic_tools topic_compare.py <topic_name_1>..<topic_name_n>"
124  quit()
125 
126  rospy.init_node("topic_compare")
127 
128  # check options
129  if "-h" in sys.argv:
130  fullUsage()
131  quit()
132  elif "-b" in sys.argv:
133  tc = ROSTopicCompare("B")
134  elif "-m" in sys.argv:
135  tc = ROSTopicCompare("MB")
136  else:
137  tc = ROSTopicCompare()
138 
139  for name in sys.argv[1:]:
140  if name[0] != "/":
141  continue
142  tc.registerTopic(name)
143 
144  rospy.on_shutdown(onShutdown)
145 
146  while not rospy.is_shutdown():
147  rospy.rostime.wallsleep(1.0)
148  tc.printBandWidth()
def __init__(self, scale="KB", captureSize=100)
def registerTopic(self, topic_name)
def isAllTopicAvailable(self, size)


jsk_topic_tools
Author(s): Kei Okada , Yusuke Furuta
autogenerated on Tue Feb 6 2018 03:45:19