4 calculate GPS lag from DF log 6 The DF log file needs to be generated with ATT, GPS and IMU bits: 7 - On copter (bit0, bit2 and bit18) set on the LOG_BITMASK parameters 8 - On rover (bit0, bit2 and bit7) set on the LOG_BITMASK parameters 9 - On plane (bit0, bit2 and bit7) set on the LOG_BITMASK parameters 10 Make sure IMU_RAW (bit 19) is not set 12 For this to work, the vehicle must move at speeds above the --minspeed parameter (defaults to 6m/s) 13 The code really only works when there is significant acceleration as well. 14 You'll need to fly quite aggressively on a copter to get a result. 17 from __future__
import print_function
18 from builtins
import range
22 from argparse
import ArgumentParser
23 parser = ArgumentParser(description=__doc__)
24 parser.add_argument(
"--plot", action=
'store_true', default=
False, help=
"plot errors")
25 parser.add_argument(
"--minspeed", type=float, default=6, help=
"minimum speed")
26 parser.add_argument(
"--gps", default=
'', help=
"GPS number")
27 parser.add_argument(
"logs", metavar=
"LOG", nargs=
"+")
29 args = parser.parse_args()
31 from pymavlink
import mavutil
36 Support having a $HOME/.pymavlink/mavextra.py for extra graphing functions 38 home = os.getenv(
'HOME')
40 extra = os.path.join(home,
'.pymavlink',
'mavextra.py')
41 if os.path.exists(extra):
43 mavuser = imp.load_source(
'pymavlink.mavuser', extra)
48 '''return summed velocity error''' 51 for i
in range(0, len(vel)-1):
52 dv = vel[i+1] - vel[i]
54 for idx
in range(1+accel_indexes[i]-shift, 1+accel_indexes[i+1]-shift):
56 dt1 = timestamps[i+1] - timestamps[i]
57 dt2 = (accel_indexes[i+1] - accel_indexes[i]) * imu_dt
70 '''work out gps velocity lag times for a log file''' 71 print(
"Processing log %s" % filename)
72 mlog = mavutil.mavlink_connection(filename)
86 m = mlog.recv_match(type=[
'GPS'+args.gps,
'IMU',
'ATT',
'GPA'+args.gps])
90 if t.startswith(
'GPS')
and m.Status >= 3
and m.Spd>args.minspeed:
92 elif t.startswith(
'GPA')
and GPS
is not None and GPS.TimeUS == m.TimeUS:
93 v =
Vector3(GPS.Spd*cos(radians(GPS.GCrs)), GPS.Spd*sin(radians(GPS.GCrs)), GPS.VZ)
95 timestamps.append(m.SMS*0.001)
96 accel_indexes.append(max(len(gaccel)-1,0))
105 dt = (m.TimeUS - IMU.TimeUS) * 1.0e-6
110 imu_dt = dtsum / dtcount
112 print(
"Loaded %u samples imu_dt=%.3f" % (len(vel), imu_dt))
117 for i
in range(0,100):
118 err =
velocity_error(timestamps, vel, gaccel, accel_indexes, imu_dt, shift=i)
122 delays.append(i*imu_dt)
123 if besti == -1
or err < besterr:
126 print(
"Best %u (%.3fs) %f" % (besti, besti*imu_dt, besterr))
129 import matplotlib.pyplot
as plt
130 plt.plot(delays, errors,
'bo-')
131 x1,x2,y1,y2 = plt.axis()
132 plt.axis((x1,x2,0,y2))
134 plt.xlabel(
'Delay(s)')
138 for filename
in args.logs: