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


rqt_tf_tree
Author(s): Thibault Kruse
autogenerated on Wed Feb 6 2019 03:16:16