Skip to content

Commit dce61d6

Browse files
peterbarkertridge
authored andcommitted
map: add option to move circle
1 parent 3dcd287 commit dce61d6

File tree

1 file changed

+22
-0
lines changed

1 file changed

+22
-0
lines changed

MAVProxy/modules/mavproxy_map/__init__.py

+22
Original file line numberDiff line numberDiff line change
@@ -33,6 +33,7 @@ def __init__(self, mpstate):
3333
self.moving_rally = None
3434
self.mission_list = None
3535
self.moving_polygon_point = None
36+
self.moving_circle = None
3637
self.icon_counter = 0
3738
self.circle_counter = 0
3839
self.draw_line = None
@@ -325,6 +326,13 @@ def polyfence_remove_circle(self, id):
325326
(seq, type) = id.split(":")
326327
self.module('fence').removecircle(int(seq))
327328

329+
def polyfence_move_circle(self, id):
330+
'''called when a fence is right-clicked and move circle is selected; start
331+
moving the circle
332+
'''
333+
(seq, t) = id.split(":")
334+
self.moving_circle = int(seq)
335+
328336
def polyfence_remove_returnpoint(self, id):
329337
'''called when a returnpoint is right-clicked and remove is selected;
330338
removes the return point
@@ -371,6 +379,7 @@ def display_polyfences_circles(self, circles, colour):
371379
lng *= 1e-7
372380
items = [
373381
MPMenuItem('Remove Circle', returnkey='popupPolyFenceRemoveCircle'),
382+
MPMenuItem('Move Circle', returnkey='popupPolyFenceMoveCircle'),
374383
]
375384
popup = MPMenuSubMenu('Popup', items)
376385
slipcircle = mp_slipmap.SlipCircle(
@@ -596,6 +605,8 @@ def handle_menu_event(self, obj):
596605
self.move_fencepoint(obj.selected[0].objkey, obj.selected[0].extra_info)
597606
elif menuitem.returnkey == 'popupPolyFenceRemoveCircle':
598607
self.polyfence_remove_circle(obj.selected[0].objkey)
608+
elif menuitem.returnkey == 'popupPolyFenceMoveCircle':
609+
self.polyfence_move_circle(obj.selected[0].objkey)
599610
elif menuitem.returnkey == 'popupPolyFenceRemoveReturnPoint':
600611
self.polyfence_remove_returnpoint(obj.selected[0].objkey)
601612
elif menuitem.returnkey == 'popupPolyFenceRemovePolygon':
@@ -672,6 +683,17 @@ def map_callback(self, obj):
672683
time.time() - self.mpstate.click_time > 0.1):
673684
self.mpstate.click(obj.latlon)
674685

686+
if obj.event.leftIsDown and self.moving_circle is not None:
687+
self.mpstate.click(obj.latlon)
688+
seq = self.moving_circle
689+
self.mpstate.functions.process_stdin("fence movecircle %u" % int(seq))
690+
self.moving_circle = None
691+
return
692+
if obj.event.rightIsDown and self.moving_circle is not None:
693+
print("Cancelled circle move")
694+
self.moving_circle = None
695+
return
696+
675697
def click_updated(self):
676698
'''called when the click position has changed'''
677699
if self.map_settings.showclicktime == 0:

0 commit comments

Comments
 (0)