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


rqt_reconfigure
Author(s): Isaac Saito, Ze'ev Klapow
autogenerated on Sat Jul 6 2019 03:49:38