mavtomfile.py 3.1 KB

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