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


mavlink
Author(s): Lorenz Meier
autogenerated on Sun Apr 7 2019 02:06:02