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 from collections import OrderedDict
00038 import os
00039 import time
00040 
00041 import dynamic_reconfigure as dyn_reconf
00042 from python_qt_binding import loadUi
00043 from python_qt_binding.QtCore import Qt, Signal
00044 from python_qt_binding.QtGui import (QHeaderView, QItemSelectionModel,
00045                                      QWidget)
00046 import rospy
00047 from rospy.exceptions import ROSException
00048 import rosservice
00049 
00050 from rqt_py_common.rqt_ros_graph import RqtRosGraph
00051 from rqt_reconfigure.filter_children_model import FilterChildrenModel
00052 from rqt_reconfigure.treenode_qstditem import TreenodeQstdItem
00053 from rqt_reconfigure.treenode_item_model import TreenodeItemModel
00054 
00055 from rqt_reconfigure.dynreconf_client_widget import DynreconfClientWidget
00056 
00057 
00058 class NodeSelectorWidget(QWidget):
00059     _COL_NAMES = ['Node']
00060 
00061     # public signal
00062     sig_node_selected = Signal(DynreconfClientWidget)
00063 
00064     def __init__(self, parent, rospack, signal_msg=None):
00065         """
00066         @param signal_msg: Signal to carries a system msg that is shown on GUI.
00067         @type signal_msg: QtCore.Signal
00068         """
00069         super(NodeSelectorWidget, self).__init__()
00070         self._parent = parent
00071         self.stretch = None
00072         self._signal_msg = signal_msg
00073 
00074         ui_file = os.path.join(rospack.get_path('rqt_reconfigure'), 'resource',
00075                                'node_selector.ui')
00076         loadUi(ui_file, self)
00077 
00078         # List of the available nodes. Since the list should be updated over
00079         # time and we don't want to create node instance per every update
00080         # cycle, This list instance should better be capable of keeping track.
00081         self._nodeitems = OrderedDict()
00082         # Dictionary. 1st elem is node's GRN name,
00083         # 2nd is TreenodeQstdItem instance.
00084         # TODO: Needs updated when nodes list updated.
00085 
00086         #  Setup treeview and models
00087         self._item_model = TreenodeItemModel()
00088         self._rootitem = self._item_model.invisibleRootItem()  # QStandardItem
00089 
00090         self._nodes_previous = None
00091 
00092         # Calling this method updates the list of the node.
00093         # Initially done only once.
00094         self._update_nodetree_pernode()
00095 
00096         # TODO(Isaac): Needs auto-update function enabled, once another
00097         #             function that updates node tree with maintaining
00098         #             collapse/expansion  state. http://goo.gl/GuwYp can be a
00099         #             help.
00100 
00101         self._collapse_button.pressed.connect(
00102                                           self._node_selector_view.collapseAll)
00103         self._expand_button.pressed.connect(self._node_selector_view.expandAll)
00104         self._refresh_button.pressed.connect(self._refresh_nodes)
00105 
00106         # Filtering preparation.
00107         self._proxy_model = FilterChildrenModel(self)
00108         self._proxy_model.setDynamicSortFilter(True)
00109         self._proxy_model.setSourceModel(self._item_model)
00110         self._node_selector_view.setModel(self._proxy_model)
00111         self._filterkey_prev = ''
00112 
00113         # This 1 line is needed to enable horizontal scrollbar. This setting
00114         # isn't available in .ui file.
00115         # Ref. http://stackoverflow.com/a/6648906/577001
00116         self._node_selector_view.header().setResizeMode(
00117                                               0, QHeaderView.ResizeToContents)
00118 
00119         # Setting slot for when user clicks on QTreeView.
00120         self.selectionModel = self._node_selector_view.selectionModel()
00121         # Note: self.selectionModel.currentChanged doesn't work to deselect
00122         # a treenode as expected. Need to use selectionChanged.
00123         self.selectionModel.selectionChanged.connect(
00124                                                   self._selection_changed_slot)
00125 
00126     def node_deselected(self, grn):
00127         """
00128         Deselect the index that corresponds to the given GRN.
00129 
00130         :type grn: str
00131         """
00132 
00133         # Obtain the corresponding index.
00134         qindex_tobe_deselected = self._item_model.get_index_from_grn(grn)
00135         rospy.logdebug('NodeSelWidt node_deselected qindex={} data={}'.format(
00136                                 qindex_tobe_deselected,
00137                                 qindex_tobe_deselected.data(Qt.DisplayRole)))
00138 
00139         # Obtain all indices currently selected.
00140         indexes_selected = self.selectionModel.selectedIndexes()
00141         for index in indexes_selected:
00142             grn_from_selectedindex = RqtRosGraph.get_upper_grn(index, '')
00143             rospy.logdebug(' Compare given grn={} grn from selected={}'.format(
00144                                                   grn, grn_from_selectedindex))
00145             # If GRN retrieved from selected index matches the given one.
00146             if grn == grn_from_selectedindex:
00147                 # Deselect the index.
00148                 self.selectionModel.select(index, QItemSelectionModel.Deselect)
00149 
00150     def node_selected(self, grn):
00151         """
00152         Select the index that corresponds to the given GRN.
00153 
00154         :type grn: str
00155         """
00156 
00157         # Obtain the corresponding index.
00158         qindex_tobe_selected = self._item_model.get_index_from_grn(grn)
00159         rospy.logdebug('NodeSelWidt node_selected qindex={} data={}'.format(
00160                                 qindex_tobe_selected,
00161                                 qindex_tobe_selected.data(Qt.DisplayRole)))
00162 
00163 
00164         # Select the index.
00165         if qindex_tobe_selected:
00166             self.selectionModel.select(qindex_tobe_selected, QItemSelectionModel.Select)
00167 
00168     def _selection_deselected(self, index_current, rosnode_name_selected):
00169         """
00170         Intended to be called from _selection_changed_slot.
00171         """
00172         self.selectionModel.select(index_current, QItemSelectionModel.Deselect)
00173 
00174         try:
00175             reconf_widget = self._nodeitems[
00176                                  rosnode_name_selected].get_dynreconf_widget()
00177         except ROSException as e:
00178             raise e
00179 
00180         # Signal to notify other pane that also contains node widget.
00181         self.sig_node_selected.emit(reconf_widget)
00182         #self.sig_node_selected.emit(self._nodeitems[rosnode_name_selected])
00183 
00184     def _selection_selected(self, index_current, rosnode_name_selected):
00185         """Intended to be called from _selection_changed_slot."""
00186         rospy.logdebug('_selection_changed_slot row={} col={} data={}'.format(
00187                           index_current.row(), index_current.column(),
00188                           index_current.data(Qt.DisplayRole)))
00189 
00190         # Determine if it's terminal treenode.
00191         found_node = False
00192         for nodeitem in self._nodeitems.itervalues():
00193             name_nodeitem = nodeitem.data(Qt.DisplayRole)
00194             name_rosnode_leaf = rosnode_name_selected[
00195                        rosnode_name_selected.rfind(RqtRosGraph.DELIM_GRN) + 1:]
00196 
00197             # If name of the leaf in the given name & the name taken from
00198             # nodeitem list matches.
00199             if ((name_nodeitem == rosnode_name_selected) and
00200                 (name_nodeitem[name_nodeitem.rfind(RqtRosGraph.DELIM_GRN) + 1:]
00201                  == name_rosnode_leaf)):
00202 
00203                 rospy.logdebug('terminal str {} MATCH {}'.format(
00204                                              name_nodeitem, name_rosnode_leaf))
00205                 found_node = True
00206                 break
00207         if not found_node:  # Only when it's NOT a terminal we deselect it.
00208             self.selectionModel.select(index_current,
00209                                        QItemSelectionModel.Deselect)
00210             return
00211 
00212         # Only when it's a terminal we move forward.
00213 
00214         item_child = self._nodeitems[rosnode_name_selected]
00215         item_widget = None
00216         try:
00217             item_widget = item_child.get_dynreconf_widget()
00218         except ROSException as e:
00219             raise e
00220         rospy.logdebug('item_selected={} child={} widget={}'.format(
00221                        index_current, item_child, item_widget))
00222         self.sig_node_selected.emit(item_widget)
00223 
00224         # Show the node as selected.
00225         #selmodel.select(index_current, QItemSelectionModel.SelectCurrent)
00226 
00227     def _selection_changed_slot(self, selected, deselected):
00228         """
00229         Sends "open ROS Node box" signal ONLY IF the selected treenode is the
00230         terminal treenode.
00231         Receives args from signal QItemSelectionModel.selectionChanged.
00232 
00233         :param selected: All indexs where selected (could be multiple)
00234         :type selected: QItemSelection
00235         :type deselected: QItemSelection
00236         """
00237 
00238         ## Getting the index where user just selected. Should be single.
00239         if not selected.indexes() and not deselected.indexes():
00240             rospy.logerr('Nothing selected? Not ideal to reach here')
00241             return
00242 
00243         index_current = None
00244         if selected.indexes():
00245             index_current = selected.indexes()[0]
00246         elif len(deselected.indexes()) == 1:
00247             # Setting length criteria as 1 is only a workaround, to avoid
00248             # Node boxes on right-hand side disappears when filter key doesn't
00249             # match them.
00250             # Indeed this workaround leaves another issue. Question for
00251             # permanent solution is asked here http://goo.gl/V4DT1
00252             index_current = deselected.indexes()[0]
00253 
00254         rospy.logdebug('  - - - index_current={}'.format(index_current))
00255 
00256         rosnode_name_selected = RqtRosGraph.get_upper_grn(index_current, '')
00257 
00258         # If retrieved node name isn't in the list of all nodes.
00259         if not rosnode_name_selected in self._nodeitems.keys():
00260             # De-select the selected item.
00261             self.selectionModel.select(index_current,
00262                                        QItemSelectionModel.Deselect)
00263             return
00264 
00265         if selected.indexes():
00266             try:
00267                 self._selection_selected(index_current, rosnode_name_selected)
00268             except ROSException as e:
00269                 #TODO: print to sysmsg pane
00270                 err_msg = e.message + '. Connection to node=' + \
00271                           format(rosnode_name_selected) + ' failed'
00272                 self._signal_msg.emit(err_msg)
00273                 rospy.logerr(err_msg)
00274 
00275         elif deselected.indexes():
00276             try:
00277                 self._selection_deselected(index_current,
00278                                            rosnode_name_selected)
00279             except ROSException as e:
00280                 rospy.logerr(e.message)
00281                 #TODO: print to sysmsg pane
00282 
00283     def get_paramitems(self):
00284         """
00285         :rtype: OrderedDict 1st elem is node's GRN name,
00286                 2nd is TreenodeQstdItem instance
00287         """
00288         return self._nodeitems
00289 
00290     def _update_nodetree_pernode(self):
00291         """
00292         """
00293 
00294         # TODO(Isaac): 11/25/2012 dynamic_reconfigure only returns params that
00295         #             are associated with nodes. In order to handle independent
00296         #             params, different approach needs taken.
00297         try:
00298             nodes = dyn_reconf.find_reconfigure_services()
00299         except rosservice.ROSServiceIOException as e:
00300             rospy.logerr("Reconfigure GUI cannot connect to master.")
00301             raise e  # TODO Make sure 'raise' here returns or finalizes func.
00302 
00303         if not nodes == self._nodes_previous:
00304             i_node_curr = 1
00305             num_nodes = len(nodes)
00306             elapsedtime_overall = 0.0
00307             for node_name_grn in nodes:
00308                 # Skip this grn if we already have it
00309                 if node_name_grn in self._nodeitems:
00310                     i_node_curr += 1
00311                     continue
00312 
00313                 time_siglenode_loop = time.time()
00314 
00315                 ####(Begin) For DEBUG ONLY; skip some dynreconf creation
00316 #                if i_node_curr % 2 != 0:
00317 #                    i_node_curr += 1
00318 #                    continue
00319                 #### (End) For DEBUG ONLY. ####
00320 
00321                 # Instantiate QStandardItem. Inside, dyn_reconf client will
00322                 # be generated too.
00323                 treenodeitem_toplevel = TreenodeQstdItem(
00324                                 node_name_grn, TreenodeQstdItem.NODE_FULLPATH)
00325                 _treenode_names = treenodeitem_toplevel.get_treenode_names()
00326 
00327                 try:
00328                     treenodeitem_toplevel.connect_param_server()
00329                 except rospy.exceptions.ROSException as e:
00330                     rospy.logerr(e.message)
00331                     #Skip item that fails to connect to its node.
00332                     continue
00333                     #TODO: Needs to show err msg on GUI too.
00334 
00335                 # Using OrderedDict here is a workaround for StdItemModel
00336                 # not returning corresponding item to index.
00337                 self._nodeitems[node_name_grn] = treenodeitem_toplevel
00338 
00339                 self._add_children_treenode(treenodeitem_toplevel,
00340                                             self._rootitem, _treenode_names)
00341 
00342                 time_siglenode_loop = time.time() - time_siglenode_loop
00343                 elapsedtime_overall += time_siglenode_loop
00344 
00345                 _str_progress = 'reconf ' + \
00346                      'loading #{}/{} {} / {}sec node={}'.format(
00347                      i_node_curr, num_nodes, round(time_siglenode_loop, 2),
00348                      round(elapsedtime_overall, 2), node_name_grn)
00349 
00350                 # NOT a debug print - please DO NOT remove. This print works
00351                 # as progress notification when loading takes long time.
00352                 rospy.logdebug(_str_progress)
00353                 i_node_curr += 1
00354 
00355     def _add_children_treenode(self, treenodeitem_toplevel,
00356                                treenodeitem_parent, child_names_left):
00357         """
00358         Evaluate current treenode and the previous treenode at the same depth.
00359         If the name of both nodes is the same, current node instance is
00360         ignored (that means children will be added to the same parent). If not,
00361         the current node gets added to the same parent node. At the end, this
00362         function gets called recursively going 1 level deeper.
00363 
00364         :type treenodeitem_toplevel: TreenodeQstdItem
00365         :type treenodeitem_parent: TreenodeQstdItem.
00366         :type child_names_left: List of str
00367         :param child_names_left: List of strings that is sorted in hierarchical
00368                                  order of params.
00369         """
00370         # TODO(Isaac): Consider moving this method to rqt_py_common.
00371 
00372         name_currentnode = child_names_left.pop(0)
00373         grn_curr = treenodeitem_toplevel.get_raw_param_name()
00374         stditem_currentnode = TreenodeQstdItem(grn_curr,
00375                                                TreenodeQstdItem.NODE_FULLPATH)
00376 
00377         # item at the bottom is your most recent node.
00378         row_index_parent = treenodeitem_parent.rowCount() - 1
00379 
00380         # Obtain and instantiate prev node in the same depth.
00381         name_prev = ''
00382         stditem_prev = None
00383         if treenodeitem_parent.child(row_index_parent):
00384             stditem_prev = treenodeitem_parent.child(row_index_parent)
00385             name_prev = stditem_prev.text()
00386 
00387         stditem = None
00388         # If the name of both nodes is the same, current node instance is
00389         # ignored (that means children will be added to the same parent)
00390         if name_prev != name_currentnode:
00391             stditem_currentnode.setText(name_currentnode)
00392 
00393             # Arrange alphabetically by display name
00394             insert_index = 0
00395             while insert_index < treenodeitem_parent.rowCount() and treenodeitem_parent.child(insert_index).text() < name_currentnode:
00396                 insert_index += 1
00397 
00398             treenodeitem_parent.insertRow(insert_index, stditem_currentnode)
00399             stditem = stditem_currentnode
00400         else:
00401             stditem = stditem_prev
00402 
00403         if child_names_left:
00404             # TODO: Model is closely bound to a certain type of view (treeview)
00405             # here. Ideally isolate those two. Maybe we should split into 2
00406             # class, 1 handles view, the other does model.
00407             self._add_children_treenode(treenodeitem_toplevel, stditem,
00408                                         child_names_left)
00409         else:  # Selectable ROS Node.
00410             #TODO: Accept even non-terminal treenode as long as it's ROS Node.
00411             self._item_model.set_item_from_index(grn_curr, stditem.index())
00412 
00413     def _prune_nodetree_pernode(self):
00414         try:
00415             nodes = dyn_reconf.find_reconfigure_services()
00416         except rosservice.ROSServiceIOException as e:
00417             rospy.logerr("Reconfigure GUI cannot connect to master.")
00418             raise e  # TODO Make sure 'raise' here returns or finalizes func.
00419 
00420         for i in reversed(range(0, self._rootitem.rowCount())):
00421             candidate_for_removal = self._rootitem.child(i).get_raw_param_name()
00422             if not candidate_for_removal in nodes:
00423                 rospy.logdebug('Removing {} because the server is no longer available.'.format(
00424                                    candidate_for_removal))
00425                 self._nodeitems[candidate_for_removal].disconnect_param_server()
00426                 self._rootitem.removeRow(i)
00427                 self._nodeitems.pop(candidate_for_removal)
00428 
00429     def _refresh_nodes(self):
00430         self._prune_nodetree_pernode()
00431         self._update_nodetree_pernode()
00432 
00433     def close_node(self):
00434         rospy.logdebug(" in close_node")
00435         # TODO(Isaac) Figure out if dynamic_reconfigure needs to be closed.
00436 
00437     def set_filter(self, filter_):
00438         """
00439         Pass fileter instance to the child proxymodel.
00440         :type filter_: BaseFilter
00441         """
00442         self._proxy_model.set_filter(filter_)
00443 
00444     def _test_sel_index(self, selected, deselected):
00445         """
00446         Method for Debug only
00447         """
00448         #index_current = self.selectionModel.currentIndex()
00449         src_model = self._item_model
00450         index_current = None
00451         index_deselected = None
00452         index_parent = None
00453         curr_qstd_item = None
00454         if selected.indexes():
00455             index_current = selected.indexes()[0]
00456             index_parent = index_current.parent()
00457             curr_qstd_item = src_model.itemFromIndex(index_current)
00458         elif deselected.indexes():
00459             index_deselected = deselected.indexes()[0]
00460             index_parent = index_deselected.parent()
00461             curr_qstd_item = src_model.itemFromIndex(index_deselected)
00462 
00463         if selected.indexes() > 0:
00464             rospy.logdebug('sel={} par={} desel={} sel.d={} par.d={}'.format(
00465                                  index_current, index_parent, index_deselected,
00466                                  index_current.data(Qt.DisplayRole),
00467                                  index_parent.data(Qt.DisplayRole),)
00468                                  + ' desel.d={} cur.item={}'.format(
00469                                  None,  # index_deselected.data(Qt.DisplayRole)
00470                                  curr_qstd_item))
00471         elif deselected.indexes():
00472             rospy.logdebug('sel={} par={} desel={} sel.d={} par.d={}'.format(
00473                                  index_current, index_parent, index_deselected,
00474                                  None, index_parent.data(Qt.DisplayRole)) +
00475                            ' desel.d={} cur.item={}'.format(
00476                                  index_deselected.data(Qt.DisplayRole),
00477                                  curr_qstd_item))


rqt_reconfigure
Author(s): Isaac Saito, Ze'ev Klapow
autogenerated on Wed Sep 16 2015 06:58:05