topic_info.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 
00003 # Copyright (c) 2011, Dorian Scholz, TU Darmstadt
00004 # All rights reserved.
00005 #
00006 # Redistribution and use in source and binary forms, with or without
00007 # modification, are permitted provided that the following conditions
00008 # are met:
00009 #
00010 #   * Redistributions of source code must retain the above copyright
00011 #     notice, this list of conditions and the following disclaimer.
00012 #   * Redistributions in binary form must reproduce the above
00013 #     copyright notice, this list of conditions and the following
00014 #     disclaimer in the documentation and/or other materials provided
00015 #     with the distribution.
00016 #   * Neither the name of the TU Darmstadt nor the names of its
00017 #     contributors may be used to endorse or promote products derived
00018 #     from this software without specific prior written permission.
00019 #
00020 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00021 # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00022 # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00023 # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00024 # COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00025 # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00026 # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00027 # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00028 # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00029 # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00030 # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00031 # POSSIBILITY OF SUCH DAMAGE.
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             # FIXME: subscribing to class AnyMsg breaks other subscribers on same node
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             # FIXME: this only works for message of class AnyMsg
00096             #self.sizes.append(len(message._buff))
00097             # time consuming workaround...
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


rqt_topic
Author(s): Dorian Scholz
autogenerated on Mon May 1 2017 02:41:14