tf_tree.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 
00036 
00037 import rospy
00038 import rospkg
00039 
00040 from tf2_msgs.srv import FrameGraph
00041 import tf2_ros
00042 
00043 from python_qt_binding import loadUi
00044 from python_qt_binding.QtCore import QFile, QIODevice, QObject, Qt, Signal
00045 from python_qt_binding.QtGui import QIcon, QImage, QPainter
00046 from python_qt_binding.QtWidgets import QFileDialog, QGraphicsScene, QWidget
00047 from python_qt_binding.QtSvg import QSvgGenerator
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 rqt_graph.interactive_graphics_view import InteractiveGraphicsView
00052 
00053 from .dotcode_tf import RosTfTreeDotcodeGenerator
00054 
00055 
00056 class RosTfTree(QObject):
00057 
00058     _deferred_fit_in_view = Signal()
00059 
00060     def __init__(self, context):
00061         super(RosTfTree, self).__init__(context)
00062         self.initialized = False
00063 
00064         self.setObjectName('RosTfTree')
00065 
00066         self._current_dotcode = None
00067 
00068         self._widget = QWidget()
00069 
00070         # factory builds generic dotcode items
00071         self.dotcode_factory = PydotFactory()
00072         # self.dotcode_factory = PygraphvizFactory()
00073         # generator builds rosgraph
00074         self.dotcode_generator = RosTfTreeDotcodeGenerator()
00075         self.tf2_buffer_ = tf2_ros.Buffer()
00076         self.tf2_listener_ = tf2_ros.TransformListener(self.tf2_buffer_)
00077 
00078         # dot_to_qt transforms into Qt elements using dot layout
00079         self.dot_to_qt = DotToQtGenerator()
00080 
00081         rp = rospkg.RosPack()
00082         ui_file = os.path.join(rp.get_path('rqt_tf_tree'), 'resource', 'RosTfTree.ui')
00083         loadUi(ui_file, self._widget, {'InteractiveGraphicsView': InteractiveGraphicsView})
00084         self._widget.setObjectName('RosTfTreeUi')
00085         if context.serial_number() > 1:
00086             self._widget.setWindowTitle(self._widget.windowTitle() + (' (%d)' % context.serial_number()))
00087 
00088         self._scene = QGraphicsScene()
00089         self._scene.setBackgroundBrush(Qt.white)
00090         self._widget.graphics_view.setScene(self._scene)
00091 
00092         self._widget.refresh_graph_push_button.setIcon(QIcon.fromTheme('view-refresh'))
00093         self._widget.refresh_graph_push_button.pressed.connect(self._update_tf_graph)
00094 
00095         self._widget.highlight_connections_check_box.toggled.connect(self._redraw_graph_view)
00096         self._widget.auto_fit_graph_check_box.toggled.connect(self._redraw_graph_view)
00097         self._widget.fit_in_view_push_button.setIcon(QIcon.fromTheme('zoom-original'))
00098         self._widget.fit_in_view_push_button.pressed.connect(self._fit_in_view)
00099 
00100         self._widget.load_dot_push_button.setIcon(QIcon.fromTheme('document-open'))
00101         self._widget.load_dot_push_button.pressed.connect(self._load_dot)
00102         self._widget.save_dot_push_button.setIcon(QIcon.fromTheme('document-save-as'))
00103         self._widget.save_dot_push_button.pressed.connect(self._save_dot)
00104         self._widget.save_as_svg_push_button.setIcon(QIcon.fromTheme('document-save-as'))
00105         self._widget.save_as_svg_push_button.pressed.connect(self._save_svg)
00106         self._widget.save_as_image_push_button.setIcon(QIcon.fromTheme('image-x-generic'))
00107         self._widget.save_as_image_push_button.pressed.connect(self._save_image)
00108 
00109         self._deferred_fit_in_view.connect(self._fit_in_view,
00110                                            Qt.QueuedConnection)
00111         self._deferred_fit_in_view.emit()
00112 
00113         context.add_widget(self._widget)
00114 
00115         self._force_refresh = False
00116 
00117     def save_settings(self, plugin_settings, instance_settings):
00118         instance_settings.set_value('auto_fit_graph_check_box_state',
00119                                     self._widget.auto_fit_graph_check_box.isChecked())
00120         instance_settings.set_value('highlight_connections_check_box_state',
00121                                     self._widget.highlight_connections_check_box.isChecked())
00122 
00123     def restore_settings(self, plugin_settings, instance_settings):
00124         self._widget.auto_fit_graph_check_box.setChecked(
00125             instance_settings.value('auto_fit_graph_check_box_state', True) in [True, 'true'])
00126         self._widget.highlight_connections_check_box.setChecked(
00127             instance_settings.value('highlight_connections_check_box_state', True) in [True, 'true'])
00128         self.initialized = True
00129         self._refresh_tf_graph()
00130 
00131     def _update_tf_graph(self):
00132         self._force_refresh = True
00133         self._refresh_tf_graph()
00134 
00135     def _refresh_tf_graph(self):
00136         if not self.initialized:
00137             return
00138         self._update_graph_view(self._generate_dotcode())
00139 
00140     def _generate_dotcode(self):
00141         force_refresh = self._force_refresh
00142         self._force_refresh = False
00143         rospy.wait_for_service('~tf2_frames')
00144         tf2_frame_srv = rospy.ServiceProxy('~tf2_frames', FrameGraph)
00145         return self.dotcode_generator.generate_dotcode(dotcode_factory=self.dotcode_factory,
00146                                                        tf2_frame_srv=tf2_frame_srv,
00147                                                        force_refresh=force_refresh)
00148 
00149     def _update_graph_view(self, dotcode):
00150         if dotcode == self._current_dotcode:
00151             return
00152         self._current_dotcode = dotcode
00153         self._redraw_graph_view()
00154 
00155     def _generate_tool_tip(self, url):
00156         return url
00157 
00158     def _redraw_graph_view(self):
00159         self._scene.clear()
00160 
00161         if self._widget.highlight_connections_check_box.isChecked():
00162             highlight_level = 3
00163         else:
00164             highlight_level = 1
00165 
00166         (nodes, edges) = self.dot_to_qt.dotcode_to_qt_items(self._current_dotcode,
00167                                                             highlight_level)
00168 
00169         for node_item in nodes.values():
00170             self._scene.addItem(node_item)
00171         for edge_items in edges.values():
00172             for edge_item in edge_items:
00173                 edge_item.add_to_scene(self._scene)
00174 
00175         self._scene.setSceneRect(self._scene.itemsBoundingRect())
00176         if self._widget.auto_fit_graph_check_box.isChecked():
00177             self._fit_in_view()
00178 
00179     def _load_dot(self, file_name=None):
00180         if file_name is None:
00181             file_name, _ = QFileDialog.getOpenFileName(
00182                 self._widget,
00183                 self.tr('Open graph from file'),
00184                 None,
00185                 self.tr('DOT graph (*.dot)'))
00186             if file_name is None or file_name == '':
00187                 return
00188 
00189         try:
00190             fhandle = open(file_name, 'rb')
00191             dotcode = fhandle.read()
00192             fhandle.close()
00193         except IOError:
00194             return
00195 
00196         self._update_graph_view(dotcode)
00197 
00198     def _fit_in_view(self):
00199         self._widget.graphics_view.fitInView(self._scene.itemsBoundingRect(),
00200                                              Qt.KeepAspectRatio)
00201 
00202     def _save_dot(self):
00203         file_name, _ = QFileDialog.getSaveFileName(self._widget,
00204                                                    self.tr('Save as DOT'),
00205                                                    'frames.dot',
00206                                                    self.tr('DOT graph (*.dot)'))
00207         if file_name is None or file_name == '':
00208             return
00209 
00210         file = QFile(file_name)
00211         if not file.open(QIODevice.WriteOnly | QIODevice.Text):
00212             return
00213 
00214         file.write(self._current_dotcode)
00215         file.close()
00216 
00217     def _save_svg(self):
00218         file_name, _ = QFileDialog.getSaveFileName(
00219             self._widget,
00220             self.tr('Save as SVG'),
00221             'frames.svg',
00222             self.tr('Scalable Vector Graphic (*.svg)'))
00223         if file_name is None or file_name == '':
00224             return
00225 
00226         generator = QSvgGenerator()
00227         generator.setFileName(file_name)
00228         generator.setSize((self._scene.sceneRect().size() * 2.0).toSize())
00229 
00230         painter = QPainter(generator)
00231         painter.setRenderHint(QPainter.Antialiasing)
00232         self._scene.render(painter)
00233         painter.end()
00234 
00235     def _save_image(self):
00236         file_name, _ = QFileDialog.getSaveFileName(
00237             self._widget,
00238             self.tr('Save as image'),
00239             'frames.png',
00240             self.tr('Image (*.bmp *.jpg *.png *.tiff)'))
00241         if file_name is None or file_name == '':
00242             return
00243 
00244         img = QImage((self._scene.sceneRect().size() * 2.0).toSize(),
00245                      QImage.Format_ARGB32_Premultiplied)
00246         painter = QPainter(img)
00247         painter.setRenderHint(QPainter.Antialiasing)
00248         self._scene.render(painter)
00249         painter.end()
00250         img.save(file_name)


rqt_tf_tree
Author(s): Thibault Kruse
autogenerated on Thu Jul 27 2017 02:33:38