4 fit best estimate of magnetometer offsets 6 from __future__
import print_function
8 import sys, time, os, math
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(
"--noise", type=float, default=0, help=
"noise to add")
15 parser.add_argument(
"--mag2", action=
'store_true', help=
"use 2nd mag from DF log")
16 parser.add_argument(
"--radius", default=500.0, type=float, help=
"target radius")
17 parser.add_argument(
"--plot", action=
'store_true', help=
"plot points in 3D")
18 parser.add_argument(
"logs", metavar=
"LOG", nargs=
"+")
20 args = parser.parse_args()
22 from pymavlink
import mavutil
29 from random
import gauss
30 v =
Vector3(gauss(0, 1), gauss(0, 1), gauss(0, 1))
39 key =
"%u:%u:%u" % (mag.x/20,mag.y/20,mag.z/20)
46 print((len(data), len(ret)))
57 '''correct a mag sample''' 60 Vector3(diag.x, offdiag.x, offdiag.y),
61 Vector3(offdiag.x, diag.y, offdiag.z),
62 Vector3(offdiag.y, offdiag.z, diag.z))
67 def radius(mag, offsets, diag, offdiag):
68 '''return radius give data point and offsets''' 69 mag =
correct(mag, offsets, diag, offdiag)
73 '''return +1 or -1 for for sorting''' 74 diff =
radius(a, offsets, diag, offdiag) -
radius(b, offsets, diag, offdiag)
82 x,y,z,r,dx,dy,dz,odx,ody,odz = p
83 if args.radius
is not None:
87 offdiag =
Vector3(odx, ody, odz)
91 mag =
correct(d, ofs, diag, offdiag)
92 err = r - mag.length()
97 from scipy
import optimize
104 if args.radius
is not None:
106 p1, ier = optimize.leastsq(sphere_error, p0[:], args=(data))
107 if not ier
in [1, 2, 3, 4]:
109 raise RuntimeError(
"Unable to find solution: %u" % ier)
110 if args.radius
is not None:
114 return (
Vector3(p1[0], p1[1], p1[2]),
120 '''find best magnetometer offset fit to a log file''' 122 print(
"Processing log %s" % filename)
123 mlog = mavutil.mavlink_connection(filename, notimestamps=args.notimestamps)
132 m = mlog.recv_match(condition=args.condition)
135 if m.get_type() ==
"SENSOR_OFFSETS":
137 offsets =
Vector3(m.mag_ofs_x, m.mag_ofs_y, m.mag_ofs_z)
138 if m.get_type() ==
"RAW_IMU":
139 mag =
Vector3(m.xmag, m.ymag, m.zmag)
141 if offsets
is not None:
142 data.append(mag - offsets +
noise())
143 if m.get_type() ==
"MAG" and not args.mag2:
144 offsets =
Vector3(m.OfsX,m.OfsY,m.OfsZ)
145 mag =
Vector3(m.MagX,m.MagY,m.MagZ)
146 data.append(mag - offsets +
noise())
147 if m.get_type() ==
"MAG2" and args.mag2:
148 offsets =
Vector3(m.OfsX,m.OfsY,m.OfsZ)
149 mag =
Vector3(m.MagX,m.MagY,m.MagZ)
150 data.append(mag - offsets +
noise())
152 print(
"Extracted %u data points" % len(data))
153 print(
"Current offsets: %s" % offsets)
169 print(
"Average %s" % avg)
178 data.sort(
lambda a,b :
radius_cmp(a,b,offsets,diag,offdiag))
179 data = data[len(data)/16:-len(data)/16]
182 (offsets, field_strength, diag, offdiag) =
fit_data(data)
184 for count
in range(3):
186 data.sort(
lambda a,b :
radius_cmp(a,b,offsets,diag,offdiag))
188 print(
"Fit %u : %s %s %s field_strength=%6.1f to %6.1f" % (
189 count, offsets, diag, offdiag,
190 radius(data[0], offsets,diag,offdiag),
radius(data[-1], offsets,diag,offdiag)))
193 data = data[len(data)/32:-len(data)/32]
196 (offsets, field_strength, diag, offdiag) =
fit_data(data)
198 print(
"Final : %s %s %s field_strength=%6.1f to %6.1f" % (
199 offsets, diag, offdiag,
200 radius(data[0], offsets, diag, offdiag),
radius(data[-1], offsets, diag, offdiag)))
203 print(
"With average : %s" % offsets)
206 data2 = [
correct(d,offsets,diag,offdiag)
for d
in orig_data]
210 '''plot data in 3D''' 211 from mpl_toolkits.mplot3d
import Axes3D
212 import matplotlib.pyplot
as plt
215 for dd, c, p
in [(orig_data,
'r', 1), (data, 'b', 2)]:
216 ax = fig.add_subplot(1, 2, p, projection=
'3d')
218 xs = [ d.x
for d
in dd ]
219 ys = [ d.y
for d
in dd ]
220 zs = [ d.z
for d
in dd ]
221 ax.scatter(xs, ys, zs, c=c, marker=
'o')
229 for filename
in args.logs: