mavgpslag.py 4.2 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139
  1. #!/usr/bin/env python
  2. '''
  3. calculate GPS lag from DF log
  4. The DF log file needs to be generated with ATT, GPS and IMU bits:
  5. - On copter (bit0, bit2 and bit18) set on the LOG_BITMASK parameters
  6. - On rover (bit0, bit2 and bit7) set on the LOG_BITMASK parameters
  7. - On plane (bit0, bit2 and bit7) set on the LOG_BITMASK parameters
  8. Make sure IMU_RAW (bit 19) is not set
  9. For this to work, the vehicle must move at speeds above the --minspeed parameter (defaults to 6m/s)
  10. The code really only works when there is significant acceleration as well.
  11. You'll need to fly quite aggressively on a copter to get a result.
  12. '''
  13. from __future__ import print_function
  14. from builtins import range
  15. import os
  16. from argparse import ArgumentParser
  17. parser = ArgumentParser(description=__doc__)
  18. parser.add_argument("--plot", action='store_true', default=False, help="plot errors")
  19. parser.add_argument("--minspeed", type=float, default=6, help="minimum speed")
  20. parser.add_argument("--gps", default='', help="GPS number")
  21. parser.add_argument("logs", metavar="LOG", nargs="+")
  22. args = parser.parse_args()
  23. from pymavlink import mavutil
  24. from pymavlink.mavextra import *
  25. from pymavlink.rotmat import Vector3
  26. '''
  27. Support having a $HOME/.pymavlink/mavextra.py for extra graphing functions
  28. '''
  29. home = os.getenv('HOME')
  30. if home is not None:
  31. extra = os.path.join(home, '.pymavlink', 'mavextra.py')
  32. if os.path.exists(extra):
  33. import imp
  34. mavuser = imp.load_source('pymavlink.mavuser', extra)
  35. from pymavlink.mavuser import *
  36. def velocity_error(timestamps, vel, gaccel, accel_indexes, imu_dt, shift=0):
  37. '''return summed velocity error'''
  38. sum = 0
  39. count = 0
  40. for i in range(0, len(vel)-1):
  41. dv = vel[i+1] - vel[i]
  42. da = Vector3()
  43. for idx in range(1+accel_indexes[i]-shift, 1+accel_indexes[i+1]-shift):
  44. da += gaccel[idx]
  45. dt1 = timestamps[i+1] - timestamps[i]
  46. dt2 = (accel_indexes[i+1] - accel_indexes[i]) * imu_dt
  47. da *= imu_dt
  48. da *= dt1/dt2
  49. #print(accel_indexes[i+1] - accel_indexes[i])
  50. ex = abs(dv.x - da.x)
  51. ey = abs(dv.y - da.y)
  52. sum += 0.5*(ex+ey)
  53. count += 1
  54. if count == 0:
  55. return None
  56. return sum/count
  57. def gps_lag(logfile):
  58. '''work out gps velocity lag times for a log file'''
  59. print("Processing log %s" % filename)
  60. mlog = mavutil.mavlink_connection(filename)
  61. timestamps = []
  62. vel = []
  63. gaccel = []
  64. accel_indexes = []
  65. ATT = None
  66. IMU = None
  67. GPS = None
  68. dtsum = 0
  69. dtcount = 0
  70. while True:
  71. m = mlog.recv_match(type=['GPS'+args.gps,'IMU','ATT','GPA'+args.gps])
  72. if m is None:
  73. break
  74. t = m.get_type()
  75. if t.startswith('GPS') and m.Status >= 3 and m.Spd>args.minspeed:
  76. GPS = m;
  77. elif t.startswith('GPA') and GPS is not None and GPS.TimeUS == m.TimeUS:
  78. v = Vector3(GPS.Spd*cos(radians(GPS.GCrs)), GPS.Spd*sin(radians(GPS.GCrs)), GPS.VZ)
  79. vel.append(v)
  80. timestamps.append(m.SMS*0.001)
  81. accel_indexes.append(max(len(gaccel)-1,0))
  82. elif t == 'ATT':
  83. ATT = m
  84. elif t == 'IMU':
  85. if ATT is not None:
  86. ga = earth_accel_df(m, ATT)
  87. ga.z += 9.80665
  88. gaccel.append(ga)
  89. if IMU is not None:
  90. dt = (m.TimeUS - IMU.TimeUS) * 1.0e-6
  91. dtsum += dt
  92. dtcount += 1
  93. IMU = m
  94. imu_dt = dtsum / dtcount
  95. print("Loaded %u samples imu_dt=%.3f" % (len(vel), imu_dt))
  96. besti = -1
  97. besterr = 0
  98. delays = []
  99. errors = []
  100. for i in range(0,100):
  101. err = velocity_error(timestamps, vel, gaccel, accel_indexes, imu_dt, shift=i)
  102. if err is None:
  103. break
  104. errors.append(err)
  105. delays.append(i*imu_dt)
  106. if besti == -1 or err < besterr:
  107. besti = i
  108. besterr = err
  109. print("Best %u (%.3fs) %f" % (besti, besti*imu_dt, besterr))
  110. if args.plot:
  111. import matplotlib.pyplot as plt
  112. plt.plot(delays, errors, 'bo-')
  113. x1,x2,y1,y2 = plt.axis()
  114. plt.axis((x1,x2,0,y2))
  115. plt.ylabel('Error')
  116. plt.xlabel('Delay(s)')
  117. plt.show()
  118. for filename in args.logs:
  119. gps_lag(filename)