rqt_smach.py
Go to the documentation of this file.
00001 # Original code forked from rqt_graph Copyright (c) 2011, Dirk Thomas, TU Darmstadt
00002 # All rights reserved.
00003 #
00004 # Adaptations for use with SMACH Copyright (c) 2013, Jonathan Bohren, The Johns
00005 # Hopkins University
00006 # All rights reserved.
00007 #
00008 # Redistribution and use in source and binary forms, with or without
00009 # modification, are permitted provided that the following conditions are met:
00010 #
00011 #   * Redistributions of source code must retain the above copyright
00012 #     notice, this list of conditions and the following disclaimer.
00013 #   * Redistributions in binary form must reproduce the above
00014 #     copyright notice, this list of conditions and the following
00015 #     disclaimer in the documentation and/or other materials provided
00016 #     with the distribution.
00017 #   * Neither the name of the TU Darmstadt nor the name of the Johns Hopkins
00018 #     University  nor the names of its contributors may be used to endorse or
00019 #     promote products derived from this software without specific prior
00020 #     written permission.
00021 #
00022 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00023 # AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00024 # IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00025 # ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
00026 # LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00027 # CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00028 # SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00029 # INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00030 # CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00031 # ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032 # POSSIBILITY OF SUCH DAMAGE.
00033 
00034 ## System Imports
00035 from __future__ import division # See PEP#238
00036 import os
00037 
00038 ## Fuerte ROS imports
00039 import roslib; roslib.load_manifest('rqt_smach')
00040 import rospy
00041 import rospkg
00042 
00043 ## QT Imports
00044 from python_qt_binding import loadUi
00045 from python_qt_binding.QtCore import QAbstractListModel, QFile, QIODevice, Qt, Signal
00046 from python_qt_binding.QtGui import QCompleter, QFileDialog, QGraphicsScene, QIcon, QImage, QPainter, QWidget
00047 from python_qt_binding.QtSvg import QSvgGenerator
00048 
00049 ## RQT
00050 from qt_gui.plugin import Plugin
00051 
00052 ## GraphViz 
00053 from qt_dotgraph.dot_to_qt import DotToQtGenerator
00054 from qt_dotgraph.pydotfactory import PydotFactory # pydot requires some hacks
00055 # TODO: use pygraphviz instead, but non-deterministic layout will first be resolved in graphviz 2.30
00056 # from qtgui_plugin.pygraphvizfactory import PygraphvizFactory
00057 
00058 ## Local imports
00059 from .dotcode import SmachGraphDotcodeGenerator, NODE_NODE_GRAPH, NODE_TOPIC_ALL_GRAPH, NODE_TOPIC_GRAPH
00060 from .interactive_graphics_view import InteractiveGraphicsView
00061 
00062 #from xdot.xdot_qt import #XDotWidget
00063 
00064 class SmachViewer(Plugin):
00065 
00066     _deferred_fit_in_view = Signal()
00067 
00068     def __init__(self, context):
00069         """Construct the GUI and initialize the graph."""
00070         ### Boilerplate RQT gui code
00071         super(SmachViewer, self).__init__(context)
00072         self.initialized = False
00073         self.setObjectName('SmachViewer')
00074 
00075         ### Member Initialization
00076         self._graph = None
00077         self._current_dotcode = None
00078         self._widget = QWidget()
00079 
00080         ### Structures for generating the visualization
00081         # factory builds generic dotcode items
00082         self.dotcode_factory = PydotFactory()
00083         # self.dotcode_factory = PygraphvizFactory()
00084         # generator builds smach_graph
00085         self.dotcode_generator = RosGraphDotcodeGenerator()
00086         # dot_to_qt transforms into Qt elements using dot layout
00087         self.dot_to_qt = DotToQtGenerator()
00088 
00089         ### Construct the GUI 
00090         # Get the QT .ui file and load it
00091         rp = rospkg.RosPack()
00092         ui_file = os.path.join(rp.get_path('rqt_smach'), 'resource', 'SmachViewer.ui')
00093         loadUi(ui_file, self._widget,
00094                 {'InteractiveGraphicsView': InteractiveGraphicsView})
00095         self._widget.setObjectName('SmachViewerUi')
00096 
00097         # Add this instance's serial number to the title if appropriate
00098         if context.serial_number() > 1:
00099             self._widget.setWindowTitle(self._widget.windowTitle() + (' (%d)' % context.serial_number()))
00100 
00101         ## Populate the UI
00102         self._scene = QGraphicsScene()
00103         self._scene.setBackgroundBrush(Qt.white)
00104         self._widget.graphics_view.setScene(self._scene)
00105 
00106         self._widget.graph_type_combo_box.insertItem(0, self.tr('Nodes only'), NODE_NODE_GRAPH)
00107         self._widget.graph_type_combo_box.insertItem(1, self.tr('Nodes/Topics (active)'), NODE_TOPIC_GRAPH)
00108         self._widget.graph_type_combo_box.insertItem(2, self.tr('Nodes/Topics (all)'), NODE_TOPIC_ALL_GRAPH)
00109         self._widget.graph_type_combo_box.setCurrentIndex(0)
00110         self._widget.graph_type_combo_box.currentIndexChanged.connect(self._refresh_smach_graph)
00111 
00112         self.node_completionmodel = NamespaceCompletionModel(self._widget.filter_line_edit, False)
00113         completer = RepeatedWordCompleter(self.node_completionmodel, self)
00114         completer.setCompletionMode(QCompleter.PopupCompletion)
00115         completer.setWrapAround(True)
00116         completer.setCaseSensitivity(Qt.CaseInsensitive)
00117         self._widget.filter_line_edit.editingFinished.connect(self._refresh_smach_graph)
00118         self._widget.filter_line_edit.setCompleter(completer)
00119 
00120         self.topic_completionmodel = NamespaceCompletionModel(self._widget.topic_filter_line_edit, False)
00121         topic_completer = RepeatedWordCompleter(self.topic_completionmodel, self)
00122         topic_completer.setCompletionMode(QCompleter.PopupCompletion)
00123         topic_completer.setWrapAround(True)
00124         topic_completer.setCaseSensitivity(Qt.CaseInsensitive)
00125         self._widget.topic_filter_line_edit.editingFinished.connect(self._refresh_smach_graph)
00126         self._widget.topic_filter_line_edit.setCompleter(topic_completer)
00127 
00128         self._widget.namespace_cluster_check_box.clicked.connect(self._refresh_smach_graph)
00129         self._widget.actionlib_check_box.clicked.connect(self._refresh_smach_graph)
00130         self._widget.dead_sinks_check_box.clicked.connect(self._refresh_smach_graph)
00131         self._widget.leaf_topics_check_box.clicked.connect(self._refresh_smach_graph)
00132         self._widget.quiet_check_box.clicked.connect(self._refresh_smach_graph)
00133 
00134         self._widget.refresh_graph_push_button.setIcon(QIcon.fromTheme('view-refresh'))
00135         self._widget.refresh_graph_push_button.pressed.connect(self._update_smach_graph)
00136 
00137         self._widget.highlight_connections_check_box.toggled.connect(self._redraw_graph_view)
00138         self._widget.auto_fit_graph_check_box.toggled.connect(self._redraw_graph_view)
00139         self._widget.fit_in_view_push_button.setIcon(QIcon.fromTheme('zoom-original'))
00140         self._widget.fit_in_view_push_button.pressed.connect(self._fit_in_view)
00141 
00142         self._widget.load_dot_push_button.setIcon(QIcon.fromTheme('document-open'))
00143         self._widget.load_dot_push_button.pressed.connect(self._load_dot)
00144         self._widget.save_dot_push_button.setIcon(QIcon.fromTheme('document-save-as'))
00145         self._widget.save_dot_push_button.pressed.connect(self._save_dot)
00146         self._widget.save_as_svg_push_button.setIcon(QIcon.fromTheme('document-save-as'))
00147         self._widget.save_as_svg_push_button.pressed.connect(self._save_svg)
00148         self._widget.save_as_image_push_button.setIcon(QIcon.fromTheme('image'))
00149         self._widget.save_as_image_push_button.pressed.connect(self._save_image)
00150 
00151         # Update the graph initially
00152         self._update_smach_graph()
00153         self._deferred_fit_in_view.connect(self._fit_in_view, Qt.QueuedConnection)
00154         self._deferred_fit_in_view.emit()
00155 
00156         # Add the widget to the user interface
00157         context.add_widget(self._widget)
00158 
00159     def shutdown_plugin(self):
00160         """Clean up all persistant resources."""
00161         pass
00162 
00163     def save_settings(self, plugin_settings, instance_settings):
00164         """Save the intrinsic configuration."""
00165         instance_settings.set_value('graph_type_combo_box_index', self._widget.graph_type_combo_box.currentIndex())
00166         instance_settings.set_value('filter_line_edit_text', self._widget.filter_line_edit.text())
00167         instance_settings.set_value('topic_filter_line_edit_text', self._widget.topic_filter_line_edit.text())
00168         instance_settings.set_value('namespace_cluster_check_box_state', self._widget.namespace_cluster_check_box.isChecked())
00169         instance_settings.set_value('actionlib_check_box_state', self._widget.actionlib_check_box.isChecked())
00170         instance_settings.set_value('dead_sinks_check_box_state', self._widget.dead_sinks_check_box.isChecked())
00171         instance_settings.set_value('leaf_topics_check_box_state', self._widget.leaf_topics_check_box.isChecked())
00172         instance_settings.set_value('quiet_check_box_state', self._widget.quiet_check_box.isChecked())
00173         instance_settings.set_value('auto_fit_graph_check_box_state', self._widget.auto_fit_graph_check_box.isChecked())
00174         instance_settings.set_value('highlight_connections_check_box_state', self._widget.highlight_connections_check_box.isChecked())
00175 
00176     def restore_settings(self, plugin_settings, instance_settings):
00177         """Restore the intrinsic configuration."""
00178         self._widget.graph_type_combo_box.setCurrentIndex(int(instance_settings.value('graph_type_combo_box_index', 0)))
00179         self._widget.filter_line_edit.setText(instance_settings.value('filter_line_edit_text', '/'))
00180         self._widget.topic_filter_line_edit.setText(instance_settings.value('topic_filter_line_edit_text', '/'))
00181         self._widget.namespace_cluster_check_box.setChecked(instance_settings.value('namespace_cluster_check_box_state', True) in [True, 'true'])
00182         self._widget.actionlib_check_box.setChecked(instance_settings.value('actionlib_check_box_state', True) in [True, 'true'])
00183         self._widget.dead_sinks_check_box.setChecked(instance_settings.value('dead_sinks_check_box_state', True) in [True, 'true'])
00184         self._widget.leaf_topics_check_box.setChecked(instance_settings.value('leaf_topics_check_box_state', True) in [True, 'true'])
00185         self._widget.quiet_check_box.setChecked(instance_settings.value('quiet_check_box_state', True) in [True, 'true'])
00186         self._widget.auto_fit_graph_check_box.setChecked(instance_settings.value('auto_fit_graph_check_box_state', True) in [True, 'true'])
00187         self._widget.highlight_connections_check_box.setChecked(instance_settings.value('highlight_connections_check_box_state', True) in [True, 'true'])
00188         self.initialized = True
00189         self._refresh_smach_graph()
00190 
00191     def _update_smach_graph(self):
00192         """Update the information in the SMACH graph to reflect the state of
00193         one or more SMACH executives at runtime."""
00194 
00195         # Re-enable controls customizing the SMACH graph
00196         self._enable_controls(True)
00197 
00198         # Re-generate the smach graph
00199         self._graph = rosgraph.impl.graph.Graph() #TODO: switch this to smach generator
00200         self._graph.set_master_stale(5.0)
00201         self._graph.set_node_stale(5.0)
00202         self._graph.update()
00203         self.node_completionmodel.refresh(self._graph.nn_nodes)
00204         self.topic_completionmodel.refresh(self._graph.nt_nodes)
00205 
00206         # Re-draw the graph
00207         self._refresh_smach_graph()
00208 
00209     def _refresh_smach_graph(self):
00210         """Generate dotcode for the SMACH graph and re-draw it."""
00211         if not self.initialized:
00212             return
00213         self._update_graph_view(self._generate_dotcode())
00214 
00215     def _generate_dotcode(self):
00216         """Generate graphviz dotcode describing the current SMACH structure and activity."""
00217 
00218         '''
00219         ns_filter = self._widget.filter_line_edit.text()
00220         topic_filter = self._widget.topic_filter_line_edit.text()
00221         graph_mode = self._widget.graph_type_combo_box.itemData(self._widget.graph_type_combo_box.currentIndex())
00222         orientation = 'LR'
00223         if self._widget.namespace_cluster_check_box.isChecked():
00224             namespace_cluster = 1
00225         else:
00226             namespace_cluster = 0
00227         accumulate_actions = self._widget.actionlib_check_box.isChecked()
00228         hide_dead_end_topics = self._widget.dead_sinks_check_box.isChecked()
00229         hide_single_connection_topics = self._widget.leaf_topics_check_box.isChecked()
00230         quiet = self._widget.quiet_check_box.isChecked()
00231 
00232         return self.dotcode_generator.generate_dotcode(
00233             smach_graph_inst=self._graph,
00234             ns_filter=ns_filter,
00235             topic_filter=topic_filter,
00236             graph_mode=graph_mode,
00237             hide_single_connection_topics=hide_single_connection_topics,
00238             hide_dead_end_topics=hide_dead_end_topics,
00239             cluster_namespaces_level=namespace_cluster,
00240             accumulate_actions=accumulate_actions,
00241             dotcode_factory=self.dotcode_factory,
00242             orientation=orientation,
00243             quiet=quiet)
00244             '''
00245 
00246     def _update_graph_view(self, dotcode):
00247         """Set the graph to display specific dotcode, and re-draw it."""
00248 
00249         if dotcode == self._current_dotcode:
00250             return
00251         self._current_dotcode = dotcode
00252         self._redraw_graph_view()
00253 
00254     def _generate_tool_tip(self, url):
00255         if url is not None and ':' in url:
00256             item_type, item_path = url.split(':', 1)
00257             if item_type == 'node':
00258                 tool_tip = 'Node:\n  %s' % (item_path)
00259                 service_names = rosservice.get_service_list(node=item_path)
00260                 if service_names:
00261                     tool_tip += '\nServices:'
00262                     for service_name in service_names:
00263                         try:
00264                             service_type = rosservice.get_service_type(service_name)
00265                             tool_tip += '\n  %s [%s]' % (service_name, service_type)
00266                         except rosservice.ROSServiceIOException as e:
00267                             tool_tip += '\n  %s' % (e)
00268                 return tool_tip
00269             elif item_type == 'topic':
00270                 topic_type, topic_name, _ = rostopic.get_topic_type(item_path)
00271                 return 'Topic:\n  %s\nType:\n  %s' % (topic_name, topic_type)
00272         return url
00273 
00274     def _redraw_graph_view(self):
00275         """Actually draw the SMACH graph in QT based on the current dotcode."""
00276         self._scene.clear()
00277 
00278         if self._widget.highlight_connections_check_box.isChecked():
00279             highlight_level = 3
00280         else:
00281             highlight_level = 1
00282 
00283         # layout graph and create qt items
00284         (nodes, edges) = self.dot_to_qt.dotcode_to_qt_items(self._current_dotcode,
00285                                                             highlight_level=highlight_level,
00286                                                             same_label_siblings=True)
00287 
00288         for node_item in nodes.itervalues():
00289             self._scene.addItem(node_item)
00290         for edge_items in edges.itervalues():
00291             for edge_item in edge_items:
00292                 edge_item.add_to_scene(self._scene)
00293 
00294         self._scene.setSceneRect(self._scene.itemsBoundingRect())
00295         if self._widget.auto_fit_graph_check_box.isChecked():
00296             self._fit_in_view()
00297 
00298     def _load_dot(self, file_name=None):
00299         """Read in dotcode and re-draw the graph to display it."""
00300 
00301         if file_name is None:
00302             file_name, _ = QFileDialog.getOpenFileName(self._widget, self.tr('Open graph from file'), None, self.tr('DOT graph (*.dot)'))
00303             if file_name is None or file_name == '':
00304                 return
00305 
00306         try:
00307             fh = open(file_name, 'rb')
00308             dotcode = fh.read()
00309             fh.close()
00310         except IOError:
00311             return
00312 
00313         # Disable the controls since we can't customize a graph loaded from
00314         # file.
00315         self._enable_controls(false)
00316 
00317         self._update_graph_view(dotcode)
00318 
00319     def _enable_controls(self, enabled):
00320         """Enable or disable controls for customizing the graph"""
00321         self._widget.graph_type_combo_box.setEnabled(enabled)
00322         self._widget.filter_line_edit.setEnabled(enabled)
00323         self._widget.topic_filter_line_edit.setEnabled(enabled)
00324         self._widget.namespace_cluster_check_box.setEnabled(enabled)
00325         self._widget.actionlib_check_box.setEnabled(enabled)
00326         self._widget.dead_sinks_check_box.setEnabled(enabled)
00327         self._widget.leaf_topics_check_box.setEnabled(enabled)
00328         self._widget.quiet_check_box.setEnabled(enabled)
00329 
00330     def _fit_in_view(self):
00331         """Scale the scene so that it fits in the window."""
00332         self._widget.graphics_view.fitInView(self._scene.itemsBoundingRect(), Qt.KeepAspectRatio)
00333 
00334     def _save_dot(self):
00335         """Save the current dotcode."""
00336         file_name, _ = QFileDialog.getSaveFileName(self._widget, self.tr('Save as DOT'), 'smach_graph.dot', self.tr('DOT graph (*.dot)'))
00337         if file_name is None or file_name == '':
00338             return
00339 
00340         handle = QFile(file_name)
00341         if not handle.open(QIODevice.WriteOnly | QIODevice.Text):
00342             return
00343 
00344         handle.write(self._current_dotcode)
00345         handle.close()
00346 
00347     def _save_svg(self):
00348         """Save the current graph as an SVG."""
00349         file_name, _ = QFileDialog.getSaveFileName(self._widget, self.tr('Save as SVG'), 'smach_graph.svg', self.tr('Scalable Vector Graphic (*.svg)'))
00350         if file_name is None or file_name == '':
00351             return
00352 
00353         generator = QSvgGenerator()
00354         generator.setFileName(file_name)
00355         generator.setSize((self._scene.sceneRect().size() * 2.0).toSize())
00356 
00357         painter = QPainter(generator)
00358         painter.setRenderHint(QPainter.Antialiasing)
00359         self._scene.render(painter)
00360         painter.end()
00361 
00362     def _save_image(self):
00363         """Save the current graph as a PNG."""
00364         file_name, _ = QFileDialog.getSaveFileName(self._widget, self.tr('Save as image'), 'smach_graph.png', self.tr('Image (*.bmp *.jpg *.png *.tiff)'))
00365         if file_name is None or file_name == '':
00366             return
00367 
00368         img = QImage((self._scene.sceneRect().size() * 2.0).toSize(), QImage.Format_ARGB32_Premultiplied)
00369         painter = QPainter(img)
00370         painter.setRenderHint(QPainter.Antialiasing)
00371         self._scene.render(painter)
00372         painter.end()
00373         img.save(file_name)
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Properties Friends


rqt_smach
Author(s): Jonathan Bohren
autogenerated on Wed Jun 26 2013 10:10:53