nav_view.py
Go to the documentation of this file.
00001 # Software License Agreement (BSD License)
00002 #
00003 # Copyright (c) 2012, Willow Garage, Inc.
00004 # All rights reserved.
00005 #
00006 # Redistribution and use in source and binary forms, with or without
00007 # modification, are permitted provided that the following conditions
00008 # are met:
00009 #
00010 #  * Redistributions of source code must retain the above copyright
00011 #    notice, this list of conditions and the following disclaimer.
00012 #  * Redistributions in binary form must reproduce the above
00013 #    copyright notice, this list of conditions and the following
00014 #    disclaimer in the documentation and/or other materials provided
00015 #    with the distribution.
00016 #  * Neither the name of Willow Garage, Inc. nor the names of its
00017 #    contributors may be used to endorse or promote products derived
00018 #    from this software without specific prior written permission.
00019 #
00020 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00021 # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00022 # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00023 # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00024 # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00025 # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00026 # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00027 # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00028 # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00029 # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00030 # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00031 # POSSIBILITY OF SUCH DAMAGE.
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 QWidget, QPixmap, QImage, QGraphicsView, QGraphicsScene, QPainterPath, QPen, QPolygonF, QVBoxLayout, QHBoxLayout, QColor, qRgb, QPushButton
00046 
00047 from rqt_py_common.topic_helpers import get_field_type
00048 
00049 def accepted_topic(topic):
00050     msg_types = [OccupancyGrid, Path, PolygonStamped, PointStamped]
00051     msg_type, array = get_field_type(topic)
00052 
00053     if not array and msg_type in msg_types:
00054         return True
00055     else:
00056         return False
00057 
00058 
00059 class PathInfo(object):
00060     def __init__(self, name=None):
00061         self.color = None
00062         self.sub = None
00063         self.cb = None
00064         self.path = None
00065         self.item = None
00066 
00067         self.name = name
00068 
00069 
00070 class NavViewWidget(QWidget):
00071 
00072     def __init__(self, map_topic='/map',
00073                  paths=['/move_base/NavFn/plan', '/move_base/TrajectoryPlannerROS/local_plan'],
00074                  polygons=['/move_base/local_costmap/robot_footprint']):
00075         super(NavViewWidget, self).__init__()
00076         self._layout = QVBoxLayout()
00077         self._button_layout = QHBoxLayout()
00078 
00079         self.setAcceptDrops(True)
00080         self.setWindowTitle('Navigation Viewer')
00081 
00082         self.paths = paths
00083         self.polygons = polygons
00084         self.map = map_topic
00085         self._tf = tf.TransformListener()
00086 
00087         self._nav_view = NavView(map_topic, paths, polygons, tf = self._tf, parent = self)
00088 
00089         self._set_pose = QPushButton('Set Pose')
00090         self._set_pose.clicked.connect(self._nav_view.pose_mode)
00091         self._set_goal = QPushButton('Set Goal')
00092         self._set_goal.clicked.connect(self._nav_view.goal_mode)
00093 
00094         self._button_layout.addWidget(self._set_pose)
00095         self._button_layout.addWidget(self._set_goal)
00096 
00097         self._layout.addLayout(self._button_layout)
00098 
00099         self._layout.addWidget(self._nav_view)
00100 
00101         self.setLayout(self._layout)
00102 
00103     def dragEnterEvent(self, e):
00104         if not e.mimeData().hasText():
00105             if not hasattr(e.source(), 'selectedItems') or len(e.source().selectedItems()) == 0:
00106                 qWarning('NavView.dragEnterEvent(): not hasattr(event.source(), selectedItems) or len(event.source().selectedItems()) == 0')
00107                 return
00108             item = e.source().selectedItems()[0]
00109             topic_name = item.data(0, Qt.UserRole)
00110             if topic_name == None:
00111                 qWarning('NavView.dragEnterEvent(): not hasattr(item, ros_topic_name_)')
00112                 return
00113 
00114         else:
00115             topic_name = str(e.mimeData().text())
00116 
00117         if accepted_topic(topic_name):
00118             e.accept()
00119             e.acceptProposedAction()
00120 
00121     def dropEvent(self, e):
00122         if e.mimeData().hasText():
00123             topic_name = str(e.mimeData().text())
00124         else:
00125             droped_item = e.source().selectedItems()[0]
00126             topic_name = str(droped_item.data(0, Qt.UserRole))
00127 
00128         topic_type, array = get_field_type(topic_name)
00129         if not array:
00130             if topic_type is OccupancyGrid:
00131                 self.map = topic_name
00132 
00133                 # Swap out the nav view for one with the new topics
00134                 self._nav_view.close()
00135                 self._nav_view = NavView(self.map, self.paths, self.polygons, self._tf, self)
00136                 self._layout.addWidget(self._nav_view)
00137             elif topic_type is Path:
00138                 self.paths.append(topic_name)
00139                 self._nav_view.add_path(topic_name)
00140             elif topic_type is PolygonStamped:
00141                 self.polygons.append(topic_name)
00142                 self._nav_view.add_polygon(topic_name)
00143 
00144     def save_settings(self, plugin_settings, instance_settings):
00145         self._nav_view.save_settings(plugin_settings, instance_settings)
00146 
00147     def restore_settings(self, plugin_settings, instance_settings):
00148         self._nav_view.restore_settings(plugin_settings, instance_settings)
00149 
00150 
00151 class NavView(QGraphicsView):
00152     map_changed = Signal()
00153     path_changed = Signal(str)
00154     polygon_changed = Signal(str)
00155 
00156     def __init__(self, map_topic='/map',
00157                  paths=['/move_base/SBPLLatticePlanner/plan', '/move_base/TrajectoryPlannerROS/local_plan'],
00158                  polygons=['/move_base/local_costmap/robot_footprint'], tf=None, parent=None):
00159         super(NavView, self).__init__()
00160         self._parent = parent
00161 
00162         self._pose_mode = False
00163         self._goal_mode = False
00164         self.last_path = None
00165 
00166 
00167         self.map_changed.connect(self._update)
00168         self.destroyed.connect(self.close)
00169 
00170         #ScrollHandDrag
00171         self.setDragMode(QGraphicsView.ScrollHandDrag)
00172 
00173         self._map = None
00174         self._map_item = None
00175 
00176         self.w = 0
00177         self.h = 0
00178 
00179         self._paths = {}
00180         self._polygons = {}
00181         self.path_changed.connect(self._update_path)
00182         self.polygon_changed.connect(self._update_polygon)
00183 
00184         self._colors = [(238, 34, 116), (68, 134, 252), (236, 228, 46), (102, 224, 18), (242, 156, 6), (240, 64, 10), (196, 30, 250)]
00185 
00186         self._scene = QGraphicsScene()
00187 
00188         if tf is None:
00189             self._tf = tf.TransformListener()
00190         else:
00191             self._tf = tf
00192         self.map_sub = rospy.Subscriber('/map', OccupancyGrid, self.map_cb)
00193 
00194         for path in paths:
00195             self.add_path(path)
00196 
00197         for poly in polygons:
00198             self.add_polygon(poly)
00199 
00200         try:
00201             self._pose_pub = rospy.Publisher('/initialpose', PoseWithCovarianceStamped, queue_size=100)
00202             self._goal_pub = rospy.Publisher('/move_base_simple/goal', PoseStamped, queue_size=100)
00203         except TypeError:
00204             self._pose_pub = rospy.Publisher('/initialpose', PoseWithCovarianceStamped)
00205             self._goal_pub = rospy.Publisher('/move_base_simple/goal', PoseStamped)
00206 
00207         self.setScene(self._scene)
00208 
00209     def add_dragdrop(self, item):
00210         # Add drag and drop functionality to all the items in the view
00211         def c(x, e):
00212             self.dragEnterEvent(e)
00213         def d(x, e):
00214             self.dropEvent(e)
00215         item.setAcceptDrops(True)
00216         item.dragEnterEvent = c
00217         item.dropEvent = d
00218 
00219     def dragEnterEvent(self, e):
00220         if self._parent:
00221             self._parent.dragEnterEvent(e)
00222 
00223     def dropEvent(self, e):
00224         if self._parent:
00225             self._parent.dropEvent(e)
00226 
00227     def wheelEvent(self, event):
00228         event.ignore()
00229         if event.delta() > 0:
00230             self.scale(1.15, 1.15)
00231         else:
00232             self.scale(0.85, 0.85)
00233 
00234     def map_cb(self, msg):
00235         self.resolution = msg.info.resolution
00236         self.w = msg.info.width
00237         self.h = msg.info.height
00238 
00239         a = numpy.array(msg.data, dtype=numpy.uint8, copy=False, order='C')
00240         a = a.reshape((self.h, self.w))
00241         if self.w % 4:
00242             e = numpy.empty((self.h, 4 - self.w % 4), dtype=a.dtype, order='C')
00243             a = numpy.append(a, e, axis=1)
00244         image = QImage(a.reshape((a.shape[0] * a.shape[1])), self.w, self.h, QImage.Format_Indexed8)
00245 
00246         for i in reversed(range(101)):
00247             image.setColor(100 - i, qRgb(i* 2.55, i * 2.55, i * 2.55))
00248         image.setColor(101, qRgb(255, 0, 0))  # not used indices
00249         image.setColor(255, qRgb(200, 200, 200))  # color for unknown value -1
00250         self._map = image
00251         self.setSceneRect(0, 0, self.w, self.h)
00252         self.map_changed.emit()
00253 
00254     def add_path(self, name):
00255         path = PathInfo(name)
00256 
00257         def c(msg):
00258             if not self._map:
00259                 return
00260 
00261             pp = QPainterPath()
00262 
00263             # Transform everything in to the map frame
00264             if not (msg.header.frame_id == '/map' or msg.header.frame_id == ''):
00265                 try:
00266                     self._tf.waitForTransform(msg.header.frame_id, '/map', rospy.Time(), rospy.Duration(10))
00267                     data = [self._tf.transformPose('/map', pose) for pose in msg.poses]
00268                 except tf.Exception:
00269                     rospy.logerr("TF Error")
00270                     data = []
00271             else:
00272                 data = msg.poses
00273 
00274             if len(data) > 0:
00275                 start = data[0].pose.position
00276                 pp.moveTo(start.x / self.resolution, start.y / self.resolution)
00277 
00278                 for pose in data:
00279                     pt = pose.pose.position
00280                     pp.lineTo(pt.x / self.resolution, pt.y / self.resolution)
00281 
00282                 path.path = pp
00283                 self.path_changed.emit(name)
00284 
00285         path.color = random.choice(self._colors)
00286         self._colors.remove(path.color)
00287 
00288         path.cb = c
00289         path.sub = rospy.Subscriber(path.name, Path, path.cb)
00290 
00291         self._paths[name] = path
00292 
00293     def add_polygon(self, name):
00294         poly = PathInfo(name)
00295 
00296         def c(msg):
00297             if not self._map:
00298                 return
00299 
00300             if not (msg.header.frame_id == '/map' or msg.header.frame_id == ''):
00301                 try:
00302                     self._tf.waitForTransform(msg.header.frame_id, '/map', rospy.Time(), rospy.Duration(10))
00303                     points_stamped = []
00304                     for pt in msg.polygon.points:
00305                         ps = PointStamped()
00306                         ps.header.frame_id = msg.header.frame_id
00307                         ps.point.x = pt.x
00308                         ps.point.y = pt.y
00309 
00310                         points_stamped.append(ps)
00311 
00312                     trans_pts = [self._tf.transformPoint('/map', pt).point for pt in points_stamped]
00313                 except tf.Exception:
00314                     rospy.logerr("TF Error")
00315                     trans_pts = []
00316             else:
00317                 trans_pts = [pt for pt in msg.polygon.points]
00318 
00319             if len(trans_pts) > 0:
00320                 pts = [QPointF(pt.x / self.resolution, pt.y / self.resolution) for pt in trans_pts]
00321 
00322                 close = trans_pts[0]
00323                 pts.append(QPointF(close.x / self.resolution, close.y / self.resolution))
00324                 poly.path = QPolygonF(pts)
00325 
00326                 self.polygon_changed.emit(name)
00327 
00328         poly.color = random.choice(self._colors)
00329         self._colors.remove(poly.color)
00330 
00331         poly.cb = c
00332         poly.sub = rospy.Subscriber(poly.name, PolygonStamped, poly.cb)
00333 
00334         self._polygons[name] = poly
00335 
00336     def pose_mode(self):
00337         if not self._pose_mode:
00338             self._pose_mode = True
00339             self._goal_mode = False
00340             self.setDragMode(QGraphicsView.NoDrag)
00341         elif self._pose_mode:
00342             self._pose_mode = False
00343             self.setDragMode(QGraphicsView.ScrollHandDrag)
00344 
00345     def goal_mode(self):
00346         if not self._goal_mode:
00347             self._goal_mode = True
00348             self._pose_mode = False
00349             self.setDragMode(QGraphicsView.NoDrag)
00350         elif self._goal_mode:
00351             self._goal_mode = False
00352             self.setDragMode(QGraphicsView.ScrollHandDrag)
00353 
00354     def draw_position(self, e, mirror=True):
00355         p = self.mapToScene(e.x(), e.y())
00356         v = (p.x() - self.drag_start[0], p.y() - self.drag_start[1])
00357         mag = sqrt(pow(v[0], 2) + pow(v[1], 2))
00358         u = (v[0]/mag, v[1]/mag)
00359 
00360         res = (u[0]*20, u[1]*20)
00361         path = self._scene.addLine(self.drag_start[0], self.drag_start[1],
00362                                    self.drag_start[0] + res[0], self.drag_start[1] + res[1])
00363 
00364         if self.last_path:
00365             self._scene.removeItem(self.last_path)
00366             self.last_path = None
00367         self.last_path = path
00368 
00369         if mirror:
00370             # Mirror point over x axis
00371             x = ((self.w / 2) - self.drag_start[0]) + (self.w /2)
00372         else:
00373             x = self.drag_start[0]
00374 
00375         map_p = [x * self.resolution, self.drag_start[1] * self.resolution]
00376 
00377         angle = atan(u[1] / u[0])
00378         quat = quaternion_from_euler(0, 0, degrees(angle))
00379 
00380         return map_p, quat
00381 
00382     def mousePressEvent(self, e):
00383         if self._goal_mode or self._pose_mode:
00384             p = self.mapToScene(e.x(), e.y())
00385             self.drag_start = (p.x(), p.y())
00386         else:
00387             super(NavView, self).mousePressEvent(e)
00388 
00389     def mouseReleaseEvent(self, e):
00390         if self._goal_mode:
00391             self._goal_mode = False
00392             map_p, quat = self.draw_position(e)
00393 
00394             msg = PoseStamped()
00395             msg.header.frame_id = '/map'
00396             msg.header.stamp = rospy.Time.now()
00397 
00398             msg.pose.position.x = map_p[0]
00399             msg.pose.position.y = map_p[1]
00400             msg.pose.orientation.w = quat[0]
00401             msg.pose.orientation.z = quat[3]
00402 
00403             self._goal_pub.publish(msg)
00404 
00405         elif self._pose_mode:
00406             self._pose_mode = False
00407             map_p, quat = self.draw_position(e)
00408 
00409             msg = PoseWithCovarianceStamped()
00410             msg.header.frame_id = '/map'
00411             msg.header.stamp = rospy.Time.now()
00412 
00413             #TODO: Is it ok to just ignore the covariance matrix here?
00414             msg.pose.pose.orientation.w = quat[0]
00415             msg.pose.pose.orientation.z = quat[3]
00416             msg.pose.pose.position.x = map_p[0]
00417             msg.pose.pose.position.y = map_p[1]
00418 
00419             self._pose_pub.publish(msg)
00420 
00421         # Clean up the path
00422         if self.last_path:
00423             self._scene.removeItem(self.last_path)
00424             self.last_path = None
00425 
00426     #def mouseMoveEvent(self, e):
00427     #    if e.buttons() == Qt.LeftButton and (self._pose_mode or self._goal_mode):
00428     #        map_p, quat = self.draw_position(e)
00429 
00430     def close(self):
00431         if self.map_sub:
00432             self.map_sub.unregister()
00433         for p in self._paths.itervalues():
00434             if p.sub:
00435                 p.sub.unregister()
00436 
00437         for p in self._polygons.itervalues():
00438             if p.sub:
00439                 p.sub.unregister()
00440 
00441         super(NavView, self).close()
00442 
00443     def _update(self):
00444         if self._map_item:
00445             self._scene.removeItem(self._map_item)
00446 
00447         pixmap = QPixmap.fromImage(self._map)
00448         self._map_item = self._scene.addPixmap(pixmap)
00449 
00450         # Everything must be mirrored
00451         self._mirror(self._map_item)
00452 
00453         # Add drag and drop functionality
00454         self.add_dragdrop(self._map_item)
00455 
00456         self.centerOn(self._map_item)
00457         self.show()
00458 
00459     def _update_path(self, name):
00460         old_item = None
00461         if name in self._paths.keys():
00462             old_item = self._paths[name].item
00463 
00464         self._paths[name].item = self._scene.addPath(self._paths[name].path, pen=QPen(QColor(*self._paths[name].color)))
00465 
00466         # Everything must be mirrored
00467         self._mirror(self._paths[name].item)
00468 
00469         if old_item:
00470             self._scene.removeItem(old_item)
00471 
00472     def _update_polygon(self, name):
00473         old_item = None
00474         if name in self._polygons.keys():
00475             old_item = self._polygons[name].item
00476 
00477         self._polygons[name].item = self._scene.addPolygon(self._polygons[name].path, pen=QPen(QColor(*self._polygons[name].color)))
00478 
00479         # Everything must be mirrored
00480         self._mirror(self._polygons[name].item)
00481 
00482         if old_item:
00483             self._scene.removeItem(old_item)
00484 
00485     def _mirror(self, item):
00486         item.scale(-1, 1)
00487         item.translate(-self.w, 0)
00488 
00489     def save_settings(self, plugin_settings, instance_settings):
00490         # TODO add any settings to be saved
00491         pass
00492 
00493     def restore_settings(self, plugin_settings, instance_settings):
00494         # TODO add any settings to be restored
00495         pass


rqt_nav_view
Author(s): Ze'ev Klapow
autogenerated on Fri Aug 28 2015 12:50:51