3 APM DataFlash log file reader 5 Copyright Andrew Tridgell 2011 6 Released under GNU GPL version 3 or later 8 Partly based on SDLog2Parser by Anton Babushkin 10 from __future__
import print_function
11 from builtins
import range
12 from builtins
import object
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),
50 "Q": (
"Q",
None, long),
54 return ord(c)
if sys.version_info.major < 3
else c
57 def __init__(self, type, name, flen, format, columns):
76 (s, mul, type) = FORMAT_TO_STRUCT[c]
80 msg_types.append(array.array)
82 msg_types.append(type)
84 print(
"DFFormat: Unsupported format char: '%s' in message %s" %
86 raise Exception(
"Unsupported format char: '%s' in message %s" %
99 self.a_indexes.append(i)
102 return (
"DFFormat(%s,%s,%s,%s)" %
107 '''desperate attempt to convert a string regardless of what garbage we get''' 109 return s.decode(
"utf-8")
110 except Exception
as e:
113 s2 = s.encode(
'utf-8',
'ignore')
124 r2 = r2.encode(
'ascii',
'ignore')
132 '''null terminate a string''' 133 if isinstance(str, bytes):
142 def __init__(self, fmt, elements, apply_multiplier):
149 d = {
'mavpackettype': self.fmt.name}
157 '''override field getter''' 159 i = self.fmt.colhash[field]
161 raise AttributeError(field)
166 if self.fmt.format[i] ==
'a':
169 v = self.fmt.msg_types[i](v)
170 if self.fmt.msg_types[i] == str:
173 v *= self.fmt.msg_mults[i]
180 ret =
"%s {" % self.fmt.name
182 for c
in self.fmt.columns:
184 if isinstance(val, float)
and math.isnan(val):
186 noisy_nan =
"\x7f\xf8\x00\x00\x00\x00\x00\x00" 187 if struct.pack(
">d", val) != noisy_nan:
189 ret +=
"%s : %s, " % (c, val)
196 '''create a binary message buffer for a message''' 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):
202 mul = self.fmt.msg_mults[i]
203 name = self.fmt.columns[i]
204 if name ==
'Mode' and 'ModeNum' in self.fmt.columns:
208 if isinstance(v,unicode):
211 if isinstance(v,str):
213 if isinstance(v, array.array):
220 ret1 = struct.pack(
"BBB", 0xA3, 0x95, self.fmt.type)
222 ret2 = struct.pack(self.fmt.msg_struct, *values)
223 except Exception
as ex:
232 '''base class for all the different ways we count time in logs''' 239 '''convert GPS week and TOW to a time in seconds since 1970''' 240 epoch = 86400*(10*365 + (1980-1969)/4 + 1 + 6 - 2)
241 return epoch + 86400*7*week + msec*0.001 - 15
253 class DFReaderClock_usec(DFReaderClock):
254 '''DFReaderClock_usec - use microsecond timestamps from messages''' 256 DFReaderClock.__init__(self)
259 '''work out time basis for the log - even newer style''' 266 '''The TimeMS in some messages is not from *our* clock!''' 267 if type.startswith(
'ACC'):
269 if type.startswith(
'GYR'):
276 if 'TimeMS' != m._fieldnames[0]:
283 if 'TimeUS' == m._fieldnames[0]:
285 m._timestamp = self.
timebase + m.TimeUS*0.000001
289 m._timestamp = self.
timebase + m.TimeMS*0.001
296 '''DFReaderClock_msec - a format where many messages have TimeMS in 297 their formats, and GPS messages have a "T" field giving msecs''' 299 '''work out time basis for the log - new style''' 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
315 '''DFReaderClock_px4 - a format where a starting time is explicitly 316 given in a message''' 318 DFReaderClock.__init__(self)
322 '''work out time basis for the log - PX4 native''' 323 t = gps.GPSTime * 1.0e-6
334 if type ==
'TIME' and 'StartTime' in m._fieldnames:
339 '''DFReaderClock_gps_interpolated - for when the only real references 340 in a message are GPS timestamps''' 342 DFReaderClock.__init__(self)
348 '''reset counters on rewind''' 354 if type
not in self.
counts:
365 if type ==
'GPS' or type ==
'GPS2':
369 '''adjust time base from GPS message''' 371 gps_week = getattr(m,
'Week',
None)
372 gps_timems = getattr(m,
'TimeMS',
None)
375 gps_week = getattr(m,
'GWk',
None)
376 gps_timems = getattr(m,
'GMS',
None)
378 if getattr(m,
'GPSTime',
None)
is not None:
386 gps_week = getattr(m,
'Wk')
387 gps_timems = getattr(m,
'TWk')
388 if gps_week
is None or gps_timems
is None:
399 if rate > self.msg_rate.get(type, 0):
406 rate = self.msg_rate.get(m.fmt.name, 50.0)
409 count = self.counts_since_gps.get(m.fmt.name, 0)
410 m._timestamp = self.
timebase + count/rate
414 '''parse a generic dataflash file''' 419 self.
mav_type = mavutil.mavlink.MAV_TYPE_FIXED_WING
425 '''reset state on rewind''' 433 self.clock.rewind_event()
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)
453 '''work out time basis for the log''' 460 self.
clock = gps_clock
464 gps_interp_msg_gps1 =
None 465 first_us_stamp =
None 466 first_ms_stamp =
None 468 have_good_clock =
False 476 if first_us_stamp
is None:
477 first_us_stamp = getattr(m,
"TimeUS",
None)
479 if first_ms_stamp
is None and (type !=
'GPS' and type !=
'GPS2'):
482 first_ms_stamp = getattr(m,
"TimeMS",
None)
484 if type ==
'GPS' or type ==
'GPS2':
485 if getattr(m,
"TimeUS", 0) != 0
and \
486 getattr(m,
"GWk", 0) != 0:
488 if not self._zero_time_base:
489 self.clock.find_time_base(m, first_us_stamp)
490 have_good_clock =
True 492 if getattr(m,
"T", 0) != 0
and \
493 getattr(m,
"Week", 0) != 0:
494 if first_ms_stamp
is None:
497 if not self._zero_time_base:
498 self.clock.find_time_base(m, first_ms_stamp)
499 have_good_clock =
True 501 if getattr(m,
"GPSTime", 0) != 0:
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)):
513 have_good_clock =
True 515 gps_interp_msg_gps1 = m
518 '''only px4-style logs use TIME''' 519 if getattr(m,
"StartTime",
None)
is not None:
522 if px4_msg_time
is not None and px4_msg_gps
is not None:
524 have_good_clock =
True 528 if not have_good_clock:
532 if first_us_stamp
is not None:
534 elif first_ms_stamp
is not None:
542 '''set time for a message''' 545 if len(m._fieldnames) > 0
and self.
clock is not None:
546 self.clock.set_message_timestamp(m)
549 return self._parse_next()
552 '''add a new message''' 557 self.clock.message_arrived(m)
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
571 if isinstance(m.Mode, str):
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:
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
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''' 591 if isinstance(type, str):
593 elif isinstance(type, list):
597 self.skip_to_type(type)
601 if type
is not None and not m.get_type()
in type:
603 if not mavutil.evaluate_condition(condition, self.
messages):
608 '''check if a condition is true''' 609 return mavutil.evaluate_condition(condition, self.
messages)
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:
619 '''return an array of tuples for all flightmodes in log. Tuple is (modestring, t0, t1)''' 625 types = set([
'MODE'])
630 tstamp = m._timestamp
636 self._flightmodes.append((self.
flightmode, tstamp,
None))
638 if tstamp
is not None:
640 self.
_flightmodes[-1] = (mode, t0, self.last_timestamp())
646 '''parse a binary dataflash file''' 647 def __init__(self, filename, zero_time_base=False, progress_callback=None):
648 DFReader.__init__(self)
651 self.filehandle.seek(0, 2)
653 self.filehandle.seek(0)
654 if platform.system() ==
"Windows":
657 self.
data_map = mmap.mmap(self.filehandle.fileno(), self.
data_len, mmap.MAP_PRIVATE, mmap.PROT_READ)
662 if sys.version_info.major < 3:
670 "Type,Length,Name,Format,Columns")
678 '''rewind to start of log''' 679 DFReader._rewind(self)
686 '''rewind to start of log''' 690 '''initialise arrays for fast recv_match()''' 697 self.offsets.append([])
698 self.counts.append(0)
708 if hdr[0] != HEAD1
or hdr[1] != HEAD2:
709 print(
"bad header 0x%02x 0x%02x" % (
u_ord(hdr[0]),
u_ord(hdr[1])), file=sys.stderr)
711 mtype =
u_ord(hdr[2])
712 self.
offsets[mtype].append(ofs)
714 if lengths[mtype] == -1:
716 print(
"unknown msg type 0x%02x" % mtype, file=sys.stderr)
721 lengths[mtype] = fmt.len
724 mlen = lengths[mtype]
726 if mtype == fmt_type:
727 body = self.
data_map[ofs+3:ofs+mlen]
728 if len(body)+3 < mlen:
731 elements = list(struct.unpack(fmt.msg_struct, body))
736 self.
formats[elements[0]] = mfmt
741 new_pct = (100 * ofs) // self.
data_len 742 if progress_callback
is not None and new_pct != pct:
743 progress_callback(new_pct)
751 '''get the last timestamp in the log''' 753 second_highest_offset = 0
760 if ofs > highest_offset:
761 second_highest_offset = highest_offset
763 elif ofs > second_highest_offset:
764 second_highest_offset = ofs
765 self.
offset = highest_offset
768 self.
offset = second_highest_offset
774 '''skip fwd to next msg matching given type set''' 779 type.update(set([
'MODE',
'MSG',
'PARM',
'STAT']))
786 self.indexes.append(0)
794 if ofs < smallest_offset:
795 smallest_offset = ofs
797 if smallest_index >= 0:
798 self.
indexes[smallest_index] += 1
799 self.
offset = smallest_offset
802 '''read one message, returning it as an object''' 810 msg_type =
u_ord(hdr[2])
811 while (hdr[0] != self.
HEAD1 or hdr[1] != self.
HEAD2 or 813 if skip_type
is None:
821 msg_type =
u_ord(hdr[2])
825 print(
"Skipped %u bad bytes in log at offset %u, type=%s" %
826 (skip_bytes, skip_start, skip_type), file=sys.stderr)
835 print(
"out of data", file=sys.stderr)
841 self.
unpackers[msg_type] = struct.Struct(fmt.msg_struct).unpack
842 elements = list(self.
unpackers[msg_type](body))
843 except Exception
as ex:
851 print(
"Failed to parse %s/%s with len %u (remaining %u)" %
852 (fmt.name, fmt.msg_struct, len(body), self.
remaining),
858 for a_index
in fmt.a_indexes:
860 elements[a_index] = array.array(
'h', elements[a_index])
861 except Exception
as e:
862 print(
"Failed to transform array: %s" %
str(e),
876 self.
offset += fmt.len - 3
886 '''return True if a file appears to be a valid text log''' 887 with open(filename,
'r') as f: 888 ret = (f.read(8000).find('FMT, ') != -1)
894 '''parse a text dataflash file''' 895 def __init__(self, filename, zero_time_base=False, progress_callback=None):
896 DFReader.__init__(self)
899 self.filehandle.seek(0, 2) 901 if platform.system() ==
"Windows":
904 self.
data_map = mmap.mmap(self.filehandle.fileno(), self.
data_len, mmap.MAP_PRIVATE, mmap.PROT_READ)
912 "Type,Length,Name,Format,Columns")
921 '''rewind to start of log''' 922 DFReader._rewind(self)
924 self.
offset = self.data_map.find(b
'FMT, ')
928 '''rewind to start of log''' 932 '''initialise arrays for fast recv_match()''' 948 self.
offsets[mtype].append(ofs)
956 ofs = self.data_map.find(b
"\n", ofs)
960 new_pct = (100 * ofs) // self.
data_len 961 if progress_callback
is not None and new_pct != pct:
962 progress_callback(new_pct)
965 for mtype
in self.counts.keys():
970 '''skip fwd to next msg matching given type set''' 975 self.type_list.update(set([
'MODE',
'MSG',
'PARM',
'STAT']))
980 self.indexes.append(0)
985 if not mtype
in self.
counts:
990 if ofs < smallest_offset:
991 smallest_offset = ofs
993 if smallest_index >= 0:
994 self.
indexes[smallest_index] += 1
995 self.
offset = smallest_offset
998 '''read one message, returning it as an object''' 1001 endline = self.data_map.find(b
'\n',self.
offset)
1004 if endline < self.
offset:
1007 if sys.version_info.major >= 3:
1008 s = s.decode(
'utf-8')
1009 elements = s.split(
", ")
1011 if len(elements) >= 2:
1019 if len(elements) == 5
and elements[-1] ==
',':
1025 msg_type = elements[0]
1027 if msg_type
not in self.
formats:
1032 if len(elements) < len(fmt.format)+1:
1036 elements = elements[1:]
1038 name = fmt.name.rstrip(
'\0')
1042 if elements[2] ==
'FMT' and elements[4] ==
'Type,Length,Name,Format':
1044 elements[4] =
"Type,Length,Name,Format,Columns" 1050 self.
formats[elements[2]] = new_fmt
1062 '''get the last timestamp in the log''' 1064 for mtype
in self.counts.keys():
1065 if len(self.
offsets[mtype]) == 0:
1068 if ofs > highest_offset:
1069 highest_offset = ofs
1070 self.
offset = highest_offset
1074 if __name__ ==
"__main__":
1075 use_profiler =
False 1077 from line_profiler
import LineProfiler
1078 profiler = LineProfiler()
1079 profiler.add_function(DFReader_binary._parse_next)
1080 profiler.add_function(DFReader_binary._add_msg)
1081 profiler.add_function(DFReader._set_time)
1082 profiler.enable_by_count()
1084 filename = sys.argv[1]
1085 if filename.endswith(
'.log'):
1094 profiler.print_stats()
def init_clock_msec(self)
def set_timebase(self, base)
def set_px4_timebase(self, time_msg)
def init_clock_px4(self, px4_msg_time, px4_msg_gps)
def __init__(self, filename, zero_time_base=False, progress_callback=None)
def find_time_base(self, gps, first_us_stamp)
def set_message_timestamp(self, m)
def param(self, name, default=None)
def message_arrived(self, m)
def gps_message_arrived(self, m)
def __getattr__(self, field)
def __init__(self, filename, zero_time_base=False, progress_callback=None)
def find_time_base(self, gps, first_ms_stamp)
def flightmode_list(self)
def type_has_good_TimeMS(self, type)
def init_clock_usec(self)
def message_arrived(self, m)
def __init__(self, fmt, elements, apply_multiplier)
def init_arrays(self, progress_callback=None)
def check_condition(self, condition)
def find_time_base(self, gps)
def set_message_timestamp(self, m)
def recv_match(self, condition=None, type=None, blocking=False)
def message_arrived(self, m)
def init_arrays(self, progress_callback=None)
def DFReader_is_text_log(filename)
def set_message_timestamp(self, m)
def init_clock_gps_interpolated(self, clock)
def set_message_timestamp(self, m)
def skip_to_type(self, type)
def _gpsTimeToTime(self, week, msec)
def skip_to_type(self, type)
def should_use_msec_field0(self, m)