mavtomfile.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 
3 '''
4 convert a MAVLink tlog file to a MATLab mfile
5 '''
6 from __future__ import print_function
7 from builtins import range
8 
9 import os
10 import re
11 from pymavlink import mavutil
12 
13 def process_tlog(filename):
14  '''convert a tlog to a .m file'''
15 
16  print("Processing %s" % filename)
17 
18  mlog = mavutil.mavlink_connection(filename, dialect=args.dialect, zero_time_base=True)
19 
20  # first walk the entire file, grabbing all messages into a hash of lists,
21  #and the first message of each type into a hash
22  msg_types = {}
23  msg_lists = {}
24 
25  types = args.types
26  if types is not None:
27  types = types.split(',')
28 
29  # note that Octave doesn't like any extra '.', '*', '-', characters in the filename
30  (head, tail) = os.path.split(filename)
31  basename = '.'.join(tail.split('.')[:-1])
32  mfilename = re.sub('[\.\-\+\*]','_', basename) + '.m'
33  # Octave also doesn't like files that don't start with a letter
34  if re.match('^[a-zA-z]', mfilename) is None:
35  mfilename = 'm_' + mfilename
36 
37  if head is not None:
38  mfilename = os.path.join(head, mfilename)
39  print("Creating %s" % mfilename)
40 
41  f = open(mfilename, "w")
42 
43  type_counters = {}
44 
45  while True:
46  m = mlog.recv_match(condition=args.condition)
47  if m is None:
48  break
49 
50  if types is not None and m.get_type() not in types:
51  continue
52  if m.get_type() == 'BAD_DATA':
53  continue
54 
55  fieldnames = m._fieldnames
56  mtype = m.get_type()
57  if mtype in ['FMT', 'PARM']:
58  continue
59 
60  if mtype not in type_counters:
61  type_counters[mtype] = 0
62  f.write("%s.columns = {'timestamp'" % mtype)
63  for field in fieldnames:
64  val = getattr(m, field)
65  if not isinstance(val, str):
66  if type(val) is not list:
67  f.write(",'%s'" % field)
68  else:
69  for i in range(0, len(val)):
70  f.write(",'%s%d'" % (field, i + 1))
71  f.write("};\n")
72 
73  type_counters[mtype] += 1
74  f.write("%s.data(%u,:) = [%f" % (mtype, type_counters[mtype], m._timestamp))
75  for field in m._fieldnames:
76  val = getattr(m, field)
77  if not isinstance(val, str):
78  if type(val) is not list:
79  f.write(",%.20g" % val)
80  else:
81  for i in range(0, len(val)):
82  f.write(",%.20g" % val[i])
83  f.write("];\n")
84  f.close()
85 
86 from argparse import ArgumentParser
87 parser = ArgumentParser(description=__doc__)
88 
89 parser.add_argument("--condition", default=None, help="select packets by condition")
90 parser.add_argument("-o", "--output", default=None, help="output filename")
91 parser.add_argument("--types", default=None, help="types of messages (comma separated)")
92 parser.add_argument("--dialect", default="ardupilotmega", help="MAVLink dialect")
93 parser.add_argument("logs", metavar="LOG", nargs="+")
94 args = parser.parse_args()
95 
96 
97 for filename in args.logs:
98  process_tlog(filename)


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