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


rqt_bag
Author(s): Aaron Blasdel, Tim Field
autogenerated on Thu Aug 17 2017 02:19:27