@@ -34,6 +34,7 @@ def __init__(self, mpstate):
34
34
self .mission_list = None
35
35
self .moving_polygon_point = None
36
36
self .moving_circle = None
37
+ self .setting_circle_radius = None
37
38
self .icon_counter = 0
38
39
self .circle_counter = 0
39
40
self .draw_line = None
@@ -333,6 +334,12 @@ def polyfence_move_circle(self, id):
333
334
(seq , t ) = id .split (":" )
334
335
self .moving_circle = int (seq )
335
336
337
+ def polyfence_set_circle_radius (self , id ):
338
+ '''called when a fence is right-clicked and change-circle-radius is selected; next click sets the radius
339
+ '''
340
+ (seq , t ) = id .split (":" )
341
+ self .setting_circle_radius = int (seq )
342
+
336
343
def polyfence_remove_returnpoint (self , id ):
337
344
'''called when a returnpoint is right-clicked and remove is selected;
338
345
removes the return point
@@ -380,6 +387,7 @@ def display_polyfences_circles(self, circles, colour):
380
387
items = [
381
388
MPMenuItem ('Remove Circle' , returnkey = 'popupPolyFenceRemoveCircle' ),
382
389
MPMenuItem ('Move Circle' , returnkey = 'popupPolyFenceMoveCircle' ),
390
+ MPMenuItem ('Set Circle Radius w/click' , returnkey = 'popupPolyFenceSetCircleRadius' ),
383
391
]
384
392
popup = MPMenuSubMenu ('Popup' , items )
385
393
slipcircle = mp_slipmap .SlipCircle (
@@ -607,6 +615,8 @@ def handle_menu_event(self, obj):
607
615
self .polyfence_remove_circle (obj .selected [0 ].objkey )
608
616
elif menuitem .returnkey == 'popupPolyFenceMoveCircle' :
609
617
self .polyfence_move_circle (obj .selected [0 ].objkey )
618
+ elif menuitem .returnkey == 'popupPolyFenceSetCircleRadius' :
619
+ self .polyfence_set_circle_radius (obj .selected [0 ].objkey )
610
620
elif menuitem .returnkey == 'popupPolyFenceRemoveReturnPoint' :
611
621
self .polyfence_remove_returnpoint (obj .selected [0 ].objkey )
612
622
elif menuitem .returnkey == 'popupPolyFenceRemovePolygon' :
@@ -694,6 +704,17 @@ def map_callback(self, obj):
694
704
self .moving_circle = None
695
705
return
696
706
707
+ if obj .event .leftIsDown and self .setting_circle_radius is not None :
708
+ self .mpstate .click (obj .latlon )
709
+ seq = self .setting_circle_radius
710
+ self .mpstate .functions .process_stdin ("fence setcircleradius %u" % int (seq ))
711
+ self .setting_circle_radius = None
712
+ return
713
+ if obj .event .rightIsDown and self .setting_circle_radius is not None :
714
+ print ("Cancelled circle move" )
715
+ self .setting_circle_radius = None
716
+ return
717
+
697
718
def click_updated (self ):
698
719
'''called when the click position has changed'''
699
720
if self .map_settings .showclicktime == 0 :
0 commit comments