Go to the documentation of this file.00001
00002
00003 '''
00004 extract mavlink parameter values
00005 '''
00006
00007 import sys, time, os
00008
00009 from argparse import ArgumentParser
00010 parser = ArgumentParser(description=__doc__)
00011 parser.add_argument("-c", "--changes", dest="changesOnly", default=False, action="store_true", help="Show only changes to parameters.")
00012 parser.add_argument("logs", metavar="LOG", nargs="+")
00013
00014 args = parser.parse_args()
00015
00016 from pymavlink import mavutil
00017
00018 parms = {}
00019
00020 def mavparms(logfile):
00021 '''extract mavlink parameters'''
00022 mlog = mavutil.mavlink_connection(filename)
00023
00024 while True:
00025 try:
00026 m = mlog.recv_match(type=['PARAM_VALUE', 'PARM'])
00027 if m is None:
00028 return
00029 except Exception:
00030 return
00031 if m.get_type() == 'PARAM_VALUE':
00032 pname = str(m.param_id).strip()
00033 value = m.param_value
00034 else:
00035 pname = m.Name
00036 value = m.Value
00037 if len(pname) > 0:
00038 if args.changesOnly is True and pname in parms and parms[pname] != value:
00039 print("%s %-15s %.6f -> %.6f" % (time.asctime(time.localtime(m._timestamp)), pname, parms[pname], value))
00040
00041 parms[pname] = value
00042
00043 total = 0.0
00044 for filename in args.logs:
00045 mavparms(filename)
00046
00047 if (args.changesOnly is False):
00048 keys = parms.keys()
00049 keys.sort()
00050 for p in keys:
00051 print("%-15s %.6f" % (p, parms[p]))