magfit_delta.py 4.4 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139
  1. #!/usr/bin/env python
  2. '''
  3. fit best estimate of magnetometer offsets using the algorithm from
  4. Bill Premerlani
  5. '''
  6. from __future__ import print_function
  7. from builtins import range
  8. import sys
  9. # command line option handling
  10. from argparse import ArgumentParser
  11. parser = ArgumentParser(description=__doc__)
  12. parser.add_argument("--no-timestamps", dest="notimestamps", action='store_true', help="Log doesn't have timestamps")
  13. parser.add_argument("--condition", default=None, help="select packets by condition")
  14. parser.add_argument("--verbose", action='store_true', default=False, help="verbose offset output")
  15. parser.add_argument("--gain", type=float, default=0.01, help="algorithm gain")
  16. parser.add_argument("--noise", type=float, default=0, help="noise to add")
  17. parser.add_argument("--max-change", type=float, default=10, help="max step change")
  18. parser.add_argument("--min-diff", type=float, default=50, help="min mag vector delta")
  19. parser.add_argument("--history", type=int, default=20, help="how many points to keep")
  20. parser.add_argument("--repeat", type=int, default=1, help="number of repeats through the data")
  21. parser.add_argument("logs", metavar="LOG", nargs="+")
  22. args = parser.parse_args()
  23. from pymavlink import mavutil
  24. from pymavlink.rotmat import Vector3
  25. def noise():
  26. '''a noise vector'''
  27. from random import gauss
  28. v = Vector3(gauss(0, 1), gauss(0, 1), gauss(0, 1))
  29. v.normalize()
  30. return v * args.noise
  31. def find_offsets(data, ofs):
  32. '''find mag offsets by applying Bills "offsets revisited" algorithm
  33. on the data
  34. This is an implementation of the algorithm from:
  35. http://gentlenav.googlecode.com/files/MagnetometerOffsetNullingRevisited.pdf
  36. '''
  37. # a limit on the maximum change in each step
  38. max_change = args.max_change
  39. # the gain factor for the algorithm
  40. gain = args.gain
  41. data2 = []
  42. for d in data:
  43. d = d.copy() + noise()
  44. d.x = float(int(d.x + 0.5))
  45. d.y = float(int(d.y + 0.5))
  46. d.z = float(int(d.z + 0.5))
  47. data2.append(d)
  48. data = data2
  49. history_idx = 0
  50. mag_history = data[0:args.history]
  51. for i in range(args.history, len(data)):
  52. B1 = mag_history[history_idx] + ofs
  53. B2 = data[i] + ofs
  54. diff = B2 - B1
  55. diff_length = diff.length()
  56. if diff_length <= args.min_diff:
  57. # the mag vector hasn't changed enough - we don't get any
  58. # information from this
  59. history_idx = (history_idx+1) % args.history
  60. continue
  61. mag_history[history_idx] = data[i]
  62. history_idx = (history_idx+1) % args.history
  63. # equation 6 of Bills paper
  64. delta = diff * (gain * (B2.length() - B1.length()) / diff_length)
  65. # limit the change from any one reading. This is to prevent
  66. # single crazy readings from throwing off the offsets for a long
  67. # time
  68. delta_length = delta.length()
  69. if max_change != 0 and delta_length > max_change:
  70. delta *= max_change / delta_length
  71. # set the new offsets
  72. ofs = ofs - delta
  73. if args.verbose:
  74. print(ofs)
  75. return ofs
  76. def magfit(logfile):
  77. '''find best magnetometer offset fit to a log file'''
  78. print("Processing log %s" % filename)
  79. # open the log file
  80. mlog = mavutil.mavlink_connection(filename, notimestamps=args.notimestamps)
  81. data = []
  82. mag = None
  83. offsets = Vector3(0,0,0)
  84. # now gather all the data
  85. while True:
  86. # get the next MAVLink message in the log
  87. m = mlog.recv_match(condition=args.condition)
  88. if m is None:
  89. break
  90. if m.get_type() == "SENSOR_OFFSETS":
  91. # update offsets that were used during this flight
  92. offsets = Vector3(m.mag_ofs_x, m.mag_ofs_y, m.mag_ofs_z)
  93. if m.get_type() == "RAW_IMU" and offsets is not None:
  94. # extract one mag vector, removing the offsets that were
  95. # used during that flight to get the raw sensor values
  96. mag = Vector3(m.xmag, m.ymag, m.zmag) - offsets
  97. data.append(mag)
  98. print("Extracted %u data points" % len(data))
  99. print("Current offsets: %s" % offsets)
  100. # run the fitting algorithm
  101. ofs = offsets
  102. ofs = Vector3(0,0,0)
  103. for r in range(args.repeat):
  104. ofs = find_offsets(data, ofs)
  105. print('Loop %u offsets %s' % (r, ofs))
  106. sys.stdout.flush()
  107. print("New offsets: %s" % ofs)
  108. total = 0.0
  109. for filename in args.logs:
  110. magfit(filename)