Skip to content

Commit

Permalink
kmlread: flake8 compliance
Browse files Browse the repository at this point in the history
  • Loading branch information
peterbarker authored and tridge committed May 15, 2024
1 parent 0a44e17 commit 0de7724
Showing 1 changed file with 114 additions and 63 deletions.
177 changes: 114 additions & 63 deletions MAVProxy/modules/mavproxy_kmlread.py
Original file line number Diff line number Diff line change
Expand Up @@ -4,51 +4,62 @@
Copyright Stephen Dade 2016
Released under the GNU GPL version 3 or later
AP_FLAKE8_CLEAN
'''

import time, math, random
import time
import random
import re

from pymavlink import mavutil, mavwp

from MAVProxy.modules.lib import mp_module
from MAVProxy.modules.lib.mp_settings import MPSetting
# from MAVProxy.modules.lib.mp_settings import MPSetting
from MAVProxy.modules.mavproxy_map import mp_slipmap
from MAVProxy.modules.lib import mp_util
from MAVProxy.modules.lib import kmlread

if mp_util.has_wxpython:
from MAVProxy.modules.lib.mp_menu import *
from MAVProxy.modules.lib.mp_menu import MPMenuCallFileDialog
from MAVProxy.modules.lib.mp_menu import MPMenuCheckbox
from MAVProxy.modules.lib.mp_menu import MPMenuItem
from MAVProxy.modules.lib.mp_menu import MPMenuSeparator
from MAVProxy.modules.lib.mp_menu import MPMenuSubMenu


class KmlReadModule(mp_module.MPModule):
def __init__(self, mpstate):
super(KmlReadModule, self).__init__(mpstate, "kmlread", "Add kml or kmz layers to map")
self.add_command('kml', self.cmd_param, "kml map handling",
["<clear|snapwp|snapfence>",
"<load> (FILENAME)", '<layers>'])
#allayers is all the loaded layers (slimap objects)
#curlayers is only the layers displayed (checked) on the map (text list of layer names)

# allayers is all the loaded layers (slimap objects)
# curlayers is only the layers displayed (checked) on the map (text list of layer names)
self.allayers = []
self.curlayers = []
self.alltextlayers = []
self.curtextlayers = []
self.menu_added_map = False
self.menu_needs_refreshing = True
#the fence manager

# the fence manager
self.fenceloader = mavwp.MAVFenceLoader()
self.snap_points = []
#make the initial map menu

# make the initial map menu
if mp_util.has_wxpython:
self.menu_fence = MPMenuSubMenu('Set Geofence', items=[])
self.menu = MPMenuSubMenu('KML Layers',
items=[MPMenuItem('Clear', 'Clear', '# kml clear')])

self.menu = MPMenuSubMenu(
'KML Layers',
items=[
MPMenuItem('Clear', 'Clear', '# kml clear'),
]
)

def cmd_param(self, args):
'''control kml reading'''
usage = "Usage: kml <clear | load (filename) | layers | toggle (layername) | colour (layername) (colour) | fence (layername)> | snapfence | snapwp"
usage = "Usage: kml <clear | load (filename) | layers | toggle (layername) | colour (layername) (colour) | fence (layername)> | snapfence | snapwp" # noqa
if len(args) < 1:
print(usage)
return
Expand Down Expand Up @@ -84,15 +95,15 @@ def cmd_snap_wp(self, args):
wpmod = self.module('wp')
wploader = wpmod.wploader
changed = False
for i in range(1,wploader.count()):
for i in range(1, wploader.count()):
w = wploader.wp(i)
if not wploader.is_location_command(w.command):
continue
lat = w.x
lon = w.y
best = None
best_dist = (threshold+1)*3
for (snap_lat,snap_lon) in self.snap_points:
for (snap_lat, snap_lon) in self.snap_points:
dist = mp_util.gps_distance(lat, lon, snap_lat, snap_lon)
if dist < best_dist:
best_dist = dist
Expand All @@ -118,13 +129,13 @@ def cmd_snap_fence(self, args):
fencemod = self.module('fence')
loader = fencemod.fenceloader
changed = False
for i in range(0,loader.count()):
for i in range(0, loader.count()):
fp = loader.point(i)
lat = fp.lat
lon = fp.lng
best = None
best_dist = (threshold+1)*3
for (snap_lat,snap_lon) in self.snap_points:
for (snap_lat, snap_lon) in self.snap_points:
dist = mp_util.gps_distance(lat, lon, snap_lat, snap_lon)
if dist < best_dist:
best_dist = dist
Expand Down Expand Up @@ -163,28 +174,28 @@ def cmd_colour(self, args):

def fencekml(self, layername):
'''set a layer as the geofence'''
#Strip quotation marks if neccessary
# Strip quotation marks if neccessary
if layername.startswith('"') and layername.endswith('"'):
layername = layername[1:-1]
#for each point in the layer, add it in

# for each point in the layer, add it in
for layer in self.allayers:
if layer.key == layername:
#clear the current fence
# clear the current fence
self.fenceloader.clear()
if len(layer.points) < 3:
return
self.fenceloader.target_system = self.target_system
self.fenceloader.target_component = self.target_component
#send centrepoint to fence[0] as the return point
# send centrepoint to fence[0] as the return point
bounds = mp_util.polygon_bounds(layer.points)
(lat, lon, width, height) = bounds
center = (lat+width/2, lon+height/2)
self.fenceloader.add_latlon(center[0], center[1])
for lat, lon in layer.points:
#add point
# add point
self.fenceloader.add_latlon(lat, lon)
#and send
# and send
self.send_fence()

def send_fence(self):
Expand All @@ -204,18 +215,19 @@ def send_fence(self):
self.param_set('FENCE_ACTION', action, 3)
return False
if (p.idx != p2.idx or
abs(p.lat - p2.lat) >= 0.00003 or
abs(p.lng - p2.lng) >= 0.00003):
abs(p.lat - p2.lat) >= 0.00003 or
abs(p.lng - p2.lng) >= 0.00003):
print("Failed to send fence point %u" % i)
self.param_set('FENCE_ACTION', action, 3)
return False
self.param_set('FENCE_ACTION', action, 3)
return True

def fetch_fence_point(self ,i):
def fetch_fence_point(self, i):
'''fetch one fence point. Taken from fence module'''
self.master.mav.fence_fetch_point_send(self.target_system,
self.target_component, i)
self.target_component,
i)
tstart = time.time()
p = None
while time.time() - tstart < 3:
Expand All @@ -228,13 +240,13 @@ def fetch_fence_point(self ,i):
self.console.error("Failed to fetch point %u" % i)
return None
return p

def togglekml(self, layername):
'''toggle the display of a kml'''
#Strip quotation marks if neccessary
# Strip quotation marks if neccessary
if layername.startswith('"') and layername.endswith('"'):
layername = layername[1:-1]
#toggle layer off (plus associated text element)
# toggle layer off (plus associated text element)
if layername in self.curlayers:
for layer in self.curlayers:
if layer == layername:
Expand All @@ -245,7 +257,7 @@ def togglekml(self, layername):
if clayer == layername:
self.mpstate.map.remove_object(clayer)
self.curtextlayers.remove(clayer)
#toggle layer on (plus associated text element)
# toggle layer on (plus associated text element)
else:
for layer in self.allayers:
if layer.key == layername:
Expand All @@ -265,7 +277,7 @@ def find_layer(self, layername):

def clearkml(self):
'''Clear the kmls from the map'''
#go through all the current layers and remove them
# go through all the current layers and remove them
for layer in self.curlayers:
self.mpstate.map.remove_object(layer)
for layer in self.curtextlayers:
Expand All @@ -275,57 +287,72 @@ def clearkml(self):
self.alltextlayers = []
self.curtextlayers = []
self.menu_needs_refreshing = True

def loadkml(self, filename):
'''Load a kml from file and put it on the map'''
#Open the zip file
# Open the zip file
nodes = kmlread.readkmz(filename)

self.snap_points = []
counter = 0

#go through each object in the kml...
# 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:
except Exception:
continue
if point is None:
continue

counter += 1

#and place any polygons on the map
# 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])
# print("Adding " + point[1])
newcolour = (random.randint(0, 255), 0, random.randint(0, 255))
curpoly = mp_slipmap.SlipPolygon(point[1]+"-"+str(counter),
point[2],
layer=2, linewidth=2, colour=newcolour)
curpoly = mp_slipmap.SlipPolygon(
point[1]+"-"+str(counter),
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

# and points - barrell image and text
if self.mpstate.map is not None and point[0] == 'Point':
#print("Adding " + point[1])
# 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))
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 idle_task(self):
'''handle GUI elements'''
Expand All @@ -334,32 +361,56 @@ def idle_task(self):
if self.module('map') is not None and not self.menu_added_map:
self.menu_added_map = True
self.module('map').add_menu(self.menu)
#(re)create the menu
# (re)create the menu
if mp_util.has_wxpython and self.menu_added_map:
# we don't dynamically update these yet due to a wx bug
self.menu.items = [ MPMenuItem('Clear', 'Clear', '# kml clear'), MPMenuItem('Load', 'Load', '# kml load ', handler=MPMenuCallFileDialog(flags=('open',), title='KML Load', wildcard='*.kml;*.kmz')), self.menu_fence, MPMenuSeparator() ]
self.menu.items = [
MPMenuItem('Clear', 'Clear', '# kml clear'),
MPMenuItem(
'Load', 'Load', '# kml load ',
handler=MPMenuCallFileDialog(
flags=('open',),
title='KML Load',
wildcard='*.kml;*.kmz',
)
),
self.menu_fence,
MPMenuSeparator(),
]
self.menu_fence.items = []
for layer in self.allayers:
#if it's a polygon, add it to the "set Geofence" list
# if it's a polygon, add it to the "set Geofence" list
if isinstance(layer, mp_slipmap.SlipPolygon):
self.menu_fence.items.append(MPMenuItem(layer.key, layer.key, '# kml fence \"' + layer.key + '\"'))
#then add all the layers to the menu, ensuring to check the active layers
#text elements aren't included on the menu
self.menu_fence.items.append(MPMenuItem(
layer.key,
layer.key,
'# kml fence \"' + layer.key + '\"',
))
# then add all the layers to the menu, ensuring to
# check the active layers text elements aren't
# included on the menu
if layer.key in self.curlayers and layer.key[-5:] != "-text":
self.menu.items.append(MPMenuCheckbox(layer.key, layer.key, '# kml toggle \"' + layer.key + '\"', checked=True))
self.menu.items.append(MPMenuCheckbox(
layer.key,
layer.key,
'# kml toggle \"' + layer.key + '\"',
checked=True,
))
elif layer.key[-5:] != "-text":
self.menu.items.append(MPMenuCheckbox(layer.key, layer.key, '# kml toggle \"' + layer.key + '\"', checked=False))
#and add the menu to the map popu menu
self.menu.items.append(MPMenuCheckbox(
layer.key,
layer.key,
'# kml toggle \"' + layer.key + '\"',
checked=False,
))
# and add the menu to the map popu menu
self.module('map').add_menu(self.menu)
self.menu_needs_refreshing = False

def mavlink_packet(self, m):
'''handle a mavlink packet'''


def init(mpstate):
'''initialise module'''
return KmlReadModule(mpstate)



0 comments on commit 0de7724

Please sign in to comment.