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')
78 self.layout().addWidget(self.
_gl_view)
86 if rospy.has_param(
'~pose_view_topic'):
87 topic = rospy.get_param(
'~pose_view_topic')
90 except AttributeError:
91 rospy.logwarn(
"invalid topic name '{}'".format(topic))
94 view_matrix_string = repr(self.
_gl_view.get_view_matrix())
95 instance_settings.set_value(
'view_matrix', view_matrix_string)
98 view_matrix_string = instance_settings.value(
'view_matrix')
100 view_matrix = eval(view_matrix_string)
104 if view_matrix
is not None:
105 self.
_gl_view.set_view_matrix(view_matrix)
113 self.
_gl_view.rotate((1, 0, 0), -65)
114 self.
_gl_view.translate((0, -3, -15))
134 matrix = matrix.transpose()
135 glMultMatrixf(matrix)
139 glColor3f(0.0, 1.0, 0.0)
140 glVertex3f(1.0, 1.0, -1.0)
141 glVertex3f(-1.0, 1.0, -1.0)
142 glVertex3f(-1.0, 1.0, 1.0)
143 glVertex3f(1.0, 1.0, 1.0)
145 glColor3f(0.5, 1.0, 0.5)
146 glVertex3f(1.0, -1.0, 1.0)
147 glVertex3f(-1.0, -1.0, 1.0)
148 glVertex3f(-1.0, -1.0, -1.0)
149 glVertex3f(1.0, -1.0, -1.0)
151 glColor3f(0.0, 0.0, 1.0)
152 glVertex3f(1.0, 1.0, 1.0)
153 glVertex3f(-1.0, 1.0, 1.0)
154 glVertex3f(-1.0, -1.0, 1.0)
155 glVertex3f(1.0, -1.0, 1.0)
157 glColor3f(0.5, 0.5, 1.0)
158 glVertex3f(1.0, -1.0, -1.0)
159 glVertex3f(-1.0, -1.0, -1.0)
160 glVertex3f(-1.0, 1.0, -1.0)
161 glVertex3f(1.0, 1.0, -1.0)
163 glColor3f(1.0, 0.5, 0.5)
164 glVertex3f(-1.0, 1.0, 1.0)
165 glVertex3f(-1.0, 1.0, -1.0)
166 glVertex3f(-1.0, -1.0, -1.0)
167 glVertex3f(-1.0, -1.0, 1.0)
169 glColor3f(1.0, 0.0, 0.0)
170 glVertex3f(1.0, 1.0, -1.0)
171 glVertex3f(1.0, 1.0, 1.0)
172 glVertex3f(1.0, -1.0, 1.0)
173 glVertex3f(1.0, -1.0, -1.0)
177 resolution_millimeters = 1
178 gridded_area_size = 100
184 glColor3f(1.0, 1.0, 1.0)
186 glVertex3f(gridded_area_size, 0, 0)
187 glVertex3f(-gridded_area_size, 0, 0)
188 glVertex3f(0, gridded_area_size, 0)
189 glVertex3f(0, -gridded_area_size, 0)
191 num_of_lines = int(gridded_area_size / resolution_millimeters)
193 for i
in range(num_of_lines):
194 glVertex3f(resolution_millimeters * i, -gridded_area_size, 0)
195 glVertex3f(resolution_millimeters * i, gridded_area_size, 0)
196 glVertex3f(gridded_area_size, resolution_millimeters * i, 0)
197 glVertex3f(-gridded_area_size, resolution_millimeters * i, 0)
199 glVertex3f(resolution_millimeters * (-i), -gridded_area_size, 0)
200 glVertex3f(resolution_millimeters * (-i), gridded_area_size, 0)
201 glVertex3f(gridded_area_size, resolution_millimeters * (-i), 0)
202 glVertex3f(-gridded_area_size, resolution_millimeters * (-i), 0)
211 glColor3f(1.0, 0.0, 0.0)
212 glVertex3f(0.0, 0.0, 0.0)
213 glVertex3f(1.0, 0.0, 0.0)
215 glColor3f(0.0, 1.0, 0.0)
216 glVertex3f(0.0, 0.0, 0.0)
217 glVertex3f(0.0, 1.0, 0.0)
219 glColor3f(0.0, 0.0, 1.0)
220 glVertex3f(0.0, 0.0, 0.0)
221 glVertex3f(0.0, 0.0, 1.0)
226 if event.button() == Qt.RightButton:
229 menu.addAction(action)
231 menu.exec_(self.
_gl_view.mapToGlobal(event.pos()))
233 @Slot(
'QDragEnterEvent*')
235 if event.mimeData().hasText():
236 topic_name = str(event.mimeData().text())
237 if len(topic_name) == 0:
238 qWarning(
'PoseViewWidget.dragEnterEvent(): event.mimeData() text is empty')
241 if not hasattr(event.source(),
'selectedItems')
or len(event.source().selectedItems()) == 0:
242 qWarning(
'PoseViewWidget.dragEnterEvent(): event.source() has no attribute selectedItems or length of selectedItems is 0')
244 item = event.source().selectedItems()[0]
245 topic_name = item.data(0, Qt.UserRole)
247 if topic_name
is None:
248 qWarning(
'PoseViewWidget.dragEnterEvent(): selectedItem has no UserRole data with a topic name')
252 msg_class, self.
_topic_name, _ = get_topic_class(topic_name)
253 if msg_class
is None:
254 qWarning(
'PoseViewWidget.dragEnterEvent(): No message class was found for topic "%s".' % topic_name)
258 quaternion_slot_path, point_slot_path = self.
_get_slot_paths(msg_class)
260 if quaternion_slot_path
is None and point_slot_path
is None:
261 qWarning(
'PoseViewWidget.dragEnterEvent(): No Pose, Quaternion or Point data was found outside of arrays in "%s" on topic "%s".'
262 % (msg_class._type, topic_name))
265 event.acceptProposedAction()
269 if event.mimeData().hasText():
270 topic_name = str(event.mimeData().text())
272 dropped_item = event.source().selectedItems()[0]
273 topic_name = str(dropped_item.data(0, Qt.UserRole))
284 path = path.split(
'/')
292 pose_slot_paths = find_slots_by_type_bfs(msg_class, Pose)
293 for path
in pose_slot_paths:
296 path = PoseViewWidget._make_path_list_from_path_string(pose_slot_paths[0])
297 return path + [
'orientation'], path + [
'position']
300 quaternion_slot_paths = find_slots_by_type_bfs(msg_class, Quaternion)
301 for path
in quaternion_slot_paths:
303 quaternion_slot_path = PoseViewWidget._make_path_list_from_path_string(path)
306 quaternion_slot_path =
None
308 point_slot_paths = find_slots_by_type_bfs(msg_class, Point)
309 for path
in point_slot_paths:
311 point_slot_path = PoseViewWidget._make_path_list_from_path_string(path)
314 point_slot_path =
None
316 return quaternion_slot_path, point_slot_path
320 msg_class, self.
_topic_name, _ = get_topic_class(topic_name)
321 quaternion_slot_path, point_slot_path = self.
_get_slot_paths(msg_class)
327 callback_args=(quaternion_slot_path, point_slot_path)
331 quaternion_slot_path = slot_paths[0]
332 point_slot_path = slot_paths[1]
334 if quaternion_slot_path
is None:
335 self.
_orientation = quaternion_about_axis(0.0, (1.0, 0.0, 0.0))
337 orientation = message
338 for slot_name
in quaternion_slot_path:
339 orientation = getattr(orientation, slot_name)
340 self.
_orientation = (orientation.x, orientation.y, orientation.z, orientation.w)
342 if point_slot_path
is None:
347 for slot_name
in point_slot_path:
348 position = getattr(position, slot_name)
349 self.
_position = (position.x, position.y, position.z)