Skip to content

Commit

Permalink
map: add options to change circle radii
Browse files Browse the repository at this point in the history
  • Loading branch information
peterbarker committed Feb 8, 2024
1 parent 830f678 commit fb468d3
Showing 1 changed file with 21 additions and 0 deletions.
21 changes: 21 additions & 0 deletions MAVProxy/modules/mavproxy_map/__init__.py
Original file line number Diff line number Diff line change
Expand Up @@ -34,6 +34,7 @@ def __init__(self, mpstate):
self.mission_list = None
self.moving_polygon_point = None
self.moving_circle = None
self.setting_circle_radius = None
self.icon_counter = 0
self.circle_counter = 0
self.draw_line = None
Expand Down Expand Up @@ -333,6 +334,12 @@ def polyfence_move_circle(self, id):
(seq, t) = id.split(":")
self.moving_circle = int(seq)

def polyfence_set_circle_radius(self, id):
'''called when a fence is right-clicked and change-circle-radius is selected; next click sets the radius
'''
(seq, t) = id.split(":")
self.setting_circle_radius = 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 @@ -380,6 +387,7 @@ def display_polyfences_circles(self, circles, colour):
items = [
MPMenuItem('Remove Circle', returnkey='popupPolyFenceRemoveCircle'),
MPMenuItem('Move Circle', returnkey='popupPolyFenceMoveCircle'),
MPMenuItem('Set Circle Radius w/click', returnkey='popupPolyFenceSetCircleRadius'),
]
popup = MPMenuSubMenu('Popup', items)
slipcircle = mp_slipmap.SlipCircle(
Expand Down Expand Up @@ -607,6 +615,8 @@ def handle_menu_event(self, obj):
self.polyfence_remove_circle(obj.selected[0].objkey)
elif menuitem.returnkey == 'popupPolyFenceMoveCircle':
self.polyfence_move_circle(obj.selected[0].objkey)
elif menuitem.returnkey == 'popupPolyFenceSetCircleRadius':
self.polyfence_set_circle_radius(obj.selected[0].objkey)
elif menuitem.returnkey == 'popupPolyFenceRemoveReturnPoint':
self.polyfence_remove_returnpoint(obj.selected[0].objkey)
elif menuitem.returnkey == 'popupPolyFenceRemovePolygon':
Expand Down Expand Up @@ -694,6 +704,17 @@ def map_callback(self, obj):
self.moving_circle = None
return

if obj.event.leftIsDown and self.setting_circle_radius is not None:
self.mpstate.click(obj.latlon)
seq = self.setting_circle_radius
self.mpstate.functions.process_stdin("fence setcircleradius %u" % int(seq))
self.setting_circle_radius = None
return
if obj.event.rightIsDown and self.setting_circle_radius is not None:
print("Cancelled circle move")
self.setting_circle_radius = 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 fb468d3

Please # to comment.