ros_pack_graph.py
Go to the documentation of this file.
00001 # Software License Agreement (BSD License)
00002 #
00003 # Copyright (c) 2011, 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 from __future__ import division
00034 import os
00035 import pickle
00036 
00037 import rospkg
00038 
00039 from python_qt_binding import loadUi
00040 from python_qt_binding.QtCore import QFile, QIODevice, Qt, Signal, Slot, QAbstractListModel
00041 from python_qt_binding.QtGui import QFileDialog, QGraphicsScene, QIcon, QImage, QPainter, QWidget, QCompleter
00042 from python_qt_binding.QtSvg import QSvgGenerator
00043 
00044 import rosservice
00045 import rostopic
00046 
00047 from .dotcode_pack import RosPackageGraphDotcodeGenerator
00048 from qt_dotgraph.pydotfactory import PydotFactory
00049 # from qt_dotgraph.pygraphvizfactory import PygraphvizFactory
00050 from qt_dotgraph.dot_to_qt import DotToQtGenerator
00051 from qt_gui_py_common.worker_thread import WorkerThread
00052 
00053 from rqt_gui_py.plugin import Plugin
00054 from rqt_graph.interactive_graphics_view import InteractiveGraphicsView
00055 
00056 
00057 class RepeatedWordCompleter(QCompleter):
00058     """A completer that completes multiple times from a list"""
00059     def pathFromIndex(self, index):
00060         path = QCompleter.pathFromIndex(self, index)
00061         lst = str(self.widget().text()).split(',')
00062         if len(lst) > 1:
00063             path = '%s, %s' % (','.join(lst[:-1]), path)
00064         return path
00065 
00066     def splitPath(self, path):
00067         path = str(path.split(',')[-1]).lstrip(' ')
00068         return [path]
00069 
00070 
00071 class StackageCompletionModel(QAbstractListModel):
00072     """Ros package and stacknames"""
00073     def __init__(self, linewidget, rospack, rosstack):
00074         super(StackageCompletionModel, self).__init__(linewidget)
00075         self.allnames = sorted(list(set(rospack.list() + rosstack.list())))
00076         self.allnames = self.allnames + ['-%s' % name for name in self.allnames]
00077 
00078     def rowCount(self, parent):
00079         return len(self.allnames)
00080 
00081     def data(self, index, role):
00082         # TODO: symbols to distinguish stacks from packages
00083         if index.isValid() and (role == Qt.DisplayRole or role == Qt.EditRole):
00084             return self.allnames[index.row()]
00085         return None
00086 
00087 
00088 class RosPackGraph(Plugin):
00089 
00090     _deferred_fit_in_view = Signal()
00091 
00092     def __init__(self, context):
00093         super(RosPackGraph, self).__init__(context)
00094         self.initialized = False
00095         self._current_dotcode = None
00096         self._update_thread = WorkerThread(self._update_thread_run, self._update_finished)
00097         self._nodes = {}
00098         self._edges = {}
00099         self._options = {}
00100         self._options_serialized = ''
00101 
00102         self.setObjectName('RosPackGraph')
00103 
00104         rospack = rospkg.RosPack()
00105         rosstack = rospkg.RosStack()
00106 
00107         # factory builds generic dotcode items
00108         self.dotcode_factory = PydotFactory()
00109         # self.dotcode_factory = PygraphvizFactory()
00110         # generator builds rosgraph
00111         self.dotcode_generator = RosPackageGraphDotcodeGenerator(rospack, rosstack)
00112         # dot_to_qt transforms into Qt elements using dot layout
00113         self.dot_to_qt = DotToQtGenerator()
00114 
00115         self._widget = QWidget()
00116         rp = rospkg.RosPack()
00117         ui_file = os.path.join(rp.get_path('rqt_dep'), 'resource', 'RosPackGraph.ui')
00118         loadUi(ui_file, self._widget, {'InteractiveGraphicsView': InteractiveGraphicsView})
00119         self._widget.setObjectName('RosPackGraphUi')
00120         if context.serial_number() > 1:
00121             self._widget.setWindowTitle(self._widget.windowTitle() + (' (%d)' % context.serial_number()))
00122 
00123         self._scene = QGraphicsScene()
00124         self._scene.setBackgroundBrush(Qt.white)
00125         self._widget.graphics_view.setScene(self._scene)
00126 
00127         self._widget.depth_combo_box.insertItem(0, self.tr('infinite'), -1)
00128         self._widget.depth_combo_box.insertItem(1, self.tr('1'), 2)
00129         self._widget.depth_combo_box.insertItem(2, self.tr('2'), 3)
00130         self._widget.depth_combo_box.insertItem(3, self.tr('3'), 4)
00131         self._widget.depth_combo_box.insertItem(4, self.tr('4'), 5)
00132         self._widget.depth_combo_box.currentIndexChanged.connect(self._refresh_rospackgraph)
00133 
00134         self._widget.directions_combo_box.insertItem(0, self.tr('depends'), 0)
00135         self._widget.directions_combo_box.insertItem(1, self.tr('depends_on'), 1)
00136         self._widget.directions_combo_box.insertItem(2, self.tr('both'), 2)
00137         self._widget.directions_combo_box.currentIndexChanged.connect(self._refresh_rospackgraph)
00138 
00139         self._widget.package_type_combo_box.insertItem(0, self.tr('wet & dry'), 3)
00140         self._widget.package_type_combo_box.insertItem(1, self.tr('wet only'), 2)
00141         self._widget.package_type_combo_box.insertItem(2, self.tr('dry only'), 1)
00142         self._widget.package_type_combo_box.currentIndexChanged.connect(self._refresh_rospackgraph)
00143 
00144         completionmodel = StackageCompletionModel(self._widget.filter_line_edit, rospack, rosstack)
00145         completer = RepeatedWordCompleter(completionmodel, self)
00146         completer.setCompletionMode(QCompleter.PopupCompletion)
00147         completer.setWrapAround(True)
00148 
00149         completer.setCaseSensitivity(Qt.CaseInsensitive)
00150         self._widget.filter_line_edit.editingFinished.connect(self._refresh_rospackgraph)
00151         self._widget.filter_line_edit.setCompleter(completer)
00152         self._widget.filter_line_edit.selectionChanged.connect(self._clear_filter)
00153         
00154         self._widget.with_stacks_check_box.clicked.connect(self._refresh_rospackgraph)
00155         self._widget.mark_check_box.clicked.connect(self._refresh_rospackgraph)
00156         self._widget.colorize_check_box.clicked.connect(self._refresh_rospackgraph)
00157         self._widget.hide_transitives_check_box.clicked.connect(self._refresh_rospackgraph)
00158 
00159         self._widget.refresh_graph_push_button.setIcon(QIcon.fromTheme('view-refresh'))
00160         self._widget.refresh_graph_push_button.pressed.connect(self._update_rospackgraph)
00161 
00162         self._widget.highlight_connections_check_box.toggled.connect(self._refresh_rospackgraph)
00163         self._widget.auto_fit_graph_check_box.toggled.connect(self._refresh_rospackgraph)
00164         self._widget.fit_in_view_push_button.setIcon(QIcon.fromTheme('zoom-original'))
00165         self._widget.fit_in_view_push_button.pressed.connect(self._fit_in_view)
00166 
00167         self._widget.load_dot_push_button.setIcon(QIcon.fromTheme('document-open'))
00168         self._widget.load_dot_push_button.pressed.connect(self._load_dot)
00169         self._widget.save_dot_push_button.setIcon(QIcon.fromTheme('document-save-as'))
00170         self._widget.save_dot_push_button.pressed.connect(self._save_dot)
00171         self._widget.save_as_svg_push_button.setIcon(QIcon.fromTheme('document-save-as'))
00172         self._widget.save_as_svg_push_button.pressed.connect(self._save_svg)
00173         self._widget.save_as_image_push_button.setIcon(QIcon.fromTheme('image'))
00174         self._widget.save_as_image_push_button.pressed.connect(self._save_image)
00175 
00176         self._deferred_fit_in_view.connect(self._fit_in_view, Qt.QueuedConnection)
00177         self._deferred_fit_in_view.emit()
00178 
00179         context.add_widget(self._widget)
00180         
00181         # If in either of following case, this turnes True
00182         # - 1st filtering key is already input by user
00183         # - filtering key is restored
00184         self._filtering_started = False
00185 
00186     def shutdown_plugin(self):
00187         self._update_thread.kill()
00188 
00189     def save_settings(self, plugin_settings, instance_settings):
00190         instance_settings.set_value('depth_combo_box_index', self._widget.depth_combo_box.currentIndex())
00191         instance_settings.set_value('directions_combo_box_index', self._widget.directions_combo_box.currentIndex())
00192         instance_settings.set_value('package_type_combo_box', self._widget.package_type_combo_box.currentIndex())
00193         instance_settings.set_value('filter_line_edit_text', self._widget.filter_line_edit.text())
00194         instance_settings.set_value('with_stacks_state', self._widget.with_stacks_check_box.isChecked())
00195         instance_settings.set_value('hide_transitives_state', self._widget.hide_transitives_check_box.isChecked())
00196         instance_settings.set_value('mark_state', self._widget.mark_check_box.isChecked())
00197         instance_settings.set_value('colorize_state', self._widget.colorize_check_box.isChecked())
00198         instance_settings.set_value('auto_fit_graph_check_box_state', self._widget.auto_fit_graph_check_box.isChecked())
00199         instance_settings.set_value('highlight_connections_check_box_state', self._widget.highlight_connections_check_box.isChecked())
00200 
00201     def restore_settings(self, plugin_settings, instance_settings):
00202         _str_filter = instance_settings.value('filter_line_edit_text', '')
00203         if (_str_filter == None or _str_filter == '') and \
00204            not self._filtering_started:
00205             _str_filter = '(Separate pkgs by comma)'
00206         else:
00207             self._filtering_started = True
00208         
00209         self._widget.depth_combo_box.setCurrentIndex(int(instance_settings.value('depth_combo_box_index', 0)))
00210         self._widget.directions_combo_box.setCurrentIndex(int(instance_settings.value('directions_combo_box_index', 0)))
00211         self._widget.package_type_combo_box.setCurrentIndex(int(instance_settings.value('package_type_combo_box', 0)))
00212         self._widget.filter_line_edit.setText(_str_filter)
00213         self._widget.with_stacks_check_box.setChecked(instance_settings.value('with_stacks_state', True) in [True, 'true'])
00214         self._widget.mark_check_box.setChecked(instance_settings.value('mark_state', True) in [True, 'true'])
00215         self._widget.colorize_check_box.setChecked(instance_settings.value('colorize_state', False) in [True, 'true'])
00216         self._widget.hide_transitives_check_box.setChecked(instance_settings.value('hide_transitives_state', False) in [True, 'true'])
00217         self._widget.auto_fit_graph_check_box.setChecked(instance_settings.value('auto_fit_graph_check_box_state', True) in [True, 'true'])
00218         self._widget.highlight_connections_check_box.setChecked(instance_settings.value('highlight_connections_check_box_state', True) in [True, 'true'])
00219         self.initialized = True
00220         self._refresh_rospackgraph()
00221 
00222     def _update_rospackgraph(self):
00223         # re-enable controls customizing fetched ROS graph
00224         self._widget.depth_combo_box.setEnabled(True)
00225         self._widget.directions_combo_box.setEnabled(True)
00226         self._widget.package_type_combo_box.setEnabled(True)
00227         self._widget.filter_line_edit.setEnabled(True)
00228         self._widget.with_stacks_check_box.setEnabled(True)
00229         self._widget.mark_check_box.setEnabled(True)
00230         self._widget.colorize_check_box.setEnabled(True)
00231         self._widget.hide_transitives_check_box.setEnabled(True)
00232 
00233         self._refresh_rospackgraph(force_update=True)
00234 
00235     def _update_options(self):
00236         self._options['depth'] = self._widget.depth_combo_box.itemData(self._widget.depth_combo_box.currentIndex())
00237         self._options['directions'] = self._widget.directions_combo_box.itemData(self._widget.directions_combo_box.currentIndex())
00238         self._options['package_types'] = self._widget.package_type_combo_box.itemData(self._widget.package_type_combo_box.currentIndex())
00239         self._options['with_stacks'] = self._widget.with_stacks_check_box.isChecked()
00240         self._options['mark_selected'] = self._widget.mark_check_box.isChecked()
00241         self._options['hide_transitives'] = self._widget.hide_transitives_check_box.isChecked()
00242         # TODO: Allow different color themes
00243         self._options['colortheme'] = True if self._widget.colorize_check_box.isChecked() else None
00244         self._options['names'] = self._widget.filter_line_edit.text().split(',')
00245         if self._options['names'] == [u'None']:
00246             self._options['names'] = []
00247         self._options['highlight_level'] = 3 if self._widget.highlight_connections_check_box.isChecked() else 1
00248         self._options['auto_fit'] = self._widget.auto_fit_graph_check_box.isChecked()
00249 
00250     def _refresh_rospackgraph(self, force_update=False):
00251         if not self.initialized:
00252             return
00253 
00254         self._update_thread.kill()
00255 
00256         self._update_options()
00257 
00258         # avoid update if options did not change and force_update is not set
00259         new_options_serialized = pickle.dumps(self._options)
00260         if new_options_serialized == self._options_serialized and not force_update:
00261             return
00262         self._options_serialized = pickle.dumps(self._options)
00263 
00264         self._scene.setBackgroundBrush(Qt.lightGray)
00265 
00266         self._update_thread.start()
00267 
00268     # this runs in a non-gui thread, so don't access widgets here directly
00269     def _update_thread_run(self):
00270         self._update_graph(self._generate_dotcode())
00271 
00272     @Slot()
00273     def _update_finished(self):
00274         self._scene.setBackgroundBrush(Qt.white)
00275         self._redraw_graph_scene()
00276 
00277     # this runs in a non-gui thread, so don't access widgets here directly
00278     def _generate_dotcode(self):
00279         includes = []
00280         excludes = []
00281         for name in self._options['names']:
00282             if name.strip().startswith('-'):
00283                 excludes.append(name.strip()[1:])
00284             else:
00285                 includes.append(name.strip())
00286         # orientation = 'LR'
00287         descendants = True
00288         ancestors = True
00289         if self._options['directions'] == 1:
00290             descendants = False
00291         if self._options['directions'] == 0:
00292             ancestors = False
00293         return self.dotcode_generator.generate_dotcode(dotcode_factory=self.dotcode_factory,
00294                                                        selected_names=includes,
00295                                                        excludes=excludes,
00296                                                        depth=self._options['depth'],
00297                                                        with_stacks=self._options['with_stacks'],
00298                                                        descendants=descendants,
00299                                                        ancestors=ancestors,
00300                                                        mark_selected=self._options['mark_selected'],
00301                                                        colortheme=self._options['colortheme'],
00302                                                        hide_transitives=self._options['hide_transitives'],
00303                                                        hide_wet=self._options['package_types'] == 1,
00304                                                        hide_dry=self._options['package_types'] == 2)
00305 
00306     # this runs in a non-gui thread, so don't access widgets here directly
00307     def _update_graph(self, dotcode):
00308         self._current_dotcode = dotcode
00309         self._nodes, self._edges = self.dot_to_qt.dotcode_to_qt_items(self._current_dotcode, self._options['highlight_level'])
00310 
00311     def _generate_tool_tip(self, url):
00312         if url is not None and ':' in url:
00313             item_type, item_path = url.split(':', 1)
00314             if item_type == 'node':
00315                 tool_tip = 'Node:\n  %s' % (item_path)
00316                 service_names = rosservice.get_service_list(node=item_path)
00317                 if service_names:
00318                     tool_tip += '\nServices:'
00319                     for service_name in service_names:
00320                         try:
00321                             service_type = rosservice.get_service_type(service_name)
00322                             tool_tip += '\n  %s [%s]' % (service_name, service_type)
00323                         except rosservice.ROSServiceIOException, e:
00324                             tool_tip += '\n  %s' % (e)
00325                 return tool_tip
00326             elif item_type == 'topic':
00327                 topic_type, topic_name, _ = rostopic.get_topic_type(item_path)
00328                 return 'Topic:\n  %s\nType:\n  %s' % (topic_name, topic_type)
00329         return url
00330 
00331     def _redraw_graph_scene(self):
00332         # remove items in order to not garbage nodes which will be continued to be used
00333         for item in self._scene.items():
00334             self._scene.removeItem(item)
00335         self._scene.clear()
00336         for node_item in self._nodes.itervalues():
00337             self._scene.addItem(node_item)
00338         for edge_items in self._edges.itervalues():
00339             for edge_item in edge_items:
00340                 edge_item.add_to_scene(self._scene)
00341 
00342         self._scene.setSceneRect(self._scene.itemsBoundingRect())
00343         if self._options['auto_fit']:
00344             self._fit_in_view()
00345 
00346     def _load_dot(self, file_name=None):
00347         if file_name is None:
00348             file_name, _ = QFileDialog.getOpenFileName(self._widget, self.tr('Open graph from file'), None, self.tr('DOT graph (*.dot)'))
00349             if file_name is None or file_name == '':
00350                 return
00351 
00352         try:
00353             fh = open(file_name, 'rb')
00354             dotcode = fh.read()
00355             fh.close()
00356         except IOError:
00357             return
00358 
00359         # disable controls customizing fetched ROS graph
00360         self._widget.depth_combo_box.setEnabled(False)
00361         self._widget.directions_combo_box.setEnabled(False)
00362         self._widget.package_type_combo_box.setEnabled(False)
00363         self._widget.filter_line_edit.setEnabled(False)
00364         self._widget.with_stacks_check_box.setEnabled(False)
00365         self._widget.mark_check_box.setEnabled(False)
00366         self._widget.colorize_check_box.setEnabled(False)
00367         self._widget.hide_transitives_check_box.setEnabled(False)
00368 
00369         self._update_graph(dotcode)
00370         self._redraw_graph_scene()
00371 
00372     @Slot()
00373     def _fit_in_view(self):
00374         self._widget.graphics_view.fitInView(self._scene.itemsBoundingRect(), Qt.KeepAspectRatio)
00375 
00376     def _save_dot(self):
00377         file_name, _ = QFileDialog.getSaveFileName(self._widget, self.tr('Save as DOT'), 'rospackgraph.dot', self.tr('DOT graph (*.dot)'))
00378         if file_name is None or file_name == '':
00379             return
00380 
00381         handle = QFile(file_name)
00382         if not handle.open(QIODevice.WriteOnly | QIODevice.Text):
00383             return
00384 
00385         handle.write(self._current_dotcode)
00386         handle.close()
00387 
00388     def _save_svg(self):
00389         file_name, _ = QFileDialog.getSaveFileName(self._widget, self.tr('Save as SVG'), 'rospackgraph.svg', self.tr('Scalable Vector Graphic (*.svg)'))
00390         if file_name is None or file_name == '':
00391             return
00392 
00393         generator = QSvgGenerator()
00394         generator.setFileName(file_name)
00395         generator.setSize((self._scene.sceneRect().size() * 2.0).toSize())
00396 
00397         painter = QPainter(generator)
00398         painter.setRenderHint(QPainter.Antialiasing)
00399         self._scene.render(painter)
00400         painter.end()
00401 
00402     def _save_image(self):
00403         file_name, _ = QFileDialog.getSaveFileName(self._widget, self.tr('Save as image'), 'rospackgraph.png', self.tr('Image (*.bmp *.jpg *.png *.tiff)'))
00404         if file_name is None or file_name == '':
00405             return
00406 
00407         img = QImage((self._scene.sceneRect().size() * 2.0).toSize(), QImage.Format_ARGB32_Premultiplied)
00408         painter = QPainter(img)
00409         painter.setRenderHint(QPainter.Antialiasing)
00410         self._scene.render(painter)
00411         painter.end()
00412         img.save(file_name)
00413     
00414     def _clear_filter(self):
00415         if not self._filtering_started:
00416             self._widget.filter_line_edit.setText('')
00417             self._filtering_started = True


rqt_dep
Author(s): Thibault Kruse
autogenerated on Mon Oct 6 2014 07:15:28