mavfft_isb.py 4.5 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143
  1. #!/usr/bin/env python
  2. '''
  3. extract ISBH and ISBD messages from AP_Logging files and produce FFT plots
  4. '''
  5. from __future__ import print_function
  6. import numpy
  7. import os
  8. import pylab
  9. import sys
  10. import time
  11. from argparse import ArgumentParser
  12. parser = ArgumentParser(description=__doc__)
  13. parser.add_argument("--condition", default=None, help="select packets by condition")
  14. parser.add_argument("logs", metavar="LOG", nargs="+")
  15. args = parser.parse_args()
  16. from pymavlink import mavutil
  17. def mavfft_fttd(logfile):
  18. '''display fft for raw ACC data in logfile'''
  19. '''object to store data about a single FFT plot'''
  20. class PlotData(object):
  21. def __init__(self, ffth):
  22. self.seqno = -1
  23. self.fftnum = ffth.N
  24. self.sensor_type = ffth.type
  25. self.instance = ffth.instance
  26. self.sample_rate_hz = ffth.smp_rate
  27. self.multiplier = ffth.mul
  28. self.data = {}
  29. self.data["X"] = []
  30. self.data["Y"] = []
  31. self.data["Z"] = []
  32. self.holes = False
  33. self.freq = None
  34. def add_fftd(self, fftd):
  35. if fftd.N != self.fftnum:
  36. print("Skipping ISBD with wrong fftnum (%u vs %u)\n" % (fftd.fftnum, self.fftnum))
  37. return
  38. if self.holes:
  39. print("Skipping ISBD(%u) for ISBH(%u) with holes in it" % (fftd.seqno, self.fftnum))
  40. return
  41. if fftd.seqno != self.seqno+1:
  42. print("ISBH(%u) has holes in it" % fftd.N)
  43. self.holes = True
  44. return
  45. self.seqno += 1
  46. self.data["X"].extend(fftd.x)
  47. self.data["Y"].extend(fftd.y)
  48. self.data["Z"].extend(fftd.z)
  49. def prefix(self):
  50. if self.sensor_type == 0:
  51. return "Accel"
  52. elif self.sensor_type == 1:
  53. return "Gyro"
  54. else:
  55. return "?Unknown Sensor Type?"
  56. def tag(self):
  57. return str(self)
  58. def __str__(self):
  59. return "%s[%u]" % (self.prefix(), self.instance)
  60. print("Processing log %s" % filename)
  61. mlog = mavutil.mavlink_connection(filename)
  62. things_to_plot = []
  63. plotdata = None
  64. msgcount = 0
  65. start_time = time.time()
  66. while True:
  67. m = mlog.recv_match(condition=args.condition)
  68. if m is None:
  69. break
  70. msgcount += 1
  71. if msgcount % 1000 == 0:
  72. sys.stderr.write(".")
  73. msg_type = m.get_type()
  74. if msg_type == "ISBH":
  75. if plotdata is not None:
  76. # close off previous data collection
  77. things_to_plot.append(plotdata)
  78. # initialise plot-data collection object
  79. plotdata = PlotData(m)
  80. continue
  81. if msg_type == "ISBD":
  82. if plotdata is None:
  83. print("Skipping ISBD outside ISBH (fftnum=%u)\n" % m.N)
  84. continue
  85. plotdata.add_fftd(m)
  86. print("", file=sys.stderr)
  87. time_delta = time.time() - start_time
  88. print("%us messages %u messages/second %u kB/second" % (msgcount, msgcount/time_delta, os.stat(filename).st_size/time_delta))
  89. print("Extracted %u fft data sets" % len(things_to_plot), file=sys.stderr)
  90. sum_fft = {}
  91. freqmap = {}
  92. count = 0
  93. first_freq = None
  94. for thing_to_plot in things_to_plot:
  95. for axis in [ "X","Y","Z" ]:
  96. d = numpy.array(thing_to_plot.data[axis])/float(thing_to_plot.multiplier)
  97. if len(d) == 0:
  98. print("No data?!?!?!")
  99. continue
  100. avg = numpy.sum(d) / len(d)
  101. d -= avg
  102. d_fft = numpy.fft.rfft(d)
  103. if thing_to_plot.tag() not in sum_fft:
  104. sum_fft[thing_to_plot.tag()] = {
  105. "X": 0,
  106. "Y": 0,
  107. "Z": 0
  108. }
  109. sum_fft[thing_to_plot.tag()][axis] = numpy.add(sum_fft[thing_to_plot.tag()][axis], d_fft)
  110. count += 1
  111. freq = numpy.fft.rfftfreq(len(d), 1.0/thing_to_plot.sample_rate_hz)
  112. freqmap[thing_to_plot.tag()] = freq
  113. for sensor in sum_fft:
  114. print("Sensor: %s" % str(sensor))
  115. pylab.figure(str(sensor))
  116. for axis in [ "X","Y","Z" ]:
  117. pylab.plot(freqmap[sensor], numpy.abs(sum_fft[sensor][axis]/count), label=axis)
  118. pylab.legend(loc='upper right')
  119. pylab.xlabel('Hz')
  120. for filename in args.logs:
  121. mavfft_fttd(filename)
  122. pylab.show()