31 from __future__
import division
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
40 from rostopic
import get_topic_class
42 from tf.transformations
import quaternion_matrix, quaternion_about_axis
43 from geometry_msgs.msg
import Quaternion, Pose, Point
45 from OpenGL.GL
import glBegin, glColor3f, glEnd, glLineWidth, glMultMatrixf, glTranslatef, \
46 glVertex3f, GL_LINES, GL_QUADS
47 from .gl_widget
import GLWidget
54 super(PoseViewWidget, self).
__init__()
56 ui_file = os.path.join(rp.get_path(
'rqt_pose_view'),
'resource',
'PoseViewWidget.ui')
67 self._gl_view.setAcceptDrops(
True)
70 self._gl_view.paintGL_original = self._gl_view.paintGL
74 self._gl_view.mouseReleaseEvent_original = self._gl_view.mouseReleaseEvent
78 self.layout().addWidget(self.
_gl_view)
83 self._update_timer.start(40)
86 view_matrix_string = repr(self._gl_view.get_view_matrix())
87 instance_settings.set_value(
'view_matrix', view_matrix_string)
90 view_matrix_string = instance_settings.value(
'view_matrix')
92 view_matrix = eval(view_matrix_string)
96 if view_matrix
is not None:
97 self._gl_view.set_view_matrix(view_matrix)
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))
109 self._gl_view.makeCurrent()
110 self._gl_view.updateGL()
113 self._gl_view.paintGL_original()
126 matrix = matrix.transpose()
127 glMultMatrixf(matrix)
131 glColor3f(0.0, 1.0, 0.0)
132 glVertex3f(1.0, 1.0, -1.0)
133 glVertex3f(-1.0, 1.0, -1.0)
134 glVertex3f(-1.0, 1.0, 1.0)
135 glVertex3f(1.0, 1.0, 1.0)
137 glColor3f(0.5, 1.0, 0.5)
138 glVertex3f(1.0, -1.0, 1.0)
139 glVertex3f(-1.0, -1.0, 1.0)
140 glVertex3f(-1.0, -1.0, -1.0)
141 glVertex3f(1.0, -1.0, -1.0)
143 glColor3f(0.0, 0.0, 1.0)
144 glVertex3f(1.0, 1.0, 1.0)
145 glVertex3f(-1.0, 1.0, 1.0)
146 glVertex3f(-1.0, -1.0, 1.0)
147 glVertex3f(1.0, -1.0, 1.0)
149 glColor3f(0.5, 0.5, 1.0)
150 glVertex3f(1.0, -1.0, -1.0)
151 glVertex3f(-1.0, -1.0, -1.0)
152 glVertex3f(-1.0, 1.0, -1.0)
153 glVertex3f(1.0, 1.0, -1.0)
155 glColor3f(1.0, 0.5, 0.5)
156 glVertex3f(-1.0, 1.0, 1.0)
157 glVertex3f(-1.0, 1.0, -1.0)
158 glVertex3f(-1.0, -1.0, -1.0)
159 glVertex3f(-1.0, -1.0, 1.0)
161 glColor3f(1.0, 0.0, 0.0)
162 glVertex3f(1.0, 1.0, -1.0)
163 glVertex3f(1.0, 1.0, 1.0)
164 glVertex3f(1.0, -1.0, 1.0)
165 glVertex3f(1.0, -1.0, -1.0)
169 resolution_millimeters = 1
170 gridded_area_size = 100
176 glColor3f(1.0, 1.0, 1.0)
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)
183 num_of_lines = int(gridded_area_size / resolution_millimeters)
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)
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)
203 glColor3f(1.0, 0.0, 0.0)
204 glVertex3f(0.0, 0.0, 0.0)
205 glVertex3f(1.0, 0.0, 0.0)
207 glColor3f(0.0, 1.0, 0.0)
208 glVertex3f(0.0, 0.0, 0.0)
209 glVertex3f(0.0, 1.0, 0.0)
211 glColor3f(0.0, 0.0, 1.0)
212 glVertex3f(0.0, 0.0, 0.0)
213 glVertex3f(0.0, 0.0, 1.0)
218 if event.button() == Qt.RightButton:
220 action = QAction(self._gl_view.tr(
"Reset view"), self.
_gl_view)
221 menu.addAction(action)
223 menu.exec_(self._gl_view.mapToGlobal(event.pos()))
225 @Slot(
'QDragEnterEvent*')
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')
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')
236 item = event.source().selectedItems()[0]
237 topic_name = item.data(0, Qt.UserRole)
239 if topic_name
is None:
240 qWarning(
'PoseViewWidget.dragEnterEvent(): selectedItem has no UserRole data with a topic name')
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)
250 quaternion_slot_path, point_slot_path = self.
_get_slot_paths(msg_class)
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))
257 event.acceptProposedAction()
261 if event.mimeData().hasText():
262 topic_name = str(event.mimeData().text())
264 dropped_item = event.source().selectedItems()[0]
265 topic_name = str(dropped_item.data(0, Qt.UserRole))
272 self._subscriber.unregister()
276 path = path.split(
'/')
284 pose_slot_paths = find_slots_by_type_bfs(msg_class, Pose)
285 for path
in pose_slot_paths:
288 path = PoseViewWidget._make_path_list_from_path_string(pose_slot_paths[0])
289 return path + [
'orientation'], path + [
'position']
292 quaternion_slot_paths = find_slots_by_type_bfs(msg_class, Quaternion)
293 for path
in quaternion_slot_paths:
295 quaternion_slot_path = PoseViewWidget._make_path_list_from_path_string(path)
298 quaternion_slot_path =
None 300 point_slot_paths = find_slots_by_type_bfs(msg_class, Point)
301 for path
in point_slot_paths:
303 point_slot_path = PoseViewWidget._make_path_list_from_path_string(path)
306 point_slot_path =
None 308 return quaternion_slot_path, point_slot_path
312 msg_class, self.
_topic_name, _ = get_topic_class(topic_name)
313 quaternion_slot_path, point_slot_path = self.
_get_slot_paths(msg_class)
319 callback_args=(quaternion_slot_path, point_slot_path)
323 quaternion_slot_path = slot_paths[0]
324 point_slot_path = slot_paths[1]
326 if quaternion_slot_path
is None:
327 self.
_orientation = quaternion_about_axis(0.0, (1.0, 0.0, 0.0))
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)
334 if point_slot_path
is None:
339 for slot_name
in point_slot_path:
340 position = getattr(position, slot_name)
341 self.
_position = (position.x, position.y, position.z)