def process(filename): '''process one logfile''' print("Processing %s" % filename) mlog = mavutil.mavlink_connection(filename, notimestamps=opts.notimestamps, robust_parsing=opts.robust) output = None count = 1 dirname = os.path.dirname(filename) while True: m = mlog.recv_match(condition=opts.condition) if m is None: break if mlog.flightmode.upper() == opts.mode.upper(): if output is None: path = os.path.join(dirname, "%s%u.log" % (opts.mode, count)) count += 1 print("Creating %s" % path) output = mavutil.mavlogfile(path, write=True) else: if output is not None: output.close() output = None if output and m.get_type() != 'BAD_DATA': timestamp = getattr(m, '_timestamp', None) output.write(struct.pack('>Q', timestamp*1.0e6)) output.write(m.get_msgbuf())
def process(filename): '''process one logfile''' print("Processing %s" % filename) mlog = mavutil.mavlink_connection(filename, notimestamps=opts.notimestamps, robust_parsing=opts.robust) output = None count = 1 dirname = os.path.dirname(filename) while True: m = mlog.recv_match(condition=opts.condition) if m is None: break if mlog.flightmode.upper() == opts.mode.upper(): if output is None: path = os.path.join(dirname, "%s%u.log" % (opts.mode, count)) count += 1 print("Creating %s" % path) output = mavutil.mavlogfile(path, write=True) else: if output is not None: output.close() output = None if output and m.get_type() != 'BAD_DATA': timestamp = getattr(m, '_timestamp', None) output.write(struct.pack('>Q', timestamp * 1.0e6)) output.write(m.get_msgbuf())
if opts.mav10: os.environ['MAVLINK10'] = '1' import mavutil if len(args) < 1: print("Usage: mavlogdump.py [options] <LOGFILE>") sys.exit(1) filename = args[0] mlog = mavutil.mavlink_connection(filename, planner_format=opts.planner, notimestamps=opts.notimestamps, robust_parsing=opts.robust) output = None if opts.output: output = mavutil.mavlogfile(opts.output, write=True) types = opts.types if types is not None: types = types.split(',') while True: m = mlog.recv_match(condition=opts.condition, blocking=opts.follow) if m is None: break if types is not None and m.get_type() not in types: continue if output: timestamp = getattr(m, '_timestamp', None) if timestamp: output.write(struct.pack('>Q', timestamp*1.0e6))
os.environ['MAVLINK10'] = '1' import mavutil if len(args) < 1: print("Usage: mavlogdump.py [options] <LOGFILE>") sys.exit(1) filename = args[0] mlog = mavutil.mavlink_connection(filename, planner_format=opts.planner, notimestamps=opts.notimestamps, robust_parsing=opts.robust) output = None if opts.output: output = mavutil.mavlogfile(opts.output, write=True) types = opts.types if types is not None: types = types.split(',') while True: m = mlog.recv_match(condition=opts.condition, blocking=opts.follow) if m is None: break if types is not None and m.get_type() not in types: continue if output: timestamp = getattr(m, '_timestamp', None) if timestamp: output.write(struct.pack('>Q', timestamp * 1.0e6))
def set_logfile(self, filename): """provide a mavlink logfile for data""" self.mlog = mavutil.mavlogfile(filename)