@@ -33,6 +33,7 @@ def __init__(self, mpstate):
33
33
self .moving_rally = None
34
34
self .mission_list = None
35
35
self .moving_polygon_point = None
36
+ self .moving_circle = None
36
37
self .icon_counter = 0
37
38
self .circle_counter = 0
38
39
self .draw_line = None
@@ -325,6 +326,13 @@ def polyfence_remove_circle(self, id):
325
326
(seq , type ) = id .split (":" )
326
327
self .module ('fence' ).removecircle (int (seq ))
327
328
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
+
328
336
def polyfence_remove_returnpoint (self , id ):
329
337
'''called when a returnpoint is right-clicked and remove is selected;
330
338
removes the return point
@@ -371,6 +379,7 @@ def display_polyfences_circles(self, circles, colour):
371
379
lng *= 1e-7
372
380
items = [
373
381
MPMenuItem ('Remove Circle' , returnkey = 'popupPolyFenceRemoveCircle' ),
382
+ MPMenuItem ('Move Circle' , returnkey = 'popupPolyFenceMoveCircle' ),
374
383
]
375
384
popup = MPMenuSubMenu ('Popup' , items )
376
385
slipcircle = mp_slipmap .SlipCircle (
@@ -596,6 +605,8 @@ def handle_menu_event(self, obj):
596
605
self .move_fencepoint (obj .selected [0 ].objkey , obj .selected [0 ].extra_info )
597
606
elif menuitem .returnkey == 'popupPolyFenceRemoveCircle' :
598
607
self .polyfence_remove_circle (obj .selected [0 ].objkey )
608
+ elif menuitem .returnkey == 'popupPolyFenceMoveCircle' :
609
+ self .polyfence_move_circle (obj .selected [0 ].objkey )
599
610
elif menuitem .returnkey == 'popupPolyFenceRemoveReturnPoint' :
600
611
self .polyfence_remove_returnpoint (obj .selected [0 ].objkey )
601
612
elif menuitem .returnkey == 'popupPolyFenceRemovePolygon' :
@@ -672,6 +683,17 @@ def map_callback(self, obj):
672
683
time .time () - self .mpstate .click_time > 0.1 ):
673
684
self .mpstate .click (obj .latlon )
674
685
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
+
675
697
def click_updated (self ):
676
698
'''called when the click position has changed'''
677
699
if self .map_settings .showclicktime == 0 :
0 commit comments