topic_statistics.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 # -*- coding: utf-8 -*-
00003 # Author: Yuki Furuta <furushchev@jsk.imi.i.u-tokyo.ac.jp>
00004 
00005 import optparse
00006 import rospy
00007 
00008 class TopicStatistics(object):
00009     def __init__(self, topic_name, duration, window_size=None):
00010         self.topic_name = topic_name
00011         self.duration = duration
00012         self.use_timer = True
00013         if window_size:
00014             self.use_timer = False
00015             self.window_size = window_size
00016         self.msgs = []
00017         self.start_time = None
00018         self.end_time = None
00019 
00020     def cb(self, msg):
00021         self.msgs.append(msg)
00022         if not self.use_timer and len(self.msgs) > self.window_size:
00023             self.stop()
00024 
00025     def start(self):
00026         print "start subscribing", self.topic_name
00027         self.start_time = rospy.Time.now()
00028         self.sub = rospy.Subscriber(self.topic_name, rospy.AnyMsg, self.cb)
00029         if self.use_timer:
00030             print "waiting for", self.duration, "[sec]..."
00031             self.timer = rospy.Timer(rospy.Duration(self.duration), self.stop, True)
00032         else:
00033             print "waiting for", self.window_size, "msgs..."
00034         rospy.spin()
00035 
00036     def stop(self, _=None):
00037         self.end_time = rospy.Time.now()
00038         self.sub.unregister()
00039         self.show_result()
00040         rospy.signal_shutdown("finished measurement")
00041 
00042     def show_result(self):
00043         d = self.end_time - self.start_time
00044         msg_size = reduce(lambda a,b: a+b, map(lambda x: len(x._buff), self.msgs))
00045         print "received", len(self.msgs), "messages for", d.to_sec(), "[sec]"
00046         print "size amount:\t", msg_size / 1000.0, "[kB]"
00047         print "size avg:\t", msg_size / 1000.0 / len(self.msgs), "[kB/msg]"
00048         if self.use_timer:
00049             print "rate:\t\t", msg_size / 1000.0 / d.to_sec(), "[kB/sec]"
00050 
00051 if __name__ == '__main__':
00052     p = optparse.OptionParser(usage="%prog [options] topic_name")
00053     p.add_option("-w", dest="window_size", type="int", default=None)
00054     p.add_option("-d", dest="duration", type="int", default=5)
00055 
00056     (opt, args) = p.parse_args(rospy.myargv())
00057     if len(args) != 2:
00058         p.print_help()
00059         exit(1)
00060 
00061     rospy.init_node("topic_statistics")
00062     t = TopicStatistics(topic_name=args[1],
00063                         window_size=opt.window_size,
00064                         duration=opt.duration)
00065     t.start()


jsk_topic_tools
Author(s): Kei Okada , Yusuke Furuta
autogenerated on Fri Sep 8 2017 03:38:56