4 show MAVLink packet loss 6 from __future__
import print_function
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=
"+")
17 args = parser.parse_args()
19 from pymavlink
import mavutil
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,
29 robust_parsing=args.robust)
36 m = mlog.recv_match(condition=args.condition)
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)
50 print(
"%u packets, %u lost %.1f%%" % (
51 mlog.mav_count, mlog.mav_loss, mlog.packet_loss()))
55 print(
"Packet loss at least partially attributed to the following:")
59 for filename
in args.logs: