magfit_gps.py 4.8 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163
  1. #!/usr/bin/env python
  2. '''
  3. fit best estimate of magnetometer offsets
  4. '''
  5. from __future__ import print_function
  6. from builtins import object
  7. from argparse import ArgumentParser
  8. parser = ArgumentParser(description=__doc__)
  9. parser.add_argument("--no-timestamps", dest="notimestamps", action='store_true', help="Log doesn't have timestamps")
  10. parser.add_argument("--minspeed", type=float, default=5.0, help="minimum ground speed to use")
  11. parser.add_argument("--condition", default=None, help="select packets by condition")
  12. parser.add_argument("--declination", type=float, default=None, help="force declination")
  13. parser.add_argument("logs", metavar="LOG", nargs="+")
  14. args = parser.parse_args()
  15. from pymavlink import mavutil
  16. class vec3(object):
  17. def __init__(self, x, y, z):
  18. self.x = x
  19. self.y = y
  20. self.z = z
  21. def __str__(self):
  22. return "%.1f %.1f %.1f" % (self.x, self.y, self.z)
  23. def heading_error1(parm, data):
  24. from math import sin, cos, atan2, degrees
  25. xofs,yofs,zofs,a1,a2,a3,a4,a5,a6,a7,a8,a9,declination = parm
  26. if args.declination is not None:
  27. declination = args.declination
  28. ret = []
  29. for d in data:
  30. x = d[0] + xofs
  31. y = d[1] + yofs
  32. z = d[2] + zofs
  33. r = d[3]
  34. p = d[4]
  35. h = d[5]
  36. headX = x*cos(p) + y*sin(r)*sin(p) + z*cos(r)*sin(p)
  37. headY = y*cos(r) - z*sin(r)
  38. heading = degrees(atan2(-headY,headX)) + declination
  39. if heading < 0:
  40. heading += 360
  41. herror = h - heading
  42. if herror > 180:
  43. herror -= 360
  44. if herror < -180:
  45. herror += 360
  46. ret.append(herror)
  47. return ret
  48. def heading_error(parm, data):
  49. from math import sin, cos, atan2, degrees
  50. from numpy import dot
  51. xofs,yofs,zofs,a1,a2,a3,a4,a5,a6,a7,a8,a9,declination = parm
  52. if args.declination is not None:
  53. declination = args.declination
  54. a = [[1.0,a2,a3],[a4,a5,a6],[a7,a8,a9]]
  55. ret = []
  56. for d in data:
  57. x = d[0] + xofs
  58. y = d[1] + yofs
  59. z = d[2] + zofs
  60. r = d[3]
  61. p = d[4]
  62. h = d[5]
  63. mv = [x, y, z]
  64. mv2 = dot(a, mv)
  65. x = mv2[0]
  66. y = mv2[1]
  67. z = mv2[2]
  68. headX = x*cos(p) + y*sin(r)*sin(p) + z*cos(r)*sin(p)
  69. headY = y*cos(r) - z*sin(r)
  70. heading = degrees(atan2(-headY,headX)) + declination
  71. if heading < 0:
  72. heading += 360
  73. herror = h - heading
  74. if herror > 180:
  75. herror -= 360
  76. if herror < -180:
  77. herror += 360
  78. ret.append(herror)
  79. return ret
  80. def fit_data(data):
  81. from scipy import optimize
  82. p0 = [0.0, 0.0, 0.0, 1, 0, 0, 0, 1, 0, 0, 0, 1, 0]
  83. if args.declination is not None:
  84. p0[-1] = args.declination
  85. p1, ier = optimize.leastsq(heading_error1, p0[:], args=(data))
  86. # p0 = p1[:]
  87. # p1, ier = optimize.leastsq(heading_error, p0[:], args=(data))
  88. print(p1)
  89. if not ier in [1, 2, 3, 4]:
  90. raise RuntimeError("Unable to find solution")
  91. return p1
  92. def magfit(logfile):
  93. '''find best magnetometer offset fit to a log file'''
  94. print("Processing log %s" % filename)
  95. mlog = mavutil.mavlink_connection(filename, notimestamps=args.notimestamps)
  96. flying = False
  97. gps_heading = 0.0
  98. data = []
  99. # get the current mag offsets
  100. m = mlog.recv_match(type='SENSOR_OFFSETS',condition=args.condition)
  101. offsets = vec3(m.mag_ofs_x, m.mag_ofs_y, m.mag_ofs_z)
  102. attitude = mlog.recv_match(type='ATTITUDE',condition=args.condition)
  103. # now gather all the data
  104. while True:
  105. m = mlog.recv_match(condition=args.condition)
  106. if m is None:
  107. break
  108. if m.get_type() == "GPS_RAW":
  109. # flying if groundspeed more than 5 m/s
  110. flying = (m.v > args.minspeed and m.fix_type == 2)
  111. gps_heading = m.hdg
  112. if m.get_type() == "GPS_RAW_INT":
  113. # flying if groundspeed more than 5 m/s
  114. flying = (m.vel/100 > args.minspeed and m.fix_type == 3)
  115. gps_heading = m.cog/100
  116. if m.get_type() == "ATTITUDE":
  117. attitude = m
  118. if m.get_type() == "SENSOR_OFFSETS":
  119. # update current offsets
  120. offsets = vec3(m.mag_ofs_x, m.mag_ofs_y, m.mag_ofs_z)
  121. if not flying:
  122. continue
  123. if m.get_type() == "RAW_IMU":
  124. data.append((m.xmag - offsets.x, m.ymag - offsets.y, m.zmag - offsets.z, attitude.roll, attitude.pitch, gps_heading))
  125. print("Extracted %u data points" % len(data))
  126. print("Current offsets: %s" % offsets)
  127. ofs2 = fit_data(data)
  128. print("Declination estimate: %.1f" % ofs2[-1])
  129. new_offsets = vec3(ofs2[0], ofs2[1], ofs2[2])
  130. a = [[ofs2[3], ofs2[4], ofs2[5]],
  131. [ofs2[6], ofs2[7], ofs2[8]],
  132. [ofs2[9], ofs2[10], ofs2[11]]]
  133. print(a)
  134. print("New offsets : %s" % new_offsets)
  135. total = 0.0
  136. for filename in args.logs:
  137. magfit(filename)