Go to the documentation of this file.00001 
00002 
00003 '''
00004 extract one mode type from a log
00005 '''
00006 
00007 import sys, time, os, struct
00008 
00009 from argparse import ArgumentParser
00010 parser = ArgumentParser(description=__doc__)
00011 
00012 parser.add_argument("--no-timestamps", dest="notimestamps", action='store_true', help="Log doesn't have timestamps")
00013 parser.add_argument("--robust", action='store_true', help="Enable robust parsing (skip over bad data)")
00014 parser.add_argument("--condition", default=None, help="select packets by condition")
00015 parser.add_argument("--mode", default='auto', help="mode to extract")
00016 parser.add_argument("logs", metavar="LOG", nargs="+")
00017 args = parser.parse_args()
00018 
00019 from pymavlink import mavutil
00020 
00021 
00022 def process(filename):
00023     '''process one logfile'''
00024     print("Processing %s" % filename)
00025     mlog = mavutil.mavlink_connection(filename, notimestamps=args.notimestamps,
00026                                       robust_parsing=args.robust)
00027 
00028 
00029     ext = os.path.splitext(filename)[1]
00030     isbin = ext in ['.bin', '.BIN']
00031     islog = ext in ['.log', '.LOG']
00032     output = None
00033     count = 1
00034     dirname = os.path.dirname(filename)
00035 
00036     if isbin or islog:
00037         extension = "bin"
00038     else:
00039         extension = "tlog"
00040 
00041     file_header = ''
00042 
00043     while True:
00044         m = mlog.recv_match()
00045         if m is None:
00046             break
00047         if (isbin or islog) and m.get_type() in ["FMT", "PARM", "CMD"]:
00048             file_header += m.get_msgbuf()
00049         if (isbin or islog) and m.get_type() == 'MSG' and m.Message.startswith("Ardu"):
00050             file_header += m.get_msgbuf()
00051         if m.get_type() in ['PARAM_VALUE','MISSION_ITEM']:
00052             timestamp = getattr(m, '_timestamp', None)
00053             file_header += struct.pack('>Q', timestamp*1.0e6) + m.get_msgbuf()
00054 
00055         if not mavutil.evaluate_condition(args.condition, mlog.messages):
00056             continue
00057 
00058         if mlog.flightmode.upper() == args.mode.upper():
00059             if output is None:
00060                 path = os.path.join(dirname, "%s%u.%s" % (args.mode, count, extension))
00061                 count += 1
00062                 print("Creating %s" % path)
00063                 output = open(path, mode='wb')
00064                 output.write(file_header)
00065         else:
00066             if output is not None:
00067                 output.close()
00068                 output = None
00069 
00070         if output and m.get_type() != 'BAD_DATA':
00071             timestamp = getattr(m, '_timestamp', None)
00072             if not isbin:
00073                 output.write(struct.pack('>Q', timestamp*1.0e6))
00074             output.write(m.get_msgbuf())
00075 
00076 for filename in args.logs:
00077     process(filename)
00078