raw_view.py
Go to the documentation of this file.
00001 # Software License Agreement (BSD License)
00002 #
00003 # Copyright (c) 2012, Willow Garage, Inc.
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 Willow Garage, Inc. 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 OWNER 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 Defines a raw view: a TopicMessageView that displays the message contents in a tree.
00034 """
00035 import rospy
00036 import codecs
00037 import math
00038 
00039 from python_qt_binding.QtCore import Qt
00040 from python_qt_binding.QtWidgets import QApplication, QAbstractItemView, QSizePolicy, QTreeWidget, QTreeWidgetItem, QWidget
00041 from .topic_message_view import TopicMessageView
00042 
00043 
00044 class RawView(TopicMessageView):
00045     name = 'Raw'
00046     """
00047     Plugin to view a message in a treeview window
00048     The message is loaded into a custum treewidget
00049     """
00050 
00051     def __init__(self, timeline, parent, topic):
00052         """
00053         :param timeline: timeline data object, ''BagTimeline''
00054         :param parent: widget that will be added to the ros_gui context, ''QWidget''
00055         """
00056         super(RawView, self).__init__(timeline, parent, topic)
00057         self.message_tree = MessageTree(parent)
00058 
00059         # This will automatically resize the message_tree to the windowsize
00060         parent.layout().addWidget(self.message_tree)
00061 
00062     def message_viewed(self, bag, msg_details):
00063         super(RawView, self).message_viewed(bag, msg_details)
00064         _, msg, t = msg_details  # topic, msg, t = msg_details
00065         if t is None:
00066             self.message_cleared()
00067         else:
00068             self.message_tree.set_message(msg)
00069 
00070     def message_cleared(self):
00071         TopicMessageView.message_cleared(self)
00072         self.message_tree.set_message(None)
00073 
00074 
00075 class MessageTree(QTreeWidget):
00076 
00077     def __init__(self, parent):
00078         super(MessageTree, self).__init__(parent)
00079         self.setSizePolicy(QSizePolicy.Expanding, QSizePolicy.Expanding)
00080         self.setHeaderHidden(True)
00081         self.setSelectionMode(QAbstractItemView.ExtendedSelection)
00082         self._msg = None
00083 
00084         self._expanded_paths = None
00085         self.keyPressEvent = self.on_key_press
00086 
00087     @property
00088     def msg(self):
00089         return self._msg
00090 
00091     def set_message(self, msg):
00092         """
00093         Clears the tree view and displays the new message
00094         :param msg: message object to display in the treeview, ''msg''
00095         """
00096         # Remember whether items were expanded or not before deleting
00097         if self._msg:
00098             for item in self.get_all_items():
00099                 path = self.get_item_path(item)
00100                 if item.isExpanded():
00101                     self._expanded_paths.add(path)
00102                 elif path in self._expanded_paths:
00103                     self._expanded_paths.remove(path)
00104             self.clear()
00105         if msg:
00106             # Populate the tree
00107             self._add_msg_object(None, '', '', msg, msg._type)
00108 
00109             if self._expanded_paths is None:
00110                 self._expanded_paths = set()
00111             else:
00112                 # Expand those that were previously expanded, and collapse any paths that
00113                 # we've seen for the first time
00114                 for item in self.get_all_items():
00115                     path = self.get_item_path(item)
00116                     if path in self._expanded_paths:
00117                         item.setExpanded(True)
00118                     else:
00119                         item.setExpanded(False)
00120         self._msg = msg
00121         QWidget.update(self)
00122 
00123     # Keyboard handler
00124     def on_key_press(self, event):
00125         key, ctrl = event.key(), event.modifiers() & Qt.ControlModifier
00126         if ctrl:
00127             if key == ord('C') or key == ord('c'):
00128                 # Ctrl-C: copy text from selected items to clipboard
00129                 self._copy_text_to_clipboard()
00130                 event.accept()
00131             elif key == ord('A') or key == ord('a'):
00132                 # Ctrl-A: select all
00133                 self._select_all()
00134 
00135     def _select_all(self):
00136         for i in self.get_all_items():
00137             if not i.isSelected():
00138                 i.setSelected(True)
00139                 i.setExpanded(True)
00140 
00141     def _copy_text_to_clipboard(self):
00142         # Get tab indented text for all selected items
00143         def get_distance(item, ancestor, distance=0):
00144             parent = item.parent()
00145             if parent == None:
00146                 return distance
00147             else:
00148                 return get_distance(parent, ancestor, distance + 1)
00149         text = ''
00150         for i in self.get_all_items():
00151             if i in self.selectedItems():
00152                 text += ('\t' * (get_distance(i, None))) + i.text(0) + '\n'
00153         # Copy the text to the clipboard
00154         clipboard = QApplication.clipboard()
00155         clipboard.setText(text)
00156 
00157     def get_item_path(self, item):
00158         return item.data(0, Qt.UserRole)[0].replace(' ', '')  # remove spaces that may get introduced in indexing, e.g. [  3] is [3]
00159 
00160     def get_all_items(self):
00161         items = []
00162         try:
00163             root = self.invisibleRootItem()
00164             self.traverse(root, items.append)
00165         except Exception:
00166             # TODO: very large messages can cause a stack overflow due to recursion
00167             pass
00168         return items
00169 
00170     def traverse(self, root, function):
00171         for i in range(root.childCount()):
00172             child = root.child(i)
00173             function(child)
00174             self.traverse(child, function)
00175 
00176     def _add_msg_object(self, parent, path, name, obj, obj_type):
00177         label = name
00178 
00179         if hasattr(obj, '__slots__'):
00180             subobjs = [(slot, getattr(obj, slot)) for slot in obj.__slots__]
00181         elif type(obj) in [list, tuple]:
00182             len_obj = len(obj)
00183             if len_obj == 0:
00184                 subobjs = []
00185             else:
00186                 w = int(math.ceil(math.log10(len_obj)))
00187                 subobjs = [('[%*d]' % (w, i), subobj) for (i, subobj) in enumerate(obj)]
00188         else:
00189             subobjs = []
00190 
00191         if type(obj) in [int, long, float]:
00192             if type(obj) == float:
00193                 obj_repr = '%.6f' % obj
00194             else:
00195                 obj_repr = str(obj)
00196 
00197             if obj_repr[0] == '-':
00198                 label += ': %s' % obj_repr
00199             else:
00200                 label += ':  %s' % obj_repr
00201 
00202         elif type(obj) in [str, bool, int, long, float, complex, rospy.Time]:
00203             # Ignore any binary data
00204             obj_repr = codecs.utf_8_decode(str(obj), 'ignore')[0]
00205 
00206             # Truncate long representations
00207             if len(obj_repr) >= 50:
00208                 obj_repr = obj_repr[:50] + '...'
00209 
00210             label += ': ' + obj_repr
00211         item = QTreeWidgetItem([label])
00212         if name == '':
00213             pass
00214         elif path.find('.') == -1 and path.find('[') == -1:
00215             self.addTopLevelItem(item)
00216         else:
00217             parent.addChild(item)
00218         item.setData(0, Qt.UserRole, (path, obj_type))
00219 
00220         for subobj_name, subobj in subobjs:
00221             if subobj is None:
00222                 continue
00223 
00224             if path == '':
00225                 subpath = subobj_name  # root field
00226             elif subobj_name.startswith('['):
00227                 subpath = '%s%s' % (path, subobj_name)  # list, dict, or tuple
00228             else:
00229                 subpath = '%s.%s' % (path, subobj_name)  # attribute (prefix with '.')
00230 
00231             if hasattr(subobj, '_type'):
00232                 subobj_type = subobj._type
00233             else:
00234                 subobj_type = type(subobj).__name__
00235 
00236             self._add_msg_object(item, subpath, subobj_name, subobj, subobj_type)


rqt_bag
Author(s): Aaron Blasdel, Tim Field
autogenerated on Thu Jun 6 2019 18:52:48