mavgpslock.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 
3 '''
4 show GPS lock events in a MAVLink log
5 '''
6 from __future__ import print_function
7 
8 import time
9 
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="+")
14 
15 args = parser.parse_args()
16 
17 from pymavlink import mavutil
18 
19 
20 def lock_time(logfile):
21  '''work out gps lock times for a log file'''
22  print("Processing log %s" % filename)
23  mlog = mavutil.mavlink_connection(filename)
24 
25  locked = False
26  start_time = 0.0
27  total_time = 0.0
28  t = None
29  m = mlog.recv_match(type=['GPS_RAW_INT','GPS_RAW'], condition=args.condition)
30  if m is None:
31  return 0
32 
33  unlock_time = time.mktime(time.localtime(m._timestamp))
34 
35  while True:
36  m = mlog.recv_match(type=['GPS_RAW_INT','GPS_RAW'], condition=args.condition)
37  if m is None:
38  if locked:
39  total_time += time.mktime(t) - start_time
40  if total_time > 0:
41  print("Lock time : %u:%02u" % (int(total_time)//60, int(total_time)%60))
42  return total_time
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))
47  locked = True
48  start_time = time.mktime(t)
49  elif m.fix_type == 1 and locked:
50  print("Lost GPS lock at %s" % time.asctime(t))
51  locked = False
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))
56  locked = False
57  total_time += time.mktime(t) - start_time
58  unlock_time = time.mktime(t)
59  return total_time
60 
61 total = 0.0
62 for filename in args.logs:
63  total += lock_time(filename)
64 
65 print("Total time locked: %u:%02u" % (int(total)//60, int(total)%60))


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