4 fit best estimate of magnetometer rotation to GPS data 6 from __future__
import print_function
7 from builtins
import range
8 from builtins
import object
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(
"--declination", default=0.0, type=float, help=
"magnetic declination")
14 parser.add_argument(
"--min-speed", default=4.0, type=float, help=
"minimum GPS speed")
15 parser.add_argument(
"logs", metavar=
"LOG", nargs=
"+")
17 args = parser.parse_args()
19 from pymavlink
import mavutil
21 from math
import radians, degrees, sin, cos, atan2
33 m2 = m.transposed() * r.r
34 (r, p, y) = m2.to_euler()
35 if (abs(r) < radians(1)
and 36 abs(p) < radians(1)
and 42 '''generate all 90 degree rotations''' 44 for yaw
in [0, 90, 180, 270]:
45 for pitch
in [0, 90, 180, 270]:
46 for roll
in [0, 90, 180, 270]:
48 m.from_euler(radians(roll), radians(pitch), radians(yaw))
50 rotations.append(
Rotation(roll, pitch, yaw, m))
54 '''give the difference between two angles in degrees''' 65 headX = mag.x*cos(p) + mag.y*sin(r)*sin(p) + mag.z*cos(r)*sin(p)
66 headY = mag.y*cos(r) - mag.z*sin(r)
67 heading = degrees(atan2(-headY,headX)) + declination
68 heading2 = degrees(attitude.yaw)
72 for i
in range(len(rotations)):
79 '''find best magnetometer rotation fit to a log file''' 81 print(
"Processing log %s" % filename)
82 mlog = mavutil.mavlink_connection(filename, notimestamps=args.notimestamps)
86 print(
"Generated %u rotations" % len(rotations))
89 total_error = [0]*len(rotations)
98 if m.get_type() ==
"ATTITUDE":
100 if m.get_type() ==
"GPS_RAW_INT":
102 if m.get_type() ==
"RAW_IMU":
103 mag =
Vector3(m.xmag, m.ymag, m.zmag)
104 if attitude
is not None and gps
is not None and gps.vel > args.min_speed*100
and gps.fix_type>=3:
105 add_errors(mag, attitude, total_error, rotations)
109 best_err = total_error[0]
110 for i
in range(len(rotations)):
112 print(
"(%u,%u,%u) err=%.2f" % (
116 total_error[i]/count))
117 if total_error[i] < best_err:
119 best_err = total_error[i]
120 r = rotations[best_i]
121 print(
"Best rotation (%u,%u,%u) err=%.2f" % (
127 for filename
in args.logs: