mavloss.py 2.2 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960
  1. #!/usr/bin/env python
  2. '''
  3. show MAVLink packet loss
  4. '''
  5. from __future__ import print_function
  6. from argparse import ArgumentParser
  7. parser = ArgumentParser(description=__doc__)
  8. parser.add_argument("--no-timestamps", dest="notimestamps", action='store_true', help="Log doesn't have timestamps")
  9. parser.add_argument("--planner", action='store_true', help="use planner file format")
  10. parser.add_argument("--robust", action='store_true', help="Enable robust parsing (skip over bad data)")
  11. parser.add_argument("--condition", default=None, help="condition for packets")
  12. parser.add_argument("--dialect", default="ardupilotmega", help="MAVLink dialect")
  13. parser.add_argument("logs", metavar="LOG", nargs="+")
  14. args = parser.parse_args()
  15. from pymavlink import mavutil
  16. def mavloss(logfile):
  17. '''work out signal loss times for a log file'''
  18. print("Processing log %s" % filename)
  19. mlog = mavutil.mavlink_connection(filename,
  20. planner_format=args.planner,
  21. notimestamps=args.notimestamps,
  22. dialect=args.dialect,
  23. robust_parsing=args.robust)
  24. # Track the reasons for MAVLink parsing errors and print them all out at the end.
  25. reason_ids = set()
  26. reasons = []
  27. while True:
  28. m = mlog.recv_match(condition=args.condition)
  29. # Stop parsing the file once we've reached the end
  30. if m is None:
  31. break
  32. # Save the parsing failure reason for this message if it's a new one
  33. if m.get_type() == 'BAD_DATA':
  34. reason_id = ''.join(m.reason.split(' ')[0:3])
  35. if reason_id not in reason_ids:
  36. reason_ids.add(reason_id)
  37. reasons.append(m.reason)
  38. # Print out the final packet loss results
  39. print("%u packets, %u lost %.1f%%" % (
  40. mlog.mav_count, mlog.mav_loss, mlog.packet_loss()))
  41. # Also print out the reasons why losses occurred
  42. if len(reasons) > 0:
  43. print("Packet loss at least partially attributed to the following:")
  44. for r in reasons:
  45. print(" * " + r)
  46. for filename in args.logs:
  47. mavloss(filename)