Skip to content

Commit

Permalink
map: add option to move circle
Browse files Browse the repository at this point in the history
  • Loading branch information
peterbarker authored and tridge committed Feb 28, 2024
1 parent 3dcd287 commit dce61d6
Showing 1 changed file with 22 additions and 0 deletions.
22 changes: 22 additions & 0 deletions MAVProxy/modules/mavproxy_map/__init__.py
Original file line number Diff line number Diff line change
Expand Up @@ -33,6 +33,7 @@ def __init__(self, mpstate):
self.moving_rally = None
self.mission_list = None
self.moving_polygon_point = None
self.moving_circle = None
self.icon_counter = 0
self.circle_counter = 0
self.draw_line = None
Expand Down Expand Up @@ -325,6 +326,13 @@ def polyfence_remove_circle(self, id):
(seq, type) = id.split(":")
self.module('fence').removecircle(int(seq))

def polyfence_move_circle(self, id):
'''called when a fence is right-clicked and move circle is selected; start
moving the circle
'''
(seq, t) = id.split(":")
self.moving_circle = int(seq)

def polyfence_remove_returnpoint(self, id):
'''called when a returnpoint is right-clicked and remove is selected;
removes the return point
Expand Down Expand Up @@ -371,6 +379,7 @@ def display_polyfences_circles(self, circles, colour):
lng *= 1e-7
items = [
MPMenuItem('Remove Circle', returnkey='popupPolyFenceRemoveCircle'),
MPMenuItem('Move Circle', returnkey='popupPolyFenceMoveCircle'),
]
popup = MPMenuSubMenu('Popup', items)
slipcircle = mp_slipmap.SlipCircle(
Expand Down Expand Up @@ -596,6 +605,8 @@ def handle_menu_event(self, obj):
self.move_fencepoint(obj.selected[0].objkey, obj.selected[0].extra_info)
elif menuitem.returnkey == 'popupPolyFenceRemoveCircle':
self.polyfence_remove_circle(obj.selected[0].objkey)
elif menuitem.returnkey == 'popupPolyFenceMoveCircle':
self.polyfence_move_circle(obj.selected[0].objkey)
elif menuitem.returnkey == 'popupPolyFenceRemoveReturnPoint':
self.polyfence_remove_returnpoint(obj.selected[0].objkey)
elif menuitem.returnkey == 'popupPolyFenceRemovePolygon':
Expand Down Expand Up @@ -672,6 +683,17 @@ def map_callback(self, obj):
time.time() - self.mpstate.click_time > 0.1):
self.mpstate.click(obj.latlon)

if obj.event.leftIsDown and self.moving_circle is not None:
self.mpstate.click(obj.latlon)
seq = self.moving_circle
self.mpstate.functions.process_stdin("fence movecircle %u" % int(seq))
self.moving_circle = None
return
if obj.event.rightIsDown and self.moving_circle is not None:
print("Cancelled circle move")
self.moving_circle = None
return

def click_updated(self):
'''called when the click position has changed'''
if self.map_settings.showclicktime == 0:
Expand Down

0 comments on commit dce61d6

Please # to comment.