nav_view.py
Go to the documentation of this file.
1 # Software License Agreement (BSD License)
2 #
3 # Copyright (c) 2012, Willow Garage, Inc.
4 # All rights reserved.
5 #
6 # Redistribution and use in source and binary forms, with or without
7 # modification, are permitted provided that the following conditions
8 # are met:
9 #
10 # * Redistributions of source code must retain the above copyright
11 # notice, this list of conditions and the following disclaimer.
12 # * Redistributions in binary form must reproduce the above
13 # copyright notice, this list of conditions and the following
14 # disclaimer in the documentation and/or other materials provided
15 # with the distribution.
16 # * Neither the name of Willow Garage, Inc. nor the names of its
17 # contributors may be used to endorse or promote products derived
18 # from this software without specific prior written permission.
19 #
20 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
21 # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
22 # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
23 # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
24 # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
25 # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
26 # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
27 # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
28 # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
29 # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
30 # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
31 # POSSIBILITY OF SUCH DAMAGE.
32 
33 import rospy
34 import tf
35 from tf.transformations import quaternion_from_euler
36 
37 import numpy
38 import random
39 from math import sqrt, atan, pi, degrees
40 
41 from nav_msgs.msg import OccupancyGrid, Path
42 from geometry_msgs.msg import PolygonStamped, PointStamped, PoseWithCovarianceStamped, PoseStamped
43 
44 from python_qt_binding.QtCore import Signal, Slot, QPointF, qWarning, Qt
45 from python_qt_binding.QtGui import QPixmap, QImage, QPainterPath, QPen, QPolygonF, QColor, qRgb
46 from python_qt_binding.QtWidgets import QWidget, QGraphicsView, QGraphicsScene, QVBoxLayout, QHBoxLayout, QPushButton
47 
48 from rqt_py_common.topic_helpers import get_field_type
49 
50 def accepted_topic(topic):
51  msg_types = [OccupancyGrid, Path, PolygonStamped, PointStamped]
52  msg_type, array = get_field_type(topic)
53 
54  if not array and msg_type in msg_types:
55  return True
56  else:
57  return False
58 
59 
60 class PathInfo(object):
61  def __init__(self, name=None):
62  self.color = None
63  self.sub = None
64  self.cb = None
65  self.path = None
66  self.item = None
67 
68  self.name = name
69 
70 
71 class NavViewWidget(QWidget):
72 
73  def __init__(self, map_topic='/map',
74  paths=['/move_base/NavFn/plan', '/move_base/TrajectoryPlannerROS/local_plan'],
75  polygons=['/move_base/local_costmap/robot_footprint']):
76  super(NavViewWidget, self).__init__()
77  self._layout = QVBoxLayout()
78  self._button_layout = QHBoxLayout()
79 
80  self.setAcceptDrops(True)
81  self.setWindowTitle('Navigation Viewer')
82 
83  self.paths = paths
84  self.polygons = polygons
85  self.map = map_topic
87 
88  self._nav_view = NavView(map_topic, paths, polygons, tf = self._tf, parent = self)
89 
90  self._set_pose = QPushButton('Set Pose')
91  self._set_pose.clicked.connect(self._nav_view.pose_mode)
92  self._set_goal = QPushButton('Set Goal')
93  self._set_goal.clicked.connect(self._nav_view.goal_mode)
94 
95  self._button_layout.addWidget(self._set_pose)
96  self._button_layout.addWidget(self._set_goal)
97 
98  self._layout.addLayout(self._button_layout)
99 
100  self._layout.addWidget(self._nav_view)
101 
102  self.setLayout(self._layout)
103 
104  def dragEnterEvent(self, e):
105  if not e.mimeData().hasText():
106  if not hasattr(e.source(), 'selectedItems') or len(e.source().selectedItems()) == 0:
107  qWarning('NavView.dragEnterEvent(): not hasattr(event.source(), selectedItems) or len(event.source().selectedItems()) == 0')
108  return
109  item = e.source().selectedItems()[0]
110  topic_name = item.data(0, Qt.UserRole)
111  if topic_name == None:
112  qWarning('NavView.dragEnterEvent(): not hasattr(item, ros_topic_name_)')
113  return
114 
115  else:
116  topic_name = str(e.mimeData().text())
117 
118  if accepted_topic(topic_name):
119  e.accept()
120  e.acceptProposedAction()
121 
122  def dropEvent(self, e):
123  if e.mimeData().hasText():
124  topic_name = str(e.mimeData().text())
125  else:
126  droped_item = e.source().selectedItems()[0]
127  topic_name = str(droped_item.data(0, Qt.UserRole))
128 
129  topic_type, array = get_field_type(topic_name)
130  if not array:
131  if topic_type is OccupancyGrid:
132  self.map = topic_name
133 
134  # Swap out the nav view for one with the new topics
135  self._nav_view.close()
136  self._nav_view = NavView(self.map, self.paths, self.polygons, self._tf, self)
137  self._layout.addWidget(self._nav_view)
138  elif topic_type is Path:
139  self.paths.append(topic_name)
140  self._nav_view.add_path(topic_name)
141  elif topic_type is PolygonStamped:
142  self.polygons.append(topic_name)
143  self._nav_view.add_polygon(topic_name)
144 
145  def save_settings(self, plugin_settings, instance_settings):
146  self._nav_view.save_settings(plugin_settings, instance_settings)
147 
148  def restore_settings(self, plugin_settings, instance_settings):
149  self._nav_view.restore_settings(plugin_settings, instance_settings)
150 
151 
152 class NavView(QGraphicsView):
153  map_changed = Signal()
154  path_changed = Signal(str)
155  polygon_changed = Signal(str)
156 
157  def __init__(self, map_topic='/map',
158  paths=['/move_base/SBPLLatticePlanner/plan', '/move_base/TrajectoryPlannerROS/local_plan'],
159  polygons=['/move_base/local_costmap/robot_footprint'], tf=None, parent=None):
160  super(NavView, self).__init__()
161  self._parent = parent
162 
163  self._pose_mode = False
164  self._goal_mode = False
165  self.last_path = None
166 
167 
168  self.map_changed.connect(self._update)
169  self.destroyed.connect(self.close)
170 
171  #ScrollHandDrag
172  self.setDragMode(QGraphicsView.ScrollHandDrag)
173 
174  self._map = None
175  self._map_item = None
176 
177  self.w = 0
178  self.h = 0
179 
180  self._paths = {}
181  self._polygons = {}
182  self.path_changed.connect(self._update_path)
183  self.polygon_changed.connect(self._update_polygon)
184 
185  self._colors = [(238, 34, 116), (68, 134, 252), (236, 228, 46), (102, 224, 18), (242, 156, 6), (240, 64, 10), (196, 30, 250)]
186 
187  self._scene = QGraphicsScene()
188 
189  if tf is None:
191  else:
192  self._tf = tf
193  self.map_sub = rospy.Subscriber('/map', OccupancyGrid, self.map_cb)
194 
195  for path in paths:
196  self.add_path(path)
197 
198  for poly in polygons:
199  self.add_polygon(poly)
200 
201  try:
202  self._pose_pub = rospy.Publisher('/initialpose', PoseWithCovarianceStamped, queue_size=100)
203  self._goal_pub = rospy.Publisher('/move_base_simple/goal', PoseStamped, queue_size=100)
204  except TypeError:
205  self._pose_pub = rospy.Publisher('/initialpose', PoseWithCovarianceStamped)
206  self._goal_pub = rospy.Publisher('/move_base_simple/goal', PoseStamped)
207 
208  self.setScene(self._scene)
209 
210  def add_dragdrop(self, item):
211  # Add drag and drop functionality to all the items in the view
212  def c(x, e):
213  self.dragEnterEvent(e)
214  def d(x, e):
215  self.dropEvent(e)
216  item.setAcceptDrops(True)
217  item.dragEnterEvent = c
218  item.dropEvent = d
219 
220  def dragEnterEvent(self, e):
221  if self._parent:
222  self._parent.dragEnterEvent(e)
223 
224  def dropEvent(self, e):
225  if self._parent:
226  self._parent.dropEvent(e)
227 
228  def wheelEvent(self, event):
229  event.ignore()
230  try:
231  delta = event.angleDelta().y()
232  except AttributeError:
233  delta = event.delta()
234  if delta > 0:
235  self.scale(1.15, 1.15)
236  else:
237  self.scale(0.85, 0.85)
238 
239  def map_cb(self, msg):
240  self.resolution = msg.info.resolution
241  self.w = msg.info.width
242  self.h = msg.info.height
243 
244  a = numpy.array(msg.data, dtype=numpy.uint8, copy=False, order='C')
245  a = a.reshape((self.h, self.w))
246  if self.w % 4:
247  e = numpy.empty((self.h, 4 - self.w % 4), dtype=a.dtype, order='C')
248  a = numpy.append(a, e, axis=1)
249  image = QImage(a.reshape((a.shape[0] * a.shape[1])), self.w, self.h, QImage.Format_Indexed8)
250 
251  for i in reversed(range(101)):
252  image.setColor(100 - i, qRgb(i* 2.55, i * 2.55, i * 2.55))
253  image.setColor(101, qRgb(255, 0, 0)) # not used indices
254  image.setColor(255, qRgb(200, 200, 200)) # color for unknown value -1
255  self._map = image
256  self.setSceneRect(0, 0, self.w, self.h)
257  self.map_changed.emit()
258 
259  def add_path(self, name):
260  path = PathInfo(name)
261 
262  def c(msg):
263  if not self._map:
264  return
265 
266  pp = QPainterPath()
267 
268  # Transform everything in to the map frame
269  if not (msg.header.frame_id == '/map' or msg.header.frame_id == ''):
270  try:
271  self._tf.waitForTransform(msg.header.frame_id, '/map', rospy.Time(), rospy.Duration(10))
272  data = [self._tf.transformPose('/map', pose) for pose in msg.poses]
273  except tf.Exception:
274  rospy.logerr("TF Error")
275  data = []
276  else:
277  data = msg.poses
278 
279  if len(data) > 0:
280  start = data[0].pose.position
281  pp.moveTo(start.x / self.resolution, start.y / self.resolution)
282 
283  for pose in data:
284  pt = pose.pose.position
285  pp.lineTo(pt.x / self.resolution, pt.y / self.resolution)
286 
287  path.path = pp
288  self.path_changed.emit(name)
289 
290  path.color = random.choice(self._colors)
291  self._colors.remove(path.color)
292 
293  path.cb = c
294  path.sub = rospy.Subscriber(path.name, Path, path.cb)
295 
296  self._paths[name] = path
297 
298  def add_polygon(self, name):
299  poly = PathInfo(name)
300 
301  def c(msg):
302  if not self._map:
303  return
304 
305  if not (msg.header.frame_id == '/map' or msg.header.frame_id == ''):
306  try:
307  self._tf.waitForTransform(msg.header.frame_id, '/map', rospy.Time(), rospy.Duration(10))
308  points_stamped = []
309  for pt in msg.polygon.points:
310  ps = PointStamped()
311  ps.header.frame_id = msg.header.frame_id
312  ps.point.x = pt.x
313  ps.point.y = pt.y
314 
315  points_stamped.append(ps)
316 
317  trans_pts = [self._tf.transformPoint('/map', pt).point for pt in points_stamped]
318  except tf.Exception:
319  rospy.logerr("TF Error")
320  trans_pts = []
321  else:
322  trans_pts = [pt for pt in msg.polygon.points]
323 
324  if len(trans_pts) > 0:
325  pts = [QPointF(pt.x / self.resolution, pt.y / self.resolution) for pt in trans_pts]
326 
327  close = trans_pts[0]
328  pts.append(QPointF(close.x / self.resolution, close.y / self.resolution))
329  poly.path = QPolygonF(pts)
330 
331  self.polygon_changed.emit(name)
332 
333  poly.color = random.choice(self._colors)
334  self._colors.remove(poly.color)
335 
336  poly.cb = c
337  poly.sub = rospy.Subscriber(poly.name, PolygonStamped, poly.cb)
338 
339  self._polygons[name] = poly
340 
341  def pose_mode(self):
342  if not self._pose_mode:
343  self._pose_mode = True
344  self._goal_mode = False
345  self.setDragMode(QGraphicsView.NoDrag)
346  elif self._pose_mode:
347  self._pose_mode = False
348  self.setDragMode(QGraphicsView.ScrollHandDrag)
349 
350  def goal_mode(self):
351  if not self._goal_mode:
352  self._goal_mode = True
353  self._pose_mode = False
354  self.setDragMode(QGraphicsView.NoDrag)
355  elif self._goal_mode:
356  self._goal_mode = False
357  self.setDragMode(QGraphicsView.ScrollHandDrag)
358 
359  def draw_position(self, e, mirror=True):
360  p = self.mapToScene(e.x(), e.y())
361  v = (p.x() - self.drag_start[0], p.y() - self.drag_start[1])
362  mag = sqrt(pow(v[0], 2) + pow(v[1], 2))
363  u = (v[0]/mag, v[1]/mag)
364 
365  res = (u[0]*20, u[1]*20)
366  path = self._scene.addLine(self.drag_start[0], self.drag_start[1],
367  self.drag_start[0] + res[0], self.drag_start[1] + res[1])
368 
369  if self.last_path:
370  self._scene.removeItem(self.last_path)
371  self.last_path = None
372  self.last_path = path
373 
374  if mirror:
375  # Mirror point over x axis
376  x = ((self.w / 2) - self.drag_start[0]) + (self.w /2)
377  else:
378  x = self.drag_start[0]
379 
380  map_p = [x * self.resolution, self.drag_start[1] * self.resolution]
381 
382  angle = atan(u[1] / u[0])
383  quat = quaternion_from_euler(0, 0, degrees(angle))
384 
385  return map_p, quat
386 
387  def mousePressEvent(self, e):
388  if self._goal_mode or self._pose_mode:
389  p = self.mapToScene(e.x(), e.y())
390  self.drag_start = (p.x(), p.y())
391  else:
392  super(NavView, self).mousePressEvent(e)
393 
394  def mouseReleaseEvent(self, e):
395  if self._goal_mode:
396  self._goal_mode = False
397  map_p, quat = self.draw_position(e)
398 
399  msg = PoseStamped()
400  msg.header.frame_id = '/map'
401  msg.header.stamp = rospy.Time.now()
402 
403  msg.pose.position.x = map_p[0]
404  msg.pose.position.y = map_p[1]
405  msg.pose.orientation.w = quat[0]
406  msg.pose.orientation.z = quat[3]
407 
408  self._goal_pub.publish(msg)
409 
410  elif self._pose_mode:
411  self._pose_mode = False
412  map_p, quat = self.draw_position(e)
413 
414  msg = PoseWithCovarianceStamped()
415  msg.header.frame_id = '/map'
416  msg.header.stamp = rospy.Time.now()
417 
418  #TODO: Is it ok to just ignore the covariance matrix here?
419  msg.pose.pose.orientation.w = quat[0]
420  msg.pose.pose.orientation.z = quat[3]
421  msg.pose.pose.position.x = map_p[0]
422  msg.pose.pose.position.y = map_p[1]
423 
424  self._pose_pub.publish(msg)
425 
426  # Clean up the path
427  if self.last_path:
428  self._scene.removeItem(self.last_path)
429  self.last_path = None
430 
431  #def mouseMoveEvent(self, e):
432  # if e.buttons() == Qt.LeftButton and (self._pose_mode or self._goal_mode):
433  # map_p, quat = self.draw_position(e)
434 
435  def close(self):
436  if self.map_sub:
437  self.map_sub.unregister()
438  for p in self._paths.values():
439  if p.sub:
440  p.sub.unregister()
441 
442  for p in self._polygons.values():
443  if p.sub:
444  p.sub.unregister()
445 
446  super(NavView, self).close()
447 
448  def _update(self):
449  if self._map_item:
450  self._scene.removeItem(self._map_item)
451 
452  pixmap = QPixmap.fromImage(self._map)
453  self._map_item = self._scene.addPixmap(pixmap)
454 
455  # Everything must be mirrored
456  self._mirror(self._map_item)
457 
458  # Add drag and drop functionality
459  self.add_dragdrop(self._map_item)
460 
461  self.centerOn(self._map_item)
462  self.show()
463 
464  def _update_path(self, name):
465  old_item = None
466  if name in self._paths.keys():
467  old_item = self._paths[name].item
468 
469  self._paths[name].item = self._scene.addPath(self._paths[name].path, pen=QPen(QColor(*self._paths[name].color)))
470 
471  # Everything must be mirrored
472  self._mirror(self._paths[name].item)
473 
474  if old_item:
475  self._scene.removeItem(old_item)
476 
477  def _update_polygon(self, name):
478  old_item = None
479  if name in self._polygons.keys():
480  old_item = self._polygons[name].item
481 
482  self._polygons[name].item = self._scene.addPolygon(self._polygons[name].path, pen=QPen(QColor(*self._polygons[name].color)))
483 
484  # Everything must be mirrored
485  self._mirror(self._polygons[name].item)
486 
487  if old_item:
488  self._scene.removeItem(old_item)
489 
490  def _mirror(self, item):
491  item.scale(-1, 1)
492  item.translate(-self.w, 0)
493 
494  def save_settings(self, plugin_settings, instance_settings):
495  # TODO add any settings to be saved
496  pass
497 
498  def restore_settings(self, plugin_settings, instance_settings):
499  # TODO add any settings to be restored
500  pass
d
Definition: setup.py:6
def add_path(self, name)
Definition: nav_view.py:259
def restore_settings(self, plugin_settings, instance_settings)
Definition: nav_view.py:498
def draw_position(self, e, mirror=True)
Definition: nav_view.py:359
def add_polygon(self, name)
Definition: nav_view.py:298
def mousePressEvent(self, e)
Definition: nav_view.py:387
def save_settings(self, plugin_settings, instance_settings)
Definition: nav_view.py:494
def wheelEvent(self, event)
Definition: nav_view.py:228
def restore_settings(self, plugin_settings, instance_settings)
Definition: nav_view.py:148
def add_dragdrop(self, item)
Definition: nav_view.py:210
def save_settings(self, plugin_settings, instance_settings)
Definition: nav_view.py:145
def _mirror(self, item)
Definition: nav_view.py:490
def __init__(self, map_topic='/map', paths=['/move_base/NavFn/plan', move_base, TrajectoryPlannerROS, local_plan, polygons=['/move_base/local_costmap/robot_footprint'])
Definition: nav_view.py:75
def __init__(self, name=None)
Definition: nav_view.py:61
def accepted_topic(topic)
Definition: nav_view.py:50
def _update_polygon(self, name)
Definition: nav_view.py:477
def __init__(self, map_topic='/map', paths=['/move_base/SBPLLatticePlanner/plan', move_base, TrajectoryPlannerROS, local_plan, polygons=['/move_base/local_costmap/robot_footprint'], tf=None, parent=None)
Definition: nav_view.py:159
def mouseReleaseEvent(self, e)
Definition: nav_view.py:394
def _update_path(self, name)
Definition: nav_view.py:464


rqt_nav_view
Author(s): Ze'ev Klapow
autogenerated on Wed Jun 5 2019 19:53:01