Skip to content

Commit

Permalink
map: fixed menu on map with multiple objects
Browse files Browse the repository at this point in the history
when you right click and the position matches multiple objects then
check each of the objects rather than just the first one
  • Loading branch information
tridge committed Aug 10, 2023
1 parent 5d54d77 commit d039c8a
Show file tree
Hide file tree
Showing 4 changed files with 65 additions and 45 deletions.
39 changes: 24 additions & 15 deletions MAVProxy/modules/mavproxy_fence.py
Original file line number Diff line number Diff line change
Expand Up @@ -465,6 +465,27 @@ def is_circle_item(self, item):
mavutil.mavlink.MAV_CMD_NAV_FENCE_CIRCLE_INCLUSION,
]

def find_polygon_point(self, polygon_start_seq, item_offset):
'''find polygon point selected on map
returns first_item, item_offset
'''
first_item = self.wploader.item(polygon_start_seq)
if first_item is None:
print("No item at %u" % polygon_start_seq)
return None, None
if not self.is_polygon_item(first_item):
print("Item %u is not a polygon vertex" % polygon_start_seq)
return None, None
original_count = int(first_item.param1)
if item_offset == original_count:
# selecting closing point on polygon selects first point
item_offset = 0
if item_offset > original_count:
print("Out-of-range point")
return None, None

return first_item, item_offset

def removepolygon_point(self, polygon_start_seq, item_offset):
'''removes item at offset item_offset from the polygon starting at
polygon_start_seq'''
Expand All @@ -473,14 +494,10 @@ def removepolygon_point(self, polygon_start_seq, item_offset):

items_to_set = []

first_item = self.wploader.item(polygon_start_seq)
if not self.is_polygon_item(first_item):
print("Item %u is not a polygon vertex" % polygon_start_seq)
first_item, item_offset = self.find_polygon_point(polygon_start_seq, item_offset)
if first_item is None:
return
original_count = int(first_item.param1)
if item_offset >= original_count:
print("Out-of-range point")
return
if original_count <= 3:
print("Too few points to remove one")
return
Expand Down Expand Up @@ -610,16 +627,8 @@ def cmd_movepolypoint(self, args):
return
polygon_start_seq = int(args[0])
item_offset = int(args[1])
first_item = self.wploader.item(polygon_start_seq)
first_item, item_offset = self.find_polygon_point(polygon_start_seq, item_offset)
if first_item is None:
print("No item at %u" % polygon_start_seq)
return
if not self.is_polygon_item(first_item):
print("Item %u is not a polygon vertex" % polygon_start_seq)
return
original_count = int(first_item.param1)
if item_offset >= original_count:
print("Out-of-range point")
return

