mavloss.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 
00003 '''
00004 show MAVLink packet loss
00005 '''
00006 
00007 import sys, time, os
00008 
00009 from argparse import ArgumentParser
00010 parser = ArgumentParser(description=__doc__)
00011 parser.add_argument("--no-timestamps", dest="notimestamps", action='store_true', help="Log doesn't have timestamps")
00012 parser.add_argument("--planner", action='store_true', help="use planner file format")
00013 parser.add_argument("--robust", action='store_true', help="Enable robust parsing (skip over bad data)")
00014 parser.add_argument("--condition", default=None, help="condition for packets")
00015 parser.add_argument("--dialect", default="ardupilotmega", help="MAVLink dialect")
00016 parser.add_argument("logs", metavar="LOG", nargs="+")
00017 
00018 args = parser.parse_args()
00019 
00020 from pymavlink import mavutil
00021 
00022 
00023 def mavloss(logfile):
00024     '''work out signal loss times for a log file'''
00025     print("Processing log %s" % filename)
00026     mlog = mavutil.mavlink_connection(filename,
00027                                       planner_format=args.planner,
00028                                       notimestamps=args.notimestamps,
00029                                       dialect=args.dialect,
00030                                       robust_parsing=args.robust)
00031 
00032     # Track the reasons for MAVLink parsing errors and print them all out at the end.
00033     reason_ids = set()
00034     reasons = []
00035 
00036     while True:
00037         m = mlog.recv_match(condition=args.condition)
00038 
00039         # Stop parsing the file once we've reached the end
00040         if m is None:
00041             break
00042 
00043         # Save the parsing failure reason for this message if it's a new one
00044         if m.get_type() == 'BAD_DATA':
00045             reason_id = ''.join(m.reason.split(' ')[0:3])
00046             if reason_id not in reason_ids:
00047                 reason_ids.add(reason_id)
00048                 reasons.append(m.reason)
00049 
00050     # Print out the final packet loss results
00051     print("%u packets, %u lost %.1f%%" % (
00052             mlog.mav_count, mlog.mav_loss, mlog.packet_loss()))
00053 
00054     # Also print out the reasons why losses occurred
00055     if len(reasons) > 0:
00056         print("Packet loss at least partially attributed to the following:")
00057         for r in reasons:
00058             print("  * " + r)
00059 
00060 for filename in args.logs:
00061     mavloss(filename)


mavlink
Author(s): Lorenz Meier
autogenerated on Thu Jun 6 2019 19:01:57