mavlogdump.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 
3 '''
4 example program that dumps a Mavlink log file. The log file is
5 assumed to be in the format that qgroundcontrol uses, which consists
6 of a series of MAVLink packets, each with a 64 bit timestamp
7 header. The timestamp is in microseconds since 1970 (unix epoch)
8 '''
9 from __future__ import print_function
10 
11 import fnmatch
12 import json
13 import os
14 import struct
15 import time
16 
17 try:
18  from pymavlink.mavextra import *
19 except:
20  print("WARNING: Numpy missing, mathematical notation will not be supported..")
21 
22 from argparse import ArgumentParser
23 parser = ArgumentParser(description=__doc__)
24 
25 parser.add_argument("--no-timestamps", dest="notimestamps", action='store_true', help="Log doesn't have timestamps")
26 parser.add_argument("--planner", action='store_true', help="use planner file format")
27 parser.add_argument("--robust", action='store_true', help="Enable robust parsing (skip over bad data)")
28 parser.add_argument("-f", "--follow", action='store_true', help="keep waiting for more data at end of file")
29 parser.add_argument("--condition", default=None, help="select packets by condition")
30 parser.add_argument("-q", "--quiet", action='store_true', help="don't display packets")
31 parser.add_argument("-o", "--output", default=None, help="output matching packets to give file")
32 parser.add_argument("-p", "--parms", action='store_true', help="preserve parameters in output with -o")
33 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.")
34 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")
35 parser.add_argument("--types", default=None, help="types of messages (comma separated with wildcard)")
36 parser.add_argument("--nottypes", default=None, help="types of messages not to include (comma separated with wildcard)")
37 parser.add_argument("--dialect", default="ardupilotmega", help="MAVLink dialect")
38 parser.add_argument("--zero-time-base", action='store_true', help="use Z time base for DF logs")
39 parser.add_argument("--no-bad-data", action='store_true', help="Don't output corrupted messages")
40 parser.add_argument("--show-source", action='store_true', help="Show source system ID and component ID")
41 parser.add_argument("--show-seq", action='store_true', help="Show sequence numbers")
42 parser.add_argument("--show-types", action='store_true', help="Shows all message types available on opened log")
43 parser.add_argument("--source-system", type=int, default=None, help="filter by source system ID")
44 parser.add_argument("--source-component", type=int, default=None, help="filter by source component ID")
45 parser.add_argument("--link", type=int, default=None, help="filter by comms link ID")
46 parser.add_argument("--mav10", action='store_true', help="parse as MAVLink1")
47 parser.add_argument("log", metavar="LOG")
48 args = parser.parse_args()
49 
50 if not args.mav10:
51  os.environ['MAVLINK20'] = '1'
52 
53 import inspect
54 
55 from pymavlink import mavutil
56 
57 
58 
59 filename = args.log
60 mlog = mavutil.mavlink_connection(filename, planner_format=args.planner,
61  notimestamps=args.notimestamps,
62  robust_parsing=args.robust,
63  dialect=args.dialect,
64  zero_time_base=args.zero_time_base)
65 
66 output = None
67 if args.output:
68  output = open(args.output, mode='wb')
69 
70 types = args.types
71 if types is not None:
72  types = types.split(',')
73 
74 nottypes = args.nottypes
75 if nottypes is not None:
76  nottypes = nottypes.split(',')
77 
78 ext = os.path.splitext(filename)[1]
79 isbin = ext in ['.bin', '.BIN', '.px4log']
80 islog = ext in ['.log', '.LOG'] # NOTE: "islog" does not mean a tlog
81 istlog = ext in ['.tlog', '.TLOG']
82 
83 if args.csv_sep == "tab":
84  args.csv_sep = "\t"
85 
86 def match_type(mtype, patterns):
87  '''return True if mtype matches pattern'''
88  for p in patterns:
89  if fnmatch.fnmatch(mtype, p):
90  return True
91  return False
92 
93 # Write out a header row as we're outputting in CSV format.
94 fields = ['timestamp']
95 offsets = {}
96 if istlog and args.format == 'csv': # we know our fields from the get-go
97  try:
98  currentOffset = 1 # Store how many fields in we are for each message.
99  for type in types:
100  try:
101  typeClass = "MAVLink_{0}_message".format(type.lower())
102  fields += [type + '.' + x for x in inspect.getargspec(getattr(mavutil.mavlink, typeClass).__init__).args[1:]]
103  offsets[type] = currentOffset
104  currentOffset += len(fields)
105  except IndexError:
106  quit()
107  except TypeError:
108  print("You must specify a list of message types if outputting CSV format via the --types argument.")
109  exit()
110 
111  # The first line output are names for all columns
112  csv_out = ["" for x in fields]
113  print(args.csv_sep.join(fields))
114 
115 if isbin and args.format == 'csv': # need to accumulate columns from message
116  if types is None or len(types) != 1:
117  print("Need exactly one type when dumping CSV from bin file")
118  quit()
119 
120 # Track the last timestamp value. Used for compressing data for the CSV output format.
121 last_timestamp = None
122 
123 # Track types found
124 available_types = set()
125 
126 # for DF logs pre-calculate types list
127 match_types=None
128 if types is not None and hasattr(mlog, 'name_to_id'):
129  for k in mlog.name_to_id.keys():
130  if match_type(k, types):
131  if nottypes is not None and match_type(k, nottypes):
132  continue
133  if match_types is None:
134  match_types = []
135  match_types.append(k)
136 
137 # 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.
138 while True:
139  m = mlog.recv_match(blocking=args.follow, type=match_types)
140  if m is None:
141  # FIXME: Make sure to output the last CSV message before dropping out of this loop
142  break
143  available_types.add(m.get_type())
144  if isbin and m.get_type() == "FMT" and args.format == 'csv':
145  if m.Name == types[0]:
146  fields += m.Columns.split(',')
147  csv_out = ["" for x in fields]
148  print(args.csv_sep.join(fields))
149 
150  if output is not None:
151  if (isbin or islog) and m.get_type() == "FMT":
152  output.write(m.get_msgbuf())
153  continue
154  if (isbin or islog) and (m.get_type() == "PARM" and args.parms):
155  output.write(m.get_msgbuf())
156  continue
157  if m.get_type() == 'PARAM_VALUE' and args.parms:
158  timestamp = getattr(m, '_timestamp', None)
159  output.write(struct.pack('>Q', int(timestamp*1.0e6)) + m.get_msgbuf())
160  continue
161 
162  if not mavutil.evaluate_condition(args.condition, mlog.messages):
163  continue
164  if args.source_system is not None and args.source_system != m.get_srcSystem():
165  continue
166  if args.source_component is not None and args.source_component != m.get_srcComponent():
167  continue
168  if args.link is not None and args.link != m._link:
169  continue
170 
171  if types is not None and m.get_type() != 'BAD_DATA' and not match_type(m.get_type(), types):
172  continue
173 
174  if nottypes is not None and match_type(m.get_type(), nottypes):
175  continue
176 
177  # Ignore BAD_DATA messages is the user requested or if they're because of a bad prefix. The
178  # latter case is normally because of a mismatched MAVLink version.
179  if m.get_type() == 'BAD_DATA' and (args.no_bad_data is True or m.reason == "Bad prefix"):
180  continue
181 
182  # Grab the timestamp.
183  timestamp = getattr(m, '_timestamp', 0.0)
184 
185  # If we're just logging, pack in the timestamp and data into the output file.
186  if output:
187  if not (isbin or islog):
188  output.write(struct.pack('>Q', int(timestamp*1.0e6)))
189  try:
190  output.write(m.get_msgbuf())
191  except Exception as ex:
192  print("Failed to write msg %s: %s" % (m.get_type(), str(ex)))
193 
194  # If quiet is specified, don't display output to the terminal.
195  if args.quiet:
196  continue
197 
198  # If JSON was ordered, serve it up. Split it nicely into metadata and data.
199  if args.format == 'json':
200  # Format our message as a Python dict, which gets us almost to proper JSON format
201  data = m.to_dict()
202 
203  # Remove the mavpackettype value as we specify that later.
204  del data['mavpackettype']
205 
206  # Also, if it's a BAD_DATA message, make it JSON-compatible by removing array objects
207  if 'data' in data and type(data['data']) is not dict:
208  data['data'] = list(data['data'])
209 
210  # Prepare the message as a single object with 'meta' and 'data' keys holding
211  # the message's metadata and actual data respectively.
212  meta = {"type": m.get_type(), "timestamp": timestamp}
213  if args.show_source:
214  meta["srcSystem"] = m.get_srcSystem()
215  meta["srcComponent"] = m.get_srcComponent()
216  outMsg = {"meta": meta, "data": data}
217 
218  # Now print out this object with stringified properly.
219  print(json.dumps(outMsg))
220  # CSV format outputs columnar data with a user-specified delimiter
221  elif args.format == 'csv':
222  data = m.to_dict()
223  type = m.get_type()
224 
225  # If this message has a duplicate timestamp, copy its data into the existing data list. Also
226  # do this if it's the first message encountered.
227  if timestamp == last_timestamp or last_timestamp is None:
228  if isbin:
229  newData = [str(data[y]) if y != "timestamp" else "" for y in fields]
230  else:
231  newData = [str(data[y.split('.')[-1]]) if y.split('.')[0] == type and y.split('.')[-1] in data else "" for y in fields]
232 
233  for i, val in enumerate(newData):
234  if val:
235  csv_out[i] = val
236 
237  # Otherwise if this is a new timestamp, print out the old output data, and store the current message for later output.
238  else:
239  csv_out[0] = "{:.8f}".format(last_timestamp)
240  print(args.csv_sep.join(csv_out))
241  if isbin:
242  csv_out = [str(data[y]) if y != "timestamp" else "" for y in fields]
243  else:
244  csv_out = [str(data[y.split('.')[-1]]) if y.split('.')[0] == type and y.split('.')[-1] in data else "" for y in fields]
245  # Otherwise we output in a standard Python dict-style format
246  else:
247  s = "%s.%02u: %s" % (time.strftime("%Y-%m-%d %H:%M:%S",
248  time.localtime(timestamp)),
249  int(timestamp*100.0)%100, m)
250  if args.show_source:
251  s += " srcSystem=%u srcComponent=%u" % (m.get_srcSystem(), m.get_srcComponent())
252  if args.show_seq:
253  s += " seq=%u" % m.get_seq()
254  if not args.show_types:
255  print(s)
256 
257  # Update our last timestamp value.
258  last_timestamp = timestamp
259 
260 if args.show_types:
261  for msgType in available_types:
262  print(msgType)


mavlink
Author(s): Lorenz Meier
autogenerated on Sun Apr 7 2019 02:06:02