def loadkml(self, filename): '''Load a kml from file and put it on the map''' #Open the zip file nodes = kmlread.readkmz(filename) self.snap_points = [] #go through each object in the kml... if nodes is None: print("No nodes found") return for n in nodes: try: point = kmlread.readObject(n) except Exception as ex: continue #and place any polygons on the map if self.mpstate.map is not None and point[0] == 'Polygon': self.snap_points.extend(point[2]) #print("Adding " + point[1]) newcolour = (random.randint(0, 255), 0, random.randint(0, 255)) curpoly = mp_slipmap.SlipPolygon(point[1], point[2], layer=2, linewidth=2, colour=newcolour) self.mpstate.map.add_object(curpoly) self.allayers.append(curpoly) self.curlayers.append(point[1]) #and points - barrell image and text if self.mpstate.map is not None and point[0] == 'Point': #print("Adding " + point[1]) icon = self.mpstate.map.icon('barrell.png') curpoint = mp_slipmap.SlipIcon(point[1], latlon=(point[2][0][0], point[2][0][1]), layer=3, img=icon, rotation=0, follow=False) curtext = mp_slipmap.SlipLabel(point[1], point=(point[2][0][0], point[2][0][1]), layer=4, label=point[1], colour=(0, 255, 255)) self.mpstate.map.add_object(curpoint) self.mpstate.map.add_object(curtext) self.allayers.append(curpoint) self.alltextlayers.append(curtext) self.curlayers.append(point[1]) self.curtextlayers.append(point[1]) self.menu_needs_refreshing = True
def load_kml(kml): '''load a kml overlay, return list of map objects''' print("Loading kml %s" % kml) nodes = kmlread.readkmz(kml) ret = [] for n in nodes: try: point = kmlread.readObject(n) except Exception as ex: continue if point[0] == 'Polygon': newcolour = (random.randint(0, 255), 0, random.randint(0, 255)) curpoly = mp_slipmap.SlipPolygon(point[1], point[2], layer=2, linewidth=2, colour=newcolour) ret.append(curpoly) if point[0] == 'Point': icon = mp_tile.mp_icon('barrell.png') curpoint = mp_slipmap.SlipIcon(point[1], latlon=(point[2][0][0], point[2][0][1]), layer=3, img=icon, rotation=0, follow=False) curtext = mp_slipmap.SlipLabel(point[1], point=(point[2][0][0], point[2][0][1]), layer=4, label=point[1], colour=(0, 255, 255)) ret.append(curpoint) ret.append(curtext) return ret