pose_view_widget.py
Go to the documentation of this file.
00001 # Copyright (c) 2011, Dorian Scholz, TU Darmstadt
00002 # All rights reserved.
00003 #
00004 # Redistribution and use in source and binary forms, with or without
00005 # modification, are permitted provided that the following conditions
00006 # are met:
00007 #
00008 #   * Redistributions of source code must retain the above copyright
00009 #     notice, this list of conditions and the following disclaimer.
00010 #   * Redistributions in binary form must reproduce the above
00011 #     copyright notice, this list of conditions and the following
00012 #     disclaimer in the documentation and/or other materials provided
00013 #     with the distribution.
00014 #   * Neither the name of the TU Darmstadt nor the names of its
00015 #     contributors may be used to endorse or promote products derived
00016 #     from this software without specific prior written permission.
00017 #
00018 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00019 # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00020 # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00021 # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00022 # COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00023 # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00024 # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00025 # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00026 # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00027 # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00028 # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00029 # POSSIBILITY OF SUCH DAMAGE.
00030 
00031 from __future__ import division
00032 import os
00033 import rospkg
00034 
00035 from python_qt_binding import loadUi
00036 from python_qt_binding.QtCore import Qt, QTimer, qWarning, Slot
00037 from python_qt_binding.QtWidgets import QAction, QMenu, QWidget
00038 
00039 import rospy
00040 from rostopic import get_topic_class
00041 from rqt_py_common.topic_helpers import find_slots_by_type_bfs
00042 from tf.transformations import quaternion_matrix, quaternion_about_axis
00043 from geometry_msgs.msg import Quaternion, Pose, Point
00044 
00045 from OpenGL.GL import glBegin, glColor3f, glEnd, glLineWidth, glMultMatrixf, glTranslatef, \
00046     glVertex3f, GL_LINES, GL_QUADS
00047 from .gl_widget import GLWidget
00048 
00049 
00050 # main class inherits from the ui window class
00051 class PoseViewWidget(QWidget):
00052 
00053     def __init__(self, plugin):
00054         super(PoseViewWidget, self).__init__()
00055         rp = rospkg.RosPack()
00056         ui_file = os.path.join(rp.get_path('rqt_pose_view'), 'resource', 'PoseViewWidget.ui')
00057         loadUi(ui_file, self)
00058         self._plugin = plugin
00059 
00060         self._position = (2.0, 2.0, 2.0)
00061         self._orientation = quaternion_about_axis(0.0, (1.0, 0.0, 0.0))
00062         self._topic_name = None
00063         self._subscriber = None
00064 
00065         # create GL view
00066         self._gl_view = GLWidget()
00067         self._gl_view.setAcceptDrops(True)
00068 
00069         # backup and replace original paint method
00070         self._gl_view.paintGL_original = self._gl_view.paintGL
00071         self._gl_view.paintGL = self._gl_view_paintGL
00072 
00073         # backup and replace original mouse release method
00074         self._gl_view.mouseReleaseEvent_original = self._gl_view.mouseReleaseEvent
00075         self._gl_view.mouseReleaseEvent = self._gl_view_mouseReleaseEvent
00076 
00077         # add GL view to widget layout
00078         self.layout().addWidget(self._gl_view)
00079 
00080         # init and start update timer with 40ms (25fps)
00081         self._update_timer = QTimer(self)
00082         self._update_timer.timeout.connect(self.update_timeout)
00083         self._update_timer.start(40)
00084 
00085     def save_settings(self, plugin_settings, instance_settings):
00086         view_matrix_string = repr(self._gl_view.get_view_matrix())
00087         instance_settings.set_value('view_matrix', view_matrix_string)
00088 
00089     def restore_settings(self, plugin_settings, instance_settings):
00090         view_matrix_string = instance_settings.value('view_matrix')
00091         try:
00092             view_matrix = eval(view_matrix_string)
00093         except Exception:
00094             view_matrix = None
00095 
00096         if view_matrix is not None:
00097             self._gl_view.set_view_matrix(view_matrix)
00098         else:
00099             self._set_default_view()
00100 
00101     def _set_default_view(self):
00102         self._gl_view.makeCurrent()
00103         self._gl_view.reset_view()
00104         self._gl_view.rotate((0, 0, 1), 45)
00105         self._gl_view.rotate((1, 0, 0), -65)
00106         self._gl_view.translate((0, -3, -15))
00107 
00108     def update_timeout(self):
00109         self._gl_view.makeCurrent()
00110         self._gl_view.updateGL()
00111 
00112     def _gl_view_paintGL(self):
00113         self._gl_view.paintGL_original()
00114         self._paintGLGrid()
00115         self._paintGLCoorsystem()
00116         self._paintGLBox()
00117 
00118     def _paintGLBox(self):
00119         # FIXME: add user configurable setting to allow use of translation as well
00120         self._position = (2.0, 2.0, 2.0)  # Set fixed translation for now
00121 
00122         glTranslatef(*self._position)     # Translate Box
00123 
00124         matrix = quaternion_matrix(self._orientation)  # convert quaternion to translation matrix
00125         # tf uses row-major while gl expects column-major
00126         matrix = matrix.transpose()
00127         glMultMatrixf(matrix)             # Rotate Box
00128 
00129         glBegin(GL_QUADS)                 # Start Drawing The Box
00130 
00131         glColor3f(0.0, 1.0, 0.0)
00132         glVertex3f(1.0, 1.0, -1.0)        # Top Right Of The Quad (Top)
00133         glVertex3f(-1.0, 1.0, -1.0)       # Top Left Of The Quad (Top)
00134         glVertex3f(-1.0, 1.0, 1.0)        # Bottom Left Of The Quad (Top)
00135         glVertex3f(1.0, 1.0, 1.0)         # Bottom Right Of The Quad (Top)
00136 
00137         glColor3f(0.5, 1.0, 0.5)
00138         glVertex3f(1.0, -1.0, 1.0)        # Top Right Of The Quad (Bottom)
00139         glVertex3f(-1.0, -1.0, 1.0)       # Top Left Of The Quad (Bottom)
00140         glVertex3f(-1.0, -1.0, -1.0)      # Bottom Left Of The Quad (Bottom)
00141         glVertex3f(1.0, -1.0, -1.0)       # Bottom Right Of The Quad (Bottom)
00142 
00143         glColor3f(0.0, 0.0, 1.0)
00144         glVertex3f(1.0, 1.0, 1.0)         # Top Right Of The Quad (Front)
00145         glVertex3f(-1.0, 1.0, 1.0)        # Top Left Of The Quad (Front)
00146         glVertex3f(-1.0, -1.0, 1.0)       # Bottom Left Of The Quad (Front)
00147         glVertex3f(1.0, -1.0, 1.0)        # Bottom Right Of The Quad (Front)
00148 
00149         glColor3f(0.5, 0.5, 1.0)
00150         glVertex3f(1.0, -1.0, -1.0)       # Bottom Left Of The Quad (Back)
00151         glVertex3f(-1.0, -1.0, -1.0)      # Bottom Right Of The Quad (Back)
00152         glVertex3f(-1.0, 1.0, -1.0)       # Top Right Of The Quad (Back)
00153         glVertex3f(1.0, 1.0, -1.0)        # Top Left Of The Quad (Back)
00154 
00155         glColor3f(1.0, 0.5, 0.5)
00156         glVertex3f(-1.0, 1.0, 1.0)        # Top Right Of The Quad (Left)
00157         glVertex3f(-1.0, 1.0, -1.0)       # Top Left Of The Quad (Left)
00158         glVertex3f(-1.0, -1.0, -1.0)      # Bottom Left Of The Quad (Left)
00159         glVertex3f(-1.0, -1.0, 1.0)       # Bottom Right Of The Quad (Left)
00160 
00161         glColor3f(1.0, 0.0, 0.0)
00162         glVertex3f(1.0, 1.0, -1.0)        # Top Right Of The Quad (Right)
00163         glVertex3f(1.0, 1.0, 1.0)         # Top Left Of The Quad (Right)
00164         glVertex3f(1.0, -1.0, 1.0)        # Bottom Left Of The Quad (Right)
00165         glVertex3f(1.0, -1.0, -1.0)       # Bottom Right Of The Quad (Right)
00166         glEnd()                           # Done Drawing The Quad
00167 
00168     def _paintGLGrid(self):
00169         resolution_millimeters = 1
00170         gridded_area_size = 100
00171 
00172         glLineWidth(1.0)
00173 
00174         glBegin(GL_LINES)
00175 
00176         glColor3f(1.0, 1.0, 1.0)
00177 
00178         glVertex3f(gridded_area_size, 0, 0)
00179         glVertex3f(-gridded_area_size, 0, 0)
00180         glVertex3f(0, gridded_area_size, 0)
00181         glVertex3f(0, -gridded_area_size, 0)
00182 
00183         num_of_lines = int(gridded_area_size / resolution_millimeters)
00184 
00185         for i in range(num_of_lines):
00186             glVertex3f(resolution_millimeters * i, -gridded_area_size, 0)
00187             glVertex3f(resolution_millimeters * i, gridded_area_size, 0)
00188             glVertex3f(gridded_area_size, resolution_millimeters * i, 0)
00189             glVertex3f(-gridded_area_size, resolution_millimeters * i, 0)
00190 
00191             glVertex3f(resolution_millimeters * (-i), -gridded_area_size, 0)
00192             glVertex3f(resolution_millimeters * (-i), gridded_area_size, 0)
00193             glVertex3f(gridded_area_size, resolution_millimeters * (-i), 0)
00194             glVertex3f(-gridded_area_size, resolution_millimeters * (-i), 0)
00195 
00196         glEnd()
00197 
00198     def _paintGLCoorsystem(self):
00199         glLineWidth(10.0)
00200 
00201         glBegin(GL_LINES)
00202 
00203         glColor3f(1.0, 0.0, 0.0)
00204         glVertex3f(0.0, 0.0, 0.0)
00205         glVertex3f(1.0, 0.0, 0.0)
00206 
00207         glColor3f(0.0, 1.0, 0.0)
00208         glVertex3f(0.0, 0.0, 0.0)
00209         glVertex3f(0.0, 1.0, 0.0)
00210 
00211         glColor3f(0.0, 0.0, 1.0)
00212         glVertex3f(0.0, 0.0, 0.0)
00213         glVertex3f(0.0, 0.0, 1.0)
00214 
00215         glEnd()
00216 
00217     def _gl_view_mouseReleaseEvent(self, event):
00218         if event.button() == Qt.RightButton:
00219             menu = QMenu(self._gl_view)
00220             action = QAction(self._gl_view.tr("Reset view"), self._gl_view)
00221             menu.addAction(action)
00222             action.triggered.connect(self._set_default_view)
00223             menu.exec_(self._gl_view.mapToGlobal(event.pos()))
00224 
00225     @Slot('QDragEnterEvent*')
00226     def dragEnterEvent(self, event):
00227         if event.mimeData().hasText():
00228             topic_name = str(event.mimeData().text())
00229             if len(topic_name) == 0:
00230                 qWarning('PoseViewWidget.dragEnterEvent(): event.mimeData() text is empty')
00231                 return
00232         else:
00233             if not hasattr(event.source(), 'selectedItems') or len(event.source().selectedItems()) == 0:
00234                 qWarning('PoseViewWidget.dragEnterEvent(): event.source() has no attribute selectedItems or length of selectedItems is 0')
00235                 return
00236             item = event.source().selectedItems()[0]
00237             topic_name = item.data(0, Qt.UserRole)
00238 
00239             if topic_name is None:
00240                 qWarning('PoseViewWidget.dragEnterEvent(): selectedItem has no UserRole data with a topic name')
00241                 return
00242 
00243         # check for valid topic
00244         msg_class, self._topic_name, _ = get_topic_class(topic_name)
00245         if msg_class is None:
00246             qWarning('PoseViewWidget.dragEnterEvent(): No message class was found for topic "%s".' % topic_name)
00247             return
00248 
00249         # check for valid message class
00250         quaternion_slot_path, point_slot_path = self._get_slot_paths(msg_class)
00251 
00252         if quaternion_slot_path is None and point_slot_path is None:
00253             qWarning('PoseViewWidget.dragEnterEvent(): No Pose, Quaternion or Point data was found outside of arrays in "%s" on topic "%s".'
00254                      % (msg_class._type, topic_name))
00255             return
00256 
00257         event.acceptProposedAction()
00258 
00259     @Slot('QDropEvent*')
00260     def dropEvent(self, event):
00261         if event.mimeData().hasText():
00262             topic_name = str(event.mimeData().text())
00263         else:
00264             dropped_item = event.source().selectedItems()[0]
00265             topic_name = str(dropped_item.data(0, Qt.UserRole))
00266 
00267         self._unregister_topic()
00268         self._subscribe_topic(topic_name)
00269 
00270     def _unregister_topic(self):
00271         if self._subscriber:
00272             self._subscriber.unregister()
00273 
00274     @staticmethod
00275     def _make_path_list_from_path_string(path):
00276         path = path.split('/')
00277         if path == ['']:
00278             return []
00279         return path
00280 
00281     @staticmethod
00282     def _get_slot_paths(msg_class):
00283         # find first Pose in msg_class
00284         pose_slot_paths = find_slots_by_type_bfs(msg_class, Pose)
00285         for path in pose_slot_paths:
00286             # make sure the path does not contain an array, because we don't want to deal with empty arrays...
00287             if '[' not in path:
00288                 path = PoseViewWidget._make_path_list_from_path_string(pose_slot_paths[0])
00289                 return path + ['orientation'], path + ['position']
00290 
00291         # if no Pose is found, find first Quaternion and Point
00292         quaternion_slot_paths = find_slots_by_type_bfs(msg_class, Quaternion)
00293         for path in quaternion_slot_paths:
00294             if '[' not in path:
00295                 quaternion_slot_path = PoseViewWidget._make_path_list_from_path_string(path)
00296                 break
00297         else:
00298             quaternion_slot_path = None
00299 
00300         point_slot_paths = find_slots_by_type_bfs(msg_class, Point)
00301         for path in point_slot_paths:
00302             if '[' not in path:
00303                 point_slot_path = PoseViewWidget._make_path_list_from_path_string(path)
00304                 break
00305         else:
00306             point_slot_path = None
00307 
00308         return quaternion_slot_path, point_slot_path
00309 
00310 
00311     def _subscribe_topic(self, topic_name):
00312         msg_class, self._topic_name, _ = get_topic_class(topic_name)
00313         quaternion_slot_path, point_slot_path = self._get_slot_paths(msg_class)
00314 
00315         self._subscriber = rospy.Subscriber(
00316                 self._topic_name,
00317                 msg_class,
00318                 self.message_callback,
00319                 callback_args=(quaternion_slot_path, point_slot_path)
00320         )
00321 
00322     def message_callback(self, message, slot_paths):
00323         quaternion_slot_path = slot_paths[0]
00324         point_slot_path = slot_paths[1]
00325 
00326         if quaternion_slot_path is None:
00327             self._orientation = quaternion_about_axis(0.0, (1.0, 0.0, 0.0))
00328         else:
00329             orientation = message
00330             for slot_name in quaternion_slot_path:
00331                 orientation = getattr(orientation, slot_name)
00332             self._orientation = (orientation.x, orientation.y, orientation.z, orientation.w)
00333 
00334         if point_slot_path is None:
00335             # if no point is given, set it to a fixed offset so the axes can be seen
00336             self._position = (2.0, 2.0, 2.0)
00337         else:
00338             position = message
00339             for slot_name in point_slot_path:
00340                 position = getattr(position, slot_name)
00341             self._position = (position.x, position.y, position.z)
00342 
00343     def shutdown_plugin(self):
00344         self._unregister_topic()


rqt_pose_view
Author(s): Dorian Scholz
autogenerated on Thu Jun 6 2019 18:58:42