mavgpslock.py 2.0 KB

1234567891011121314151617181920212223242526272829303132333435363738394041424344454647484950515253545556575859606162636465
  1. #!/usr/bin/env python
  2. '''
  3. show GPS lock events in a MAVLink log
  4. '''
  5. from __future__ import print_function
  6. import time
  7. from argparse import ArgumentParser
  8. parser = ArgumentParser(description=__doc__)
  9. parser.add_argument("--condition", default=None, help="condition for packets")
  10. parser.add_argument("logs", metavar="LOG", nargs="+")
  11. args = parser.parse_args()
  12. from pymavlink import mavutil
  13. def lock_time(logfile):
  14. '''work out gps lock times for a log file'''
  15. print("Processing log %s" % filename)
  16. mlog = mavutil.mavlink_connection(filename)
  17. locked = False
  18. start_time = 0.0
  19. total_time = 0.0
  20. t = None
  21. m = mlog.recv_match(type=['GPS_RAW_INT','GPS_RAW'], condition=args.condition)
  22. if m is None:
  23. return 0
  24. unlock_time = time.mktime(time.localtime(m._timestamp))
  25. while True:
  26. m = mlog.recv_match(type=['GPS_RAW_INT','GPS_RAW'], condition=args.condition)
  27. if m is None:
  28. if locked:
  29. total_time += time.mktime(t) - start_time
  30. if total_time > 0:
  31. print("Lock time : %u:%02u" % (int(total_time)//60, int(total_time)%60))
  32. return total_time
  33. t = time.localtime(m._timestamp)
  34. if m.fix_type >= 2 and not locked:
  35. print("Locked at %s after %u seconds" % (time.asctime(t),
  36. time.mktime(t) - unlock_time))
  37. locked = True
  38. start_time = time.mktime(t)
  39. elif m.fix_type == 1 and locked:
  40. print("Lost GPS lock at %s" % time.asctime(t))
  41. locked = False
  42. total_time += time.mktime(t) - start_time
  43. unlock_time = time.mktime(t)
  44. elif m.fix_type == 0 and locked:
  45. print("Lost protocol lock at %s" % time.asctime(t))
  46. locked = False
  47. total_time += time.mktime(t) - start_time
  48. unlock_time = time.mktime(t)
  49. return total_time
  50. total = 0.0
  51. for filename in args.logs:
  52. total += lock_time(filename)
  53. print("Total time locked: %u:%02u" % (int(total)//60, int(total)%60))