pose_view_widget.py
Go to the documentation of this file.
1 # Copyright (c) 2011, Dorian Scholz, TU Darmstadt
2 # All rights reserved.
3 #
4 # Redistribution and use in source and binary forms, with or without
5 # modification, are permitted provided that the following conditions
6 # are met:
7 #
8 # * Redistributions of source code must retain the above copyright
9 # notice, this list of conditions and the following disclaimer.
10 # * Redistributions in binary form must reproduce the above
11 # copyright notice, this list of conditions and the following
12 # disclaimer in the documentation and/or other materials provided
13 # with the distribution.
14 # * Neither the name of the TU Darmstadt nor the names of its
15 # contributors may be used to endorse or promote products derived
16 # from this software without specific prior written permission.
17 #
18 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
19 # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
20 # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
21 # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
22 # COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
23 # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
24 # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
25 # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
26 # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
27 # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
28 # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
29 # POSSIBILITY OF SUCH DAMAGE.
30 
31 from __future__ import division
32 import os
33 import rospkg
34 
35 from python_qt_binding import loadUi
36 from python_qt_binding.QtCore import Qt, QTimer, qWarning, Slot
37 from python_qt_binding.QtWidgets import QAction, QMenu, QWidget
38 
39 import rospy
40 from rostopic import get_topic_class
41 from rqt_py_common.topic_helpers import find_slots_by_type_bfs
42 from tf.transformations import quaternion_matrix, quaternion_about_axis
43 from geometry_msgs.msg import Quaternion, Pose, Point
44 
45 from OpenGL.GL import glBegin, glColor3f, glEnd, glLineWidth, glMultMatrixf, glTranslatef, \
46  glVertex3f, GL_LINES, GL_QUADS
47 from .gl_widget import GLWidget
48 
49 
50 # main class inherits from the ui window class
51 class PoseViewWidget(QWidget):
52 
53  def __init__(self, plugin):
54  super(PoseViewWidget, self).__init__()
55  rp = rospkg.RosPack()
56  ui_file = os.path.join(rp.get_path('rqt_pose_view'), 'resource', 'PoseViewWidget.ui')
57  loadUi(ui_file, self)
58  self._plugin = plugin
59 
60  self._position = (2.0, 2.0, 2.0)
61  self._orientation = quaternion_about_axis(0.0, (1.0, 0.0, 0.0))
62  self._topic_name = None
63  self._subscriber = None
64 
65  # create GL view
66  self._gl_view = GLWidget()
67  self._gl_view.setAcceptDrops(True)
68 
69  # backup and replace original paint method
70  self._gl_view.paintGL_original = self._gl_view.paintGL
71  self._gl_view.paintGL = self._gl_view_paintGL
72 
73  # backup and replace original mouse release method
74  self._gl_view.mouseReleaseEvent_original = self._gl_view.mouseReleaseEvent
75  self._gl_view.mouseReleaseEvent = self._gl_view_mouseReleaseEvent
76 
77  # add GL view to widget layout
78  self.layout().addWidget(self._gl_view)
79 
80  # init and start update timer with 40ms (25fps)
81  self._update_timer = QTimer(self)
82  self._update_timer.timeout.connect(self.update_timeout)
83  self._update_timer.start(40)
84 
85  def save_settings(self, plugin_settings, instance_settings):
86  view_matrix_string = repr(self._gl_view.get_view_matrix())
87  instance_settings.set_value('view_matrix', view_matrix_string)
88 
89  def restore_settings(self, plugin_settings, instance_settings):
90  view_matrix_string = instance_settings.value('view_matrix')
91  try:
92  view_matrix = eval(view_matrix_string)
93  except Exception:
94  view_matrix = None
95 
96  if view_matrix is not None:
97  self._gl_view.set_view_matrix(view_matrix)
98  else:
99  self._set_default_view()
100 
101  def _set_default_view(self):
102  self._gl_view.makeCurrent()
103  self._gl_view.reset_view()
104  self._gl_view.rotate((0, 0, 1), 45)
105  self._gl_view.rotate((1, 0, 0), -65)
106  self._gl_view.translate((0, -3, -15))
107 
108  def update_timeout(self):
109  self._gl_view.makeCurrent()
110  self._gl_view.updateGL()
111 
112  def _gl_view_paintGL(self):
113  self._gl_view.paintGL_original()
114  self._paintGLGrid()
115  self._paintGLCoorsystem()
116  self._paintGLBox()
117 
118  def _paintGLBox(self):
119  # FIXME: add user configurable setting to allow use of translation as well
120  self._position = (2.0, 2.0, 2.0) # Set fixed translation for now
121 
122  glTranslatef(*self._position) # Translate Box
123 
124  matrix = quaternion_matrix(self._orientation) # convert quaternion to translation matrix
125  # tf uses row-major while gl expects column-major
126  matrix = matrix.transpose()
127  glMultMatrixf(matrix) # Rotate Box
128 
129  glBegin(GL_QUADS) # Start Drawing The Box
130 
131  glColor3f(0.0, 1.0, 0.0)
132  glVertex3f(1.0, 1.0, -1.0) # Top Right Of The Quad (Top)
133  glVertex3f(-1.0, 1.0, -1.0) # Top Left Of The Quad (Top)
134  glVertex3f(-1.0, 1.0, 1.0) # Bottom Left Of The Quad (Top)
135  glVertex3f(1.0, 1.0, 1.0) # Bottom Right Of The Quad (Top)
136 
137  glColor3f(0.5, 1.0, 0.5)
138  glVertex3f(1.0, -1.0, 1.0) # Top Right Of The Quad (Bottom)
139  glVertex3f(-1.0, -1.0, 1.0) # Top Left Of The Quad (Bottom)
140  glVertex3f(-1.0, -1.0, -1.0) # Bottom Left Of The Quad (Bottom)
141  glVertex3f(1.0, -1.0, -1.0) # Bottom Right Of The Quad (Bottom)
142 
143  glColor3f(0.0, 0.0, 1.0)
144  glVertex3f(1.0, 1.0, 1.0) # Top Right Of The Quad (Front)
145  glVertex3f(-1.0, 1.0, 1.0) # Top Left Of The Quad (Front)
146  glVertex3f(-1.0, -1.0, 1.0) # Bottom Left Of The Quad (Front)
147  glVertex3f(1.0, -1.0, 1.0) # Bottom Right Of The Quad (Front)
148 
149  glColor3f(0.5, 0.5, 1.0)
150  glVertex3f(1.0, -1.0, -1.0) # Bottom Left Of The Quad (Back)
151  glVertex3f(-1.0, -1.0, -1.0) # Bottom Right Of The Quad (Back)
152  glVertex3f(-1.0, 1.0, -1.0) # Top Right Of The Quad (Back)
153  glVertex3f(1.0, 1.0, -1.0) # Top Left Of The Quad (Back)
154 
155  glColor3f(1.0, 0.5, 0.5)
156  glVertex3f(-1.0, 1.0, 1.0) # Top Right Of The Quad (Left)
157  glVertex3f(-1.0, 1.0, -1.0) # Top Left Of The Quad (Left)
158  glVertex3f(-1.0, -1.0, -1.0) # Bottom Left Of The Quad (Left)
159  glVertex3f(-1.0, -1.0, 1.0) # Bottom Right Of The Quad (Left)
160 
161  glColor3f(1.0, 0.0, 0.0)
162  glVertex3f(1.0, 1.0, -1.0) # Top Right Of The Quad (Right)
163  glVertex3f(1.0, 1.0, 1.0) # Top Left Of The Quad (Right)
164  glVertex3f(1.0, -1.0, 1.0) # Bottom Left Of The Quad (Right)
165  glVertex3f(1.0, -1.0, -1.0) # Bottom Right Of The Quad (Right)
166  glEnd() # Done Drawing The Quad
167 
168  def _paintGLGrid(self):
169  resolution_millimeters = 1
170  gridded_area_size = 100
171 
172  glLineWidth(1.0)
173 
174  glBegin(GL_LINES)
175 
176  glColor3f(1.0, 1.0, 1.0)
177 
178  glVertex3f(gridded_area_size, 0, 0)
179  glVertex3f(-gridded_area_size, 0, 0)
180  glVertex3f(0, gridded_area_size, 0)
181  glVertex3f(0, -gridded_area_size, 0)
182 
183  num_of_lines = int(gridded_area_size / resolution_millimeters)
184 
185  for i in range(num_of_lines):
186  glVertex3f(resolution_millimeters * i, -gridded_area_size, 0)
187  glVertex3f(resolution_millimeters * i, gridded_area_size, 0)
188  glVertex3f(gridded_area_size, resolution_millimeters * i, 0)
189  glVertex3f(-gridded_area_size, resolution_millimeters * i, 0)
190 
191  glVertex3f(resolution_millimeters * (-i), -gridded_area_size, 0)
192  glVertex3f(resolution_millimeters * (-i), gridded_area_size, 0)
193  glVertex3f(gridded_area_size, resolution_millimeters * (-i), 0)
194  glVertex3f(-gridded_area_size, resolution_millimeters * (-i), 0)
195 
196  glEnd()
197 
199  glLineWidth(10.0)
200 
201  glBegin(GL_LINES)
202 
203  glColor3f(1.0, 0.0, 0.0)
204  glVertex3f(0.0, 0.0, 0.0)
205  glVertex3f(1.0, 0.0, 0.0)
206 
207  glColor3f(0.0, 1.0, 0.0)
208  glVertex3f(0.0, 0.0, 0.0)
209  glVertex3f(0.0, 1.0, 0.0)
210 
211  glColor3f(0.0, 0.0, 1.0)
212  glVertex3f(0.0, 0.0, 0.0)
213  glVertex3f(0.0, 0.0, 1.0)
214 
215  glEnd()
216 
217  def _gl_view_mouseReleaseEvent(self, event):
218  if event.button() == Qt.RightButton:
219  menu = QMenu(self._gl_view)
220  action = QAction(self._gl_view.tr("Reset view"), self._gl_view)
221  menu.addAction(action)
222  action.triggered.connect(self._set_default_view)
223  menu.exec_(self._gl_view.mapToGlobal(event.pos()))
224 
225  @Slot('QDragEnterEvent*')
226  def dragEnterEvent(self, event):
227  if event.mimeData().hasText():
228  topic_name = str(event.mimeData().text())
229  if len(topic_name) == 0:
230  qWarning('PoseViewWidget.dragEnterEvent(): event.mimeData() text is empty')
231  return
232  else:
233  if not hasattr(event.source(), 'selectedItems') or len(event.source().selectedItems()) == 0:
234  qWarning('PoseViewWidget.dragEnterEvent(): event.source() has no attribute selectedItems or length of selectedItems is 0')
235  return
236  item = event.source().selectedItems()[0]
237  topic_name = item.data(0, Qt.UserRole)
238 
239  if topic_name is None:
240  qWarning('PoseViewWidget.dragEnterEvent(): selectedItem has no UserRole data with a topic name')
241  return
242 
243  # check for valid topic
244  msg_class, self._topic_name, _ = get_topic_class(topic_name)
245  if msg_class is None:
246  qWarning('PoseViewWidget.dragEnterEvent(): No message class was found for topic "%s".' % topic_name)
247  return
248 
249  # check for valid message class
250  quaternion_slot_path, point_slot_path = self._get_slot_paths(msg_class)
251 
252  if quaternion_slot_path is None and point_slot_path is None:
253  qWarning('PoseViewWidget.dragEnterEvent(): No Pose, Quaternion or Point data was found outside of arrays in "%s" on topic "%s".'
254  % (msg_class._type, topic_name))
255  return
256 
257  event.acceptProposedAction()
258 
259  @Slot('QDropEvent*')
260  def dropEvent(self, event):
261  if event.mimeData().hasText():
262  topic_name = str(event.mimeData().text())
263  else:
264  dropped_item = event.source().selectedItems()[0]
265  topic_name = str(dropped_item.data(0, Qt.UserRole))
266 
267  self._unregister_topic()
268  self._subscribe_topic(topic_name)
269 
270  def _unregister_topic(self):
271  if self._subscriber:
272  self._subscriber.unregister()
273 
274  @staticmethod
276  path = path.split('/')
277  if path == ['']:
278  return []
279  return path
280 
281  @staticmethod
282  def _get_slot_paths(msg_class):
283  # find first Pose in msg_class
284  pose_slot_paths = find_slots_by_type_bfs(msg_class, Pose)
285  for path in pose_slot_paths:
286  # make sure the path does not contain an array, because we don't want to deal with empty arrays...
287  if '[' not in path:
288  path = PoseViewWidget._make_path_list_from_path_string(pose_slot_paths[0])
289  return path + ['orientation'], path + ['position']
290 
291  # if no Pose is found, find first Quaternion and Point
292  quaternion_slot_paths = find_slots_by_type_bfs(msg_class, Quaternion)
293  for path in quaternion_slot_paths:
294  if '[' not in path:
295  quaternion_slot_path = PoseViewWidget._make_path_list_from_path_string(path)
296  break
297  else:
298  quaternion_slot_path = None
299 
300  point_slot_paths = find_slots_by_type_bfs(msg_class, Point)
301  for path in point_slot_paths:
302  if '[' not in path:
303  point_slot_path = PoseViewWidget._make_path_list_from_path_string(path)
304  break
305  else:
306  point_slot_path = None
307 
308  return quaternion_slot_path, point_slot_path
309 
310 
311  def _subscribe_topic(self, topic_name):
312  msg_class, self._topic_name, _ = get_topic_class(topic_name)
313  quaternion_slot_path, point_slot_path = self._get_slot_paths(msg_class)
314 
315  self._subscriber = rospy.Subscriber(
316  self._topic_name,
317  msg_class,
318  self.message_callback,
319  callback_args=(quaternion_slot_path, point_slot_path)
320  )
321 
322  def message_callback(self, message, slot_paths):
323  quaternion_slot_path = slot_paths[0]
324  point_slot_path = slot_paths[1]
325 
326  if quaternion_slot_path is None:
327  self._orientation = quaternion_about_axis(0.0, (1.0, 0.0, 0.0))
328  else:
329  orientation = message
330  for slot_name in quaternion_slot_path:
331  orientation = getattr(orientation, slot_name)
332  self._orientation = (orientation.x, orientation.y, orientation.z, orientation.w)
333 
334  if point_slot_path is None:
335  # if no point is given, set it to a fixed offset so the axes can be seen
336  self._position = (2.0, 2.0, 2.0)
337  else:
338  position = message
339  for slot_name in point_slot_path:
340  position = getattr(position, slot_name)
341  self._position = (position.x, position.y, position.z)
342 
343  def shutdown_plugin(self):
344  self._unregister_topic()
def restore_settings(self, plugin_settings, instance_settings)
def save_settings(self, plugin_settings, instance_settings)
def message_callback(self, message, slot_paths)


rqt_pose_view
Author(s): Dorian Scholz
autogenerated on Sat Jun 8 2019 18:05:11