nav_view.py
Go to the documentation of this file.
00001 import roslib;roslib.load_manifest('rqt_nav_view')
00002 import rospy
00003 import tf
00004 
00005 import numpy
00006 import random
00007 
00008 from nav_msgs.msg import OccupancyGrid, Path
00009 from geometry_msgs.msg import PolygonStamped, PointStamped
00010 
00011 from python_qt_binding.QtCore import Signal, QPointF
00012 from python_qt_binding.QtGui import QWidget, QPixmap, QImage, QGraphicsView, QGraphicsScene, QPainterPath, QPen, QPolygonF, QVBoxLayout, QColor, qRgb
00013 
00014 
00015 class PathInfo(object):
00016     def __init__(self, name=None):
00017         self.color = None
00018         self.sub = None
00019         self.cb = None
00020         self.path = None
00021         self.item = None
00022 
00023         self.name = name
00024 
00025 
00026 class NavViewWidget(QWidget):
00027 
00028     def __init__(self, map_topic='/map',
00029                  paths=['/move_base/SBPLLatticePlanner/plan', '/move_base/TrajectoryPlannerROS/local_plan'],
00030                  polygons=['/move_base/local_costmap/robot_footprint']):
00031         super(NavViewWidget, self).__init__()
00032         self._layout = QVBoxLayout()
00033 
00034         self.setWindowTitle('Navigation Viewer')
00035         self._nav_view = NavView(map_topic, paths, polygons)
00036         self._layout.addWidget(self._nav_view)
00037 
00038         self.setLayout(self._layout)
00039 
00040 
00041 class NavView(QGraphicsView):
00042     map_changed = Signal()
00043     path_changed = Signal(str)
00044     polygon_changed = Signal(str)
00045 
00046     def __init__(self, map_topic='/map',
00047                  paths=['/move_base/SBPLLatticePlanner/plan', '/move_base/TrajectoryPlannerROS/local_plan'],
00048                  polygons=['/move_base/local_costmap/robot_footprint']):
00049         super(NavView, self).__init__()
00050 
00051         self.map_changed.connect(self._update)
00052         self.destroyed.connect(self.close)
00053 
00054         #ScrollHandDrag
00055         self.setDragMode(QGraphicsView.ScrollHandDrag)
00056 
00057         self._map = None
00058         self._map_item = None
00059 
00060         self.w = 0
00061         self.h = 0
00062 
00063         self._paths = {}
00064         self._polygons = {}
00065         self.path_changed.connect(self._update_path)
00066         self.polygon_changed.connect(self._update_polygon)
00067 
00068         self._colors = [(238, 34, 116), (68, 134, 252), (236, 228, 46), (102, 224, 18), (242, 156, 6), (240, 64, 10), (196, 30, 250)]
00069 
00070         self._scene = QGraphicsScene()
00071 
00072         self._tf = tf.TransformListener()
00073         self.map_sub = rospy.Subscriber('/map', OccupancyGrid, self.map_cb)
00074 
00075         for path in paths:
00076             self.add_path(path)
00077 
00078         for poly in polygons:
00079             self.add_polygon(poly)
00080 
00081         self.setScene(self._scene)
00082 
00083     def wheelEvent(self, event):
00084         event.ignore()
00085         if event.delta() > 0:
00086             self.scale(1.15, 1.15)
00087         else:
00088             self.scale(0.85, 0.85)
00089 
00090     def map_cb(self, msg):
00091         self.resolution = msg.info.resolution
00092         self.w = msg.info.width
00093         self.h = msg.info.height
00094 
00095         a = numpy.array(msg.data, dtype=numpy.uint8, copy=False, order='C')
00096         a = a.reshape((self.h, self.w))
00097         if self.w % 4:
00098             e = numpy.empty((self.h, 4 - self.w % 4), dtype=a.dtype, order='C')
00099             a = numpy.append(a, e, axis=1)
00100         image = QImage(a.reshape((a.shape[0] * a.shape[1])), self.w, self.h, QImage.Format_Indexed8)
00101 
00102         for i in range(101):
00103             image.setColor(i, qRgb(i * 2.55, i * 2.55, i * 2.55))
00104         image.setColor(101, qRgb(255, 0, 0))  # not used indices
00105         image.setColor(255, qRgb(0, 0, 150))  # color for unknown value -1
00106         self._map = image
00107         self.setSceneRect(0, 0, self.w, self.h)
00108         self.map_changed.emit()
00109 
00110     def add_path(self, name):
00111         path = PathInfo(name)
00112 
00113         def c(msg):
00114             pp = QPainterPath()
00115 
00116             # Transform everything in to the map frame
00117             if not (msg.header.frame_id == '/map' or msg.header.frame_id == ''):
00118                 try:
00119                     self._tf.waitForTransform(msg.header.frame_id, '/map', rospy.Time(), rospy.Duration(10))
00120                     data = [self._tf.transformPose('/map', pose) for pose in msg.poses]
00121                 except tf.Exception:
00122                     rospy.logerr("TF Error")
00123                     data = []
00124             else:
00125                 data = msg.poses
00126 
00127             if len(data) > 0:
00128                 start = data[0].pose.position
00129                 pp.moveTo(start.x / self.resolution, start.y / self.resolution)
00130 
00131                 for pose in data:
00132                     pt = pose.pose.position
00133                     pp.lineTo(pt.x / self.resolution, pt.y / self.resolution)
00134 
00135                 path.path = pp
00136                 self.path_changed.emit(name)
00137 
00138         path.color = random.choice(self._colors)
00139         self._colors.remove(path.color)
00140 
00141         path.cb = c
00142         path.sub = rospy.Subscriber(path.name, Path, path.cb)
00143 
00144         self._paths[name] = path
00145 
00146     def add_polygon(self, name):
00147         poly = PathInfo(name)
00148 
00149         def c(msg):
00150             if not (msg.header.frame_id == '/map' or msg.header.frame_id == ''):
00151                 try:
00152                     self._tf.waitForTransform(msg.header.frame_id, '/map', rospy.Time(), rospy.Duration(10))
00153                     points_stamped = []
00154                     for pt in msg.polygon.points:
00155                         ps = PointStamped()
00156                         ps.header.frame_id = msg.header.frame_id
00157                         ps.point.x = pt.x
00158                         ps.point.y = pt.y
00159 
00160                         points_stamped.append(ps)
00161 
00162                     trans_pts = [self._tf.transformPoint('/map', pt).point for pt in points_stamped]
00163                 except tf.Exception:
00164                     rospy.logerr("TF Error")
00165                     trans_pts = []
00166             else:
00167                 trans_pts = [pt for pt in msg.polygon.points]
00168 
00169             if len(trans_pts) > 0:
00170                 pts = [QPointF(pt.x / self.resolution, pt.y / self.resolution) for pt in trans_pts]
00171 
00172                 close = trans_pts[0]
00173                 pts.append(QPointF(close.x / self.resolution, close.y / self.resolution))
00174                 poly.path = QPolygonF(pts)
00175 
00176                 self.polygon_changed.emit(name)
00177 
00178         poly.color = random.choice(self._colors)
00179         self._colors.remove(poly.color)
00180 
00181         poly.cb = c
00182         poly.sub = rospy.Subscriber(poly.name, PolygonStamped, poly.cb)
00183 
00184         self._polygons[name] = poly
00185 
00186     def close(self):
00187         if self.map_sub:
00188             self.map_sub.unregister()
00189         for p in self._paths.itervalues():
00190             if p.sub:
00191                 p.sub.unregister()
00192 
00193         for p in self._polygons.itervalues():
00194             if p.sub:
00195                 p.sub.unregister()
00196 
00197     def _update(self):
00198         if self._map_item:
00199             self._scene.removeItem(self._map_item)
00200 
00201         pixmap = QPixmap.fromImage(self._map)
00202         self._map_item = self._scene.addPixmap(pixmap)
00203 
00204         # Everything must be mirrored
00205         self._mirror(self._map_item)
00206 
00207         self.centerOn(self._map_item)
00208         self.show()
00209 
00210     def _update_path(self, name):
00211         old_item = None
00212         if name in self._paths.keys():
00213             old_item = self._paths[name].item
00214 
00215         self._paths[name].item = self._scene.addPath(self._paths[name].path, pen=QPen(QColor(*self._paths[name].color)))
00216 
00217         # Everything must be mirrored
00218         self._mirror(self._paths[name].item)
00219 
00220         if old_item:
00221             self._scene.removeItem(old_item)
00222 
00223     def _update_polygon(self, name):
00224         old_item = None
00225         if name in self._polygons.keys():
00226             old_item = self._polygons[name].item
00227 
00228         self._polygons[name].item = self._scene.addPolygon(self._polygons[name].path, pen=QPen(QColor(*self._polygons[name].color)))
00229 
00230         # Everything must be mirrored
00231         self._mirror(self._polygons[name].item)
00232 
00233         if old_item:
00234             self._scene.removeItem(old_item)
00235 
00236     def _mirror(self, item):
00237         item.scale(-1, 1)
00238         item.translate(-self.w, 0)


rqt_nav_view
Author(s): Ze'ev Klapow
autogenerated on Fri Jan 3 2014 11:55:48