Skip to content

Option --no_param_auto_fetch to only fetch params on request. Preload added to menu. #939

New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Open
wants to merge 1 commit into
base: master
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 2 additions & 0 deletions MAVProxy/mavproxy.py
Original file line number Diff line number Diff line change
Expand Up @@ -1236,6 +1236,7 @@ def set_mav_version(mav10, mav20, autoProtocol, mavversionArg):
parser.add_option("--mavversion", type='choice', choices=['1.0', '2.0'] , help="Force MAVLink Version (1.0, 2.0). Otherwise autodetect version")
parser.add_option("--nowait", action='store_true', default=False, help="don't wait for HEARTBEAT on startup")
parser.add_option("-c", "--continue", dest='continue_mode', action='store_true', default=False, help="continue logs")
parser.add_option("--no_auto_fetch", dest='params_auto_fetch', action='store_false', default=True, help="Do not auto fetch parameters on vehicle detect")
parser.add_option("--dialect", default="ardupilotmega", help="MAVLink dialect")
parser.add_option("--rtscts", action='store_true', help="enable hardware RTS/CTS flow control")
parser.add_option("--moddebug", type=int, help="module debug level", default=0)
Expand Down Expand Up @@ -1282,6 +1283,7 @@ def set_mav_version(mav10, mav20, autoProtocol, mavversionArg):
mpstate.status.exit = False
mpstate.command_map = command_map
mpstate.continue_mode = opts.continue_mode
mpstate.params_auto_fetch = opts.params_auto_fetch
# queues for logging
mpstate.logqueue = Queue.Queue()
mpstate.logqueue_raw = Queue.Queue()
Expand Down
35 changes: 32 additions & 3 deletions MAVProxy/modules/mavproxy_param.py
Original file line number Diff line number Diff line change
Expand Up @@ -19,11 +19,17 @@
class ParamState:
'''this class is separated to make it possible to use the parameter
functions on a secondary connection'''
IDLE = 0
FETCHING_ALL = 1
FETCHING_ONE = 2

def __init__(self, mav_param, logdir, vehicle_name, parm_file, mpstate, sysid):
self.fetch_state = ParamState.IDLE
self.mav_param_set = set()
self.mav_param_count = 0
self.param_period = mavutil.periodic_event(1)
self.fetch_one = dict()
self.preloaded = set()
self.mav_param = mav_param
self.logdir = logdir
self.vehicle_name = vehicle_name
Expand Down Expand Up @@ -93,6 +99,7 @@ def handle_mavlink_packet(self, master, m):
# Note: the xml specifies param_index is a uint16, so -1 in that field will show as 65535
# We accept both -1 and 65535 as 'unknown index' to future proof us against someday having that
# xml fixed.
self.preloaded.discard(m.param_id)
if self.fetch_set is not None:
self.fetch_set.discard(m.param_index)
if m.param_index != -1 and m.param_index != 65535 and m.param_index not in self.mav_param_set:
Expand All @@ -110,6 +117,7 @@ def handle_mavlink_packet(self, master, m):
else:
print("%s = %s" % (param_id, str(value)))
if added_new_parameter and len(self.mav_param_set) == m.param_count:
self.fetch_state = ParamState.IDLE
print("Received %u parameters" % m.param_count)
if self.logdir is not None:
self.mav_param.save(os.path.join(self.logdir, self.parm_file), '*', verbose=True)
Expand All @@ -126,23 +134,25 @@ def fetch_check(self, master, force=False):
if self.param_period.trigger() or force:
if master is None:
return
if len(self.mav_param_set) == 0 and not self.ftp_started:
if len(self.mav_param_set) == 0 and not self.ftp_started and (self.mpstate.params_auto_fetch or not self.fetch_state == ParamState.IDLE):
if not self.use_ftp():
master.param_fetch_all()
else:
self.ftp_start()
elif not self.ftp_started and self.mav_param_count != 0 and len(self.mav_param_set) != self.mav_param_count:
self.fetch_state = ParamState.FETCHING_ALL
elif not self.ftp_started and self.mav_param_count != 0 and (len(self.mav_param_set) != self.mav_param_count) and (self.mpstate.params_auto_fetch or not self.fetch_state == ParamState.IDLE):
if master.time_since('PARAM_VALUE') >= 1 or force:
diff = set(range(self.mav_param_count)).difference(self.mav_param_set)
count = 0
while len(diff) > 0 and count < 10:
idx = diff.pop()
master.param_fetch_one(idx)
self.fetch_state = ParamState.FETCHING_ONE
if self.fetch_set is None:
self.fetch_set = set()
self.fetch_set.add(idx)
count += 1

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Extra whitespace needs to be removed

