4 fit best estimate of magnetometer offsets, trying to take into account motor interference 6 from __future__
import print_function
7 from builtins
import range
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(
"--condition",dest=
"condition", default=
None, help=
"select packets by condition")
13 parser.add_argument(
"--noise", type=float, default=0, help=
"noise to add")
14 parser.add_argument(
"logs", metavar=
"LOG", nargs=
"+")
16 args = parser.parse_args()
18 from pymavlink
import mavutil
24 from random
import gauss
25 v =
Vector3(gauss(0, 1), gauss(0, 1), gauss(0, 1))
34 key =
"%u:%u:%u" % (mag.x/20,mag.y/20,mag.z/20)
41 print(len(data), len(ret))
45 '''return radius give data point and offsets''' 47 return (mag + offsets + motor*motor_ofs).length()
50 '''return radius give data point and offsets''' 51 diff =
radius(a, offsets, motor_ofs) -
radius(b, offsets, motor_ofs)
65 err = r -
radius((mag,motor), ofs, motor_ofs)
70 from scipy
import optimize
72 p0 = [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]
73 p1, ier = optimize.leastsq(sphere_error, p0[:], args=(data))
74 if not ier
in [1, 2, 3, 4]:
75 raise RuntimeError(
"Unable to find solution")
76 return (
Vector3(p1[0], p1[1], p1[2]),
Vector3(p1[3], p1[4], p1[5]), p1[6])
79 '''find best magnetometer offset fit to a log file''' 81 print(
"Processing log %s" % filename)
82 mlog = mavutil.mavlink_connection(filename, notimestamps=args.notimestamps)
93 m = mlog.recv_match(condition=args.condition)
96 if m.get_type() ==
"PARAM_VALUE" and m.param_id ==
"RC3_MIN":
97 rc3_min =
float(m.param_value)
98 if m.get_type() ==
"SENSOR_OFFSETS":
100 offsets =
Vector3(m.mag_ofs_x, m.mag_ofs_y, m.mag_ofs_z)
101 if m.get_type() ==
"SERVO_OUTPUT_RAW":
102 motor_pwm = m.servo1_raw + m.servo2_raw + m.servo3_raw + m.servo4_raw
104 rc3_min = mlog.param(
'RC3_MIN', 1100)
105 rc3_max = mlog.param(
'RC3_MAX', 1900)
106 motor = (motor_pwm - rc3_min) / (rc3_max - rc3_min)
111 if m.get_type() ==
"RAW_IMU":
112 mag =
Vector3(m.xmag, m.ymag, m.zmag)
114 data.append((mag - offsets +
noise(), motor))
116 print(
"Extracted %u data points" % len(data))
117 print(
"Current offsets: %s" % offsets)
122 (offsets, motor_ofs, field_strength) =
fit_data(data)
124 for count
in range(3):
126 data.sort(
lambda a,b :
radius_cmp(a,b,offsets,motor_ofs))
128 print(
"Fit %u : %s %s field_strength=%6.1f to %6.1f" % (
129 count, offsets, motor_ofs,
130 radius(data[0], offsets, motor_ofs),
radius(data[-1], offsets, motor_ofs)))
133 data = data[len(data)/8:-len(data)/8]
136 (offsets, motor_ofs, field_strength) =
fit_data(data)
138 print(
"Final : %s %s field_strength=%6.1f to %6.1f" % (
140 radius(data[0], offsets, motor_ofs),
radius(data[-1], offsets, motor_ofs)))
141 print(
"mavgraph.py '%s' 'mag_field(RAW_IMU)' 'mag_field_motors(RAW_IMU,SENSOR_OFFSETS,(%f,%f,%f),SERVO_OUTPUT_RAW,(%f,%f,%f))'" % (
143 offsets.x,offsets.y,offsets.z,
144 motor_ofs.x, motor_ofs.y, motor_ofs.z))
147 for filename
in args.logs: