magfit_rotation_gps.py 3.8 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128
  1. #!/usr/bin/env python
  2. '''
  3. fit best estimate of magnetometer rotation to GPS data
  4. '''
  5. from __future__ import print_function
  6. from builtins import range
  7. from builtins import object
  8. from argparse import ArgumentParser
  9. parser = ArgumentParser(description=__doc__)
  10. parser.add_argument("--no-timestamps",dest="notimestamps", action='store_true', help="Log doesn't have timestamps")
  11. parser.add_argument("--declination", default=0.0, type=float, help="magnetic declination")
  12. parser.add_argument("--min-speed", default=4.0, type=float, help="minimum GPS speed")
  13. parser.add_argument("logs", metavar="LOG", nargs="+")
  14. args = parser.parse_args()
  15. from pymavlink import mavutil
  16. from pymavlink.rotmat import Vector3, Matrix3
  17. from math import radians, degrees, sin, cos, atan2
  18. class Rotation(object):
  19. def __init__(self, roll, pitch, yaw, r):
  20. self.roll = roll
  21. self.pitch = pitch
  22. self.yaw = yaw
  23. self.r = r
  24. def in_rotations_list(rotations, m):
  25. for r in rotations:
  26. m2 = m.transposed() * r.r
  27. (r, p, y) = m2.to_euler()
  28. if (abs(r) < radians(1) and
  29. abs(p) < radians(1) and
  30. abs(y) < radians(1)):
  31. return True
  32. return False
  33. def generate_rotations():
  34. '''generate all 90 degree rotations'''
  35. rotations = []
  36. for yaw in [0, 90, 180, 270]:
  37. for pitch in [0, 90, 180, 270]:
  38. for roll in [0, 90, 180, 270]:
  39. m = Matrix3()
  40. m.from_euler(radians(roll), radians(pitch), radians(yaw))
  41. if not in_rotations_list(rotations, m):
  42. rotations.append(Rotation(roll, pitch, yaw, m))
  43. return rotations
  44. def angle_diff(angle1, angle2):
  45. '''give the difference between two angles in degrees'''
  46. ret = angle1 - angle2
  47. if ret > 180:
  48. ret -= 360;
  49. if ret < -180:
  50. ret += 360
  51. return ret
  52. def heading_difference(mag, attitude, declination):
  53. r = attitude.roll
  54. p = attitude.pitch
  55. headX = mag.x*cos(p) + mag.y*sin(r)*sin(p) + mag.z*cos(r)*sin(p)
  56. headY = mag.y*cos(r) - mag.z*sin(r)
  57. heading = degrees(atan2(-headY,headX)) + declination
  58. heading2 = degrees(attitude.yaw)
  59. return abs(angle_diff(heading, heading2))
  60. def add_errors(mag, attitude, total_error, rotations):
  61. for i in range(len(rotations)):
  62. r = rotations[i].r
  63. rmag = r * mag
  64. total_error[i] += heading_difference(rmag, attitude, args.declination)
  65. def magfit(logfile):
  66. '''find best magnetometer rotation fit to a log file'''
  67. print("Processing log %s" % filename)
  68. mlog = mavutil.mavlink_connection(filename, notimestamps=args.notimestamps)
  69. # generate 90 degree rotations
  70. rotations = generate_rotations()
  71. print("Generated %u rotations" % len(rotations))
  72. count = 0
  73. total_error = [0]*len(rotations)
  74. attitude = None
  75. gps = None
  76. # now gather all the data
  77. while True:
  78. m = mlog.recv_match()
  79. if m is None:
  80. break
  81. if m.get_type() == "ATTITUDE":
  82. attitude = m
  83. if m.get_type() == "GPS_RAW_INT":
  84. gps = m
  85. if m.get_type() == "RAW_IMU":
  86. mag = Vector3(m.xmag, m.ymag, m.zmag)
  87. if attitude is not None and gps is not None and gps.vel > args.min_speed*100 and gps.fix_type>=3:
  88. add_errors(mag, attitude, total_error, rotations)
  89. count += 1
  90. best_i = 0
  91. best_err = total_error[0]
  92. for i in range(len(rotations)):
  93. r = rotations[i]
  94. print("(%u,%u,%u) err=%.2f" % (
  95. r.roll,
  96. r.pitch,
  97. r.yaw,
  98. total_error[i]/count))
  99. if total_error[i] < best_err:
  100. best_i = i
  101. best_err = total_error[i]
  102. r = rotations[best_i]
  103. print("Best rotation (%u,%u,%u) err=%.2f" % (
  104. r.roll,
  105. r.pitch,
  106. r.yaw,
  107. best_err/count))
  108. for filename in args.logs:
  109. magfit(filename)