DFReader.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 '''
3 APM DataFlash log file reader
4 
5 Copyright Andrew Tridgell 2011
6 Released under GNU GPL version 3 or later
7 
8 Partly based on SDLog2Parser by Anton Babushkin
9 '''
10 from __future__ import print_function
11 from builtins import range
12 from builtins import object
13 
14 import array
15 import math
16 import sys
17 import os
18 import mmap
19 import platform
20 
21 import struct
22 import sys
23 from . import mavutil
24 
25 try:
26  long # Python 2 has long
27 except NameError:
28  long = int # But Python 3 does not
29 
30 FORMAT_TO_STRUCT = {
31  "a": ("64s", None, str),
32  "b": ("b", None, int),
33  "B": ("B", None, int),
34  "h": ("h", None, int),
35  "H": ("H", None, int),
36  "i": ("i", None, int),
37  "I": ("I", None, int),
38  "f": ("f", None, float),
39  "n": ("4s", None, str),
40  "N": ("16s", None, str),
41  "Z": ("64s", None, str),
42  "c": ("h", 0.01, float),
43  "C": ("H", 0.01, float),
44  "e": ("i", 0.01, float),
45  "E": ("I", 0.01, float),
46  "L": ("i", 1.0e-7, float),
47  "d": ("d", None, float),
48  "M": ("b", None, int),
49  "q": ("q", None, long), # Backward compat
50  "Q": ("Q", None, long), # Backward compat
51  }
52 
53 def u_ord(c):
54  return ord(c) if sys.version_info.major < 3 else c
55 
56 class DFFormat(object):
57  def __init__(self, type, name, flen, format, columns):
58  self.type = type
59  self.name = null_term(name)
60  self.len = flen
61  self.format = format
62  self.columns = columns.split(',')
63 
64  if self.columns == ['']:
65  self.columns = []
66 
67  msg_struct = "<"
68  msg_mults = []
69  msg_types = []
70  msg_fmts = []
71  for c in format:
72  if u_ord(c) == 0:
73  break
74  try:
75  msg_fmts.append(c)
76  (s, mul, type) = FORMAT_TO_STRUCT[c]
77  msg_struct += s
78  msg_mults.append(mul)
79  if c == "a":
80  msg_types.append(array.array)
81  else:
82  msg_types.append(type)
83  except KeyError as e:
84  print("DFFormat: Unsupported format char: '%s' in message %s" %
85  (c, name))
86  raise Exception("Unsupported format char: '%s' in message %s" %
87  (c, name))
88 
89  self.msg_struct = msg_struct
90  self.msg_types = msg_types
91  self.msg_mults = msg_mults
92  self.msg_fmts = msg_fmts
93  self.colhash = {}
94  for i in range(len(self.columns)):
95  self.colhash[self.columns[i]] = i
96  self.a_indexes = []
97  for i in range(0, len(self.msg_fmts)):
98  if self.msg_fmts[i] == 'a':
99  self.a_indexes.append(i)
100 
101  def __str__(self):
102  return ("DFFormat(%s,%s,%s,%s)" %
103  (self.type, self.name, self.format, self.columns))
104 
105 
106 def to_string(s):
107  '''desperate attempt to convert a string regardless of what garbage we get'''
108  try:
109  return s.decode("utf-8")
110  except Exception as e:
111  pass
112  try:
113  s2 = s.encode('utf-8', 'ignore')
114  x = u"%s" % s2
115  return s2
116  except Exception:
117  pass
118  # so its a nasty one. Let's grab as many characters as we can
119  r = ''
120  while s != '':
121  try:
122  r2 = r + s[0]
123  s = s[1:]
124  r2 = r2.encode('ascii', 'ignore')
125  x = u"%s" % r2
126  r = r2
127  except Exception:
128  break
129  return r + '_XXX'
130 
131 def null_term(str):
132  '''null terminate a string'''
133  if isinstance(str, bytes):
134  str = to_string(str)
135  idx = str.find("\0")
136  if idx != -1:
137  str = str[:idx]
138  return str
139 
140 
141 class DFMessage(object):
142  def __init__(self, fmt, elements, apply_multiplier):
143  self.fmt = fmt
144  self._elements = elements
145  self._apply_multiplier = apply_multiplier
146  self._fieldnames = fmt.columns
147 
148  def to_dict(self):
149  d = {'mavpackettype': self.fmt.name}
150 
151  for field in self._fieldnames:
152  d[field] = self.__getattr__(field)
153 
154  return d
155 
156  def __getattr__(self, field):
157  '''override field getter'''
158  try:
159  i = self.fmt.colhash[field]
160  except Exception:
161  raise AttributeError(field)
162  if isinstance(self._elements[i], bytes):
163  v = self._elements[i].decode("utf-8")
164  else:
165  v = self._elements[i]
166  if self.fmt.format[i] == 'a':
167  pass
168  elif self.fmt.format[i] != 'M' or self._apply_multiplier:
169  v = self.fmt.msg_types[i](v)
170  if self.fmt.msg_types[i] == str:
171  v = null_term(v)
172  if self.fmt.msg_mults[i] is not None and self._apply_multiplier:
173  v *= self.fmt.msg_mults[i]
174  return v
175 
176  def get_type(self):
177  return self.fmt.name
178 
179  def __str__(self):
180  ret = "%s {" % self.fmt.name
181  col_count = 0
182  for c in self.fmt.columns:
183  val = self.__getattr__(c)
184  if isinstance(val, float) and math.isnan(val):
185  # quiet nans have more non-zero values:
186  noisy_nan = "\x7f\xf8\x00\x00\x00\x00\x00\x00"
187  if struct.pack(">d", val) != noisy_nan:
188  val = "qnan"
189  ret += "%s : %s, " % (c, val)
190  col_count += 1
191  if col_count != 0:
192  ret = ret[:-2]
193  return ret + '}'
194 
195  def get_msgbuf(self):
196  '''create a binary message buffer for a message'''
197  values = []
198  is_py2 = sys.version_info < (3,0)
199  for i in range(len(self.fmt.columns)):
200  if i >= len(self.fmt.msg_mults):
201  continue
202  mul = self.fmt.msg_mults[i]
203  name = self.fmt.columns[i]
204  if name == 'Mode' and 'ModeNum' in self.fmt.columns:
205  name = 'ModeNum'
206  v = self.__getattr__(name)
207  if is_py2:
208  if isinstance(v,unicode): # NOQA
209  v = str(v)
210  else:
211  if isinstance(v,str):
212  v = bytes(v,'ascii')
213  if isinstance(v, array.array):
214  v = v.tostring()
215  if mul is not None:
216  v /= mul
217  v = int(round(v))
218  values.append(v)
219 
220  ret1 = struct.pack("BBB", 0xA3, 0x95, self.fmt.type)
221  try:
222  ret2 = struct.pack(self.fmt.msg_struct, *values)
223  except Exception as ex:
224  return None
225  return ret1 + ret2
226 
227  def get_fieldnames(self):
228  return self._fieldnames
229 
230 
231 class DFReaderClock(object):
232  '''base class for all the different ways we count time in logs'''
233 
234  def __init__(self):
235  self.set_timebase(0)
236  self.timestamp = 0
237 
238  def _gpsTimeToTime(self, week, msec):
239  '''convert GPS week and TOW to a time in seconds since 1970'''
240  epoch = 86400*(10*365 + int((1980-1969)/4) + 1 + 6 - 2)
241  return epoch + 86400*7*week + msec*0.001 - 15
242 
243  def set_timebase(self, base):
244  self.timebase = base
245 
246  def message_arrived(self, m):
247  pass
248 
249  def rewind_event(self):
250  pass
251 
252 
253 class DFReaderClock_usec(DFReaderClock):
254  '''DFReaderClock_usec - use microsecond timestamps from messages'''
255  def __init__(self):
256  DFReaderClock.__init__(self)
257 
258  def find_time_base(self, gps, first_us_stamp):
259  '''work out time basis for the log - even newer style'''
260  t = self._gpsTimeToTime(gps.GWk, gps.GMS)
261  self.set_timebase(t - gps.TimeUS*0.000001)
262  # this ensures FMT messages get appropriate timestamp:
263  self.timestamp = self.timebase + first_us_stamp*0.000001
264 
265  def type_has_good_TimeMS(self, type):
266  '''The TimeMS in some messages is not from *our* clock!'''
267  if type.startswith('ACC'):
268  return False
269  if type.startswith('GYR'):
270  return False
271  return True
272 
274  if not self.type_has_good_TimeMS(m.get_type()):
275  return False
276  if 'TimeMS' != m._fieldnames[0]:
277  return False
278  if self.timebase + m.TimeMS*0.001 < self.timestamp:
279  return False
280  return True
281 
282  def set_message_timestamp(self, m):
283  if 'TimeUS' == m._fieldnames[0]:
284  # only format messages don't have a TimeUS in them...
285  m._timestamp = self.timebase + m.TimeUS*0.000001
286  elif self.should_use_msec_field0(m):
287  # ... in theory. I expect there to be some logs which are not
288  # "pure":
289  m._timestamp = self.timebase + m.TimeMS*0.001
290  else:
291  m._timestamp = self.timestamp
292  self.timestamp = m._timestamp
293 
294 
296  '''DFReaderClock_msec - a format where many messages have TimeMS in
297  their formats, and GPS messages have a "T" field giving msecs'''
298  def find_time_base(self, gps, first_ms_stamp):
299  '''work out time basis for the log - new style'''
300  t = self._gpsTimeToTime(gps.Week, gps.TimeMS)
301  self.set_timebase(t - gps.T*0.001)
302  self.timestamp = self.timebase + first_ms_stamp*0.001
303 
304  def set_message_timestamp(self, m):
305  if 'TimeMS' == m._fieldnames[0]:
306  m._timestamp = self.timebase + m.TimeMS*0.001
307  elif m.get_type() in ['GPS', 'GPS2']:
308  m._timestamp = self.timebase + m.T*0.001
309  else:
310  m._timestamp = self.timestamp
311  self.timestamp = m._timestamp
312 
313 
315  '''DFReaderClock_px4 - a format where a starting time is explicitly
316  given in a message'''
317  def __init__(self):
318  DFReaderClock.__init__(self)
319  self.px4_timebase = 0
320 
321  def find_time_base(self, gps):
322  '''work out time basis for the log - PX4 native'''
323  t = gps.GPSTime * 1.0e-6
324  self.timebase = t - self.px4_timebase
325 
326  def set_px4_timebase(self, time_msg):
327  self.px4_timebase = time_msg.StartTime * 1.0e-6
328 
329  def set_message_timestamp(self, m):
330  m._timestamp = self.timebase + self.px4_timebase
331 
332  def message_arrived(self, m):
333  type = m.get_type()
334  if type == 'TIME' and 'StartTime' in m._fieldnames:
335  self.set_px4_timebase(m)
336 
337 
339  '''DFReaderClock_gps_interpolated - for when the only real references
340  in a message are GPS timestamps'''
341  def __init__(self):
342  DFReaderClock.__init__(self)
343  self.msg_rate = {}
344  self.counts = {}
346 
347  def rewind_event(self):
348  '''reset counters on rewind'''
349  self.counts = {}
350  self.counts_since_gps = {}
351 
352  def message_arrived(self, m):
353  type = m.get_type()
354  if type not in self.counts:
355  self.counts[type] = 1
356  else:
357  self.counts[type] += 1
358  # this preserves existing behaviour - but should we be doing this
359  # if type == 'GPS'?
360  if type not in self.counts_since_gps:
361  self.counts_since_gps[type] = 1
362  else:
363  self.counts_since_gps[type] += 1
364 
365  if type == 'GPS' or type == 'GPS2':
366  self.gps_message_arrived(m)
367 
368  def gps_message_arrived(self, m):
369  '''adjust time base from GPS message'''
370  # msec-style GPS message?
371  gps_week = getattr(m, 'Week', None)
372  gps_timems = getattr(m, 'TimeMS', None)
373  if gps_week is None:
374  # usec-style GPS message?
375  gps_week = getattr(m, 'GWk', None)
376  gps_timems = getattr(m, 'GMS', None)
377  if gps_week is None:
378  if getattr(m, 'GPSTime', None) is not None:
379  # PX4-style timestamp; we've only been called
380  # because we were speculatively created in case no
381  # better clock was found.
382  return
383 
384  if gps_week is None:
385  # AvA-style logs
386  gps_week = getattr(m, 'Wk')
387  gps_timems = getattr(m, 'TWk')
388  if gps_week is None or gps_timems is None:
389  return
390 
391  t = self._gpsTimeToTime(gps_week, gps_timems)
392 
393  deltat = t - self.timebase
394  if deltat <= 0:
395  return
396 
397  for type in self.counts_since_gps:
398  rate = self.counts_since_gps[type] / deltat
399  if rate > self.msg_rate.get(type, 0):
400  self.msg_rate[type] = rate
401  self.msg_rate['IMU'] = 50.0
402  self.timebase = t
403  self.counts_since_gps = {}
404 
405  def set_message_timestamp(self, m):
406  rate = self.msg_rate.get(m.fmt.name, 50.0)
407  if int(rate) == 0:
408  rate = 50
409  count = self.counts_since_gps.get(m.fmt.name, 0)
410  m._timestamp = self.timebase + count/rate
411 
412 
413 class DFReader(object):
414  '''parse a generic dataflash file'''
415  def __init__(self):
416  # read the whole file into memory for simplicity
417  self.clock = None
418  self.timestamp = 0
419  self.mav_type = mavutil.mavlink.MAV_TYPE_FIXED_WING
420  self.verbose = False
421  self.params = {}
422  self._flightmodes = None
423 
424  def _rewind(self):
425  '''reset state on rewind'''
426  self.messages = {'MAV': self}
427  if self._flightmodes is not None and len(self._flightmodes) > 0:
428  self.flightmode = self._flightmodes[0][0]
429  else:
430  self.flightmode = "UNKNOWN"
431  self.percent = 0
432  if self.clock:
433  self.clock.rewind_event()
434 
435  def init_clock_px4(self, px4_msg_time, px4_msg_gps):
436  self.clock = DFReaderClock_px4()
437  if not self._zero_time_base:
438  self.clock.set_px4_timebase(px4_msg_time)
439  self.clock.find_time_base(px4_msg_gps)
440  return True
441 
442  def init_clock_msec(self):
443  # it is a new style flash log with full timestamps
444  self.clock = DFReaderClock_msec()
445 
446  def init_clock_usec(self):
447  self.clock = DFReaderClock_usec()
448 
449  def init_clock_gps_interpolated(self, clock):
450  self.clock = clock
451 
452  def init_clock(self):
453  '''work out time basis for the log'''
454 
455  self._rewind()
456 
457  # speculatively create a gps clock in case we don't find anything
458  # better
459  gps_clock = DFReaderClock_gps_interpolated()
460  self.clock = gps_clock
461 
462  px4_msg_time = None
463  px4_msg_gps = None
464  gps_interp_msg_gps1 = None
465  first_us_stamp = None
466  first_ms_stamp = None
467 
468  have_good_clock = False
469  while True:
470  m = self.recv_msg()
471  if m is None:
472  break
473 
474  type = m.get_type()
475 
476  if first_us_stamp is None:
477  first_us_stamp = getattr(m, "TimeUS", None)
478 
479  if first_ms_stamp is None and (type != 'GPS' and type != 'GPS2'):
480  # Older GPS messages use TimeMS for msecs past start
481  # of gps week
482  first_ms_stamp = getattr(m, "TimeMS", None)
483 
484  if type == 'GPS' or type == 'GPS2':
485  if getattr(m, "TimeUS", 0) != 0 and \
486  getattr(m, "GWk", 0) != 0: # everything-usec-timestamped
487  self.init_clock_usec()
488  if not self._zero_time_base:
489  self.clock.find_time_base(m, first_us_stamp)
490  have_good_clock = True
491  break
492  if getattr(m, "T", 0) != 0 and \
493  getattr(m, "Week", 0) != 0: # GPS is msec-timestamped
494  if first_ms_stamp is None:
495  first_ms_stamp = m.T
496  self.init_clock_msec()
497  if not self._zero_time_base:
498  self.clock.find_time_base(m, first_ms_stamp)
499  have_good_clock = True
500  break
501  if getattr(m, "GPSTime", 0) != 0: # px4-style-only
502  px4_msg_gps = m
503  if getattr(m, "Week", 0) != 0:
504  if (gps_interp_msg_gps1 is not None and
505  (gps_interp_msg_gps1.TimeMS != m.TimeMS or
506  gps_interp_msg_gps1.Week != m.Week)):
507  # we've received two distinct, non-zero GPS
508  # packets without finding a decent clock to
509  # use; fall back to interpolation. Q: should
510  # we wait a few more messages befoe doing
511  # this?
512  self.init_clock_gps_interpolated(gps_clock)
513  have_good_clock = True
514  break
515  gps_interp_msg_gps1 = m
516 
517  elif type == 'TIME':
518  '''only px4-style logs use TIME'''
519  if getattr(m, "StartTime", None) is not None:
520  px4_msg_time = m
521 
522  if px4_msg_time is not None and px4_msg_gps is not None:
523  self.init_clock_px4(px4_msg_time, px4_msg_gps)
524  have_good_clock = True
525  break
526 
527 # print("clock is " + str(self.clock))
528  if not have_good_clock:
529  # we failed to find any GPS messages to set a time
530  # base for usec and msec clocks. Also, not a
531  # PX4-style log
532  if first_us_stamp is not None:
533  self.init_clock_usec()
534  elif first_ms_stamp is not None:
535  self.init_clock_msec()
536 
537  self._rewind()
538 
539  return
540 
541  def _set_time(self, m):
542  '''set time for a message'''
543  # really just left here for profiling
544  m._timestamp = self.timestamp
545  if len(m._fieldnames) > 0 and self.clock is not None:
546  self.clock.set_message_timestamp(m)
547 
548  def recv_msg(self):
549  return self._parse_next()
550 
551  def _add_msg(self, m):
552  '''add a new message'''
553  type = m.get_type()
554  self.messages[type] = m
555 
556  if self.clock:
557  self.clock.message_arrived(m)
558 
559  if type == 'MSG':
560  if m.Message.find("Rover") != -1:
561  self.mav_type = mavutil.mavlink.MAV_TYPE_GROUND_ROVER
562  elif m.Message.find("Plane") != -1:
563  self.mav_type = mavutil.mavlink.MAV_TYPE_FIXED_WING
564  elif m.Message.find("Copter") != -1:
565  self.mav_type = mavutil.mavlink.MAV_TYPE_QUADROTOR
566  elif m.Message.startswith("Antenna"):
567  self.mav_type = mavutil.mavlink.MAV_TYPE_ANTENNA_TRACKER
568  elif m.Message.find("ArduSub") != -1:
569  self.mav_type = mavutil.mavlink.MAV_TYPE_SUBMARINE
570  if type == 'MODE':
571  if isinstance(m.Mode, str):
572  self.flightmode = m.Mode.upper()
573  elif 'ModeNum' in m._fieldnames:
574  mapping = mavutil.mode_mapping_bynumber(self.mav_type)
575  if mapping is not None and m.ModeNum in mapping:
576  self.flightmode = mapping[m.ModeNum]
577  else:
578  self.flightmode = 'UNKNOWN'
579  else:
580  self.flightmode = mavutil.mode_string_acm(m.Mode)
581  if type == 'STAT' and 'MainState' in m._fieldnames:
582  self.flightmode = mavutil.mode_string_px4(m.MainState)
583  if type == 'PARM' and getattr(m, 'Name', None) is not None:
584  self.params[m.Name] = m.Value
585  self._set_time(m)
586 
587  def recv_match(self, condition=None, type=None, blocking=False):
588  '''recv the next message that matches the given condition
589  type can be a string or a list of strings'''
590  if type is not None:
591  if isinstance(type, str):
592  type = set([type])
593  elif isinstance(type, list):
594  type = set(type)
595  while True:
596  if type is not None:
597  self.skip_to_type(type)
598  m = self.recv_msg()
599  if m is None:
600  return None
601  if type is not None and not m.get_type() in type:
602  continue
603  if not mavutil.evaluate_condition(condition, self.messages):
604  continue
605  return m
606 
607  def check_condition(self, condition):
608  '''check if a condition is true'''
609  return mavutil.evaluate_condition(condition, self.messages)
610 
611  def param(self, name, default=None):
612  '''convenient function for returning an arbitrary MAVLink
613  parameter with a default'''
614  if name not in self.params:
615  return default
616  return self.params[name]
617 
618  def flightmode_list(self):
619  '''return an array of tuples for all flightmodes in log. Tuple is (modestring, t0, t1)'''
620  tstamp = None
621  fmode = None
622  if self._flightmodes is None:
623  self._rewind()
624  self._flightmodes = []
625  types = set(['MODE'])
626  while True:
627  m = self.recv_match(type=types)
628  if m is None:
629  break
630  tstamp = m._timestamp
631  if self.flightmode == fmode:
632  continue
633  if len(self._flightmodes) > 0:
634  (mode, t0, t1) = self._flightmodes[-1]
635  self._flightmodes[-1] = (mode, t0, tstamp)
636  self._flightmodes.append((self.flightmode, tstamp, None))
637  fmode = self.flightmode
638  if tstamp is not None:
639  (mode, t0, t1) = self._flightmodes[-1]
640  self._flightmodes[-1] = (mode, t0, self.last_timestamp())
641 
642  self._rewind()
643  return self._flightmodes
644 
646  '''parse a binary dataflash file'''
647  def __init__(self, filename, zero_time_base=False, progress_callback=None):
648  DFReader.__init__(self)
649  # read the whole file into memory for simplicity
650  self.filehandle = open(filename, 'rb')
651  self.filehandle.seek(0, 2)
652  self.data_len = self.filehandle.tell()
653  self.filehandle.seek(0)
654  if platform.system() == "Windows":
655  self.data_map = mmap.mmap(self.filehandle.fileno(), self.data_len, None, mmap.ACCESS_READ)
656  else:
657  self.data_map = mmap.mmap(self.filehandle.fileno(), self.data_len, mmap.MAP_PRIVATE, mmap.PROT_READ)
658 
659  self.HEAD1 = 0xA3
660  self.HEAD2 = 0x95
661  self.unpackers = {}
662  if sys.version_info.major < 3:
663  self.HEAD1 = chr(self.HEAD1)
664  self.HEAD2 = chr(self.HEAD2)
665  self.formats = {
666  0x80: DFFormat(0x80,
667  'FMT',
668  89,
669  'BBnNZ',
670  "Type,Length,Name,Format,Columns")
671  }
672  self._zero_time_base = zero_time_base
673  self.prev_type = None
674  self.init_clock()
675  self.prev_type = None
676  self._rewind()
677  self.init_arrays(progress_callback)
678 
679  def _rewind(self):
680  '''rewind to start of log'''
681  DFReader._rewind(self)
682  self.offset = 0
683  self.remaining = self.data_len
684  self.type_nums = None
685  self.timestamp = 0
686 
687  def rewind(self):
688  '''rewind to start of log'''
689  self._rewind()
690 
691  def init_arrays(self, progress_callback=None):
692  '''initialise arrays for fast recv_match()'''
693  self.offsets = []
694  self.counts = []
695  self._count = 0
696  self.name_to_id = {}
697  self.id_to_name = {}
698  for i in range(256):
699  self.offsets.append([])
700  self.counts.append(0)
701  fmt_type = 0x80
702  ofs = 0
703  pct = 0
704  HEAD1 = self.HEAD1
705  HEAD2 = self.HEAD2
706  lengths = [-1] * 256
707 
708  while ofs+3 < self.data_len:
709  hdr = self.data_map[ofs:ofs+3]
710  if hdr[0] != HEAD1 or hdr[1] != HEAD2:
711  print("bad header 0x%02x 0x%02x" % (u_ord(hdr[0]), u_ord(hdr[1])), file=sys.stderr)
712  break
713  mtype = u_ord(hdr[2])
714  self.offsets[mtype].append(ofs)
715 
716  if lengths[mtype] == -1:
717  if not mtype in self.formats:
718  print("unknown msg type 0x%02x (%u)" % (mtype, mtype),
719  file=sys.stderr)
720  break
721  self.offset = ofs
722  self._parse_next()
723  fmt = self.formats[mtype]
724  lengths[mtype] = fmt.len
725 
726  self.counts[mtype] += 1
727  mlen = lengths[mtype]
728 
729  if mtype == fmt_type:
730  body = self.data_map[ofs+3:ofs+mlen]
731  if len(body)+3 < mlen:
732  break
733  fmt = self.formats[mtype]
734  elements = list(struct.unpack(fmt.msg_struct, body))
735  mfmt = DFFormat(
736  elements[0],
737  null_term(elements[2]), elements[1],
738  null_term(elements[3]), null_term(elements[4]))
739  self.formats[elements[0]] = mfmt
740  self.name_to_id[mfmt.name] = mfmt.type
741  self.id_to_name[mfmt.type] = mfmt.name
742 
743  ofs += mlen
744  if progress_callback is not None:
745  new_pct = (100 * ofs) // self.data_len
746  if new_pct != pct:
747  progress_callback(new_pct)
748  pct = new_pct
749 
750  for i in range(256):
751  self._count += self.counts[i]
752  self.offset = 0
753 
754  def last_timestamp(self):
755  '''get the last timestamp in the log'''
756  highest_offset = 0
757  second_highest_offset = 0
758  for i in range(256):
759  if self.counts[i] == -1:
760  continue
761  if len(self.offsets[i]) == 0:
762  continue
763  ofs = self.offsets[i][-1]
764  if ofs > highest_offset:
765  second_highest_offset = highest_offset
766  highest_offset = ofs
767  elif ofs > second_highest_offset:
768  second_highest_offset = ofs
769  self.offset = highest_offset
770  m = self.recv_msg()
771  if m is None:
772  self.offset = second_highest_offset
773  m = self.recv_msg()
774  return m._timestamp
775 
776 
777  def skip_to_type(self, type):
778  '''skip fwd to next msg matching given type set'''
779 
780  if self.type_nums is None:
781  # always add some key msg types so we can track flightmode, params etc
782  type = type.copy()
783  type.update(set(['MODE','MSG','PARM','STAT']))
784  self.indexes = []
785  self.type_nums = []
786  for t in type:
787  if not t in self.name_to_id:
788  continue
789  self.type_nums.append(self.name_to_id[t])
790  self.indexes.append(0)
791  smallest_index = -1
792  smallest_offset = self.data_len
793  for i in range(len(self.type_nums)):
794  mtype = self.type_nums[i]
795  if self.indexes[i] >= self.counts[mtype]:
796  continue
797  ofs = self.offsets[mtype][self.indexes[i]]
798  if ofs < smallest_offset:
799  smallest_offset = ofs
800  smallest_index = i
801  if smallest_index >= 0:
802  self.indexes[smallest_index] += 1
803  self.offset = smallest_offset
804 
805  def _parse_next(self):
806  '''read one message, returning it as an object'''
807 
808  # skip over bad messages; after this loop has run msg_type
809  # indicates the message which starts at self.offset (including
810  # signature bytes and msg_type itself)
811  skip_type = None
812  skip_start = 0
813  while True:
814  if self.data_len - self.offset < 3:
815  return None
816 
817  hdr = self.data_map[self.offset:self.offset+3]
818  if hdr[0] == self.HEAD1 and hdr[1] == self.HEAD2:
819  # signature found
820  if skip_type is not None:
821  # emit message about skipped bytes
822  if self.remaining >= 528:
823  # APM logs often contain garbage at end
824  skip_bytes = self.offset - skip_start
825  print("Skipped %u bad bytes in log at offset %u, type=%s (prev=%s)" %
826  (skip_bytes, skip_start, skip_type, self.prev_type),
827  file=sys.stderr)
828  skip_type = None
829  # check we recognise this message type:
830  msg_type = u_ord(hdr[2])
831  if msg_type in self.formats:
832  # recognised message found
833  self.prev_type = msg_type
834  break;
835  # message was not recognised; fall through so these
836  # bytes are considered "skipped". The signature bytes
837  # are easily recognisable in the "Skipped bytes"
838  # message.
839  if skip_type is None:
840  skip_type = (u_ord(hdr[0]), u_ord(hdr[1]), u_ord(hdr[2]))
841  skip_start = self.offset
842  self.offset += 1
843  self.remaining -= 1
844 
845  self.offset += 3
846  self.remaining = self.data_len - self.offset
847 
848  fmt = self.formats[msg_type]
849  if self.remaining < fmt.len-3:
850  # out of data - can often happen half way through a message
851  if self.verbose:
852  print("out of data", file=sys.stderr)
853  return None
854  body = self.data_map[self.offset:self.offset+fmt.len-3]
855  elements = None
856  try:
857  if not msg_type in self.unpackers:
858  self.unpackers[msg_type] = struct.Struct(fmt.msg_struct).unpack
859  elements = list(self.unpackers[msg_type](body))
860  except Exception as ex:
861  print(ex)
862  if self.remaining < 528:
863  # we can have garbage at the end of an APM2 log
864  return None
865  # we should also cope with other corruption; logs
866  # transfered via DataFlash_MAVLink may have blocks of 0s
867  # in them, for example
868  print("Failed to parse %s/%s with len %u (remaining %u)" %
869  (fmt.name, fmt.msg_struct, len(body), self.remaining),
870  file=sys.stderr)
871  if elements is None:
872  return self._parse_next()
873  name = fmt.name
874  # transform elements which can't be done at unpack time:
875  for a_index in fmt.a_indexes:
876  try:
877  elements[a_index] = array.array('h', elements[a_index])
878  except Exception as e:
879  print("Failed to transform array: %s" % str(e),
880  file=sys.stderr)
881 
882  if name == 'FMT':
883  # add to formats
884  # name, len, format, headings
885  try:
886  self.formats[elements[0]] = DFFormat(
887  elements[0],
888  null_term(elements[2]), elements[1],
889  null_term(elements[3]), null_term(elements[4]))
890  except Exception:
891  return self._parse_next()
892 
893  self.offset += fmt.len - 3
894  self.remaining = self.data_len - self.offset
895  m = DFMessage(fmt, elements, True)
896  self._add_msg(m)
897  self.percent = 100.0 * (self.offset / float(self.data_len))
898 
899  return m
900 
901 
902 def DFReader_is_text_log(filename):
903  '''return True if a file appears to be a valid text log'''
904  with open(filename, 'r') as f:
905  ret = (f.read(8000).find('FMT, ') != -1)
906 
907  return ret
908 
909 
911  '''parse a text dataflash file'''
912  def __init__(self, filename, zero_time_base=False, progress_callback=None):
913  DFReader.__init__(self)
914  # read the whole file into memory for simplicity
915  self.filehandle = open(filename, 'r')
916  self.filehandle.seek(0, 2)
917  self.data_len = self.filehandle.tell()
918  if platform.system() == "Windows":
919  self.data_map = mmap.mmap(self.filehandle.fileno(), self.data_len, None, mmap.ACCESS_READ)
920  else:
921  self.data_map = mmap.mmap(self.filehandle.fileno(), self.data_len, mmap.MAP_PRIVATE, mmap.PROT_READ)
922  self.offset = 0
923 
924  self.formats = {
925  'FMT': DFFormat(0x80,
926  'FMT',
927  89,
928  'BBnNZ',
929  "Type,Length,Name,Format,Columns")
930  }
931  self._rewind()
932  self._zero_time_base = zero_time_base
933  self.init_clock()
934  self._rewind()
935  self.init_arrays(progress_callback)
936 
937  def _rewind(self):
938  '''rewind to start of log'''
939  DFReader._rewind(self)
940  # find the first valid line
941  self.offset = self.data_map.find(b'FMT, ')
942  self.type_list = None
943 
944  def rewind(self):
945  '''rewind to start of log'''
946  self._rewind()
947 
948  def init_arrays(self, progress_callback=None):
949  '''initialise arrays for fast recv_match()'''
950  self.offsets = {}
951  self.counts = {}
952  self._count = 0
953  ofs = self.offset
954  pct = 0
955 
956  while ofs+16 < self.data_len:
957  mtype = self.data_map[ofs:ofs+4]
958  if mtype[3] == ',':
959  mtype = mtype[0:3]
960  if not mtype in self.offsets:
961  self.counts[mtype] = 0
962  self.offsets[mtype] = []
963  self.offset = ofs
964  self._parse_next()
965  self.offsets[mtype].append(ofs)
966 
967  self.counts[mtype] += 1
968 
969  if mtype == "FMT":
970  self.offset = ofs
971  self._parse_next()
972 
973  ofs = self.data_map.find(b"\n", ofs)
974  if ofs == -1:
975  break
976  ofs += 1
977  new_pct = (100 * ofs) // self.data_len
978  if progress_callback is not None and new_pct != pct:
979  progress_callback(new_pct)
980  pct = new_pct
981 
982  for mtype in self.counts.keys():
983  self._count += self.counts[mtype]
984  self.offset = 0
985 
986  def skip_to_type(self, type):
987  '''skip fwd to next msg matching given type set'''
988 
989  if self.type_list is None:
990  # always add some key msg types so we can track flightmode, params etc
991  self.type_list = type.copy()
992  self.type_list.update(set(['MODE','MSG','PARM','STAT']))
993  self.type_list = list(self.type_list)
994  self.indexes = []
995  self.type_nums = []
996  for t in self.type_list:
997  self.indexes.append(0)
998  smallest_index = -1
999  smallest_offset = self.data_len
1000  for i in range(len(self.type_list)):
1001  mtype = self.type_list[i]
1002  if not mtype in self.counts:
1003  continue
1004  if self.indexes[i] >= self.counts[mtype]:
1005  continue
1006  ofs = self.offsets[mtype][self.indexes[i]]
1007  if ofs < smallest_offset:
1008  smallest_offset = ofs
1009  smallest_index = i
1010  if smallest_index >= 0:
1011  self.indexes[smallest_index] += 1
1012  self.offset = smallest_offset
1013 
1014  def _parse_next(self):
1015  '''read one message, returning it as an object'''
1016 
1017  while True:
1018  endline = self.data_map.find(b'\n',self.offset)
1019  if endline == -1:
1020  endline = self.data_len
1021  if endline < self.offset:
1022  break
1023  s = self.data_map[self.offset:endline].rstrip()
1024  if sys.version_info.major >= 3:
1025  s = s.decode('utf-8')
1026  elements = s.split(", ")
1027  self.offset = endline+1
1028  if len(elements) >= 2:
1029  # this_line is good
1030  break
1031 
1032  if self.offset > self.data_len:
1033  return None
1034 
1035  # cope with empty structures
1036  if len(elements) == 5 and elements[-1] == ',':
1037  elements[-1] = ''
1038  elements.append('')
1039 
1040  self.percent = 100.0 * (self.offset / float(self.data_len))
1041 
1042  msg_type = elements[0]
1043 
1044  if msg_type not in self.formats:
1045  return self._parse_next()
1046 
1047  fmt = self.formats[msg_type]
1048 
1049  if len(elements) < len(fmt.format)+1:
1050  # not enough columns
1051  return self._parse_next()
1052 
1053  elements = elements[1:]
1054 
1055  name = fmt.name.rstrip('\0')
1056  if name == 'FMT':
1057  # add to formats
1058  # name, len, format, headings
1059  if elements[2] == 'FMT' and elements[4] == 'Type,Length,Name,Format':
1060  # some logs have the 'Columns' column missing from text logs
1061  elements[4] = "Type,Length,Name,Format,Columns"
1062  new_fmt = DFFormat(int(elements[0]),
1063  elements[2],
1064  int(elements[1]),
1065  elements[3],
1066  elements[4])
1067  self.formats[elements[2]] = new_fmt
1068 
1069  try:
1070  m = DFMessage(fmt, elements, False)
1071  except ValueError:
1072  return self._parse_next()
1073 
1074  self._add_msg(m)
1075 
1076  return m
1077 
1078  def last_timestamp(self):
1079  '''get the last timestamp in the log'''
1080  highest_offset = 0
1081  for mtype in self.counts.keys():
1082  if len(self.offsets[mtype]) == 0:
1083  continue
1084  ofs = self.offsets[mtype][-1]
1085  if ofs > highest_offset:
1086  highest_offset = ofs
1087  self.offset = highest_offset
1088  m = self.recv_msg()
1089  return m._timestamp
1090 
1091 if __name__ == "__main__":
1092  use_profiler = False
1093  if use_profiler:
1094  from line_profiler import LineProfiler
1095  profiler = LineProfiler()
1096  profiler.add_function(DFReader_binary._parse_next)
1097  profiler.add_function(DFReader_binary._add_msg)
1098  profiler.add_function(DFReader._set_time)
1099  profiler.enable_by_count()
1100 
1101  filename = sys.argv[1]
1102  if filename.endswith('.log'):
1103  log = DFReader_text(filename)
1104  else:
1105  log = DFReader_binary(filename)
1106  while True:
1107  m = log.recv_msg()
1108  if m is None:
1109  break
1110  if use_profiler:
1111  profiler.print_stats()


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