mavlogdump.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 
00003 '''
00004 example program that dumps a Mavlink log file. The log file is
00005 assumed to be in the format that qgroundcontrol uses, which consists
00006 of a series of MAVLink packets, each with a 64 bit timestamp
00007 header. The timestamp is in microseconds since 1970 (unix epoch)
00008 '''
00009 
00010 import sys, time, os, struct, json
00011 
00012 from argparse import ArgumentParser
00013 parser = ArgumentParser(description=__doc__)
00014 
00015 parser.add_argument("--no-timestamps", dest="notimestamps", action='store_true', help="Log doesn't have timestamps")
00016 parser.add_argument("--planner", action='store_true', help="use planner file format")
00017 parser.add_argument("--robust", action='store_true', help="Enable robust parsing (skip over bad data)")
00018 parser.add_argument("-f", "--follow", action='store_true', help="keep waiting for more data at end of file")
00019 parser.add_argument("--condition", default=None, help="select packets by condition")
00020 parser.add_argument("-q", "--quiet", action='store_true', help="don't display packets")
00021 parser.add_argument("-o", "--output", default=None, help="output matching packets to give file")
00022 parser.add_argument("-p", "--parms", action='store_true', help="preserve parameters in output with -o")
00023 parser.add_argument("--format", default=None, help="Change the output format between 'standard', 'json', and 'csv'. For the CSV output, you must supply types that you want.")
00024 parser.add_argument("--csv_sep", dest="csv_sep", default=",", help="Select the delimiter between columns for the output CSV file. Use 'tab' to specify tabs. Only applies when --format=csv")
00025 parser.add_argument("--types", default=None, help="types of messages (comma separated)")
00026 parser.add_argument("--nottypes", default=None, help="types of messages not to include (comma separated)")
00027 parser.add_argument("--dialect", default="ardupilotmega", help="MAVLink dialect")
00028 parser.add_argument("--zero-time-base", action='store_true', help="use Z time base for DF logs")
00029 parser.add_argument("--no-bad-data", action='store_true', help="Don't output corrupted messages")
00030 parser.add_argument("log", metavar="LOG")
00031 args = parser.parse_args()
00032 
00033 import inspect
00034 
00035 from pymavlink import mavutil
00036 
00037 
00038 filename = args.log
00039 mlog = mavutil.mavlink_connection(filename, planner_format=args.planner,
00040                                   notimestamps=args.notimestamps,
00041                                   robust_parsing=args.robust,
00042                                   dialect=args.dialect,
00043                                   zero_time_base=args.zero_time_base)
00044 
00045 output = None
00046 if args.output:
00047     output = open(args.output, mode='wb')
00048 
00049 types = args.types
00050 if types is not None:
00051     types = types.split(',')
00052 
00053 nottypes = args.nottypes
00054 if nottypes is not None:
00055     nottypes = nottypes.split(',')
00056 
00057 ext = os.path.splitext(filename)[1]
00058 isbin = ext in ['.bin', '.BIN']
00059 islog = ext in ['.log', '.LOG']
00060 
00061 if args.csv_sep == "tab":
00062     args.csv_sep = "\t"
00063 
00064 # Write out a header row as we're outputting in CSV format.
00065 fields = ['timestamp']
00066 offsets = {}
00067 if args.format == 'csv':
00068     try:
00069         currentOffset = 1 # Store how many fields in we are for each message.
00070         for type in types:
00071             try:
00072                 typeClass = "MAVLink_{0}_message".format(type.lower())
00073                 fields += [type + '.' + x for x in inspect.getargspec(getattr(mavutil.mavlink, typeClass).__init__).args[1:]]
00074                 offsets[type] = currentOffset
00075                 currentOffset += len(fields)
00076             except IndexError:
00077                 quit()
00078     except TypeError:
00079         print("You must specify a list of message types if outputting CSV format via the --types argument.")
00080         exit()
00081 
00082     # The first line output are names for all columns
00083     print(','.join(fields))
00084 
00085 # Track the last timestamp value. Used for compressing data for the CSV output format.
00086 last_timestamp = None
00087 
00088 # Keep track of data from the current timestep. If the following timestep has the same data, it's stored in here as well. Output should therefore have entirely unique timesteps.
00089 csv_out = ["" for x in fields]
00090 while True:
00091     m = mlog.recv_match(blocking=args.follow)
00092     if m is None:
00093         # FIXME: Make sure to output the last CSV message before dropping out of this loop
00094         break
00095     if output is not None:
00096         if (isbin or islog) and m.get_type() == "FMT":
00097             output.write(m.get_msgbuf())
00098             continue
00099         if (isbin or islog) and (m.get_type() == "PARM" and args.parms):
00100             output.write(m.get_msgbuf())
00101             continue
00102         if m.get_type() == 'PARAM_VALUE' and args.parms:
00103             timestamp = getattr(m, '_timestamp', None)
00104             output.write(struct.pack('>Q', timestamp*1.0e6) + m.get_msgbuf())
00105             continue
00106     if not mavutil.evaluate_condition(args.condition, mlog.messages):
00107         continue
00108 
00109     if types is not None and m.get_type() not in types and m.get_type() != 'BAD_DATA':
00110         continue
00111 
00112     if nottypes is not None and m.get_type() in nottypes:
00113         continue
00114 
00115     # Ignore BAD_DATA messages is the user requested or if they're because of a bad prefix. The
00116     # latter case is normally because of a mismatched MAVLink version.
00117     if m.get_type() == 'BAD_DATA' and (args.no_bad_data is True or m.reason == "Bad prefix"):
00118         continue
00119 
00120     # Grab the timestamp.
00121     timestamp = getattr(m, '_timestamp', 0.0)
00122 
00123     # If we're just logging, pack in the timestamp and data into the output file.
00124     if output:
00125         if not (isbin or islog):
00126             output.write(struct.pack('>Q', timestamp*1.0e6))
00127         try:
00128             output.write(m.get_msgbuf())
00129         except Exception as ex:
00130             print("Failed to write msg %s" % m.get_type())
00131             pass
00132 
00133     # If quiet is specified, don't display output to the terminal.
00134     if args.quiet:
00135         continue
00136 
00137     # If JSON was ordered, serve it up. Split it nicely into metadata and data.
00138     if args.format == 'json':
00139         # Format our message as a Python dict, which gets us almost to proper JSON format
00140         data = m.to_dict()
00141 
00142         # Remove the mavpackettype value as we specify that later.
00143         del data['mavpackettype']
00144 
00145         # Also, if it's a BAD_DATA message, make it JSON-compatible by removing array objects
00146         if 'data' in data and type(data['data']) is not dict:
00147             data['data'] = list(data['data'])
00148 
00149         # Prepare the message as a single object with 'meta' and 'data' keys holding
00150         # the message's metadata and actual data respectively.
00151         outMsg = {"meta": {"type": m.get_type(), "timestamp": timestamp}, "data": data}
00152 
00153         # Now print out this object with stringified properly.
00154         print(json.dumps(outMsg))
00155     # CSV format outputs columnar data with a user-specified delimiter
00156     elif args.format == 'csv':
00157         data = m.to_dict()
00158         type = m.get_type()
00159 
00160         # If this message has a duplicate timestamp, copy its data into the existing data list. Also
00161         # do this if it's the first message encountered.
00162         if timestamp == last_timestamp or last_timestamp is None:
00163             newData = [str(data[y.split('.')[-1]]) if y.split('.')[0] == type and y.split('.')[-1] in data else "" for y in fields]
00164             for i, val in enumerate(newData):
00165                 if val:
00166                     csv_out[i] = val
00167 
00168         # Otherwise if this is a new timestamp, print out the old output data, and store the current message for later output.
00169         else:
00170             csv_out[0] = "{:.8f}".format(last_timestamp)
00171             print(args.csv_sep.join(csv_out))
00172             csv_out = [str(data[y.split('.')[-1]]) if y.split('.')[0] == type and y.split('.')[-1] in data else "" for y in fields]
00173     # Otherwise we output in a standard Python dict-style format
00174     else:
00175         print("%s.%02u: %s" % (
00176             time.strftime("%Y-%m-%d %H:%M:%S",
00177                           time.localtime(timestamp)),
00178                           int(timestamp*100.0)%100, m))
00179 
00180     # Update our last timestamp value.
00181     last_timestamp = timestamp
00182 


mavlink
Author(s): Lorenz Meier
autogenerated on Wed Sep 9 2015 18:06:17