DFReader.py 37 KB

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