mavextract.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 
3 '''
4 extract one mode type from a log
5 '''
6 from __future__ import print_function
7 
8 import os
9 import struct
10 
11 from argparse import ArgumentParser
12 parser = ArgumentParser(description=__doc__)
13 
14 parser.add_argument("--no-timestamps", dest="notimestamps", action='store_true', help="Log doesn't have timestamps")
15 parser.add_argument("--robust", action='store_true', help="Enable robust parsing (skip over bad data)")
16 parser.add_argument("--condition", default=None, help="select packets by condition")
17 parser.add_argument("--mode", default='auto', help="mode to extract")
18 parser.add_argument("--link", default=None, type=int, help="only extract specific comms link")
19 parser.add_argument("logs", metavar="LOG", nargs="+")
20 args = parser.parse_args()
21 
22 from pymavlink import mavutil
23 
24 def older_message(m, lastm):
25  '''return true if m is older than lastm by timestamp'''
26  atts = {'time_boot_ms' : 1.0e-3,
27  'time_unix_usec' : 1.0e-6,
28  'time_usec' : 1.0e-6}
29  for a in list(atts.keys()):
30  if hasattr(m, a):
31  mul = atts[a]
32  t1 = m.getattr(a) * mul
33  t2 = lastm.getattr(a) * mul
34  if t2 >= t1 and t2 - t1 < 60:
35  return True
36  return False
37 
38 def process(filename):
39  '''process one logfile'''
40  print("Processing %s" % filename)
41  mlog = mavutil.mavlink_connection(filename, notimestamps=args.notimestamps,
42  robust_parsing=args.robust)
43 
44 
45  ext = os.path.splitext(filename)[1]
46  isbin = ext in ['.bin', '.BIN']
47  islog = ext in ['.log', '.LOG']
48  output = None
49  count = 1
50  dirname = os.path.dirname(filename)
51 
52  if isbin or islog:
53  extension = "bin"
54  else:
55  extension = "tlog"
56 
57  file_header = ''
58 
59  messages = []
60 
61  # we allow a list of modes that map to one mode number. This allows for --mode=AUTO,RTL and consider the RTL as part of AUTO
62  modes = args.mode.upper().split(',')
63  flightmode = None
64 
65  while True:
66  m = mlog.recv_match()
67  if m is None:
68  break
69  if args.link is not None and m._link != args.link:
70  continue
71 
72  mtype = m.get_type()
73  if mtype in messages:
74  if older_message(m, messages[mtype]):
75  continue
76 
77  # we don't use mlog.flightmode as that can be wrong if we are extracting a single link
78  if mtype == 'HEARTBEAT' and m.get_srcComponent() != mavutil.mavlink.MAV_COMP_ID_GIMBAL and m.type != mavutil.mavlink.MAV_TYPE_GCS:
79  flightmode = mavutil.mode_string_v10(m).upper()
80  if mtype == 'MODE':
81  flightmode = mlog.flightmode
82 
83  if (isbin or islog) and m.get_type() in ["FMT", "PARM", "CMD"]:
84  file_header += m.get_msgbuf()
85  if (isbin or islog) and m.get_type() == 'MSG' and m.Message.startswith("Ardu"):
86  file_header += m.get_msgbuf()
87  if m.get_type() in ['PARAM_VALUE','MISSION_ITEM']:
88  timestamp = getattr(m, '_timestamp', None)
89  file_header += struct.pack('>Q', timestamp*1.0e6) + m.get_msgbuf()
90 
91  if not mavutil.evaluate_condition(args.condition, mlog.messages):
92  continue
93 
94  if flightmode in modes:
95  if output is None:
96  path = os.path.join(dirname, "%s%u.%s" % (modes[0], count, extension))
97  count += 1
98  print("Creating %s" % path)
99  output = open(path, mode='wb')
100  output.write(file_header)
101  else:
102  if output is not None:
103  output.close()
104  output = None
105 
106  if output and m.get_type() != 'BAD_DATA':
107  timestamp = getattr(m, '_timestamp', None)
108  if not isbin:
109  output.write(struct.pack('>Q', timestamp*1.0e6))
110  output.write(m.get_msgbuf())
111 
112 for filename in args.logs:
113  process(filename)
114 


mavlink
Author(s): Lorenz Meier
autogenerated on Sun Apr 7 2019 02:06:02