4 show GPS lock events in a MAVLink log 6 from __future__
import print_function
10 from argparse
import ArgumentParser
11 parser = ArgumentParser(description=__doc__)
12 parser.add_argument(
"--condition", default=
None, help=
"condition for packets")
13 parser.add_argument(
"logs", metavar=
"LOG", nargs=
"+")
15 args = parser.parse_args()
17 from pymavlink
import mavutil
21 '''work out gps lock times for a log file''' 22 print(
"Processing log %s" % filename)
23 mlog = mavutil.mavlink_connection(filename)
29 m = mlog.recv_match(type=[
'GPS_RAW_INT',
'GPS_RAW'], condition=args.condition)
33 unlock_time = time.mktime(time.localtime(m._timestamp))
36 m = mlog.recv_match(type=[
'GPS_RAW_INT',
'GPS_RAW'], condition=args.condition)
39 total_time += time.mktime(t) - start_time
41 print(
"Lock time : %u:%02u" % (
int(total_time)//60,
int(total_time)%60))
43 t = time.localtime(m._timestamp)
44 if m.fix_type >= 2
and not locked:
45 print(
"Locked at %s after %u seconds" % (time.asctime(t),
46 time.mktime(t) - unlock_time))
48 start_time = time.mktime(t)
49 elif m.fix_type == 1
and locked:
50 print(
"Lost GPS lock at %s" % time.asctime(t))
52 total_time += time.mktime(t) - start_time
53 unlock_time = time.mktime(t)
54 elif m.fix_type == 0
and locked:
55 print(
"Lost protocol lock at %s" % time.asctime(t))
57 total_time += time.mktime(t) - start_time
58 unlock_time = time.mktime(t)
62 for filename
in args.logs:
65 print(
"Total time locked: %u:%02u" % (
int(total)//60,
int(total)%60))