forked from ArduPilot/pymavlink
-
Notifications
You must be signed in to change notification settings - Fork 0
/
mav_replay_estimator.py
executable file
·146 lines (113 loc) · 4.21 KB
/
mav_replay_estimator.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
#!/usr/bin/env python
'''
estimate attitude from an ArduPilot replay log using a python state estimator
'''
from __future__ import print_function
from builtins import range
import os
from argparse import ArgumentParser
parser = ArgumentParser()
parser.add_argument("log", metavar="LOG")
parser.add_argument("--debug", action='store_true')
args = parser.parse_args()
from pymavlink import mavutil
from pymavlink.rotmat import Vector3, Matrix3
from math import degrees
GRAVITY_MSS = 9.80665
class Estimator(object):
'''state estimator'''
def __init__(self):
self.r = Matrix3()
self.vel = Vector3()
self.pos = Vector3()
def update_GPS(self, position, velocity):
'''handle new GPS sample'''
if args.debug:
print('GPS: ', position, velocity)
def update_MAG(self, field):
'''handle new magnetometer sample'''
if args.debug:
print('MAG: ', field)
def update_BARO(self, altitude):
'''handle new barometer sample'''
if args.debug:
print('BARO: ', altitude)
def update_IMU(self, delta_velocity, dv_dt, delta_angle, da_dt):
'''handle new IMU sample'''
# rotate using delta_angle
self.r.rotate(delta_angle)
# inertial update with accelerometer. This will diverge very quickly
# without corrections
earth_dvel = self.r * delta_velocity
earth_dvel.z += GRAVITY_MSS*dv_dt
self.vel += earth_dvel
self.pos += self.vel * dv_dt
# normalise the rotation matrix to stop numerical errors creeping in
self.r.normalize()
def estimate(filename):
'''run estimator over a replay log'''
print("Processing log %s" % filename)
mlog = mavutil.mavlink_connection(filename)
est = Estimator()
output = { 'SIM.Roll' : [],
'SIM.Pitch' : [],
'EK3.Roll' : [],
'EK3.Pitch' : [],
'EST.Roll' : [],
'EST.Pitch' : [],
}
RGPI = None
RFRH = None
while True:
# we want replay sensor data, plus EKF3 result and SITL data
m = mlog.recv_match(type=['XKF1','SIM','RFRH','RFRF','RISH','RISI','RGPH','RGPI','RGPJ','RFRH','RBRH','RBRI','RMGH','RMGI'])
if m is None:
break
t = m.get_type()
if t == 'XKF1' and m.C == 0:
# output attitude of first EKF3 lane
tsec = m.TimeUS*1.0e-6
output['EK3.Roll'].append((tsec, m.Roll))
output['EK3.Pitch'].append((tsec, m.Pitch))
if t == 'SIM':
# output SITL attitude
tsec = m.TimeUS*1.0e-6
output['SIM.Roll'].append((tsec, m.Roll))
output['SIM.Pitch'].append((tsec, m.Pitch))
if t == 'RFRH':
# replay frame header, used for timestamp of the frame
RFRH = m
if t == 'RGPI' and m.I == 0:
# GPS0 status info, remember it so we know if we have a 3D fix
RGPI = m
if t == 'RGPJ' and m.I == 0 and RGPI.Stat >= 3:
# update on GPS0, with 3D fix
pos = Vector3(m.Lat*1.0e-7, m.Lon*1.0e-7, m.Alt*1.0e-2)
vel = Vector3(m.VX, m.VY, m.VZ)
est.update_GPS(pos, vel)
if t == 'RMGI' and m.I == 0 and m.H == 1:
# first compass sample, healthy compass
field = Vector3(m.FX, m.FY, m.FZ)
est.update_MAG(field)
if t == 'RBRI' and m.I == 0:
# first baro sample
est.update_BARO(m.Alt)
if t == 'RISI' and m.I == 0:
# update on IMU0
dvel = Vector3(m.DVX, m.DVY, m.DVZ)
dang = Vector3(m.DAX, m.DAY, m.DAZ)
est.update_IMU(dvel, m.DVDT, dang, m.DADT)
# output euler roll/pitch
r,p,y = est.r.to_euler()
tsec = RFRH.TimeUS*1.0e-6
output['EST.Roll'].append((tsec, degrees(r)))
output['EST.Pitch'].append((tsec, degrees(p)))
# graph all the fields we've output
import matplotlib.pyplot as plt
for k in output.keys():
t = [ v[0] for v in output[k] ]
y = [ v[1] for v in output[k] ]
plt.plot(t, y, label=k)
plt.legend(loc='upper left')
plt.show()
estimate(args.log)