latlon = self.mpstate.click_location
Expand Down
10 changes: 5 additions & 5 deletions MAVProxy/modules/mavproxy_map/__init__.py
Original file line number Diff line number Diff line change
Expand Up @@ -258,14 +258,14 @@ def display_waypoints(self):
self.mission_list = self.module('wp').wploader.view_list()
polygons = self.module('wp').wploader.polygon_list()
self.map.add_object(mp_slipmap.SlipClearLayer('Mission'))
items = [MPMenuItem('WP Set', returnkey='popupMissionSet'),
MPMenuItem('WP Remove', returnkey='popupMissionRemove'),
MPMenuItem('WP Move', returnkey='popupMissionMove'),
MPMenuItem('WP Split', returnkey='popupMissionSplit'),
]
for i in range(len(polygons)):
p = polygons[i]
if len(p) > 1:
items = [MPMenuItem('WP Set', returnkey='popupMissionSet'),
MPMenuItem('WP Remove', returnkey='popupMissionRemove'),
MPMenuItem('WP Move', returnkey='popupMissionMove'),
MPMenuItem('WP Split', returnkey='popupMissionSplit'),
]
popup = MPMenuSubMenu('Popup', items)
self.map.add_object(mp_slipmap.SlipPolygon('mission %u' % i, p,
layer='Mission', linewidth=2, colour=(255,255,255),
Expand Down
53 changes: 29 additions & 24 deletions MAVProxy/modules/mavproxy_map/mp_slipmap_ui.py
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,7 @@
import numpy as np
import os
import time
import copy

from ..lib.wx_loader import wx

Expand Down Expand Up @@ -55,7 +56,7 @@ def __init__(self, state):
state.grid = True
state.follow = True
state.download = True
state.popup_object = None
state.popup_objects = None
state.popup_latlon = None
state.popup_started = False
state.default_popup = None
Expand Down Expand Up @@ -110,16 +111,17 @@ def on_menu(self, event):
'''handle menu selection'''
state = self.state
# see if it is a popup menu
if state.popup_object is not None:
obj = state.popup_object
ret = obj.popup_menu.find_selected(event)
if ret is not None:
ret.call_handler()
state.event_queue.put(SlipMenuEvent(state.popup_latlon, event,
[SlipObjectSelection(obj.key, 0, obj.layer, obj.selection_info())],
ret))
state.popup_object = None
state.popup_latlon = None
if state.popup_objects is not None:
for obj in state.popup_objects:
ret = obj.popup_menu.find_selected(event)
if ret is not None:
ret.call_handler()
state.event_queue.put(SlipMenuEvent(state.popup_latlon, event,
[SlipObjectSelection(obj.key, 0, obj.layer, obj.selection_info())],
ret))
break
state.popup_objects = None
state.popup_latlon = None
if state.default_popup is not None:
ret = state.default_popup.popup.find_selected(event)
if ret is not None:
Expand Down Expand Up @@ -614,18 +616,21 @@ def selected_objects(self, pos):
selected.sort(key=lambda c: c.distance)
return selected

def show_popup(self, selected, pos):
def show_popup(self, objs, pos):
'''show popup menu for an object'''
state = self.state
if selected.popup_menu is not None:
import copy
popup_menu = selected.popup_menu
if state.default_popup is not None and state.default_popup.combine:
popup_menu = None
popups = [ p.popup_menu for p in objs ]
if state.default_popup is not None and state.default_popup.combine:
popups.append(state.default_popup.popup)
popup_menu = popups[0]
if len(popups) > 1:
for p in popups[1:]:
popup_menu = copy.deepcopy(popup_menu)
popup_menu.add(MPMenuSeparator())
popup_menu.combine(state.default_popup.popup)
wx_menu = popup_menu.wx_menu()
state.frame.PopupMenu(wx_menu, pos)
popup_menu.combine(p)
wx_menu = popup_menu.wx_menu()
state.frame.PopupMenu(wx_menu, pos)

def show_default_popup(self, pos):
'''show default popup menu'''
Expand Down Expand Up @@ -659,14 +664,14 @@ def on_mouse(self, event):
selected = self.selected_objects(pos)
state.event_queue.put(SlipMouseEvent(latlon, event, selected))
if event.RightDown():
state.popup_object = None
state.popup_objects = None
state.popup_latlon = None
if len(selected) > 0:
obj = state.layers[selected[0].layer][selected[0].objkey]
if obj.popup_menu is not None:
state.popup_object = obj
objs = [ state.layers[s.layer][s.objkey] for s in selected if state.layers[s.layer][s.objkey].popup_menu is not None ]
if len(objs) > 0:
state.popup_objects = objs
state.popup_latlon = latlon
self.show_popup(obj, pos)
self.show_popup(objs, pos)
state.popup_started = True
if not state.popup_started and state.default_popup is not None:
state.popup_latlon = latlon
Expand Down
8 changes: 7 additions & 1 deletion MAVProxy/modules/mavproxy_map/mp_slipmap_util.py
Original file line number Diff line number Diff line change
Expand Up @@ -282,7 +282,13 @@ def clicked(self, px, py):
'''
if self.hidden:
return None
for i in range(len(self._pix_points)):
num_points = len(self._pix_points)
if num_points <= 0:
return None
for idx in range(num_points):
# the odd ordering here is to that the home point, which is index 0, is checked last
# as home cannot be moved
i = (idx+1) % num_points
if self._pix_points[i] is None:
continue
(pixx,pixy) = self._pix_points[i]
Expand Down

0 comments on commit d039c8a

Please sign in to comment.