00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
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
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
00066 self._gl_view = GLWidget()
00067 self._gl_view.setAcceptDrops(True)
00068
00069
00070 self._gl_view.paintGL_original = self._gl_view.paintGL
00071 self._gl_view.paintGL = self._gl_view_paintGL
00072
00073
00074 self._gl_view.mouseReleaseEvent_original = self._gl_view.mouseReleaseEvent
00075 self._gl_view.mouseReleaseEvent = self._gl_view_mouseReleaseEvent
00076
00077
00078 self.layout().addWidget(self._gl_view)
00079
00080
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
00120 self._position = (2.0, 2.0, 2.0)
00121
00122 glTranslatef(*self._position)
00123
00124 matrix = quaternion_matrix(self._orientation)
00125 glMultMatrixf(matrix)
00126
00127 glBegin(GL_QUADS)
00128
00129 glColor3f(0.0, 1.0, 0.0)
00130 glVertex3f(1.0, 1.0, -1.0)
00131 glVertex3f(-1.0, 1.0, -1.0)
00132 glVertex3f(-1.0, 1.0, 1.0)
00133 glVertex3f(1.0, 1.0, 1.0)
00134
00135 glColor3f(0.5, 1.0, 0.5)
00136 glVertex3f(1.0, -1.0, 1.0)
00137 glVertex3f(-1.0, -1.0, 1.0)
00138 glVertex3f(-1.0, -1.0, -1.0)
00139 glVertex3f(1.0, -1.0, -1.0)
00140
00141 glColor3f(0.0, 0.0, 1.0)
00142 glVertex3f(1.0, 1.0, 1.0)
00143 glVertex3f(-1.0, 1.0, 1.0)
00144 glVertex3f(-1.0, -1.0, 1.0)
00145 glVertex3f(1.0, -1.0, 1.0)
00146
00147 glColor3f(0.5, 0.5, 1.0)
00148 glVertex3f(1.0, -1.0, -1.0)
00149 glVertex3f(-1.0, -1.0, -1.0)
00150 glVertex3f(-1.0, 1.0, -1.0)
00151 glVertex3f(1.0, 1.0, -1.0)
00152
00153 glColor3f(1.0, 0.5, 0.5)
00154 glVertex3f(-1.0, 1.0, 1.0)
00155 glVertex3f(-1.0, 1.0, -1.0)
00156 glVertex3f(-1.0, -1.0, -1.0)
00157 glVertex3f(-1.0, -1.0, 1.0)
00158
00159 glColor3f(1.0, 0.0, 0.0)
00160 glVertex3f(1.0, 1.0, -1.0)
00161 glVertex3f(1.0, 1.0, 1.0)
00162 glVertex3f(1.0, -1.0, 1.0)
00163 glVertex3f(1.0, -1.0, -1.0)
00164 glEnd()
00165
00166 def _paintGLGrid(self):
00167 resolution_millimeters = 1
00168 gridded_area_size = 100
00169
00170 glLineWidth(1.0)
00171
00172 glBegin(GL_LINES)
00173
00174 glColor3f(1.0, 1.0, 1.0)
00175
00176 glVertex3f(gridded_area_size, 0, 0)
00177 glVertex3f(-gridded_area_size, 0, 0)
00178 glVertex3f(0, gridded_area_size, 0)
00179 glVertex3f(0, -gridded_area_size, 0)
00180
00181 num_of_lines = int(gridded_area_size / resolution_millimeters)
00182
00183 for i in range(num_of_lines):
00184 glVertex3f(resolution_millimeters * i, -gridded_area_size, 0)
00185 glVertex3f(resolution_millimeters * i, gridded_area_size, 0)
00186 glVertex3f(gridded_area_size, resolution_millimeters * i, 0)
00187 glVertex3f(-gridded_area_size, resolution_millimeters * i, 0)
00188
00189 glVertex3f(resolution_millimeters * (-i), -gridded_area_size, 0)
00190 glVertex3f(resolution_millimeters * (-i), gridded_area_size, 0)
00191 glVertex3f(gridded_area_size, resolution_millimeters * (-i), 0)
00192 glVertex3f(-gridded_area_size, resolution_millimeters * (-i), 0)
00193
00194 glEnd()
00195
00196 def _paintGLCoorsystem(self):
00197 glLineWidth(10.0)
00198
00199 glBegin(GL_LINES)
00200
00201 glColor3f(1.0, 0.0, 0.0)
00202 glVertex3f(0.0, 0.0, 0.0)
00203 glVertex3f(1.0, 0.0, 0.0)
00204
00205 glColor3f(0.0, 1.0, 0.0)
00206 glVertex3f(0.0, 0.0, 0.0)
00207 glVertex3f(0.0, 1.0, 0.0)
00208
00209 glColor3f(0.0, 0.0, 1.0)
00210 glVertex3f(0.0, 0.0, 0.0)
00211 glVertex3f(0.0, 0.0, 1.0)
00212
00213 glEnd()
00214
00215 def _gl_view_mouseReleaseEvent(self, event):
00216 if event.button() == Qt.RightButton:
00217 menu = QMenu(self._gl_view)
00218 action = QAction(self._gl_view.tr("Reset view"), self._gl_view)
00219 menu.addAction(action)
00220 action.triggered.connect(self._set_default_view)
00221 menu.exec_(self._gl_view.mapToGlobal(event.pos()))
00222
00223 @Slot('QDragEnterEvent*')
00224 def dragEnterEvent(self, event):
00225 if event.mimeData().hasText():
00226 topic_name = str(event.mimeData().text())
00227 if len(topic_name) == 0:
00228 qWarning('PoseViewWidget.dragEnterEvent(): event.mimeData() text is empty')
00229 return
00230 else:
00231 if not hasattr(event.source(), 'selectedItems') or len(event.source().selectedItems()) == 0:
00232 qWarning('PoseViewWidget.dragEnterEvent(): event.source() has no attribute selectedItems or length of selectedItems is 0')
00233 return
00234 item = event.source().selectedItems()[0]
00235 topic_name = item.data(0, Qt.UserRole)
00236
00237 if topic_name is None:
00238 qWarning('PoseViewWidget.dragEnterEvent(): selectedItem has no UserRole data with a topic name')
00239 return
00240
00241
00242 msg_class, self._topic_name, _ = get_topic_class(topic_name)
00243 if msg_class is None:
00244 qWarning('PoseViewWidget.dragEnterEvent(): No message class was found for topic "%s".' % topic_name)
00245 return
00246
00247
00248 quaternion_slot_path, point_slot_path = self._get_slot_paths(msg_class)
00249
00250 if quaternion_slot_path is None and point_slot_path is None:
00251 qWarning('PoseViewWidget.dragEnterEvent(): No Pose, Quaternion or Point data was found outside of arrays in "%s" on topic "%s".'
00252 % (msg_class._type, topic_name))
00253 return
00254
00255 event.acceptProposedAction()
00256
00257 @Slot('QDropEvent*')
00258 def dropEvent(self, event):
00259 if event.mimeData().hasText():
00260 topic_name = str(event.mimeData().text())
00261 else:
00262 dropped_item = event.source().selectedItems()[0]
00263 topic_name = str(dropped_item.data(0, Qt.UserRole))
00264
00265 self._unregister_topic()
00266 self._subscribe_topic(topic_name)
00267
00268 def _unregister_topic(self):
00269 if self._subscriber:
00270 self._subscriber.unregister()
00271
00272 @staticmethod
00273 def _make_path_list_from_path_string(path):
00274 path = path.split('/')
00275 if path == ['']:
00276 return []
00277 return path
00278
00279 @staticmethod
00280 def _get_slot_paths(msg_class):
00281
00282 pose_slot_paths = find_slots_by_type_bfs(msg_class, Pose)
00283 for path in pose_slot_paths:
00284
00285 if '[' not in path:
00286 path = PoseViewWidget._make_path_list_from_path_string(pose_slot_paths[0])
00287 return path + ['orientation'], path + ['position']
00288
00289
00290 quaternion_slot_paths = find_slots_by_type_bfs(msg_class, Quaternion)
00291 for path in quaternion_slot_paths:
00292 if '[' not in path:
00293 quaternion_slot_path = PoseViewWidget._make_path_list_from_path_string(path)
00294 break
00295 else:
00296 quaternion_slot_path = None
00297
00298 point_slot_paths = find_slots_by_type_bfs(msg_class, Point)
00299 for path in point_slot_paths:
00300 if '[' not in path:
00301 point_slot_path = PoseViewWidget._make_path_list_from_path_string(path)
00302 break
00303 else:
00304 point_slot_path = None
00305
00306 return quaternion_slot_path, point_slot_path
00307
00308
00309 def _subscribe_topic(self, topic_name):
00310 msg_class, self._topic_name, _ = get_topic_class(topic_name)
00311 quaternion_slot_path, point_slot_path = self._get_slot_paths(msg_class)
00312
00313 self._subscriber = rospy.Subscriber(
00314 self._topic_name,
00315 msg_class,
00316 self.message_callback,
00317 callback_args=(quaternion_slot_path, point_slot_path)
00318 )
00319
00320 def message_callback(self, message, slot_paths):
00321 quaternion_slot_path = slot_paths[0]
00322 point_slot_path = slot_paths[1]
00323
00324 if quaternion_slot_path is None:
00325 self._orientation = quaternion_about_axis(0.0, (1.0, 0.0, 0.0))
00326 else:
00327 orientation = message
00328 for slot_name in quaternion_slot_path:
00329 orientation = getattr(orientation, slot_name)
00330 self._orientation = (orientation.x, orientation.y, orientation.z, orientation.w)
00331
00332 if point_slot_path is None:
00333
00334 self._position = (2.0, 2.0, 2.0)
00335 else:
00336 position = message
00337 for slot_name in point_slot_path:
00338 position = getattr(position, slot_name)
00339 self._position = (position.x, position.y, position.z)
00340
00341 def shutdown_plugin(self):
00342 self._unregister_topic()