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


mavlink
Author(s): Lorenz Meier
autogenerated on Sun Jul 7 2019 03:22:07