Skip to content

Commit f82fc33

Browse files
committed
map: added dropdown selection of frame to FlyTo
and remember previous frame and value
1 parent 3982d43 commit f82fc33

File tree

3 files changed

+95
-8
lines changed

3 files changed

+95
-8
lines changed

MAVProxy/modules/lib/mp_menu.py

Lines changed: 81 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -361,9 +361,6 @@ def call(self):
361361
'''show a value dialog'''
362362
from MAVProxy.modules.lib.wx_loader import wx
363363
title = self.title
364-
if title.find('FLYTOFRAMEUNITS') != -1 and self.settings is not None:
365-
frameunits = "%s %s" % (self.settings.flytoframe, self.settings.height_unit)
366-
title = title.replace('FLYTOFRAMEUNITS', frameunits)
367364
try:
368365
dlg = wx.TextEntryDialog(None, title, title, defaultValue=str(self.default))
369366
except TypeError:
@@ -372,6 +369,87 @@ def call(self):
372369
return None
373370
return dlg.GetValue()
374371

372+
# memory of last dropdowns
373+
last_dropdown_selection = {}
374+
last_value_selection = {}
375+
376+
class MPMenuCallTextDropdownDialog(object):
377+
'''used to create a value dialog with dropdown callback'''
378+
def __init__(self, title='Enter Value', default='',
379+
dropdown_options=None,
380+
dropdown_label='Select option',
381+
default_dropdown=None):
382+
self.title = title
383+
self.default = default
384+
self.default_dropdown = default_dropdown
385+
self.dropdown_options = dropdown_options or []
386+
self.dropdown_label = dropdown_label
387+
388+
def call(self):
389+
'''show a value dialog with dropdown'''
390+
from MAVProxy.modules.lib.wx_loader import wx
391+
392+
# Create a custom dialog
393+
dlg = wx.Dialog(None, title=self.title, size=(400, 150))
394+
395+
# Create a vertical box sizer for the dialog
396+
main_sizer = wx.BoxSizer(wx.VERTICAL)
397+
398+
# Create a horizontal sizer for the text entry and dropdown
399+
input_sizer = wx.BoxSizer(wx.HORIZONTAL)
400+
401+
# Text entry label and control
402+
text_label = wx.StaticText(dlg, label="Value:")
403+
default = last_value_selection.get(self.title, self.default)
404+
text_ctrl = wx.TextCtrl(dlg, value=str(default), size=(200, -1))
405+
406+
# Add text control components to input sizer
407+
input_sizer.Add(text_label, 0, wx.ALL | wx.ALIGN_CENTER_VERTICAL, 5)
408+
input_sizer.Add(text_ctrl, 1, wx.ALL | wx.EXPAND, 5)
409+
410+
# Dropdown label and control
411+
dropdown_label = wx.StaticText(dlg, label=self.dropdown_label)
412+
dropdown_ctrl = wx.Choice(dlg, choices=self.dropdown_options)
413+
414+
# Select first item by default if options exist
415+
if self.dropdown_options:
416+
default_idx = 0
417+
for i in range(len(self.dropdown_options)):
418+
if self.dropdown_options[i] == self.default_dropdown:
419+
default_idx = i
420+
dropdown_ctrl.SetSelection(last_dropdown_selection.get(self.title,default_idx))
421+
422+
# Add dropdown components to input sizer
423+
input_sizer.Add(dropdown_label, 0, wx.ALL | wx.ALIGN_CENTER_VERTICAL, 5)
424+
input_sizer.Add(dropdown_ctrl, 0, wx.ALL | wx.EXPAND, 5)
425+
426+
# Add the input sizer to the main sizer
427+
main_sizer.Add(input_sizer, 0, wx.ALL | wx.EXPAND, 5)
428+
429+
# Create button sizer with OK and Cancel buttons
430+
button_sizer = dlg.CreateButtonSizer(wx.OK | wx.CANCEL)
431+
main_sizer.Add(button_sizer, 0, wx.ALL | wx.ALIGN_CENTER, 10)
432+
433+
# Set the sizer for the dialog
434+
dlg.SetSizer(main_sizer)
435+
436+
# Fit the dialog to its contents
437+
dlg.Fit()
438+
439+
# Show the dialog and get the result
440+
if dlg.ShowModal() != wx.ID_OK:
441+
return None
442+
443+
text_value = text_ctrl.GetValue()
444+
dropdown_index = dropdown_ctrl.GetSelection()
445+
dropdown_value = self.dropdown_options[dropdown_index] if dropdown_index != -1 and self.dropdown_options else ""
446+
447+
last_dropdown_selection[self.title] = dropdown_index
448+
last_value_selection[self.title] = text_value
449+
450+
# Return tuple with text value and selected dropdown value
451+
return text_value + " " + dropdown_value
452+
375453
class MPMenuConfirmDialog(object):
376454
'''used to create a confirmation dialog'''
377455
def __init__(self, title='Confirmation', message='', callback=None, args=None):

MAVProxy/modules/mavproxy_map/__init__.py

Lines changed: 4 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -103,8 +103,10 @@ def __init__(self, mpstate):
103103

104104
self.default_popup = MPMenuSubMenu('Popup', items=[])
105105
self.add_menu(MPMenuItem('Fly To', 'Fly To', '# guided ',
106-
handler=MPMenuCallTextDialog(title='Altitude (FLYTOFRAMEUNITS)', default=self.mpstate.settings.guidedalt,
107-
settings=self.settings)))
106+
handler=MPMenuCallTextDropdownDialog(title='Altitude', default=self.mpstate.settings.guidedalt,
107+
dropdown_label='Frame',
108+
dropdown_options=['AboveHome','AGL','AMSL'],
109+
default_dropdown=self.settings.flytoframe)))
108110
self.add_menu(MPMenuItem('Terrain Check', 'Terrain Check', '# terrain check'))
109111
self.add_menu(MPMenuItem('Show Position', 'Show Position', 'showPosition'))
110112
self.add_menu(MPMenuItem('Google Maps Link', 'Google Maps Link', 'printGoogleMapsLink'))

MAVProxy/modules/mavproxy_mode.py

Lines changed: 10 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -81,10 +81,19 @@ def cmd_guided(self, args):
8181
if args[0] == "forward":
8282
return self.cmd_guided_forward(args[1:])
8383

84-
if len(args) != 1 and len(args) != 3:
84+
if len(args) == 2:
85+
frames = ['AboveHome', 'AGL', 'AMSL']
86+
if args[1] in frames:
87+
self.settings.flytoframe = args[1]
88+
else:
89+
print("Usage: guided ALTITUDE %s" % '|'.join(frames))
90+
return
91+
elif len(args) != 1 and len(args) != 3:
8592
print("Usage: guided ALTITUDE | guided LAT LON ALTITUDE | guided forward METRES")
8693
return
8794

95+
frame = self.flyto_frame()
96+
8897
if len(args) == 3:
8998
latitude = float(args[0])
9099
longitude = float(args[1])
@@ -99,8 +108,6 @@ def cmd_guided(self, args):
99108

100109
altitude = self.height_convert_from_units(altitude)
101110

102-
frame = self.flyto_frame()
103-
104111
print("Guided %s %s frame %u" % (str(latlon), str(altitude), frame))
105112

106113
if self.settings.guided_use_reposition:

0 commit comments

Comments
 (0)