00001
00002 '''
00003 APM DataFlash log file reader
00004
00005 Copyright Andrew Tridgell 2011
00006 Released under GNU GPL version 3 or later
00007
00008 Partly based on SDLog2Parser by Anton Babushkin
00009 '''
00010
00011 import struct, time, os
00012 from . import mavutil
00013
00014 FORMAT_TO_STRUCT = {
00015 "b": ("b", None, int),
00016 "B": ("B", None, int),
00017 "h": ("h", None, int),
00018 "H": ("H", None, int),
00019 "i": ("i", None, int),
00020 "I": ("I", None, int),
00021 "f": ("f", None, float),
00022 "n": ("4s", None, str),
00023 "N": ("16s", None, str),
00024 "Z": ("64s", None, str),
00025 "c": ("h", 0.01, float),
00026 "C": ("H", 0.01, float),
00027 "e": ("i", 0.01, float),
00028 "E": ("I", 0.01, float),
00029 "L": ("i", 1.0e-7, float),
00030 "d": ("d", None, float),
00031 "M": ("b", None, int),
00032 "q": ("q", None, long),
00033 "Q": ("Q", None, long),
00034 }
00035
00036 class DFFormat(object):
00037 def __init__(self, type, name, flen, format, columns):
00038 self.type = type
00039 self.name = name
00040 self.len = flen
00041 self.format = format
00042 self.columns = columns.split(',')
00043
00044 if self.columns == ['']:
00045 self.columns = []
00046
00047 msg_struct = "<"
00048 msg_mults = []
00049 msg_types = []
00050 for c in format:
00051 if ord(c) == 0:
00052 break
00053 try:
00054 (s, mul, type) = FORMAT_TO_STRUCT[c]
00055 msg_struct += s
00056 msg_mults.append(mul)
00057 msg_types.append(type)
00058 except KeyError as e:
00059 raise Exception("Unsupported format char: '%s' in message %s" % (c, name))
00060
00061 self.msg_struct = msg_struct
00062 self.msg_types = msg_types
00063 self.msg_mults = msg_mults
00064 self.colhash = {}
00065 for i in range(len(self.columns)):
00066 self.colhash[self.columns[i]] = i
00067
00068 def __str__(self):
00069 return "DFFormat(%s,%s,%s,%s)" % (self.type, self.name, self.format, self.columns)
00070
00071 def null_term(str):
00072 '''null terminate a string'''
00073 idx = str.find("\0")
00074 if idx != -1:
00075 str = str[:idx]
00076 return str
00077
00078 class DFMessage(object):
00079 def __init__(self, fmt, elements, apply_multiplier):
00080 self.fmt = fmt
00081 self._elements = elements
00082 self._apply_multiplier = apply_multiplier
00083 self._fieldnames = fmt.columns
00084
00085 def to_dict(self):
00086 d = {'mavpackettype': self.fmt.name}
00087
00088 for field in self._fieldnames:
00089 d[field] = self.__getattr__(field)
00090
00091 return d
00092
00093 def __getattr__(self, field):
00094 '''override field getter'''
00095 try:
00096 i = self.fmt.colhash[field]
00097 except Exception:
00098 raise AttributeError(field)
00099 v = self._elements[i]
00100 if self.fmt.format[i] != 'M' or self._apply_multiplier:
00101 v = self.fmt.msg_types[i](v)
00102 if self.fmt.msg_types[i] == str:
00103 v = null_term(v)
00104 if self.fmt.msg_mults[i] is not None and self._apply_multiplier:
00105 v *= self.fmt.msg_mults[i]
00106 return v
00107
00108 def get_type(self):
00109 return self.fmt.name
00110
00111 def __str__(self):
00112 ret = "%s {" % self.fmt.name
00113 col_count = 0
00114 for c in self.fmt.columns:
00115 ret += "%s : %s, " % (c, self.__getattr__(c))
00116 col_count += 1
00117 if col_count != 0:
00118 ret = ret[:-2]
00119 return ret + '}'
00120
00121 def get_msgbuf(self):
00122 '''create a binary message buffer for a message'''
00123 values = []
00124 for i in range(len(self.fmt.columns)):
00125 if i >= len(self.fmt.msg_mults):
00126 continue
00127 mul = self.fmt.msg_mults[i]
00128 name = self.fmt.columns[i]
00129 if name == 'Mode' and 'ModeNum' in self.fmt.columns:
00130 name = 'ModeNum'
00131 v = self.__getattr__(name)
00132 if mul is not None:
00133 v /= mul
00134 values.append(v)
00135 return struct.pack("BBB", 0xA3, 0x95, self.fmt.type) + struct.pack(self.fmt.msg_struct, *values)
00136
00137
00138 class DFReaderClock():
00139 '''base class for all the different ways we count time in logs'''
00140
00141 def __init__(self):
00142 self.set_timebase(0)
00143 self.timestamp = 0
00144
00145 def _gpsTimeToTime(self, week, msec):
00146 '''convert GPS week and TOW to a time in seconds since 1970'''
00147 epoch = 86400*(10*365 + (1980-1969)/4 + 1 + 6 - 2)
00148 return epoch + 86400*7*week + msec*0.001 - 15
00149
00150 def set_timebase(self, base):
00151 self.timebase = base
00152
00153 def message_arrived(self, m):
00154 pass
00155
00156 def rewind_event(self):
00157 pass
00158
00159 class DFReaderClock_usec(DFReaderClock):
00160 '''DFReaderClock_usec - use microsecond timestamps from messages'''
00161 def __init__(self):
00162 DFReaderClock.__init__(self)
00163
00164 def find_time_base(self, gps, first_us_stamp):
00165 '''work out time basis for the log - even newer style'''
00166 t = self._gpsTimeToTime(gps.GWk, gps.GMS)
00167 self.set_timebase(t - gps.TimeUS*0.000001)
00168
00169 self.timestamp = self.timebase + first_us_stamp*0.000001
00170
00171 def type_has_good_TimeMS(self, type):
00172 '''The TimeMS in some messages is not from *our* clock!'''
00173 if type.startswith('ACC'):
00174 return False;
00175 if type.startswith('GYR'):
00176 return False;
00177 return True
00178
00179 def should_use_msec_field0(self, m):
00180 if not self.type_has_good_TimeMS(m.get_type()):
00181 return False
00182 if 'TimeMS' != m._fieldnames[0]:
00183 return False
00184 if self.timebase + m.TimeMS*0.001 < self.timestamp:
00185 return False
00186 return True;
00187
00188 def set_message_timestamp(self, m):
00189 if 'TimeUS' == m._fieldnames[0]:
00190
00191 m._timestamp = self.timebase + m.TimeUS*0.000001
00192 elif self.should_use_msec_field0(m):
00193
00194
00195 m._timestamp = self.timebase + m.TimeMS*0.001
00196 else:
00197 m._timestamp = self.timestamp
00198 self.timestamp = m._timestamp
00199
00200 class DFReaderClock_msec(DFReaderClock):
00201 '''DFReaderClock_msec - a format where many messages have TimeMS in their formats, and GPS messages have a "T" field giving msecs '''
00202 def find_time_base(self, gps, first_ms_stamp):
00203 '''work out time basis for the log - new style'''
00204 t = self._gpsTimeToTime(gps.Week, gps.TimeMS)
00205 self.set_timebase(t - gps.T*0.001)
00206 self.timestamp = self.timebase + first_ms_stamp*0.001
00207
00208 def set_message_timestamp(self, m):
00209 if 'TimeMS' == m._fieldnames[0]:
00210 m._timestamp = self.timebase + m.TimeMS*0.001
00211 elif m.get_type() in ['GPS','GPS2']:
00212 m._timestamp = self.timebase + m.T*0.001
00213 else:
00214 m._timestamp = self.timestamp
00215 self.timestamp = m._timestamp
00216
00217 class DFReaderClock_px4(DFReaderClock):
00218 '''DFReaderClock_px4 - a format where a starting time is explicitly given in a message'''
00219 def __init__(self):
00220 DFReaderClock.__init__(self)
00221 self.px4_timebase = 0
00222
00223 def find_time_base(self, gps):
00224 '''work out time basis for the log - PX4 native'''
00225 t = gps.GPSTime * 1.0e-6
00226 self.timebase = t - self.px4_timebase
00227
00228 def set_px4_timebase(self, time_msg):
00229 self.px4_timebase = time_msg.StartTime * 1.0e-6
00230
00231 def set_message_timestamp(self, m):
00232 m._timestamp = self.timebase + self.px4_timebase
00233
00234 def message_arrived(self, m):
00235 type = m.get_type()
00236 if type == 'TIME' and 'StartTime' in m._fieldnames:
00237 self.set_px4_timebase(m)
00238
00239 class DFReaderClock_gps_interpolated(DFReaderClock):
00240 '''DFReaderClock_gps_interpolated - for when the only real references in a message are GPS timestamps '''
00241 def __init__(self):
00242 DFReaderClock.__init__(self)
00243 self.msg_rate = {}
00244 self.counts = {}
00245 self.counts_since_gps = {}
00246
00247 def rewind_event(self):
00248 '''reset counters on rewind'''
00249 self.counts = {}
00250 self.counts_since_gps = {}
00251
00252 def message_arrived(self, m):
00253 type = m.get_type()
00254 if not type in self.counts:
00255 self.counts[type] = 1
00256 else:
00257 self.counts[type] += 1
00258
00259
00260 if not type in self.counts_since_gps:
00261 self.counts_since_gps[type] = 1
00262 else:
00263 self.counts_since_gps[type] += 1
00264
00265 if type == 'GPS' or type == 'GPS2':
00266 self.gps_message_arrived(m)
00267
00268 def gps_message_arrived(self, m):
00269 '''adjust time base from GPS message'''
00270
00271 gps_week = getattr(m, 'Week', None)
00272 gps_timems = getattr(m, 'TimeMS', None)
00273 if gps_week is None:
00274
00275 gps_week = getattr(m, 'GWk', None)
00276 gps_timems = getattr(m, 'GMS', None)
00277 if gps_week is None:
00278 if getattr(m, 'GPSTime', None) is not None:
00279
00280
00281
00282 return;
00283
00284 t = self._gpsTimeToTime(gps_week, gps_timems)
00285
00286 deltat = t - self.timebase
00287 if deltat <= 0:
00288 return
00289
00290 for type in self.counts_since_gps:
00291 rate = self.counts_since_gps[type] / deltat
00292 if rate > self.msg_rate.get(type, 0):
00293 self.msg_rate[type] = rate
00294 self.msg_rate['IMU'] = 50.0
00295 self.timebase = t
00296 self.counts_since_gps = {}
00297
00298 def set_message_timestamp(self, m):
00299 rate = self.msg_rate.get(m.fmt.name, 50.0)
00300 if int(rate) == 0:
00301 rate = 50
00302 count = self.counts_since_gps.get(m.fmt.name, 0)
00303 m._timestamp = self.timebase + count/rate
00304
00305
00306 class DFReader(object):
00307 '''parse a generic dataflash file'''
00308 def __init__(self):
00309
00310 self.clock = None
00311 self.timestamp = 0
00312 self.mav_type = mavutil.mavlink.MAV_TYPE_FIXED_WING
00313 self.verbose = False
00314 self.params = {}
00315
00316 def _rewind(self):
00317 '''reset state on rewind'''
00318 self.messages = { 'MAV' : self }
00319 self.flightmode = "UNKNOWN"
00320 self.percent = 0
00321 if self.clock:
00322 self.clock.rewind_event()
00323
00324 def init_clock_px4(self, px4_msg_time, px4_msg_gps):
00325 self.clock = DFReaderClock_px4()
00326 if not self._zero_time_base:
00327 self.clock.set_px4_timebase(px4_msg_time)
00328 self.clock.find_time_base(px4_msg_gps)
00329 return True
00330
00331 def init_clock_msec(self):
00332
00333 self.clock = DFReaderClock_msec()
00334
00335 def init_clock_usec(self):
00336 self.clock = DFReaderClock_usec()
00337
00338 def init_clock_gps_interpolated(self, clock):
00339 self.clock = clock
00340
00341 def init_clock(self):
00342 '''work out time basis for the log'''
00343
00344 self._rewind()
00345
00346
00347
00348 gps_clock = DFReaderClock_gps_interpolated()
00349 self.clock = gps_clock
00350
00351 px4_msg_time = None
00352 px4_msg_gps = None
00353 gps_interp_msg_gps1 = None
00354 gps_interp_msg_gps2 = None
00355 first_us_stamp = None
00356 first_ms_stamp = None
00357
00358 have_good_clock = False
00359 while True:
00360 m = self.recv_msg()
00361 if m is None:
00362 break;
00363
00364 type = m.get_type()
00365
00366 if first_us_stamp is None:
00367 first_us_stamp = getattr(m, "TimeUS", None);
00368
00369 if first_ms_stamp is None and (type != 'GPS' and type != 'GPS2'):
00370
00371
00372 first_ms_stamp = getattr(m, "TimeMS", None);
00373
00374 if type == 'GPS' or type == 'GPS2':
00375 if getattr(m, "TimeUS", 0) != 0 and \
00376 getattr(m, "GWk", 0) != 0:
00377 self.init_clock_usec()
00378 if not self._zero_time_base:
00379 self.clock.find_time_base(m, first_us_stamp)
00380 have_good_clock = True
00381 break
00382 if getattr(m, "T", 0) != 0 and \
00383 getattr(m, "Week", 0) != 0:
00384 if first_ms_stamp is None:
00385 first_ms_stamp = m.T
00386 self.init_clock_msec()
00387 if not self._zero_time_base:
00388 self.clock.find_time_base(m, first_ms_stamp)
00389 have_good_clock = True
00390 break
00391 if getattr(m, "GPSTime", 0) != 0:
00392 px4_msg_gps = m
00393 if getattr(m, "Week", 0) != 0:
00394 if gps_interp_msg_gps1 is not None and \
00395 (gps_interp_msg_gps1.TimeMS != m.TimeMS or \
00396 gps_interp_msg_gps1.Week != m.Week):
00397
00398
00399
00400
00401
00402 self.init_clock_gps_interpolated(gps_clock)
00403 have_good_clock = True
00404 break
00405 gps_interp_msg_gps1 = m
00406
00407 elif type == 'TIME':
00408 '''only px4-style logs use TIME'''
00409 if getattr(m, "StartTime", None) != None:
00410 px4_msg_time = m;
00411
00412 if px4_msg_time is not None and px4_msg_gps is not None:
00413 self.init_clock_px4(px4_msg_time, px4_msg_gps)
00414 have_good_clock = True
00415 break
00416
00417
00418 if not have_good_clock:
00419
00420
00421
00422 if first_us_stamp is not None:
00423 self.init_clock_usec()
00424 elif first_ms_stamp is not None:
00425 self.init_clock_msec()
00426
00427 self._rewind()
00428
00429 return
00430
00431 def _set_time(self, m):
00432 '''set time for a message'''
00433
00434 m._timestamp = self.timestamp
00435 if len(m._fieldnames) > 0 and self.clock is not None:
00436 self.clock.set_message_timestamp(m)
00437
00438 def recv_msg(self):
00439 return self._parse_next()
00440
00441 def _add_msg(self, m):
00442 '''add a new message'''
00443 type = m.get_type()
00444 self.messages[type] = m
00445
00446 if self.clock:
00447 self.clock.message_arrived(m)
00448
00449 if type == 'MSG':
00450 if m.Message.find("Rover") != -1:
00451 self.mav_type = mavutil.mavlink.MAV_TYPE_GROUND_ROVER
00452 elif m.Message.find("Plane") != -1:
00453 self.mav_type = mavutil.mavlink.MAV_TYPE_FIXED_WING
00454 elif m.Message.find("Copter") != -1:
00455 self.mav_type = mavutil.mavlink.MAV_TYPE_QUADROTOR
00456 elif m.Message.startswith("Antenna"):
00457 self.mav_type = mavutil.mavlink.MAV_TYPE_ANTENNA_TRACKER
00458 if type == 'MODE':
00459 if isinstance(m.Mode, str):
00460 self.flightmode = m.Mode.upper()
00461 elif 'ModeNum' in m._fieldnames:
00462 mapping = mavutil.mode_mapping_bynumber(self.mav_type)
00463 if mapping is not None and m.ModeNum in mapping:
00464 self.flightmode = mapping[m.ModeNum]
00465 else:
00466 self.flightmode = mavutil.mode_string_acm(m.Mode)
00467 if type == 'STAT' and 'MainState' in m._fieldnames:
00468 self.flightmode = mavutil.mode_string_px4(m.MainState)
00469 if type == 'PARM' and getattr(m, 'Name', None) is not None:
00470 self.params[m.Name] = m.Value
00471 self._set_time(m)
00472
00473 def recv_match(self, condition=None, type=None, blocking=False):
00474 '''recv the next message that matches the given condition
00475 type can be a string or a list of strings'''
00476 if type is not None and not isinstance(type, list):
00477 type = [type]
00478 while True:
00479 m = self.recv_msg()
00480 if m is None:
00481 return None
00482 if type is not None and not m.get_type() in type:
00483 continue
00484 if not mavutil.evaluate_condition(condition, self.messages):
00485 continue
00486 return m
00487
00488 def check_condition(self, condition):
00489 '''check if a condition is true'''
00490 return mavutil.evaluate_condition(condition, self.messages)
00491
00492 def param(self, name, default=None):
00493 '''convenient function for returning an arbitrary MAVLink
00494 parameter with a default'''
00495 if not name in self.params:
00496 return default
00497 return self.params[name]
00498
00499 class DFReader_binary(DFReader):
00500 '''parse a binary dataflash file'''
00501 def __init__(self, filename, zero_time_base=False):
00502 DFReader.__init__(self)
00503
00504 f = open(filename, mode='rb')
00505 self.data = f.read()
00506 self.data_len = len(self.data)
00507 f.close()
00508 self.HEAD1 = 0xA3
00509 self.HEAD2 = 0x95
00510 self.formats = {
00511 0x80 : DFFormat(0x80, 'FMT', 89, 'BBnNZ', "Type,Length,Name,Format,Columns")
00512 }
00513 self._zero_time_base = zero_time_base
00514 self.init_clock()
00515 self._rewind()
00516
00517 def _rewind(self):
00518 '''rewind to start of log'''
00519 DFReader._rewind(self)
00520 self.offset = 0
00521 self.remaining = self.data_len
00522
00523 def _parse_next(self):
00524 '''read one message, returning it as an object'''
00525 if self.data_len - self.offset < 3:
00526 return None
00527
00528 hdr = self.data[self.offset:self.offset+3]
00529 skip_bytes = 0
00530 skip_type = None
00531
00532 while (ord(hdr[0]) != self.HEAD1 or ord(hdr[1]) != self.HEAD2 or ord(hdr[2]) not in self.formats):
00533 if skip_type is None:
00534 skip_type = (ord(hdr[0]), ord(hdr[1]), ord(hdr[2]))
00535 skip_bytes += 1
00536 self.offset += 1
00537 if self.data_len - self.offset < 3:
00538 return None
00539 hdr = self.data[self.offset:self.offset+3]
00540 msg_type = ord(hdr[2])
00541 if skip_bytes != 0:
00542 if self.remaining < 528:
00543 return None
00544 print("Skipped %u bad bytes in log %s remaining=%u" % (skip_bytes, skip_type, self.remaining))
00545 self.remaining -= skip_bytes
00546
00547 self.offset += 3
00548 self.remaining -= 3
00549
00550 if not msg_type in self.formats:
00551 if self.verbose:
00552 print("unknown message type %02x" % msg_type)
00553 raise Exception("Unknown message type %02x" % msg_type)
00554 fmt = self.formats[msg_type]
00555 if self.remaining < fmt.len-3:
00556
00557 if self.verbose:
00558 print("out of data")
00559 return None
00560 body = self.data[self.offset:self.offset+(fmt.len-3)]
00561 elements = None
00562 try:
00563 elements = list(struct.unpack(fmt.msg_struct, body))
00564 except Exception:
00565 if self.remaining < 528:
00566
00567 return None
00568
00569
00570
00571 print("Failed to parse %s/%s with len %u (remaining %u)" % (fmt.name, fmt.msg_struct, len(body), self.remaining))
00572 if elements is None:
00573 return self._parse_next()
00574 name = null_term(fmt.name)
00575 if name == 'FMT':
00576
00577
00578 self.formats[elements[0]] = DFFormat(elements[0],
00579 null_term(elements[2]), elements[1],
00580 null_term(elements[3]), null_term(elements[4]))
00581
00582 self.offset += fmt.len-3
00583 self.remaining -= fmt.len-3
00584 m = DFMessage(fmt, elements, True)
00585 self._add_msg(m)
00586
00587 self.percent = 100.0 * (self.offset / float(self.data_len))
00588
00589 return m
00590
00591 def DFReader_is_text_log(filename):
00592 '''return True if a file appears to be a valid text log'''
00593 f = open(filename)
00594 ret = (f.read(8000).find('FMT, ') != -1)
00595 f.close()
00596 return ret
00597
00598 class DFReader_text(DFReader):
00599 '''parse a text dataflash file'''
00600 def __init__(self, filename, zero_time_base=False):
00601 DFReader.__init__(self)
00602
00603 f = open(filename, mode='r')
00604 self.lines = f.readlines()
00605 f.close()
00606 self.formats = {
00607 'FMT' : DFFormat(0x80, 'FMT', 89, 'BBnNZ', "Type,Length,Name,Format,Columns")
00608 }
00609 self._rewind()
00610 self._zero_time_base = zero_time_base
00611 self.init_clock()
00612 self._rewind()
00613
00614 def _rewind(self):
00615 '''rewind to start of log'''
00616 DFReader._rewind(self)
00617 self.line = 0
00618
00619 while self.line < len(self.lines):
00620 if self.lines[self.line].startswith("FMT, "):
00621 break
00622 self.line += 1
00623
00624 def _parse_next(self):
00625 '''read one message, returning it as an object'''
00626 while self.line < len(self.lines):
00627 s = self.lines[self.line].rstrip()
00628 elements = s.split(", ")
00629
00630 self.line += 1
00631 if len(elements) >= 2:
00632 break
00633
00634 if self.line >= len(self.lines):
00635 return None
00636
00637
00638 if len(elements) == 5 and elements[-1] == ',':
00639 elements[-1] = ''
00640 elements.append('')
00641
00642 self.percent = 100.0 * (self.line / float(len(self.lines)))
00643
00644 msg_type = elements[0]
00645
00646 if not msg_type in self.formats:
00647 return self._parse_next()
00648
00649 fmt = self.formats[msg_type]
00650
00651 if len(elements) < len(fmt.format)+1:
00652
00653 return self._parse_next()
00654
00655 elements = elements[1:]
00656
00657 name = fmt.name.rstrip('\0')
00658 if name == 'FMT':
00659
00660
00661 self.formats[elements[2]] = DFFormat(int(elements[0]), elements[2], int(elements[1]), elements[3], elements[4])
00662
00663 try:
00664 m = DFMessage(fmt, elements, False)
00665 except ValueError:
00666 return self._parse_next()
00667
00668 self._add_msg(m)
00669
00670 return m
00671
00672
00673 if __name__ == "__main__":
00674 import sys
00675 use_profiler = False
00676 if use_profiler:
00677 from line_profiler import LineProfiler
00678 profiler = LineProfiler()
00679 profiler.add_function(DFReader_binary._parse_next)
00680 profiler.add_function(DFReader_binary._add_msg)
00681 profiler.add_function(DFReader._set_time)
00682 profiler.enable_by_count()
00683
00684 filename = sys.argv[1]
00685 if filename.endswith('.log'):
00686 log = DFReader_text(filename)
00687 else:
00688 log = DFReader_binary(filename)
00689 while True:
00690 m = log.recv_msg()
00691 if m is None:
00692 break
00693
00694 if use_profiler:
00695 profiler.print_stats()
00696