Go to the documentation of this file.00001
00002
00003 '''
00004 convert a MAVLink tlog file to a MATLab mfile
00005 '''
00006
00007 import sys, os
00008 import re
00009 from pymavlink import mavutil
00010
00011 def process_tlog(filename):
00012 '''convert a tlog to a .m file'''
00013
00014 print("Processing %s" % filename)
00015
00016 mlog = mavutil.mavlink_connection(filename, dialect=args.dialect, zero_time_base=True)
00017
00018
00019
00020 msg_types = {}
00021 msg_lists = {}
00022
00023 types = args.types
00024 if types is not None:
00025 types = types.split(',')
00026
00027
00028 (head, tail) = os.path.split(filename)
00029 basename = '.'.join(tail.split('.')[:-1])
00030 mfilename = re.sub('[\.\-\+\*]','_', basename) + '.m'
00031
00032 if (re.match('^[a-zA-z]', mfilename) == None):
00033 mfilename = 'm_' + mfilename
00034
00035 if head is not None:
00036 mfilename = os.path.join(head, mfilename)
00037 print("Creating %s" % mfilename)
00038
00039 f = open(mfilename, "w")
00040
00041 type_counters = {}
00042
00043 while True:
00044 m = mlog.recv_match(condition=args.condition)
00045 if m is None:
00046 break
00047
00048 if types is not None and m.get_type() not in types:
00049 continue
00050 if m.get_type() == 'BAD_DATA':
00051 continue
00052
00053 fieldnames = m._fieldnames
00054 mtype = m.get_type()
00055 if mtype in ['FMT', 'PARM']:
00056 continue
00057
00058 if mtype not in type_counters:
00059 type_counters[mtype] = 0
00060 f.write("%s.columns = {'timestamp'" % mtype)
00061 for field in fieldnames:
00062 val = getattr(m, field)
00063 if not isinstance(val, str):
00064 if type(val) is not list:
00065 f.write(",'%s'" % field)
00066 else:
00067 for i in range(0, len(val)):
00068 f.write(",'%s%d'" % (field, i + 1))
00069 f.write("};\n")
00070
00071 type_counters[mtype] += 1
00072 f.write("%s.data(%u,:) = [%f" % (mtype, type_counters[mtype], m._timestamp))
00073 for field in m._fieldnames:
00074 val = getattr(m, field)
00075 if not isinstance(val, str):
00076 if type(val) is not list:
00077 f.write(",%.20g" % val)
00078 else:
00079 for i in range(0, len(val)):
00080 f.write(",%.20g" % val[i])
00081 f.write("];\n")
00082 f.close()
00083
00084 from argparse import ArgumentParser
00085 parser = ArgumentParser(description=__doc__)
00086
00087 parser.add_argument("--condition", default=None, help="select packets by condition")
00088 parser.add_argument("-o", "--output", default=None, help="output filename")
00089 parser.add_argument("--types", default=None, help="types of messages (comma separated)")
00090 parser.add_argument("--dialect", default="ardupilotmega", help="MAVLink dialect")
00091 parser.add_argument("logs", metavar="LOG", nargs="+")
00092 args = parser.parse_args()
00093
00094
00095 for filename in args.logs:
00096 process_tlog(filename)