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


rqt_reconfigure
Author(s): Isaac Saito, Ze'ev Klapow
autogenerated on Mon Oct 6 2014 07:15:23