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
00032
00033 import rospy
00034 import tf
00035 from tf.transformations import quaternion_from_euler
00036
00037 import numpy
00038 import random
00039 from math import sqrt, atan, pi, degrees
00040
00041 from nav_msgs.msg import OccupancyGrid, Path
00042 from geometry_msgs.msg import PolygonStamped, PointStamped, PoseWithCovarianceStamped, PoseStamped
00043
00044 from python_qt_binding.QtCore import Signal, Slot, QPointF, qWarning, Qt
00045 from python_qt_binding.QtGui import QPixmap, QImage, QPainterPath, QPen, QPolygonF, QColor, qRgb
00046 from python_qt_binding.QtWidgets import QWidget, QGraphicsView, QGraphicsScene, QVBoxLayout, QHBoxLayout, QPushButton
00047
00048 from rqt_py_common.topic_helpers import get_field_type
00049
00050 def accepted_topic(topic):
00051 msg_types = [OccupancyGrid, Path, PolygonStamped, PointStamped]
00052 msg_type, array = get_field_type(topic)
00053
00054 if not array and msg_type in msg_types:
00055 return True
00056 else:
00057 return False
00058
00059
00060 class PathInfo(object):
00061 def __init__(self, name=None):
00062 self.color = None
00063 self.sub = None
00064 self.cb = None
00065 self.path = None
00066 self.item = None
00067
00068 self.name = name
00069
00070
00071 class NavViewWidget(QWidget):
00072
00073 def __init__(self, map_topic='/map',
00074 paths=['/move_base/NavFn/plan', '/move_base/TrajectoryPlannerROS/local_plan'],
00075 polygons=['/move_base/local_costmap/robot_footprint']):
00076 super(NavViewWidget, self).__init__()
00077 self._layout = QVBoxLayout()
00078 self._button_layout = QHBoxLayout()
00079
00080 self.setAcceptDrops(True)
00081 self.setWindowTitle('Navigation Viewer')
00082
00083 self.paths = paths
00084 self.polygons = polygons
00085 self.map = map_topic
00086 self._tf = tf.TransformListener()
00087
00088 self._nav_view = NavView(map_topic, paths, polygons, tf = self._tf, parent = self)
00089
00090 self._set_pose = QPushButton('Set Pose')
00091 self._set_pose.clicked.connect(self._nav_view.pose_mode)
00092 self._set_goal = QPushButton('Set Goal')
00093 self._set_goal.clicked.connect(self._nav_view.goal_mode)
00094
00095 self._button_layout.addWidget(self._set_pose)
00096 self._button_layout.addWidget(self._set_goal)
00097
00098 self._layout.addLayout(self._button_layout)
00099
00100 self._layout.addWidget(self._nav_view)
00101
00102 self.setLayout(self._layout)
00103
00104 def dragEnterEvent(self, e):
00105 if not e.mimeData().hasText():
00106 if not hasattr(e.source(), 'selectedItems') or len(e.source().selectedItems()) == 0:
00107 qWarning('NavView.dragEnterEvent(): not hasattr(event.source(), selectedItems) or len(event.source().selectedItems()) == 0')
00108 return
00109 item = e.source().selectedItems()[0]
00110 topic_name = item.data(0, Qt.UserRole)
00111 if topic_name == None:
00112 qWarning('NavView.dragEnterEvent(): not hasattr(item, ros_topic_name_)')
00113 return
00114
00115 else:
00116 topic_name = str(e.mimeData().text())
00117
00118 if accepted_topic(topic_name):
00119 e.accept()
00120 e.acceptProposedAction()
00121
00122 def dropEvent(self, e):
00123 if e.mimeData().hasText():
00124 topic_name = str(e.mimeData().text())
00125 else:
00126 droped_item = e.source().selectedItems()[0]
00127 topic_name = str(droped_item.data(0, Qt.UserRole))
00128
00129 topic_type, array = get_field_type(topic_name)
00130 if not array:
00131 if topic_type is OccupancyGrid:
00132 self.map = topic_name
00133
00134
00135 self._nav_view.close()
00136 self._nav_view = NavView(self.map, self.paths, self.polygons, self._tf, self)
00137 self._layout.addWidget(self._nav_view)
00138 elif topic_type is Path:
00139 self.paths.append(topic_name)
00140 self._nav_view.add_path(topic_name)
00141 elif topic_type is PolygonStamped:
00142 self.polygons.append(topic_name)
00143 self._nav_view.add_polygon(topic_name)
00144
00145 def save_settings(self, plugin_settings, instance_settings):
00146 self._nav_view.save_settings(plugin_settings, instance_settings)
00147
00148 def restore_settings(self, plugin_settings, instance_settings):
00149 self._nav_view.restore_settings(plugin_settings, instance_settings)
00150
00151
00152 class NavView(QGraphicsView):
00153 map_changed = Signal()
00154 path_changed = Signal(str)
00155 polygon_changed = Signal(str)
00156
00157 def __init__(self, map_topic='/map',
00158 paths=['/move_base/SBPLLatticePlanner/plan', '/move_base/TrajectoryPlannerROS/local_plan'],
00159 polygons=['/move_base/local_costmap/robot_footprint'], tf=None, parent=None):
00160 super(NavView, self).__init__()
00161 self._parent = parent
00162
00163 self._pose_mode = False
00164 self._goal_mode = False
00165 self.last_path = None
00166
00167
00168 self.map_changed.connect(self._update)
00169 self.destroyed.connect(self.close)
00170
00171
00172 self.setDragMode(QGraphicsView.ScrollHandDrag)
00173
00174 self._map = None
00175 self._map_item = None
00176
00177 self.w = 0
00178 self.h = 0
00179
00180 self._paths = {}
00181 self._polygons = {}
00182 self.path_changed.connect(self._update_path)
00183 self.polygon_changed.connect(self._update_polygon)
00184
00185 self._colors = [(238, 34, 116), (68, 134, 252), (236, 228, 46), (102, 224, 18), (242, 156, 6), (240, 64, 10), (196, 30, 250)]
00186
00187 self._scene = QGraphicsScene()
00188
00189 if tf is None:
00190 self._tf = tf.TransformListener()
00191 else:
00192 self._tf = tf
00193 self.map_sub = rospy.Subscriber('/map', OccupancyGrid, self.map_cb)
00194
00195 for path in paths:
00196 self.add_path(path)
00197
00198 for poly in polygons:
00199 self.add_polygon(poly)
00200
00201 try:
00202 self._pose_pub = rospy.Publisher('/initialpose', PoseWithCovarianceStamped, queue_size=100)
00203 self._goal_pub = rospy.Publisher('/move_base_simple/goal', PoseStamped, queue_size=100)
00204 except TypeError:
00205 self._pose_pub = rospy.Publisher('/initialpose', PoseWithCovarianceStamped)
00206 self._goal_pub = rospy.Publisher('/move_base_simple/goal', PoseStamped)
00207
00208 self.setScene(self._scene)
00209
00210 def add_dragdrop(self, item):
00211
00212 def c(x, e):
00213 self.dragEnterEvent(e)
00214 def d(x, e):
00215 self.dropEvent(e)
00216 item.setAcceptDrops(True)
00217 item.dragEnterEvent = c
00218 item.dropEvent = d
00219
00220 def dragEnterEvent(self, e):
00221 if self._parent:
00222 self._parent.dragEnterEvent(e)
00223
00224 def dropEvent(self, e):
00225 if self._parent:
00226 self._parent.dropEvent(e)
00227
00228 def wheelEvent(self, event):
00229 event.ignore()
00230 try:
00231 delta = event.angleDelta().y()
00232 except AttributeError:
00233 delta = event.delta()
00234 if delta > 0:
00235 self.scale(1.15, 1.15)
00236 else:
00237 self.scale(0.85, 0.85)
00238
00239 def map_cb(self, msg):
00240 self.resolution = msg.info.resolution
00241 self.w = msg.info.width
00242 self.h = msg.info.height
00243
00244 a = numpy.array(msg.data, dtype=numpy.uint8, copy=False, order='C')
00245 a = a.reshape((self.h, self.w))
00246 if self.w % 4:
00247 e = numpy.empty((self.h, 4 - self.w % 4), dtype=a.dtype, order='C')
00248 a = numpy.append(a, e, axis=1)
00249 image = QImage(a.reshape((a.shape[0] * a.shape[1])), self.w, self.h, QImage.Format_Indexed8)
00250
00251 for i in reversed(range(101)):
00252 image.setColor(100 - i, qRgb(i* 2.55, i * 2.55, i * 2.55))
00253 image.setColor(101, qRgb(255, 0, 0))
00254 image.setColor(255, qRgb(200, 200, 200))
00255 self._map = image
00256 self.setSceneRect(0, 0, self.w, self.h)
00257 self.map_changed.emit()
00258
00259 def add_path(self, name):
00260 path = PathInfo(name)
00261
00262 def c(msg):
00263 if not self._map:
00264 return
00265
00266 pp = QPainterPath()
00267
00268
00269 if not (msg.header.frame_id == '/map' or msg.header.frame_id == ''):
00270 try:
00271 self._tf.waitForTransform(msg.header.frame_id, '/map', rospy.Time(), rospy.Duration(10))
00272 data = [self._tf.transformPose('/map', pose) for pose in msg.poses]
00273 except tf.Exception:
00274 rospy.logerr("TF Error")
00275 data = []
00276 else:
00277 data = msg.poses
00278
00279 if len(data) > 0:
00280 start = data[0].pose.position
00281 pp.moveTo(start.x / self.resolution, start.y / self.resolution)
00282
00283 for pose in data:
00284 pt = pose.pose.position
00285 pp.lineTo(pt.x / self.resolution, pt.y / self.resolution)
00286
00287 path.path = pp
00288 self.path_changed.emit(name)
00289
00290 path.color = random.choice(self._colors)
00291 self._colors.remove(path.color)
00292
00293 path.cb = c
00294 path.sub = rospy.Subscriber(path.name, Path, path.cb)
00295
00296 self._paths[name] = path
00297
00298 def add_polygon(self, name):
00299 poly = PathInfo(name)
00300
00301 def c(msg):
00302 if not self._map:
00303 return
00304
00305 if not (msg.header.frame_id == '/map' or msg.header.frame_id == ''):
00306 try:
00307 self._tf.waitForTransform(msg.header.frame_id, '/map', rospy.Time(), rospy.Duration(10))
00308 points_stamped = []
00309 for pt in msg.polygon.points:
00310 ps = PointStamped()
00311 ps.header.frame_id = msg.header.frame_id
00312 ps.point.x = pt.x
00313 ps.point.y = pt.y
00314
00315 points_stamped.append(ps)
00316
00317 trans_pts = [self._tf.transformPoint('/map', pt).point for pt in points_stamped]
00318 except tf.Exception:
00319 rospy.logerr("TF Error")
00320 trans_pts = []
00321 else:
00322 trans_pts = [pt for pt in msg.polygon.points]
00323
00324 if len(trans_pts) > 0:
00325 pts = [QPointF(pt.x / self.resolution, pt.y / self.resolution) for pt in trans_pts]
00326
00327 close = trans_pts[0]
00328 pts.append(QPointF(close.x / self.resolution, close.y / self.resolution))
00329 poly.path = QPolygonF(pts)
00330
00331 self.polygon_changed.emit(name)
00332
00333 poly.color = random.choice(self._colors)
00334 self._colors.remove(poly.color)
00335
00336 poly.cb = c
00337 poly.sub = rospy.Subscriber(poly.name, PolygonStamped, poly.cb)
00338
00339 self._polygons[name] = poly
00340
00341 def pose_mode(self):
00342 if not self._pose_mode:
00343 self._pose_mode = True
00344 self._goal_mode = False
00345 self.setDragMode(QGraphicsView.NoDrag)
00346 elif self._pose_mode:
00347 self._pose_mode = False
00348 self.setDragMode(QGraphicsView.ScrollHandDrag)
00349
00350 def goal_mode(self):
00351 if not self._goal_mode:
00352 self._goal_mode = True
00353 self._pose_mode = False
00354 self.setDragMode(QGraphicsView.NoDrag)
00355 elif self._goal_mode:
00356 self._goal_mode = False
00357 self.setDragMode(QGraphicsView.ScrollHandDrag)
00358
00359 def draw_position(self, e, mirror=True):
00360 p = self.mapToScene(e.x(), e.y())
00361 v = (p.x() - self.drag_start[0], p.y() - self.drag_start[1])
00362 mag = sqrt(pow(v[0], 2) + pow(v[1], 2))
00363 u = (v[0]/mag, v[1]/mag)
00364
00365 res = (u[0]*20, u[1]*20)
00366 path = self._scene.addLine(self.drag_start[0], self.drag_start[1],
00367 self.drag_start[0] + res[0], self.drag_start[1] + res[1])
00368
00369 if self.last_path:
00370 self._scene.removeItem(self.last_path)
00371 self.last_path = None
00372 self.last_path = path
00373
00374 if mirror:
00375
00376 x = ((self.w / 2) - self.drag_start[0]) + (self.w /2)
00377 else:
00378 x = self.drag_start[0]
00379
00380 map_p = [x * self.resolution, self.drag_start[1] * self.resolution]
00381
00382 angle = atan(u[1] / u[0])
00383 quat = quaternion_from_euler(0, 0, degrees(angle))
00384
00385 return map_p, quat
00386
00387 def mousePressEvent(self, e):
00388 if self._goal_mode or self._pose_mode:
00389 p = self.mapToScene(e.x(), e.y())
00390 self.drag_start = (p.x(), p.y())
00391 else:
00392 super(NavView, self).mousePressEvent(e)
00393
00394 def mouseReleaseEvent(self, e):
00395 if self._goal_mode:
00396 self._goal_mode = False
00397 map_p, quat = self.draw_position(e)
00398
00399 msg = PoseStamped()
00400 msg.header.frame_id = '/map'
00401 msg.header.stamp = rospy.Time.now()
00402
00403 msg.pose.position.x = map_p[0]
00404 msg.pose.position.y = map_p[1]
00405 msg.pose.orientation.w = quat[0]
00406 msg.pose.orientation.z = quat[3]
00407
00408 self._goal_pub.publish(msg)
00409
00410 elif self._pose_mode:
00411 self._pose_mode = False
00412 map_p, quat = self.draw_position(e)
00413
00414 msg = PoseWithCovarianceStamped()
00415 msg.header.frame_id = '/map'
00416 msg.header.stamp = rospy.Time.now()
00417
00418
00419 msg.pose.pose.orientation.w = quat[0]
00420 msg.pose.pose.orientation.z = quat[3]
00421 msg.pose.pose.position.x = map_p[0]
00422 msg.pose.pose.position.y = map_p[1]
00423
00424 self._pose_pub.publish(msg)
00425
00426
00427 if self.last_path:
00428 self._scene.removeItem(self.last_path)
00429 self.last_path = None
00430
00431
00432
00433
00434
00435 def close(self):
00436 if self.map_sub:
00437 self.map_sub.unregister()
00438 for p in self._paths.values():
00439 if p.sub:
00440 p.sub.unregister()
00441
00442 for p in self._polygons.values():
00443 if p.sub:
00444 p.sub.unregister()
00445
00446 super(NavView, self).close()
00447
00448 def _update(self):
00449 if self._map_item:
00450 self._scene.removeItem(self._map_item)
00451
00452 pixmap = QPixmap.fromImage(self._map)
00453 self._map_item = self._scene.addPixmap(pixmap)
00454
00455
00456 self._mirror(self._map_item)
00457
00458
00459 self.add_dragdrop(self._map_item)
00460
00461 self.centerOn(self._map_item)
00462 self.show()
00463
00464 def _update_path(self, name):
00465 old_item = None
00466 if name in self._paths.keys():
00467 old_item = self._paths[name].item
00468
00469 self._paths[name].item = self._scene.addPath(self._paths[name].path, pen=QPen(QColor(*self._paths[name].color)))
00470
00471
00472 self._mirror(self._paths[name].item)
00473
00474 if old_item:
00475 self._scene.removeItem(old_item)
00476
00477 def _update_polygon(self, name):
00478 old_item = None
00479 if name in self._polygons.keys():
00480 old_item = self._polygons[name].item
00481
00482 self._polygons[name].item = self._scene.addPolygon(self._polygons[name].path, pen=QPen(QColor(*self._polygons[name].color)))
00483
00484
00485 self._mirror(self._polygons[name].item)
00486
00487 if old_item:
00488 self._scene.removeItem(old_item)
00489
00490 def _mirror(self, item):
00491 item.scale(-1, 1)
00492 item.translate(-self.w, 0)
00493
00494 def save_settings(self, plugin_settings, instance_settings):
00495
00496 pass
00497
00498 def restore_settings(self, plugin_settings, instance_settings):
00499
00500 pass