def param_use_xml_filepath(self, filepath):
self.param_help.xml_filepath = filepath

Expand All @@ -162,6 +172,7 @@ def ftp_start(self):
self.ftp_started = True
self.ftp_count = None
ftp.cmd_get(["@PARAM/param.pck"], callback=self.ftp_callback, callback_progress=self.ftp_callback_progress)
self.fetch_state = ParamState.FETCHING_ALL

def log_params(self, params):
'''log PARAM_VALUE messages so that we can extract parameters from a tlog when using ftp download'''
Expand Down Expand Up @@ -213,6 +224,8 @@ def ftp_callback_progress(self, fh, total_size):
def ftp_callback(self, fh):
'''callback from ftp fetch of parameters'''
self.ftp_started = False
self.fetch_state = ParamState.IDLE

if fh is None:
# the fetch failed
self.ftp_failed = True
Expand Down Expand Up @@ -277,6 +290,7 @@ def ftp_callback(self, fh):
return
self.param_types = {}
self.mav_param_set = set()
self.preloaded = set()
self.fetch_one = dict()
self.fetch_set = None
self.mav_param.clear()
Expand Down Expand Up @@ -305,6 +319,7 @@ def fetch_all(self, master):
self.mav_param_set = set()
else:
self.ftp_start()
self.fetch_state = ParamState.FETCHING_ALL

def handle_command(self, master, mpstate, args):
'''handle parameter commands'''
Expand All @@ -320,25 +335,29 @@ def handle_command(self, master, mpstate, args):
print("Requested parameter list (ftp)")
else:
print("Requested parameter list")
self.fetch_state = ParamState.FETCHING_ALL
else:
found = False
pname = args[1].upper()
for p in self.mav_param.keys():
if fnmatch.fnmatch(p, pname):
master.param_fetch_one(p)
self.fetch_state = ParamState.FETCHING_ONE
if p not in self.fetch_one:
self.fetch_one[p] = 0
self.fetch_one[p] += 1
found = True
print("Requested parameter %s" % p)
if not found and args[1].find('*') == -1:
master.param_fetch_one(pname)
self.fetch_state = ParamState.FETCHING_ONE
if pname not in self.fetch_one:
self.fetch_one[pname] = 0
self.fetch_one[pname] += 1
print("Requested parameter %s" % pname)
elif args[0] == "ftp":
self.ftp_start()
self.fetch_state = ParamState.FETCHING_ALL

elif args[0] == "save":
if len(args) < 2:
Expand Down Expand Up @@ -402,11 +421,15 @@ def handle_command(self, master, mpstate, args):
else:
param_wildcard = "*"
self.mav_param.load(args[1].strip('"'), param_wildcard, master)
self.fetch_state = ParamState.LOADED
elif args[0] == "preload":
if len(args) < 2:
print("Usage: param preload <filename>")
return
self.mav_param.load(args[1].strip('"'))
self.preloaded = set()
for param_name in self.mav_param.keys():
self.preloaded.add(param_name)
elif args[0] == "forceload":
if len(args) < 2:
print("Usage: param forceload <filename> [wildcard]")
Expand All @@ -416,6 +439,7 @@ def handle_command(self, master, mpstate, args):
else:
param_wildcard = "*"
self.mav_param.load(args[1].strip('"'), param_wildcard, master, check=False)
self.fetch_state = ParamState.FORCE_LOADED
elif args[0] == "ftpload":
if len(args) < 2:
print("Usage: param ftpload <filename> [wildcard]")
Expand All @@ -425,6 +449,7 @@ def handle_command(self, master, mpstate, args):
else:
param_wildcard = "*"
self.ftp_load(args[1].strip('"'), param_wildcard, master)
self.fetch_state = ParamState.LOADED
elif args[0] == "download":
self.param_help.param_help_download()
elif args[0] == "apropos":
Expand Down Expand Up @@ -573,6 +598,10 @@ def __init__(self, mpstate, **kwargs):
handler=MPMenuCallFileDialog(flags=('open',),
title='Param Load',
wildcard='ParmFiles(*.parm,*.param)|*.parm;*.param')),
MPMenuItem('Preload', 'Preload', '# param preload ',
handler=MPMenuCallFileDialog(flags=('open',),
title='Param Preload',
wildcard='ParmFiles(*.parm,*.param)|*.parm;*.param')),
MPMenuItem('Save', 'Save', '# param save ',
handler=MPMenuCallFileDialog(flags=('save', 'overwrite_prompt'),
title='Param Save',
Expand Down