33 from __future__
import division, with_statement
35 from cStringIO
import StringIO
as BufferType
37 from io
import BytesIO
as BufferType
39 from python_qt_binding.QtCore
import qWarning
43 from rostopic
import ROSTopicHz
57 self.
message_class = roslib.message.get_message_class(topic_type)
58 except Exception
as e:
60 qWarning(
'TopicInfo.__init__(): %s' % (e))
63 self.
error =
'can not get message class for type "%s"' % topic_type
64 qWarning(
'TopicInfo.__init__(): topic "%s": %s' % (topic_name, self.
error))
89 self._subscriber.unregister()
92 ROSTopicHz.callback_hz(self, message)
94 self.timestamps.append(rospy.get_time())
100 message.serialize(buff)
101 self.sizes.append(len(buff.getvalue()))
103 if len(self.
timestamps) > self.window_size - 1:
104 self.timestamps.pop(0)
112 return None,
None,
None,
None 113 current_time = rospy.get_time()
115 return None,
None,
None,
None 118 total = sum(self.
sizes)
119 bytes_per_s = total / (current_time - self.
timestamps[0])
121 max_size = max(self.
sizes)
122 min_size = min(self.
sizes)
123 return bytes_per_s, mean_size, min_size, max_size
127 return None,
None,
None,
None 130 mean = sum(self.
times) / n
131 rate = 1. / mean
if mean > 0.
else 0
132 min_delta = min(self.
times)
133 max_delta = max(self.
times)
134 return rate, mean, min_delta, max_delta
def start_monitoring(self)
def toggle_monitoring(self)
def __init__(self, topic_name, topic_type)
def stop_monitoring(self)
def message_callback(self, message)