message_tree_model.py
Go to the documentation of this file.
00001 # Copyright (c) 2011, Dorian Scholz, TU Darmstadt
00002 # All rights reserved.
00003 #
00004 # Redistribution and use in source and binary forms, with or without
00005 # modification, are permitted provided that the following conditions
00006 # are met:
00007 #
00008 #   * Redistributions of source code must retain the above copyright
00009 #     notice, this list of conditions and the following disclaimer.
00010 #   * Redistributions in binary form must reproduce the above
00011 #     copyright notice, this list of conditions and the following
00012 #     disclaimer in the documentation and/or other materials provided
00013 #     with the distribution.
00014 #   * Neither the name of the TU Darmstadt nor the names of its
00015 #     contributors may be used to endorse or promote products derived
00016 #     from this software without specific prior written permission.
00017 #
00018 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00019 # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00020 # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00021 # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00022 # COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00023 # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00024 # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00025 # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00026 # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00027 # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00028 # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00029 # POSSIBILITY OF SUCH DAMAGE.
00030 
00031 import rospy
00032 from python_qt_binding.QtGui import QStandardItem, QStandardItemModel
00033 from .data_items import ReadonlyItem
00034 
00035 
00036 class MessageTreeModel(QStandardItemModel):
00037 
00038     def __init__(self, parent=None):
00039         # FIXME: why is this not working? should be the same as the following line...
00040         #super(MessageTreeModel, self).__init__(parent)
00041         QStandardItemModel.__init__(self, parent)
00042 
00043     def add_message(self, message_instance, message_name='', message_type='', message_path=''):
00044         if message_instance is None:
00045             return
00046         self._recursive_create_items(self, message_instance, message_name, message_type, message_path)
00047 
00048     def _get_toplevel_items(self, index_list):
00049         items = [self.itemFromIndex(index) for index in index_list]
00050         uniqueItems = {}
00051         for item in items:
00052             while item.parent() is not None:
00053                 item = item.parent()
00054             if item.row() not in uniqueItems:
00055                 uniqueItems[item.row()] = item
00056         return uniqueItems.values()
00057 
00058     def _get_data_items_for_path(self, slot_name, slot_type_name, slot_path, **kwargs):
00059         return (QStandardItem(slot_name), QStandardItem(slot_type_name), QStandardItem(slot_path))
00060 
00061     def _recursive_create_items(self, parent, slot, slot_name, slot_type_name, slot_path, **kwargs):
00062         row = []
00063         for item in self._get_data_items_for_path(slot_name, slot_type_name, slot_path, **kwargs):
00064             item._path = slot_path
00065             item._user_data = kwargs.get('user_data', None)
00066             row.append(item)
00067 
00068         is_leaf_node = False
00069         if hasattr(slot, '__slots__') and hasattr(slot, '_slot_types'):
00070             for child_slot_name, child_slot_type in zip(slot.__slots__, slot._slot_types):
00071                 child_slot_path = slot_path + '/' + child_slot_name
00072                 child_slot = getattr(slot, child_slot_name)
00073                 self._recursive_create_items(row[0], child_slot, child_slot_name, child_slot_type, child_slot_path, **kwargs)
00074 
00075         elif type(slot) in (list, tuple) and (len(slot) > 0) and hasattr(slot[0], '__slots__'):
00076             child_slot_type = slot_type_name[:slot_type_name.find('[')]
00077             for index, child_slot in enumerate(slot):
00078                 child_slot_name = '[%d]' % index
00079                 child_slot_path = slot_path + child_slot_name
00080                 self._recursive_create_items(row[0], child_slot, child_slot_name, child_slot_type, child_slot_path, **kwargs)
00081 
00082         else:
00083             is_leaf_node = True
00084 
00085         if parent is self and kwargs.get('top_level_row_number', None) is not None:
00086             parent.insertRow(kwargs['top_level_row_number'], row)
00087         else:
00088             parent.appendRow(row)
00089 
00090         return (row, is_leaf_node)
00091 
00092     '''
00093     NOTE: I (Isaac Saito) suspect that this function might have same/similar
00094           functionality with _recursive_create_items.
00095 
00096     @summary: Evaluate current node and the previous node on the same depth.
00097               If the name of both nodes at the same depth is the same,
00098               current name is added to the previous node.
00099               If not, the current name gets added to the parent node.
00100               At the end, this function calls itself recursively going down
00101               1 level deeper.
00102     @param stditem_parent: QStandardItem.
00103     @param names_on_branch: List of strings each of which
00104                             represents the name of the node.
00105                             Ex. If you have a hierarchy that looks like:
00106 
00107                                  /top_node/sub_node/subsub_node
00108 
00109                             then this list would look like:
00110 
00111                                  [ top_node, sub_node, subsub_node ]
00112     @author: Isaac Saito
00113     '''
00114     @staticmethod
00115     def _build_tree_recursive(stditem_parent, names_on_branch):
00116         name_curr = names_on_branch.pop(0)
00117         stditem_curr = ReadonlyItem(name_curr)
00118 
00119         row_index_parent = stditem_parent.rowCount() - 1
00120         # item at the bottom is your most recent node.
00121 
00122         name_prev = ''
00123         stditem_prev = None
00124         if not stditem_parent.child(row_index_parent) == None:
00125             stditem_prev = stditem_parent.child(row_index_parent)
00126             name_prev = stditem_prev.text()
00127 
00128         stditem = None
00129         if not name_prev == name_curr:
00130             stditem_parent.appendRow(stditem_curr)
00131             stditem = stditem_curr
00132         else:
00133             stditem = stditem_prev
00134 
00135         rospy.logdebug('add_tree_node 1 name_curr=%s ' + '\n\t\t\t\t\tname_prev=%s row_index_parent=%d', name_curr, name_prev, row_index_parent)
00136         if (0 < len(names_on_branch)):
00137             MessageTreeModel._build_tree_recursive(stditem, names_on_branch)


rqt_py_common
Author(s): Dorian Scholz, Isaac Saito
autogenerated on Mon Oct 6 2014 07:15:13