DFReader.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
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     def get_fieldnames(self):
00138         return self._fieldnames
00139 
00140 class DFReaderClock():
00141     '''base class for all the different ways we count time in logs'''
00142 
00143     def __init__(self):
00144         self.set_timebase(0)
00145         self.timestamp = 0
00146 
00147     def _gpsTimeToTime(self, week, msec):
00148         '''convert GPS week and TOW to a time in seconds since 1970'''
00149         epoch = 86400*(10*365 + (1980-1969)/4 + 1 + 6 - 2)
00150         return epoch + 86400*7*week + msec*0.001 - 15
00151 
00152     def set_timebase(self, base):
00153         self.timebase = base
00154 
00155     def message_arrived(self, m):
00156         pass
00157 
00158     def rewind_event(self):
00159         pass
00160 
00161 class DFReaderClock_usec(DFReaderClock):
00162     '''DFReaderClock_usec - use microsecond timestamps from messages'''
00163     def __init__(self):
00164         DFReaderClock.__init__(self)
00165 
00166     def find_time_base(self, gps, first_us_stamp):
00167         '''work out time basis for the log - even newer style'''
00168         t = self._gpsTimeToTime(gps.GWk, gps.GMS)
00169         self.set_timebase(t - gps.TimeUS*0.000001)
00170         # this ensures FMT messages get appropriate timestamp:
00171         self.timestamp = self.timebase + first_us_stamp*0.000001
00172 
00173     def type_has_good_TimeMS(self, type):
00174         '''The TimeMS in some messages is not from *our* clock!'''
00175         if type.startswith('ACC'):
00176             return False;
00177         if type.startswith('GYR'):
00178             return False;
00179         return True
00180 
00181     def should_use_msec_field0(self, m):
00182         if not self.type_has_good_TimeMS(m.get_type()):
00183             return False
00184         if 'TimeMS' != m._fieldnames[0]:
00185             return False
00186         if self.timebase + m.TimeMS*0.001 < self.timestamp:
00187             return False
00188         return True;
00189 
00190     def set_message_timestamp(self, m):
00191         if 'TimeUS' == m._fieldnames[0]:
00192             # only format messages don't have a TimeUS in them...
00193             m._timestamp = self.timebase + m.TimeUS*0.000001
00194         elif self.should_use_msec_field0(m):
00195             # ... in theory. I expect there to be some logs which are not
00196             # "pure":
00197             m._timestamp = self.timebase + m.TimeMS*0.001
00198         else:
00199             m._timestamp = self.timestamp
00200         self.timestamp = m._timestamp
00201 
00202 class DFReaderClock_msec(DFReaderClock):
00203     '''DFReaderClock_msec - a format where many messages have TimeMS in their formats, and GPS messages have a "T" field giving msecs '''
00204     def find_time_base(self, gps, first_ms_stamp):
00205         '''work out time basis for the log - new style'''
00206         t = self._gpsTimeToTime(gps.Week, gps.TimeMS)
00207         self.set_timebase(t - gps.T*0.001)
00208         self.timestamp = self.timebase + first_ms_stamp*0.001
00209 
00210     def set_message_timestamp(self, m):
00211         if 'TimeMS' == m._fieldnames[0]:
00212             m._timestamp = self.timebase + m.TimeMS*0.001
00213         elif m.get_type() in ['GPS','GPS2']:
00214             m._timestamp = self.timebase + m.T*0.001
00215         else:
00216             m._timestamp = self.timestamp
00217         self.timestamp = m._timestamp
00218 
00219 class DFReaderClock_px4(DFReaderClock):
00220     '''DFReaderClock_px4 - a format where a starting time is explicitly given in a message'''
00221     def __init__(self):
00222         DFReaderClock.__init__(self)
00223         self.px4_timebase = 0
00224 
00225     def find_time_base(self, gps):
00226         '''work out time basis for the log - PX4 native'''
00227         t = gps.GPSTime * 1.0e-6
00228         self.timebase = t - self.px4_timebase
00229 
00230     def set_px4_timebase(self, time_msg):
00231         self.px4_timebase = time_msg.StartTime * 1.0e-6
00232 
00233     def set_message_timestamp(self, m):
00234         m._timestamp = self.timebase + self.px4_timebase
00235 
00236     def message_arrived(self, m):
00237         type = m.get_type()
00238         if type == 'TIME' and 'StartTime' in m._fieldnames:
00239             self.set_px4_timebase(m)
00240 
00241 class DFReaderClock_gps_interpolated(DFReaderClock):
00242     '''DFReaderClock_gps_interpolated - for when the only real references in a message are GPS timestamps '''
00243     def __init__(self):
00244         DFReaderClock.__init__(self)
00245         self.msg_rate = {}
00246         self.counts = {}
00247         self.counts_since_gps = {}
00248 
00249     def rewind_event(self):
00250         '''reset counters on rewind'''
00251         self.counts = {}
00252         self.counts_since_gps = {}
00253 
00254     def message_arrived(self, m):
00255         type = m.get_type()
00256         if not type in self.counts:
00257             self.counts[type] = 1
00258         else:
00259             self.counts[type] += 1
00260         # this preserves existing behaviour - but should we be doing this
00261         # if type == 'GPS'?
00262         if not type in self.counts_since_gps:
00263             self.counts_since_gps[type] = 1
00264         else:
00265             self.counts_since_gps[type] += 1
00266 
00267         if type == 'GPS' or type == 'GPS2':
00268             self.gps_message_arrived(m)
00269 
00270     def gps_message_arrived(self, m):
00271         '''adjust time base from GPS message'''
00272         # msec-style GPS message?
00273         gps_week = getattr(m, 'Week', None)
00274         gps_timems = getattr(m, 'TimeMS', None)
00275         if gps_week is None:
00276             # usec-style GPS message?
00277             gps_week = getattr(m, 'GWk', None)
00278             gps_timems = getattr(m, 'GMS', None)
00279             if gps_week is None:
00280                 if getattr(m, 'GPSTime', None) is not None:
00281                     # PX4-style timestamp; we've only been called
00282                     # because we were speculatively created in case no
00283                     # better clock was found.
00284                     return;
00285 
00286         t = self._gpsTimeToTime(gps_week, gps_timems) 
00287 
00288         deltat = t - self.timebase
00289         if deltat <= 0:
00290             return
00291 
00292         for type in self.counts_since_gps:
00293             rate = self.counts_since_gps[type] / deltat
00294             if rate > self.msg_rate.get(type, 0):
00295                 self.msg_rate[type] = rate
00296         self.msg_rate['IMU'] = 50.0
00297         self.timebase = t
00298         self.counts_since_gps = {}
00299 
00300     def set_message_timestamp(self, m):
00301         rate = self.msg_rate.get(m.fmt.name, 50.0)
00302         if int(rate) == 0:
00303             rate = 50
00304         count = self.counts_since_gps.get(m.fmt.name, 0)
00305         m._timestamp = self.timebase + count/rate
00306 
00307 
00308 class DFReader(object):
00309     '''parse a generic dataflash file'''
00310     def __init__(self):
00311         # read the whole file into memory for simplicity
00312         self.clock = None
00313         self.timestamp = 0
00314         self.mav_type = mavutil.mavlink.MAV_TYPE_FIXED_WING
00315         self.verbose = False
00316         self.params = {}
00317 
00318     def _rewind(self):
00319         '''reset state on rewind'''
00320         self.messages = { 'MAV' : self }
00321         self.flightmode = "UNKNOWN"
00322         self.percent = 0
00323         if self.clock:
00324             self.clock.rewind_event()
00325 
00326     def init_clock_px4(self, px4_msg_time, px4_msg_gps):
00327         self.clock = DFReaderClock_px4()
00328         if not self._zero_time_base:
00329             self.clock.set_px4_timebase(px4_msg_time)
00330             self.clock.find_time_base(px4_msg_gps)
00331         return True
00332 
00333     def init_clock_msec(self):
00334         # it is a new style flash log with full timestamps
00335         self.clock = DFReaderClock_msec()
00336 
00337     def init_clock_usec(self):
00338         self.clock = DFReaderClock_usec()
00339 
00340     def init_clock_gps_interpolated(self, clock):
00341         self.clock = clock
00342 
00343     def init_clock(self):
00344         '''work out time basis for the log'''
00345 
00346         self._rewind()
00347 
00348         # speculatively create a gps clock in case we don't find anything
00349         # better
00350         gps_clock = DFReaderClock_gps_interpolated()
00351         self.clock = gps_clock
00352 
00353         px4_msg_time = None
00354         px4_msg_gps = None
00355         gps_interp_msg_gps1 = None
00356         gps_interp_msg_gps2 = None
00357         first_us_stamp = None
00358         first_ms_stamp = None
00359 
00360         have_good_clock = False
00361         while True:
00362             m = self.recv_msg()
00363             if m is None:
00364                 break;
00365 
00366             type = m.get_type()
00367 
00368             if first_us_stamp is None:
00369                 first_us_stamp = getattr(m, "TimeUS", None);
00370 
00371             if first_ms_stamp is None and (type != 'GPS' and type != 'GPS2'):
00372                 # Older GPS messages use TimeMS for msecs past start
00373                 # of gps week
00374                 first_ms_stamp = getattr(m, "TimeMS", None);
00375 
00376             if type == 'GPS' or type == 'GPS2':
00377                 if getattr(m, "TimeUS", 0) != 0 and \
00378                    getattr(m, "GWk", 0) != 0: # everything-usec-timestamped
00379                     self.init_clock_usec()
00380                     if not self._zero_time_base:
00381                         self.clock.find_time_base(m, first_us_stamp)
00382                     have_good_clock = True
00383                     break
00384                 if getattr(m, "T", 0) != 0 and \
00385                    getattr(m, "Week", 0) != 0: # GPS is msec-timestamped
00386                     if first_ms_stamp is None:
00387                         first_ms_stamp = m.T
00388                     self.init_clock_msec()
00389                     if not self._zero_time_base:
00390                         self.clock.find_time_base(m, first_ms_stamp)
00391                     have_good_clock = True
00392                     break
00393                 if getattr(m, "GPSTime", 0) != 0: # px4-style-only
00394                     px4_msg_gps = m
00395                 if getattr(m, "Week", 0) != 0:
00396                     if gps_interp_msg_gps1 is not None and \
00397                        (gps_interp_msg_gps1.TimeMS != m.TimeMS or \
00398                         gps_interp_msg_gps1.Week != m.Week):
00399                         # we've received two distinct, non-zero GPS
00400                         # packets without finding a decent clock to
00401                         # use; fall back to interpolation. Q: should
00402                         # we wait a few more messages befoe doing
00403                         # this?
00404                         self.init_clock_gps_interpolated(gps_clock)
00405                         have_good_clock = True
00406                         break
00407                     gps_interp_msg_gps1 = m
00408 
00409             elif type == 'TIME':
00410                 '''only px4-style logs use TIME'''
00411                 if getattr(m, "StartTime", None) != None:
00412                     px4_msg_time = m;
00413 
00414             if px4_msg_time is not None and px4_msg_gps is not None:
00415                 self.init_clock_px4(px4_msg_time, px4_msg_gps)
00416                 have_good_clock = True
00417                 break
00418 
00419 #        print("clock is " + str(self.clock))
00420         if not have_good_clock:
00421             # we failed to find any GPS messages to set a time
00422             # base for usec and msec clocks.  Also, not a
00423             # PX4-style log
00424             if first_us_stamp is not None:
00425                 self.init_clock_usec()
00426             elif first_ms_stamp is not None:
00427                 self.init_clock_msec()
00428 
00429         self._rewind()
00430 
00431         return
00432 
00433     def _set_time(self, m):
00434         '''set time for a message'''
00435         # really just left here for profiling
00436         m._timestamp = self.timestamp
00437         if len(m._fieldnames) > 0 and self.clock is not None:
00438             self.clock.set_message_timestamp(m)
00439 
00440     def recv_msg(self):
00441         return self._parse_next()
00442 
00443     def _add_msg(self, m):
00444         '''add a new message'''
00445         type = m.get_type()
00446         self.messages[type] = m
00447 
00448         if self.clock:
00449             self.clock.message_arrived(m)
00450 
00451         if type == 'MSG':
00452             if m.Message.find("Rover") != -1:
00453                 self.mav_type = mavutil.mavlink.MAV_TYPE_GROUND_ROVER
00454             elif m.Message.find("Plane") != -1:
00455                 self.mav_type = mavutil.mavlink.MAV_TYPE_FIXED_WING
00456             elif m.Message.find("Copter") != -1:
00457                 self.mav_type = mavutil.mavlink.MAV_TYPE_QUADROTOR
00458             elif m.Message.startswith("Antenna"):
00459                 self.mav_type = mavutil.mavlink.MAV_TYPE_ANTENNA_TRACKER
00460         if type == 'MODE':
00461             if isinstance(m.Mode, str):
00462                 self.flightmode = m.Mode.upper()
00463             elif 'ModeNum' in m._fieldnames:
00464                 mapping = mavutil.mode_mapping_bynumber(self.mav_type)
00465                 if mapping is not None and m.ModeNum in mapping:
00466                     self.flightmode = mapping[m.ModeNum]
00467             else:
00468                 self.flightmode = mavutil.mode_string_acm(m.Mode)
00469         if type == 'STAT' and 'MainState' in m._fieldnames:
00470             self.flightmode = mavutil.mode_string_px4(m.MainState)
00471         if type == 'PARM' and getattr(m, 'Name', None) is not None:
00472             self.params[m.Name] = m.Value
00473         self._set_time(m)
00474 
00475     def recv_match(self, condition=None, type=None, blocking=False):
00476         '''recv the next message that matches the given condition
00477         type can be a string or a list of strings'''
00478         if type is not None and not isinstance(type, list):
00479             type = [type]
00480         while True:
00481             m = self.recv_msg()
00482             if m is None:
00483                 return None
00484             if type is not None and not m.get_type() in type:
00485                 continue
00486             if not mavutil.evaluate_condition(condition, self.messages):
00487                 continue
00488             return m
00489 
00490     def check_condition(self, condition):
00491         '''check if a condition is true'''
00492         return mavutil.evaluate_condition(condition, self.messages)
00493 
00494     def param(self, name, default=None):
00495         '''convenient function for returning an arbitrary MAVLink
00496            parameter with a default'''
00497         if not name in self.params:
00498             return default
00499         return self.params[name]
00500 
00501 class DFReader_binary(DFReader):
00502     '''parse a binary dataflash file'''
00503     def __init__(self, filename, zero_time_base=False):
00504         DFReader.__init__(self)
00505         # read the whole file into memory for simplicity
00506         f = open(filename, mode='rb')
00507         self.data = f.read()
00508         self.data_len = len(self.data)
00509         f.close()
00510         self.HEAD1 = 0xA3
00511         self.HEAD2 = 0x95
00512         self.formats = {
00513             0x80 : DFFormat(0x80, 'FMT', 89, 'BBnNZ', "Type,Length,Name,Format,Columns")
00514         }
00515         self._zero_time_base = zero_time_base
00516         self.init_clock()
00517         self._rewind()
00518 
00519     def _rewind(self):
00520         '''rewind to start of log'''
00521         DFReader._rewind(self)
00522         self.offset = 0
00523         self.remaining = self.data_len
00524 
00525     def _parse_next(self):
00526         '''read one message, returning it as an object'''
00527         if self.data_len - self.offset < 3:
00528             return None
00529             
00530         hdr = self.data[self.offset:self.offset+3]
00531         skip_bytes = 0
00532         skip_type = None
00533         # skip over bad messages
00534         while (ord(hdr[0]) != self.HEAD1 or ord(hdr[1]) != self.HEAD2 or ord(hdr[2]) not in self.formats):
00535             if skip_type is None:
00536                 skip_type = (ord(hdr[0]), ord(hdr[1]), ord(hdr[2]))
00537             skip_bytes += 1
00538             self.offset += 1
00539             if self.data_len - self.offset < 3:
00540                 return None
00541             hdr = self.data[self.offset:self.offset+3]
00542         msg_type = ord(hdr[2])
00543         if skip_bytes != 0:
00544             if self.remaining < 528:
00545                 return None
00546             print("Skipped %u bad bytes in log %s remaining=%u" % (skip_bytes, skip_type, self.remaining))
00547             self.remaining -= skip_bytes
00548 
00549         self.offset += 3
00550         self.remaining -= 3
00551 
00552         if not msg_type in self.formats:
00553             if self.verbose:
00554                 print("unknown message type %02x" % msg_type)
00555             raise Exception("Unknown message type %02x" % msg_type)
00556         fmt = self.formats[msg_type]
00557         if self.remaining < fmt.len-3:
00558             # out of data - can often happen half way through a message
00559             if self.verbose:
00560                 print("out of data")
00561             return None
00562         body = self.data[self.offset:self.offset+(fmt.len-3)]
00563         elements = None
00564         try:
00565             elements = list(struct.unpack(fmt.msg_struct, body))
00566         except Exception:
00567             if self.remaining < 528:
00568                 # we can have garbage at the end of an APM2 log
00569                 return None
00570             # we should also cope with other corruption; logs
00571             # transfered via DataFlash_MAVLink may have blocks of 0s
00572             # in them, for example
00573             print("Failed to parse %s/%s with len %u (remaining %u)" % (fmt.name, fmt.msg_struct, len(body), self.remaining))
00574         if elements is None:
00575             return self._parse_next()
00576         name = null_term(fmt.name)
00577         if name == 'FMT':
00578             # add to formats
00579             # name, len, format, headings
00580             self.formats[elements[0]] = DFFormat(elements[0],
00581                                                  null_term(elements[2]), elements[1],
00582                                                  null_term(elements[3]), null_term(elements[4]))
00583 
00584         self.offset += fmt.len-3
00585         self.remaining -= fmt.len-3
00586         m = DFMessage(fmt, elements, True)
00587         self._add_msg(m)
00588 
00589         self.percent = 100.0 * (self.offset / float(self.data_len))
00590         
00591         return m
00592 
00593 def DFReader_is_text_log(filename):
00594     '''return True if a file appears to be a valid text log'''
00595     f = open(filename)
00596     ret = (f.read(8000).find('FMT, ') != -1)
00597     f.close()
00598     return ret
00599 
00600 class DFReader_text(DFReader):
00601     '''parse a text dataflash file'''
00602     def __init__(self, filename, zero_time_base=False):
00603         DFReader.__init__(self)
00604         # read the whole file into memory for simplicity
00605         f = open(filename, mode='r')
00606         self.lines = f.readlines()
00607         f.close()
00608         self.formats = {
00609             'FMT' : DFFormat(0x80, 'FMT', 89, 'BBnNZ', "Type,Length,Name,Format,Columns")
00610         }
00611         self._rewind()
00612         self._zero_time_base = zero_time_base
00613         self.init_clock()
00614         self._rewind()
00615 
00616     def _rewind(self):
00617         '''rewind to start of log'''
00618         DFReader._rewind(self)
00619         self.line = 0
00620         # find the first valid line
00621         while self.line < len(self.lines):
00622             if self.lines[self.line].startswith("FMT, "):
00623                 break
00624             self.line += 1
00625 
00626     def _parse_next(self):
00627         '''read one message, returning it as an object'''
00628 
00629         this_line = self.line
00630         while self.line < len(self.lines):
00631             s = self.lines[self.line].rstrip()
00632             elements = s.split(", ")
00633             this_line = self.line
00634             # move to next line
00635             self.line += 1
00636             if len(elements) >= 2:
00637                 # this_line is good
00638                 break
00639 
00640         if this_line >= len(self.lines):
00641             return None
00642 
00643         # cope with empty structures
00644         if len(elements) == 5 and elements[-1] == ',':
00645             elements[-1] = ''
00646             elements.append('')
00647 
00648         self.percent = 100.0 * (this_line / float(len(self.lines)))
00649 
00650         msg_type = elements[0]
00651 
00652         if not msg_type in self.formats:
00653             return self._parse_next()
00654         
00655         fmt = self.formats[msg_type]
00656 
00657         if len(elements) < len(fmt.format)+1:
00658             # not enough columns
00659             return self._parse_next()
00660 
00661         elements = elements[1:]
00662         
00663         name = fmt.name.rstrip('\0')
00664         if name == 'FMT':
00665             # add to formats
00666             # name, len, format, headings
00667             self.formats[elements[2]] = DFFormat(int(elements[0]), elements[2], int(elements[1]), elements[3], elements[4])
00668 
00669         try:
00670             m = DFMessage(fmt, elements, False)
00671         except ValueError:
00672             return self._parse_next()
00673 
00674         self._add_msg(m)
00675 
00676         return m
00677 
00678 
00679 if __name__ == "__main__":
00680     import sys
00681     use_profiler = False
00682     if use_profiler:
00683         from line_profiler import LineProfiler
00684         profiler = LineProfiler()
00685         profiler.add_function(DFReader_binary._parse_next)
00686         profiler.add_function(DFReader_binary._add_msg)
00687         profiler.add_function(DFReader._set_time)
00688         profiler.enable_by_count()
00689                     
00690     filename = sys.argv[1]
00691     if filename.endswith('.log'):
00692         log = DFReader_text(filename)
00693     else:
00694         log = DFReader_binary(filename)
00695     while True:
00696         m = log.recv_msg()
00697         if m is None:
00698             break
00699         #print(m)
00700     if use_profiler:
00701         profiler.print_stats()
00702 


mavlink
Author(s): Lorenz Meier
autogenerated on Sun May 22 2016 04:05:43