Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011 from __future__ import division
00012 import os
00013 import math
00014 import threading
00015
00016 from python_qt_binding import loadUi
00017 from python_qt_binding.QtGui import QWidget
00018
00019 import rospkg
00020 import rospy
00021 from rocon_qt_library.widgets import QMapAnnotation
00022 from rocon_qt_library.interfaces import MapAnnotationInterface
00023
00024 from qt_gui.plugin import Plugin
00025
00026
00027
00028
00029
00030
00031 class MapAnnotation(Plugin):
00032
00033 def __init__(self, context):
00034 self._lock = threading.Lock()
00035 self._context = context
00036 super(MapAnnotation, self).__init__(context)
00037
00038 self.initialised = False
00039 self.is_setting_dlg_live = False
00040
00041 self._widget = QWidget()
00042 rospack = rospkg.RosPack()
00043 ui_file = os.path.join(rospack.get_path('concert_qt_map_annotation'), 'ui', 'concert_map_annotation.ui')
00044
00045 loadUi(ui_file, self._widget, {'QMapAnnotation': QMapAnnotation})
00046 if context.serial_number() > 1:
00047 self._widget.setWindowTitle(
00048 self._widget.windowTitle() + (' (%d)' % context.serial_number()))
00049
00050 self._default_map_topic = 'map'
00051 self._default_viz_markers_topic = 'viz_markers'
00052 self._default_wc_namespace_param = 'wc_namespace_param'
00053 self._default_wc_namespace = 'world_canvas'
00054
00055 context.add_widget(self._widget)
00056 self.setObjectName('Map Annotation')
00057
00058
00059 self._set_map_annotation_interface()
00060
00061 def _set_map_annotation_interface(self):
00062
00063 wc_namespace_param = rospy.get_param('~wc_namespace_param')
00064 wc_namespace = rospy.get_param(wc_namespace_param, self._default_wc_namespace)
00065
00066
00067 scene_slot = self._widget.map_annotation.draw_scene
00068
00069 self._widget.map_annotation.init_map_annotation_interface(
00070 scene_update_slot=scene_slot,
00071 wc_namespace=wc_namespace
00072 )
00073
00074 def _get_remaps(self, remap_from, remappings):
00075 for r in remappings:
00076 if r.remap_from == remap_from:
00077 return r.remap_to
00078 return remap_from