4 show times when signal is lost 6 from __future__
import print_function
10 from argparse
import ArgumentParser
11 parser = ArgumentParser(description=__doc__)
12 parser.add_argument(
"--no-timestamps", dest=
"notimestamps", action=
'store_true', help=
"Log doesn't have timestamps")
13 parser.add_argument(
"--planner", action=
'store_true', help=
"use planner file format")
14 parser.add_argument(
"--robust", action=
'store_true', help=
"Enable robust parsing (skip over bad data)")
15 parser.add_argument(
"--deltat", type=float, default=1.0, help=
"loss threshold in seconds")
16 parser.add_argument(
"--condition", default=
None, help=
"select packets by condition")
17 parser.add_argument(
"--types", default=
None, help=
"types of messages (comma separated)")
18 parser.add_argument(
"logs", metavar=
"LOG", nargs=
"+")
20 args = parser.parse_args()
22 from pymavlink
import mavutil
26 '''work out signal loss times for a log file''' 27 print(
"Processing log %s" % filename)
28 mlog = mavutil.mavlink_connection(filename,
29 planner_format=args.planner,
30 notimestamps=args.notimestamps,
31 robust_parsing=args.robust)
37 types = types.split(
',')
40 m = mlog.recv_match(condition=args.condition)
43 if types
is not None and m.get_type()
not in types:
46 if not 'usec' in m._fieldnames:
52 if t - last_t > args.deltat:
53 print(
"Sig lost for %.1fs at %s" % (t-last_t, time.asctime(time.localtime(t))))
57 for filename
in args.logs: