35 from tf.transformations
import quaternion_from_euler
39 from math
import sqrt, atan, pi, degrees
41 from nav_msgs.msg
import OccupancyGrid, Path
42 from geometry_msgs.msg
import PolygonStamped, PointStamped, PoseWithCovarianceStamped, PoseStamped
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
51 msg_types = [OccupancyGrid, Path, PolygonStamped, PointStamped]
52 msg_type, array = get_field_type(topic)
54 if not array
and msg_type
in msg_types:
74 paths=[
'/move_base/NavFn/plan',
'/move_base/TrajectoryPlannerROS/local_plan'],
75 polygons=[
'/move_base/local_costmap/robot_footprint']):
76 super(NavViewWidget, self).
__init__()
80 self.setAcceptDrops(
True)
81 self.setWindowTitle(
'Navigation Viewer')
91 self._set_pose.clicked.connect(self._nav_view.pose_mode)
93 self._set_goal.clicked.connect(self._nav_view.goal_mode)
95 self._button_layout.addWidget(self.
_set_pose)
96 self._button_layout.addWidget(self.
_set_goal)
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')
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_)')
116 topic_name = str(e.mimeData().text())
120 e.acceptProposedAction()
123 if e.mimeData().hasText():
124 topic_name = str(e.mimeData().text())
126 droped_item = e.source().selectedItems()[0]
127 topic_name = str(droped_item.data(0, Qt.UserRole))
129 topic_type, array = get_field_type(topic_name)
131 if topic_type
is OccupancyGrid:
132 self.
map = topic_name
135 self._nav_view.close()
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)
146 self._nav_view.save_settings(plugin_settings, instance_settings)
149 self._nav_view.restore_settings(plugin_settings, instance_settings)
153 map_changed = Signal()
154 path_changed = Signal(str)
155 polygon_changed = Signal(str)
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):
168 self.map_changed.connect(self.
_update)
169 self.destroyed.connect(self.
close)
172 self.setDragMode(QGraphicsView.ScrollHandDrag)
185 self.
_colors = [(238, 34, 116), (68, 134, 252), (236, 228, 46), (102, 224, 18), (242, 156, 6), (240, 64, 10), (196, 30, 250)]
198 for poly
in polygons:
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)
205 self.
_pose_pub = rospy.Publisher(
'/initialpose', PoseWithCovarianceStamped)
206 self.
_goal_pub = rospy.Publisher(
'/move_base_simple/goal', PoseStamped)
208 self.setScene(self.
_scene)
216 item.setAcceptDrops(
True)
217 item.dragEnterEvent = c
222 self._parent.dragEnterEvent(e)
226 self._parent.dropEvent(e)
231 delta = event.angleDelta().y()
232 except AttributeError:
233 delta = event.delta()
235 self.scale(1.15, 1.15)
237 self.scale(0.85, 0.85)
241 self.
w = msg.info.width
242 self.
h = msg.info.height
244 a = numpy.array(msg.data, dtype=numpy.uint8, copy=
False, order=
'C')
245 a = a.reshape((self.
h, self.
w))
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)
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))
254 image.setColor(255, qRgb(200, 200, 200))
256 self.setSceneRect(0, 0, self.
w, self.
h)
257 self.map_changed.emit()
269 if not (msg.header.frame_id ==
'/map' or msg.header.frame_id ==
''):
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]
274 rospy.logerr(
"TF Error")
280 start = data[0].pose.position
284 pt = pose.pose.position
288 self.path_changed.emit(name)
290 path.color = random.choice(self.
_colors)
291 self._colors.remove(path.color)
294 path.sub = rospy.Subscriber(path.name, Path, path.cb)
305 if not (msg.header.frame_id ==
'/map' or msg.header.frame_id ==
''):
307 self._tf.waitForTransform(msg.header.frame_id,
'/map', rospy.Time(), rospy.Duration(10))
309 for pt
in msg.polygon.points:
311 ps.header.frame_id = msg.header.frame_id
315 points_stamped.append(ps)
317 trans_pts = [self._tf.transformPoint(
'/map', pt).point
for pt
in points_stamped]
319 rospy.logerr(
"TF Error")
322 trans_pts = [pt
for pt
in msg.polygon.points]
324 if len(trans_pts) > 0:
329 poly.path = QPolygonF(pts)
331 self.polygon_changed.emit(name)
333 poly.color = random.choice(self.
_colors)
334 self._colors.remove(poly.color)
337 poly.sub = rospy.Subscriber(poly.name, PolygonStamped, poly.cb)
345 self.setDragMode(QGraphicsView.NoDrag)
348 self.setDragMode(QGraphicsView.ScrollHandDrag)
354 self.setDragMode(QGraphicsView.NoDrag)
357 self.setDragMode(QGraphicsView.ScrollHandDrag)
360 p = self.mapToScene(e.x(), e.y())
362 mag = sqrt(pow(v[0], 2) + pow(v[1], 2))
363 u = (v[0]/mag, v[1]/mag)
365 res = (u[0]*20, u[1]*20)
382 angle = atan(u[1] / u[0])
383 quat = quaternion_from_euler(0, 0, degrees(angle))
389 p = self.mapToScene(e.x(), e.y())
400 msg.header.frame_id =
'/map' 401 msg.header.stamp = rospy.Time.now()
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]
408 self._goal_pub.publish(msg)
414 msg = PoseWithCovarianceStamped()
415 msg.header.frame_id =
'/map' 416 msg.header.stamp = rospy.Time.now()
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]
424 self._pose_pub.publish(msg)
437 self.map_sub.unregister()
438 for p
in self._paths.values():
442 for p
in self._polygons.values():
446 super(NavView, self).
close()
452 pixmap = QPixmap.fromImage(self.
_map)
453 self.
_map_item = self._scene.addPixmap(pixmap)
466 if name
in self._paths.keys():
467 old_item = self.
_paths[name].item
469 self.
_paths[name].item = self._scene.addPath(self.
_paths[name].path, pen=QPen(QColor(*self.
_paths[name].color)))
475 self._scene.removeItem(old_item)
479 if name
in self._polygons.keys():
488 self._scene.removeItem(old_item)
492 item.translate(-self.
w, 0)
def restore_settings(self, plugin_settings, instance_settings)
def draw_position(self, e, mirror=True)
def add_polygon(self, name)
def mousePressEvent(self, e)
def save_settings(self, plugin_settings, instance_settings)
def wheelEvent(self, event)
def add_dragdrop(self, item)
def __init__(self, name=None)
def accepted_topic(topic)
def _update_polygon(self, name)
def dragEnterEvent(self, e)
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)
def mouseReleaseEvent(self, e)
def _update_path(self, name)