topic_info.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 
3 # Copyright (c) 2011, Dorian Scholz, TU Darmstadt
4 # All rights reserved.
5 #
6 # Redistribution and use in source and binary forms, with or without
7 # modification, are permitted provided that the following conditions
8 # are met:
9 #
10 # * Redistributions of source code must retain the above copyright
11 # notice, this list of conditions and the following disclaimer.
12 # * Redistributions in binary form must reproduce the above
13 # copyright notice, this list of conditions and the following
14 # disclaimer in the documentation and/or other materials provided
15 # with the distribution.
16 # * Neither the name of the TU Darmstadt nor the names of its
17 # contributors may be used to endorse or promote products derived
18 # from this software without specific prior written permission.
19 #
20 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
21 # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
22 # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
23 # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
24 # COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
25 # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
26 # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
27 # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
28 # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
29 # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
30 # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
31 # POSSIBILITY OF SUCH DAMAGE.
32 
33 from __future__ import division, with_statement
34 try:
35  from cStringIO import StringIO
36 except ImportError:
37  from io import StringIO
38 
39 from python_qt_binding.QtCore import qWarning
40 
41 import roslib
42 import rospy
43 from rostopic import ROSTopicHz
44 
45 
46 class TopicInfo(ROSTopicHz):
47 
48  def __init__(self, topic_name, topic_type):
49  super(TopicInfo, self).__init__(100)
50  self._topic_name = topic_name
51  self.error = None
52  self._subscriber = None
53  self.monitoring = False
54  self._reset_data()
55  self.message_class = None
56  try:
57  self.message_class = roslib.message.get_message_class(topic_type)
58  except Exception as e:
59  self.message_class = None
60  qWarning('TopicInfo.__init__(): %s' % (e))
61 
62  if self.message_class is None:
63  self.error = 'can not get message class for type "%s"' % topic_type
64  qWarning('TopicInfo.__init__(): topic "%s": %s' % (topic_name, self.error))
65 
66  def _reset_data(self):
67  self.last_message = None
68  self.times = []
69  self.timestamps = []
70  self.sizes = []
71 
72  def toggle_monitoring(self):
73  if self.monitoring:
74  self.stop_monitoring()
75  else:
76  self.start_monitoring()
77 
78  def start_monitoring(self):
79  if self.message_class is not None:
80  self.monitoring = True
81  # FIXME: subscribing to class AnyMsg breaks other subscribers on same node
82  self._subscriber = rospy.Subscriber(self._topic_name, self.message_class, self.message_callback)
83 
84  def stop_monitoring(self):
85  self.monitoring = False
86  self._reset_data()
87  if self._subscriber is not None:
88  self._subscriber.unregister()
89 
90  def message_callback(self, message):
91  ROSTopicHz.callback_hz(self, message)
92  with self.lock:
93  self.timestamps.append(rospy.get_time())
94 
95  # FIXME: this only works for message of class AnyMsg
96  #self.sizes.append(len(message._buff))
97  # time consuming workaround...
98  buff = StringIO()
99  message.serialize(buff)
100  self.sizes.append(len(buff.getvalue()))
101 
102  if len(self.timestamps) > self.window_size - 1:
103  self.timestamps.pop(0)
104  self.sizes.pop(0)
105  assert(len(self.timestamps) == len(self.sizes))
106 
107  self.last_message = message
108 
109  def get_bw(self):
110  if len(self.timestamps) < 2:
111  return None, None, None, None
112  current_time = rospy.get_time()
113  if current_time <= self.timestamps[0]:
114  return None, None, None, None
115 
116  with self.lock:
117  total = sum(self.sizes)
118  bytes_per_s = total / (current_time - self.timestamps[0])
119  mean_size = total / len(self.timestamps)
120  max_size = max(self.sizes)
121  min_size = min(self.sizes)
122  return bytes_per_s, mean_size, min_size, max_size
123 
124  def get_hz(self):
125  if not self.times:
126  return None, None, None, None
127  with self.lock:
128  n = len(self.times)
129  mean = sum(self.times) / n
130  rate = 1. / mean if mean > 0. else 0
131  min_delta = min(self.times)
132  max_delta = max(self.times)
133  return rate, mean, min_delta, max_delta
def message_callback(self, message)
Definition: topic_info.py:90
def __init__(self, topic_name, topic_type)
Definition: topic_info.py:48


rqt_dyn_tune
Author(s):
autogenerated on Mon Jun 10 2019 14:52:08