Skip to content

Commit 3192cae

Browse files
peterbarkertridge
authored andcommitted
map: add options to change circle radii
1 parent 2578dbb commit 3192cae

File tree

1 file changed

+21
-0
lines changed

1 file changed

+21
-0
lines changed

Diff for: MAVProxy/modules/mavproxy_map/__init__.py

+21
Original file line numberDiff line numberDiff line change
@@ -34,6 +34,7 @@ def __init__(self, mpstate):
3434
self.mission_list = None
3535
self.moving_polygon_point = None
3636
self.moving_circle = None
37+
self.setting_circle_radius = None
3738
self.icon_counter = 0
3839
self.circle_counter = 0
3940
self.draw_line = None
@@ -333,6 +334,12 @@ def polyfence_move_circle(self, id):
333334
(seq, t) = id.split(":")
334335
self.moving_circle = int(seq)
335336

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+
336343
def polyfence_remove_returnpoint(self, id):
337344
'''called when a returnpoint is right-clicked and remove is selected;
338345
removes the return point
@@ -380,6 +387,7 @@ def display_polyfences_circles(self, circles, colour):
380387
items = [
381388
MPMenuItem('Remove Circle', returnkey='popupPolyFenceRemoveCircle'),
382389
MPMenuItem('Move Circle', returnkey='popupPolyFenceMoveCircle'),
390+
MPMenuItem('Set Circle Radius w/click', returnkey='popupPolyFenceSetCircleRadius'),
383391
]
384392
popup = MPMenuSubMenu('Popup', items)
385393
slipcircle = mp_slipmap.SlipCircle(
@@ -607,6 +615,8 @@ def handle_menu_event(self, obj):
607615
self.polyfence_remove_circle(obj.selected[0].objkey)
608616
elif menuitem.returnkey == 'popupPolyFenceMoveCircle':
609617
self.polyfence_move_circle(obj.selected[0].objkey)
618+
elif menuitem.returnkey == 'popupPolyFenceSetCircleRadius':
619+
self.polyfence_set_circle_radius(obj.selected[0].objkey)
610620
elif menuitem.returnkey == 'popupPolyFenceRemoveReturnPoint':
611621
self.polyfence_remove_returnpoint(obj.selected[0].objkey)
612622
elif menuitem.returnkey == 'popupPolyFenceRemovePolygon':
@@ -694,6 +704,17 @@ def map_callback(self, obj):
694704
self.moving_circle = None
695705
return
696706

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+
697718
def click_updated(self):
698719
'''called when the click position has changed'''
699720
if self.map_settings.showclicktime == 0:

0 commit comments

Comments
 (0)