4 fit best estimate of magnetometer offsets 6 from __future__
import print_function
7 from builtins
import object
9 from argparse
import ArgumentParser
10 parser = ArgumentParser(description=__doc__)
11 parser.add_argument(
"--no-timestamps", dest=
"notimestamps", action=
'store_true', help=
"Log doesn't have timestamps")
12 parser.add_argument(
"--minspeed", type=float, default=5.0, help=
"minimum ground speed to use")
13 parser.add_argument(
"--condition", default=
None, help=
"select packets by condition")
14 parser.add_argument(
"--declination", type=float, default=
None, help=
"force declination")
15 parser.add_argument(
"logs", metavar=
"LOG", nargs=
"+")
17 args = parser.parse_args()
19 from pymavlink
import mavutil
28 return "%.1f %.1f %.1f" % (self.
x, self.
y, self.
z)
31 from math
import sin, cos, atan2, degrees
32 xofs,yofs,zofs,a1,a2,a3,a4,a5,a6,a7,a8,a9,declination = parm
34 if args.declination
is not None:
35 declination = args.declination
46 headX = x*cos(p) + y*sin(r)*sin(p) + z*cos(r)*sin(p)
47 headY = y*cos(r) - z*sin(r)
48 heading = degrees(atan2(-headY,headX)) + declination
60 from math
import sin, cos, atan2, degrees
62 xofs,yofs,zofs,a1,a2,a3,a4,a5,a6,a7,a8,a9,declination = parm
64 if args.declination
is not None:
65 declination = args.declination
67 a = [[1.0,a2,a3],[a4,a5,a6],[a7,a8,a9]]
83 headX = x*cos(p) + y*sin(r)*sin(p) + z*cos(r)*sin(p)
84 headY = y*cos(r) - z*sin(r)
85 heading = degrees(atan2(-headY,headX)) + declination
97 from scipy
import optimize
99 p0 = [0.0, 0.0, 0.0, 1, 0, 0, 0, 1, 0, 0, 0, 1, 0]
100 if args.declination
is not None:
101 p0[-1] = args.declination
102 p1, ier = optimize.leastsq(heading_error1, p0[:], args=(data))
108 if not ier
in [1, 2, 3, 4]:
109 raise RuntimeError(
"Unable to find solution")
113 '''find best magnetometer offset fit to a log file''' 114 print(
"Processing log %s" % filename)
115 mlog = mavutil.mavlink_connection(filename, notimestamps=args.notimestamps)
123 m = mlog.recv_match(type=
'SENSOR_OFFSETS',condition=args.condition)
124 offsets =
vec3(m.mag_ofs_x, m.mag_ofs_y, m.mag_ofs_z)
126 attitude = mlog.recv_match(type=
'ATTITUDE',condition=args.condition)
130 m = mlog.recv_match(condition=args.condition)
133 if m.get_type() ==
"GPS_RAW":
135 flying = (m.v > args.minspeed
and m.fix_type == 2)
137 if m.get_type() ==
"GPS_RAW_INT":
139 flying = (m.vel/100 > args.minspeed
and m.fix_type == 3)
140 gps_heading = m.cog/100
141 if m.get_type() ==
"ATTITUDE":
143 if m.get_type() ==
"SENSOR_OFFSETS":
145 offsets =
vec3(m.mag_ofs_x, m.mag_ofs_y, m.mag_ofs_z)
148 if m.get_type() ==
"RAW_IMU":
149 data.append((m.xmag - offsets.x, m.ymag - offsets.y, m.zmag - offsets.z, attitude.roll, attitude.pitch, gps_heading))
150 print(
"Extracted %u data points" % len(data))
151 print(
"Current offsets: %s" % offsets)
153 print(
"Declination estimate: %.1f" % ofs2[-1])
154 new_offsets =
vec3(ofs2[0], ofs2[1], ofs2[2])
155 a = [[ofs2[3], ofs2[4], ofs2[5]],
156 [ofs2[6], ofs2[7], ofs2[8]],
157 [ofs2[9], ofs2[10], ofs2[11]]]
159 print(
"New offsets : %s" % new_offsets)
162 for filename
in args.logs: