Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033 from __future__ import division, with_statement
00034 try:
00035 from cStringIO import StringIO
00036 except ImportError:
00037 from io import StringIO
00038
00039 from python_qt_binding.QtCore import qWarning
00040
00041 import roslib
00042 import rospy
00043 from rostopic import ROSTopicHz
00044
00045
00046 class TopicInfo(ROSTopicHz):
00047
00048 def __init__(self, topic_name, topic_type):
00049 super(TopicInfo, self).__init__(100)
00050 self._topic_name = topic_name
00051 self.error = None
00052 self._subscriber = None
00053 self.monitoring = False
00054 self._reset_data()
00055 self.message_class = None
00056 try:
00057 self.message_class = roslib.message.get_message_class(topic_type)
00058 except Exception as e:
00059 self.message_class = None
00060 qWarning('TopicInfo.__init__(): %s' % (e))
00061
00062 if self.message_class is None:
00063 self.error = 'can not get message class for type "%s"' % topic_type
00064 qWarning('TopicInfo.__init__(): topic "%s": %s' % (topic_name, self.error))
00065
00066 def _reset_data(self):
00067 self.last_message = None
00068 self.times = []
00069 self.timestamps = []
00070 self.sizes = []
00071
00072 def toggle_monitoring(self):
00073 if self.monitoring:
00074 self.stop_monitoring()
00075 else:
00076 self.start_monitoring()
00077
00078 def start_monitoring(self):
00079 if self.message_class is not None:
00080 self.monitoring = True
00081
00082 self._subscriber = rospy.Subscriber(self._topic_name, self.message_class, self.message_callback)
00083
00084 def stop_monitoring(self):
00085 self.monitoring = False
00086 self._reset_data()
00087 if self._subscriber is not None:
00088 self._subscriber.unregister()
00089
00090 def message_callback(self, message):
00091 ROSTopicHz.callback_hz(self, message)
00092 with self.lock:
00093 self.timestamps.append(rospy.get_time())
00094
00095
00096
00097
00098 buff = StringIO()
00099 message.serialize(buff)
00100 self.sizes.append(len(buff.getvalue()))
00101
00102 if len(self.timestamps) > self.window_size - 1:
00103 self.timestamps.pop(0)
00104 self.sizes.pop(0)
00105 assert(len(self.timestamps) == len(self.sizes))
00106
00107 self.last_message = message
00108
00109 def get_bw(self):
00110 if len(self.timestamps) < 2:
00111 return None, None, None, None
00112 current_time = rospy.get_time()
00113 if current_time <= self.timestamps[0]:
00114 return None, None, None, None
00115
00116 with self.lock:
00117 total = sum(self.sizes)
00118 bytes_per_s = total / (current_time - self.timestamps[0])
00119 mean_size = total / len(self.timestamps)
00120 max_size = max(self.sizes)
00121 min_size = min(self.sizes)
00122 return bytes_per_s, mean_size, min_size, max_size
00123
00124 def get_hz(self):
00125 if not self.times:
00126 return None, None, None, None
00127 with self.lock:
00128 n = len(self.times)
00129 mean = sum(self.times) / n
00130 rate = 1. / mean if mean > 0. else 0
00131 min_delta = min(self.times)
00132 max_delta = max(self.times)
00133 return rate, mean, min_delta, max_delta