node_selector_widget.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 # Author: Isaac Saito
00034 
00035 from __future__ import division
00036 
00037 import os
00038 import sys
00039 
00040 import dynamic_reconfigure as dyn_reconf
00041 from python_qt_binding import loadUi
00042 from python_qt_binding.QtCore import Qt, QTimer, Signal
00043 from python_qt_binding.QtGui import QStandardItemModel, QWidget
00044 import rospy
00045 import rosservice
00046 
00047 from .parameter_item import ParameterItem
00048 
00049 class NodeSelectorWidget(QWidget):
00050     _COL_NAMES = ['Node']
00051 
00052     # public signal
00053     sig_node_selected = Signal(str)
00054 
00055     def __init__(self):
00056         super(NodeSelectorWidget, self).__init__()
00057         self.stretch = None
00058 
00059         ui_file = os.path.join(os.path.dirname(os.path.realpath(__file__)),
00060                                'ui/node_selector.ui')
00061         loadUi(ui_file, self)
00062 
00063         #  Setup treeview and models
00064         self._std_model = QStandardItemModel()
00065         self._node_selector_view.setModel(self._std_model)
00066         self._rootitem = self._std_model.invisibleRootItem()
00067 
00068         self._nodes_previous = None
00069 
00070         # Calling this method updates the list of the node. 
00071         # Initially done only once.
00072         self._update_nodetree()
00073         
00074         # Setting slot for when user clickes on QTreeView.
00075         selectionModel = self._node_selector_view.selectionModel()
00076         selectionModel.selectionChanged.connect(self._selection_changed_slot)
00077 
00078         #TODO(Isaac): Needs auto-update function enabled, once another function
00079         #             that updates node tree with maintaining collapse/expansion
00080         #             state. http://goo.gl/GuwYp can be a help.
00081         
00082 #        self.timer = QTimer()
00083 #        self.timer.timeout.connect(self._refresh_nodes)
00084 #        self.timer.start(5000) #  5sec interval is fast enough.
00085 
00086         self._collapse_button.pressed.connect(self._node_selector_view.collapseAll)
00087         self._expand_button.pressed.connect(self._node_selector_view.expandAll)
00088 
00089     def _selection_changed_slot(self, selected, deselected):
00090         """
00091         Overriden from QItemSelectionModel.
00092         
00093         :type new_item_select: QItemSelection
00094         :type old_item_select: QItemSelection
00095         """
00096 
00097         index_current = self._node_selector_view.selectionModel().currentIndex()
00098         rospy.logdebug('_selection_changed_slot row=%d col=%d data=%s ' +
00099                        'data.parent=%s child(0, 0)=%s',
00100                        index_current.row(),
00101                        index_current.column(),
00102                        index_current.data(Qt.DisplayRole),
00103                        index_current.parent().data(Qt.DisplayRole),
00104                        index_current.child(0, 0).data(Qt.DisplayRole))
00105 
00106         if not index_current.child(0, 0).data(Qt.DisplayRole) == None:
00107             return #  Meaning the tree has no nodes.
00108 
00109         #  get the text of the selected item
00110         node_name_selected = self.get_full_grn_recur(index_current, '')
00111         rospy.logdebug('_selection_changed_slot node_name_selected=%s',
00112                        node_name_selected)
00113         self.sig_node_selected.emit(node_name_selected)
00114 
00115     def get_full_grn_recur(self, model_index, str_grn):
00116         """
00117         
00118         Create full path format of GRN (Graph Resource Names, see  
00119         http://www.ros.org/wiki/Names). 
00120         
00121         An example: /wide_stereo/left/image_color/compressed
00122         
00123         Bulid GRN by recursively transcending parents & children of 
00124         QModelIndex instance.
00125         
00126         Upon its very 1st call, the argument is the index where user clicks on on
00127         the view object (here QTreeView is used but should work with other View).
00128         str_grn can be 0-length string.           
00129         
00130         :type model_index: QModelIndex
00131         :type str_grn: str
00132         :param str_grn: This could be an incomplete or a complete GRN format.         
00133         """
00134         #TODO(Isaac) Consider moving this to rqt_py_common. 
00135 
00136         rospy.logdebug('get_full_grn_recur in str=%s', str_grn)
00137         if model_index.data(Qt.DisplayRole) == None:
00138             return str_grn
00139         str_grn = '/' + str(model_index.data(Qt.DisplayRole)) + str_grn
00140         rospy.logdebug('get_full_grn_recur out str=%s', str_grn)
00141         return self.get_full_grn_recur(model_index.parent(), str_grn)
00142 
00143     def _update_nodetree(self):
00144         """
00145         """
00146 
00147         #TODO(Isaac): 11/25/2012 dynamic_reconfigure only returns params that 
00148         #             are associated with nodes. In order to handle independent
00149         #             params, different approach needs taken.
00150         try:
00151             nodes = dyn_reconf.find_reconfigure_services()
00152         except rosservice.ROSServiceIOException as e:
00153             rospy.logerr("Reconfigure GUI cannot connect to master.")
00154             raise e  #TODO Make sure 'raise' here returns or finalizes this func.
00155 
00156         if not nodes == self._nodes_previous:
00157             paramname_prev = ''
00158             paramitem_top_prev = None
00159             i_debug = 0
00160             for node_name_grn in nodes:
00161                 p = ParameterItem(node_name_grn)
00162                 p.set_param_name(node_name_grn)
00163                 names = p.get_param_names()
00164 
00165                 i_debug += 1
00166                 rospy.logdebug('_update_nodetree i=%d names=%s',
00167                                i_debug, names)
00168 
00169                 self._add_tree_node(p, self._rootitem, names)
00170 
00171     def _add_tree_node(self, param_item_full, stditem_parent, child_names_left):
00172         """
00173         
00174         Evaluate current node and the previous node on the same depth.
00175         If the name of both nodes is the same, current node instance is ignored.
00176         If not, the current node gets added to the same parent node.
00177         At the end, this function gets called recursively going down 1 level.
00178         
00179         :type param_item_full: ParameterItem
00180         :type stditem_parent: QStandardItem.
00181         :type child_names_left: List of str
00182         :param child_names_left: List of strings that is sorted in hierarchical 
00183                                  order of params.
00184         """
00185         #TODO(Isaac): Consider moving to rqt_py_common. 
00186 
00187         name_curr = child_names_left.pop(0)
00188         stditem_curr = ParameterItem(param_item_full.get_raw_param_name())
00189 
00190         # item at the bottom is your most recent node.
00191         row_index_parent = stditem_parent.rowCount() - 1
00192 
00193         # Obtain and instantiate prev node in the same depth.
00194         name_prev = ''
00195         stditem_prev = None
00196         if not stditem_parent.child(row_index_parent) == None:
00197             stditem_prev = stditem_parent.child(row_index_parent)
00198             name_prev = stditem_prev.text()
00199 
00200         stditem = None
00201         if name_prev != name_curr:
00202             stditem_curr.setText(name_curr)
00203             stditem_parent.appendRow(stditem_curr)
00204             stditem = stditem_curr
00205         else:
00206             stditem = stditem_prev
00207 
00208         rospy.logdebug('add_tree_node 1 name_curr=%s ' +
00209                        '\n\t\t\t\t\tname_prev=%s row_index_parent=%d',
00210                        name_curr, name_prev, row_index_parent)
00211 
00212         if len(child_names_left) != 0:
00213             #TODO: View & Model are closely bound here. Ideally isolate this 2.
00214             #       Maybe we should split into 2 classs, 1 handles view,
00215             #       the other does model.
00216             self._add_tree_node(param_item_full, stditem, child_names_left)
00217 
00218     def _refresh_nodes(self):
00219         #TODO(Isaac) In the future, do NOT remove all nodes. Instead,
00220         #            remove only the ones that are gone. And add new ones too.
00221 
00222         model = self._rootitem
00223         if model.hasChildren():
00224             row_count = model.rowCount()
00225             model.removeRows(0, row_count)
00226             rospy.logdebug("ParamWidget _refresh_nodes row_count=%s", row_count)
00227         self._update_nodetree()
00228 
00229     def close_node(self):
00230         rospy.logdebug(" in close_node")
00231         #TODO(Isaac) Figure out if dynamic_reconfigure needs to be closed.
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Properties Friends


rqt_param
Author(s): Isaac Saito, Ze'ev Klapow
autogenerated on Wed Dec 19 2012 23:57:05