topic_statistics.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 # -*- coding: utf-8 -*-
3 # Author: Yuki Furuta <furushchev@jsk.imi.i.u-tokyo.ac.jp>
4 
5 import optparse
6 import rospy
7 
8 class TopicStatistics(object):
9  def __init__(self, topic_name, duration, window_size=None):
10  self.topic_name = topic_name
11  self.duration = duration
12  self.use_timer = True
13  if window_size:
14  self.use_timer = False
15  self.window_size = window_size
16  self.msgs = []
17  self.start_time = None
18  self.end_time = None
19 
20  def cb(self, msg):
21  self.msgs.append(msg)
22  if not self.use_timer and len(self.msgs) > self.window_size:
23  self.stop()
24 
25  def start(self):
26  print "start subscribing", self.topic_name
27  self.start_time = rospy.Time.now()
28  self.sub = rospy.Subscriber(self.topic_name, rospy.AnyMsg, self.cb)
29  if self.use_timer:
30  print "waiting for", self.duration, "[sec]..."
31  self.timer = rospy.Timer(rospy.Duration(self.duration), self.stop, True)
32  else:
33  print "waiting for", self.window_size, "msgs..."
34  rospy.spin()
35 
36  def stop(self, _=None):
37  self.end_time = rospy.Time.now()
38  self.sub.unregister()
39  self.show_result()
40  rospy.signal_shutdown("finished measurement")
41 
42  def show_result(self):
43  d = self.end_time - self.start_time
44  msg_size = reduce(lambda a,b: a+b, map(lambda x: len(x._buff), self.msgs))
45  print "received", len(self.msgs), "messages for", d.to_sec(), "[sec]"
46  print "size amount:\t", msg_size / 1000.0, "[kB]"
47  print "size avg:\t", msg_size / 1000.0 / len(self.msgs), "[kB/msg]"
48  if self.use_timer:
49  print "rate:\t\t", msg_size / 1000.0 / d.to_sec(), "[kB/sec]"
50 
51 if __name__ == '__main__':
52  p = optparse.OptionParser(usage="%prog [options] topic_name")
53  p.add_option("-w", dest="window_size", type="int", default=None)
54  p.add_option("-d", dest="duration", type="int", default=5)
55 
56  (opt, args) = p.parse_args(rospy.myargv())
57  if len(args) != 2:
58  p.print_help()
59  exit(1)
60 
61  rospy.init_node("topic_statistics")
62  t = TopicStatistics(topic_name=args[1],
63  window_size=opt.window_size,
64  duration=opt.duration)
65  t.start()
def __init__(self, topic_name, duration, window_size=None)


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