-
Notifications
You must be signed in to change notification settings - Fork 70
/
Copy pathfusion.py
211 lines (189 loc) · 9.64 KB
/
fusion.py
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
# Sensor fusion for the micropython board. 25th June 2015
# Ported to MicroPython by Peter Hinch.
# Released under the MIT License (MIT)
# Copyright (c) 2017, 2018 Peter Hinch
# V0.9 Time calculations devolved to deltat.py
# V0.8 Calibrate wait argument can be a function or an integer in ms.
# V0.7 Yaw replaced with heading
# V0.65 waitfunc now optional
# Supports 6 and 9 degrees of freedom sensors. Tested with InvenSense MPU-9150 9DOF sensor.
# Source https://github.com/xioTechnologies/Open-Source-AHRS-With-x-IMU.git
# also https://github.com/kriswiner/MPU-9250.git
# Ported to Python. Integrator timing adapted for pyboard.
# See README.md for documentation.
# Portability: the only assumption is presence of time.sleep() used in mag
# calibration.
try:
import utime as time
except ImportError:
import time
from math import sqrt, atan2, asin, degrees, radians
from deltat import DeltaT
class Fusion(object):
'''
Class provides sensor fusion allowing heading, pitch and roll to be extracted. This uses the Madgwick algorithm.
The update method must be called peiodically. The calculations take 1.6mS on the Pyboard.
'''
declination = 0 # Optional offset for true north. A +ve value adds to heading
def __init__(self, timediff=None):
self.magbias = (0, 0, 0) # local magnetic bias factors: set from calibration
self.deltat = DeltaT(timediff) # Time between updates
self.q = [1.0, 0.0, 0.0, 0.0] # vector to hold quaternion
GyroMeasError = radians(40) # Original code indicates this leads to a 2 sec response time
self.beta = sqrt(3.0 / 4.0) * GyroMeasError # compute beta (see README)
self.pitch = 0
self.heading = 0
self.roll = 0
def calibrate(self, getxyz, stopfunc, wait=0):
magmax = list(getxyz()) # Initialise max and min lists with current values
magmin = magmax[:]
while not stopfunc():
if wait != 0:
if callable(wait):
wait()
else:
time.sleep(wait/1000) # Portable
magxyz = tuple(getxyz())
for x in range(3):
magmax[x] = max(magmax[x], magxyz[x])
magmin[x] = min(magmin[x], magxyz[x])
self.magbias = tuple(map(lambda a, b: (a +b)/2, magmin, magmax))
def update_nomag(self, accel, gyro, ts=None): # 3-tuples (x, y, z) for accel, gyro
ax, ay, az = accel # Units G (but later normalised)
gx, gy, gz = (radians(x) for x in gyro) # Units deg/s
q1, q2, q3, q4 = (self.q[x] for x in range(4)) # short name local variable for readability
# Auxiliary variables to avoid repeated arithmetic
_2q1 = 2 * q1
_2q2 = 2 * q2
_2q3 = 2 * q3
_2q4 = 2 * q4
_4q1 = 4 * q1
_4q2 = 4 * q2
_4q3 = 4 * q3
_8q2 = 8 * q2
_8q3 = 8 * q3
q1q1 = q1 * q1
q2q2 = q2 * q2
q3q3 = q3 * q3
q4q4 = q4 * q4
# Normalise accelerometer measurement
norm = sqrt(ax * ax + ay * ay + az * az)
if (norm == 0):
return # handle NaN
norm = 1 / norm # use reciprocal for division
ax *= norm
ay *= norm
az *= norm
# Gradient decent algorithm corrective step
s1 = _4q1 * q3q3 + _2q3 * ax + _4q1 * q2q2 - _2q2 * ay
s2 = _4q2 * q4q4 - _2q4 * ax + 4 * q1q1 * q2 - _2q1 * ay - _4q2 + _8q2 * q2q2 + _8q2 * q3q3 + _4q2 * az
s3 = 4 * q1q1 * q3 + _2q1 * ax + _4q3 * q4q4 - _2q4 * ay - _4q3 + _8q3 * q2q2 + _8q3 * q3q3 + _4q3 * az
s4 = 4 * q2q2 * q4 - _2q2 * ax + 4 * q3q3 * q4 - _2q3 * ay
norm = 1 / sqrt(s1 * s1 + s2 * s2 + s3 * s3 + s4 * s4) # normalise step magnitude
s1 *= norm
s2 *= norm
s3 *= norm
s4 *= norm
# Compute rate of change of quaternion
qDot1 = 0.5 * (-q2 * gx - q3 * gy - q4 * gz) - self.beta * s1
qDot2 = 0.5 * (q1 * gx + q3 * gz - q4 * gy) - self.beta * s2
qDot3 = 0.5 * (q1 * gy - q2 * gz + q4 * gx) - self.beta * s3
qDot4 = 0.5 * (q1 * gz + q2 * gy - q3 * gx) - self.beta * s4
# Integrate to yield quaternion
deltat = self.deltat(ts)
q1 += qDot1 * deltat
q2 += qDot2 * deltat
q3 += qDot3 * deltat
q4 += qDot4 * deltat
norm = 1 / sqrt(q1 * q1 + q2 * q2 + q3 * q3 + q4 * q4) # normalise quaternion
self.q = q1 * norm, q2 * norm, q3 * norm, q4 * norm
self.heading = 0
self.pitch = degrees(-asin(2.0 * (self.q[1] * self.q[3] - self.q[0] * self.q[2])))
self.roll = degrees(atan2(2.0 * (self.q[0] * self.q[1] + self.q[2] * self.q[3]),
self.q[0] * self.q[0] - self.q[1] * self.q[1] - self.q[2] * self.q[2] + self.q[3] * self.q[3]))
def update(self, accel, gyro, mag, ts=None): # 3-tuples (x, y, z) for accel, gyro and mag data
mx, my, mz = (mag[x] - self.magbias[x] for x in range(3)) # Units irrelevant (normalised)
ax, ay, az = accel # Units irrelevant (normalised)
gx, gy, gz = (radians(x) for x in gyro) # Units deg/s
q1, q2, q3, q4 = (self.q[x] for x in range(4)) # short name local variable for readability
# Auxiliary variables to avoid repeated arithmetic
_2q1 = 2 * q1
_2q2 = 2 * q2
_2q3 = 2 * q3
_2q4 = 2 * q4
_2q1q3 = 2 * q1 * q3
_2q3q4 = 2 * q3 * q4
q1q1 = q1 * q1
q1q2 = q1 * q2
q1q3 = q1 * q3
q1q4 = q1 * q4
q2q2 = q2 * q2
q2q3 = q2 * q3
q2q4 = q2 * q4
q3q3 = q3 * q3
q3q4 = q3 * q4
q4q4 = q4 * q4
# Normalise accelerometer measurement
norm = sqrt(ax * ax + ay * ay + az * az)
if (norm == 0):
return # handle NaN
norm = 1 / norm # use reciprocal for division
ax *= norm
ay *= norm
az *= norm
# Normalise magnetometer measurement
norm = sqrt(mx * mx + my * my + mz * mz)
if (norm == 0):
return # handle NaN
norm = 1 / norm # use reciprocal for division
mx *= norm
my *= norm
mz *= norm
# Reference direction of Earth's magnetic field
_2q1mx = 2 * q1 * mx
_2q1my = 2 * q1 * my
_2q1mz = 2 * q1 * mz
_2q2mx = 2 * q2 * mx
hx = mx * q1q1 - _2q1my * q4 + _2q1mz * q3 + mx * q2q2 + _2q2 * my * q3 + _2q2 * mz * q4 - mx * q3q3 - mx * q4q4
hy = _2q1mx * q4 + my * q1q1 - _2q1mz * q2 + _2q2mx * q3 - my * q2q2 + my * q3q3 + _2q3 * mz * q4 - my * q4q4
_2bx = sqrt(hx * hx + hy * hy)
_2bz = -_2q1mx * q3 + _2q1my * q2 + mz * q1q1 + _2q2mx * q4 - mz * q2q2 + _2q3 * my * q4 - mz * q3q3 + mz * q4q4
_4bx = 2 * _2bx
_4bz = 2 * _2bz
# Gradient descent algorithm corrective step
s1 = (-_2q3 * (2 * q2q4 - _2q1q3 - ax) + _2q2 * (2 * q1q2 + _2q3q4 - ay) - _2bz * q3 * (_2bx * (0.5 - q3q3 - q4q4)
+ _2bz * (q2q4 - q1q3) - mx) + (-_2bx * q4 + _2bz * q2) * (_2bx * (q2q3 - q1q4) + _2bz * (q1q2 + q3q4) - my)
+ _2bx * q3 * (_2bx * (q1q3 + q2q4) + _2bz * (0.5 - q2q2 - q3q3) - mz))
s2 = (_2q4 * (2 * q2q4 - _2q1q3 - ax) + _2q1 * (2 * q1q2 + _2q3q4 - ay) - 4 * q2 * (1 - 2 * q2q2 - 2 * q3q3 - az)
+ _2bz * q4 * (_2bx * (0.5 - q3q3 - q4q4) + _2bz * (q2q4 - q1q3) - mx) + (_2bx * q3 + _2bz * q1) * (_2bx * (q2q3 - q1q4)
+ _2bz * (q1q2 + q3q4) - my) + (_2bx * q4 - _4bz * q2) * (_2bx * (q1q3 + q2q4) + _2bz * (0.5 - q2q2 - q3q3) - mz))
s3 = (-_2q1 * (2 * q2q4 - _2q1q3 - ax) + _2q4 * (2 * q1q2 + _2q3q4 - ay) - 4 * q3 * (1 - 2 * q2q2 - 2 * q3q3 - az)
+ (-_4bx * q3 - _2bz * q1) * (_2bx * (0.5 - q3q3 - q4q4) + _2bz * (q2q4 - q1q3) - mx)
+ (_2bx * q2 + _2bz * q4) * (_2bx * (q2q3 - q1q4) + _2bz * (q1q2 + q3q4) - my)
+ (_2bx * q1 - _4bz * q3) * (_2bx * (q1q3 + q2q4) + _2bz * (0.5 - q2q2 - q3q3) - mz))
s4 = (_2q2 * (2 * q2q4 - _2q1q3 - ax) + _2q3 * (2 * q1q2 + _2q3q4 - ay) + (-_4bx * q4 + _2bz * q2) * (_2bx * (0.5 - q3q3 - q4q4)
+ _2bz * (q2q4 - q1q3) - mx) + (-_2bx * q1 + _2bz * q3) * (_2bx * (q2q3 - q1q4) + _2bz * (q1q2 + q3q4) - my)
+ _2bx * q2 * (_2bx * (q1q3 + q2q4) + _2bz * (0.5 - q2q2 - q3q3) - mz))
norm = 1 / sqrt(s1 * s1 + s2 * s2 + s3 * s3 + s4 * s4) # normalise step magnitude
s1 *= norm
s2 *= norm
s3 *= norm
s4 *= norm
# Compute rate of change of quaternion
qDot1 = 0.5 * (-q2 * gx - q3 * gy - q4 * gz) - self.beta * s1
qDot2 = 0.5 * (q1 * gx + q3 * gz - q4 * gy) - self.beta * s2
qDot3 = 0.5 * (q1 * gy - q2 * gz + q4 * gx) - self.beta * s3
qDot4 = 0.5 * (q1 * gz + q2 * gy - q3 * gx) - self.beta * s4
# Integrate to yield quaternion
deltat = self.deltat(ts)
q1 += qDot1 * deltat
q2 += qDot2 * deltat
q3 += qDot3 * deltat
q4 += qDot4 * deltat
norm = 1 / sqrt(q1 * q1 + q2 * q2 + q3 * q3 + q4 * q4) # normalise quaternion
self.q = q1 * norm, q2 * norm, q3 * norm, q4 * norm
self.heading = self.declination + degrees(atan2(2.0 * (self.q[1] * self.q[2] + self.q[0] * self.q[3]),
self.q[0] * self.q[0] + self.q[1] * self.q[1] - self.q[2] * self.q[2] - self.q[3] * self.q[3]))
self.pitch = degrees(-asin(2.0 * (self.q[1] * self.q[3] - self.q[0] * self.q[2])))
self.roll = degrees(atan2(2.0 * (self.q[0] * self.q[1] + self.q[2] * self.q[3]),
self.q[0] * self.q[0] - self.q[1] * self.q[1] - self.q[2] * self.q[2] + self.q[3] * self.q[3]))