Пример #1
0
    def draw(self, img, pixmapper, bounds):
        '''draw a polygon on the image'''
        if self.hidden:
            return
        (lat,lon,w,h) = bounds
        # note that w and h are in degrees
        spacing = 1000
        while True:
            start = mp_util.latlon_round((lat,lon), spacing)
            lat2 = mp_util.constrain(lat+h*0.5,-85,85)
            lon2 = mp_util.wrap_180(lon+w)
            dist = mp_util.gps_distance(lat2,lon,lat2,lon2)
            count = int(dist / spacing)
            if count < 2:
                spacing /= 10
            elif count > 50:
                spacing *= 10
            else:
                break

        count += 10

        for i in range(count):
            # draw vertical lines of constant longitude
            pos1 = mp_util.gps_newpos(start[0], start[1], 90, i*spacing)
            pos3 = (pos1[0]+h*2, pos1[1])
            self.draw_line(img, pixmapper, pos1, pos3, self.colour, self.linewidth)

            # draw horizontal lines of constant latitude
            pos1 = mp_util.gps_newpos(start[0], start[1], 0, i*spacing)
            pos3 = (pos1[0], pos1[1]+w*2)
            self.draw_line(img, pixmapper, pos1, pos3, self.colour, self.linewidth)
Пример #2
0
    def redraw_map(self):
        '''redraw the map with current settings'''
        state = self.state

        view_same = (self.last_view is not None and self.map_img is not None
                     and self.last_view == self.current_view())

        if view_same and not state.need_redraw:
            return

        # get the new map
        self.map_img = state.mt.area_to_image(state.lat, state.lon,
                                              state.width, state.height,
                                              state.ground_width)
        if state.brightness != 0:  # valid state.brightness range is [-255, 255]
            brightness = np.uint8(np.abs(state.brightness))
            if state.brightness > 0:
                self.map_img = np.where((255 - self.map_img) < brightness, 255,
                                        self.map_img + brightness)
            else:
                self.map_img = np.where((255 + self.map_img) < brightness, 0,
                                        self.map_img - brightness)

        # find display bounding box
        (lat2, lon2) = self.coordinates(state.width - 1, state.height - 1)
        bounds = (lat2, state.lon, state.lat - lat2,
                  mp_util.wrap_180(lon2 - state.lon))

        # get the image
        img = self.map_img.copy()

        # possibly draw a grid
        if state.grid:
            SlipGrid('grid', layer=3, linewidth=1,
                     colour=(255, 255, 0)).draw(img, self.pixmapper, bounds)

        # draw layer objects
        keys = state.layers.keys()
        keys = sorted(list(keys))
        for k in keys:
            self.draw_objects(state.layers[k], bounds, img)

        # draw information objects
        for key in state.info:
            state.info[key].draw(state.panel, state.panel.information)

        # display the image
        self.imagePanel.set_image(img)

        self.update_position()

        self.mainSizer.Fit(self)
        self.Refresh()
        self.last_view = self.current_view()
        self.SetFocus()
        state.need_redraw = False
Пример #3
0
 def coord(self, offset=(0, 0)):
     '''return lat,lon within a tile given (offsetx,offsety)'''
     (tilex, tiley) = self.tile
     (offsetx, offsety) = offset
     world_tiles = 1 << self.zoom
     x = (tilex + 1.0 * offsetx / TILES_WIDTH) / (world_tiles / 2.) - 1
     y = (tiley + 1.0 * offsety / TILES_HEIGHT) / (world_tiles / 2.) - 1
     lon = mp_util.wrap_180(x * 180.0)
     y = exp(-y * 2 * pi)
     e = (y - 1) / (y + 1)
     lat = 180.0 / pi * asin(e)
     return (lat, lon)
Пример #4
0
 def coord_to_tile(self, lat, lon, zoom):
     '''convert lat/lon/zoom to a TileInfo'''
     world_tiles = 1<<zoom
     lon = mp_util.wrap_180(lon)
     x = world_tiles / 360.0 * (lon + 180.0)
     tiles_pre_radian = world_tiles / (2 * pi)
     e = sin(radians(lat))
     e = mp_util.constrain(e, -1+1.0e-15, 1-1.0e-15)
     y = world_tiles/2 + 0.5*log((1+e)/(1-e)) * (-tiles_pre_radian)
     offsetx = int((x - int(x)) * TILES_WIDTH)
     offsety = int((y - int(y)) * TILES_HEIGHT)
     return TileInfo((int(x) % world_tiles, int(y) % world_tiles), zoom, self.service, offset=(offsetx, offsety))
Пример #5
0
    def mavlink_packet(self, m):
        '''handle an incoming mavlink packet'''
        if not self.mpstate.map:
            # don't draw if no map
            return

        if m.get_type() != 'GLOBAL_POSITION_INT':
            return
        self.update_target(m.time_boot_ms)

        if self.target_pos is None:
            return

        if self.follow_settings.disable_msg:
            return

        if self.follow_settings.type == 'guided':
            # send normal guided mode packet
            self.master.mav.mission_item_int_send(self.settings.target_system,
                                                  self.settings.target_component,
                                                  0,
                                                  self.module('wp').get_default_frame(),
                                                  mavutil.mavlink.MAV_CMD_NAV_WAYPOINT,
                                                  2, 0, 0, 0, 0, 0,
                                                  int(self.target_pos[0]*1.0e7), int(self.target_pos[1]*1.0e7),
                                                  self.follow_settings.altitude)

        elif self.follow_settings.type == 'yaw':
            # display yaw from vehicle to target
            vehicle = (m.lat*1.0e-7, m.lon*1.0e-7)
            vehicle_yaw = math.degrees(self.master.field('ATTITUDE', 'yaw', 0))
            target_bearing = mp_util.gps_bearing(vehicle[0], vehicle[1], self.target_pos[0], self.target_pos[1])
            # wrap the angle from -180 to 180 thus commanding the vehicle to turn left or right
            # note its in centi-degrees so *100
            relyaw = mp_util.wrap_180(target_bearing - vehicle_yaw) * 100

            self.master.mav.command_long_send(self.settings.target_system,
                                                  self.settings.target_component,
                                                  mavutil.mavlink.MAV_CMD_NAV_SET_YAW_SPEED, 0,
                                                  relyaw,
                                                  self.follow_settings.vehicle_throttle,
                                                  0, 0, 0, 0, 0)
Пример #6
0
 def constrain_latlon(self):
     self.state.lat = mp_util.constrain(self.state.lat, -85, 85)
     self.state.lon = mp_util.wrap_180(self.state.lon)
Пример #7
0
                      default=False,
                      help="show debug info")
    (opts, args) = parser.parse_args()

    lat = opts.lat
    lon = opts.lon
    ground_width = opts.width

    if opts.boundary:
        boundary = mp_util.polygon_load(opts.boundary)
        bounds = mp_util.polygon_bounds(boundary)
        lat = bounds[0] + bounds[2]
        lon = bounds[1]
        ground_width = max(
            mp_util.gps_distance(lat, lon, lat,
                                 mp_util.wrap_180(lon + bounds[3])),
            mp_util.gps_distance(lat, lon, lat - bounds[2], lon))
        print(lat, lon, ground_width)

    mt = MPTile(debug=opts.debug,
                service=opts.service,
                tile_delay=opts.delay,
                max_zoom=opts.max_zoom)
    if opts.zoom is None:
        zooms = range(mt.min_zoom, mt.max_zoom + 1)
    else:
        zooms = [opts.zoom]
    for zoom in zooms:
        tlist = mt.area_to_tile_list(lat,
                                     lon,
                                     width=1024,
Пример #8
0
    parser.add_option("--max-zoom", type='int', default=19, help="maximum tile zoom")
    parser.add_option("--delay", type='float', default=1.0, help="tile download delay")
    parser.add_option("--boundary", default=None, help="region boundary")
    parser.add_option("--debug", action='store_true', default=False, help="show debug info")
    (opts, args) = parser.parse_args()

    lat = opts.lat
    lon = opts.lon
    ground_width = opts.width

    if opts.boundary:
        boundary = mp_util.polygon_load(opts.boundary)
        bounds = mp_util.polygon_bounds(boundary)
        lat = bounds[0]+bounds[2]
        lon = bounds[1]
        ground_width = max(mp_util.gps_distance(lat, lon, lat, mp_util.wrap_180(lon+bounds[3])),
                           mp_util.gps_distance(lat, lon, lat-bounds[2], lon))
        print(lat, lon, ground_width)

    mt = MPTile(debug=opts.debug, service=opts.service,
            tile_delay=opts.delay, max_zoom=opts.max_zoom)
    if opts.zoom is None:
        zooms = range(mt.min_zoom, mt.max_zoom+1)
    else:
        zooms = [opts.zoom]
    for zoom in zooms:
        tlist = mt.area_to_tile_list(lat, lon, width=1024, height=1024,
                         ground_width=ground_width, zoom=zoom)
        print("zoom %u needs %u tiles" % (zoom, len(tlist)))
        for tile in tlist:
            mt.load_tile(tile)