mavgpslock.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 
00003 '''
00004 show GPS lock events in a MAVLink log
00005 '''
00006 
00007 import sys, time, os
00008 
00009 from argparse import ArgumentParser
00010 parser = ArgumentParser(description=__doc__)
00011 parser.add_argument("--condition", default=None, help="condition for packets")
00012 parser.add_argument("logs", metavar="LOG", nargs="+")
00013 
00014 args = parser.parse_args()
00015 
00016 from pymavlink import mavutil
00017 
00018 
00019 def lock_time(logfile):
00020     '''work out gps lock times for a log file'''
00021     print("Processing log %s" % filename)
00022     mlog = mavutil.mavlink_connection(filename)
00023 
00024     locked = False
00025     start_time = 0.0
00026     total_time = 0.0
00027     t = None
00028     m = mlog.recv_match(type=['GPS_RAW_INT','GPS_RAW'], condition=args.condition)
00029     if m is None:
00030         return 0
00031 
00032     unlock_time = time.mktime(time.localtime(m._timestamp))
00033 
00034     while True:
00035         m = mlog.recv_match(type=['GPS_RAW_INT','GPS_RAW'], condition=args.condition)
00036         if m is None:
00037             if locked:
00038                 total_time += time.mktime(t) - start_time
00039             if total_time > 0:
00040                 print("Lock time : %u:%02u" % (int(total_time)/60, int(total_time)%60))
00041             return total_time
00042         t = time.localtime(m._timestamp)
00043         if m.fix_type >= 2 and not locked:
00044             print("Locked at %s after %u seconds" % (time.asctime(t),
00045                                                      time.mktime(t) - unlock_time))
00046             locked = True
00047             start_time = time.mktime(t)
00048         elif m.fix_type == 1 and locked:
00049             print("Lost GPS lock at %s" % time.asctime(t))
00050             locked = False
00051             total_time += time.mktime(t) - start_time
00052             unlock_time = time.mktime(t)
00053         elif m.fix_type == 0 and locked:
00054             print("Lost protocol lock at %s" % time.asctime(t))
00055             locked = False
00056             total_time += time.mktime(t) - start_time
00057             unlock_time = time.mktime(t)
00058     return total_time
00059 
00060 total = 0.0
00061 for filename in args.logs:
00062     total += lock_time(filename)
00063 
00064 print("Total time locked: %u:%02u" % (int(total)/60, int(total)%60))


mavlink
Author(s): Lorenz Meier
autogenerated on Wed Sep 9 2015 18:06:17