mavflighttime.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 
00003 '''
00004 work out total flight time for a mavlink log
00005 '''
00006 
00007 import sys, time, os, glob
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("--groundspeed", type=float, default=3.0, help="groundspeed threshold")
00013 parser.add_argument("logs", metavar="LOG", nargs="+")
00014 
00015 args = parser.parse_args()
00016 
00017 from pymavlink import mavutil
00018 from pymavlink.mavextra import distance_two
00019 
00020 
00021 def flight_time(logfile):
00022     '''work out flight time for a log file'''
00023     print("Processing log %s" % filename)
00024     mlog = mavutil.mavlink_connection(filename)
00025 
00026     in_air = False
00027     start_time = 0.0
00028     total_time = 0.0
00029     total_dist = 0.0
00030     t = None
00031     last_msg = None
00032 
00033     while True:
00034         m = mlog.recv_match(type=['GPS','GPS_RAW_INT'], condition=args.condition)
00035         if m is None:
00036             if in_air:
00037                 total_time += time.mktime(t) - start_time
00038             if total_time > 0:
00039                 print("Flight time : %u:%02u" % (int(total_time)/60, int(total_time)%60))
00040             return (total_time, total_dist)
00041         if m.get_type() == 'GPS_RAW_INT':
00042             groundspeed = m.vel*0.01
00043             status = m.fix_type
00044         else:
00045             groundspeed = m.Spd
00046             status = m.Status
00047         if status < 3:
00048             continue
00049         t = time.localtime(m._timestamp)
00050         if groundspeed > args.groundspeed and not in_air:
00051             print("In air at %s (percent %.0f%% groundspeed %.1f)" % (time.asctime(t), mlog.percent, groundspeed))
00052             in_air = True
00053             start_time = time.mktime(t)
00054         elif groundspeed < args.groundspeed and in_air:
00055             print("On ground at %s (percent %.1f%% groundspeed %.1f  time=%.1f seconds)" % (
00056                 time.asctime(t), mlog.percent, groundspeed, time.mktime(t) - start_time))
00057             in_air = False
00058             total_time += time.mktime(t) - start_time
00059 
00060         if last_msg is not None:
00061             total_dist += distance_two(last_msg, m)
00062         last_msg = m
00063     return (total_time, total_dist)
00064 
00065 total_time = 0.0
00066 total_dist = 0.0
00067 for filename in args.logs:
00068     for f in glob.glob(filename):
00069         (ftime, fdist) = flight_time(f)
00070         total_time += ftime
00071         total_dist += fdist
00072 
00073 print("Total time in air: %u:%02u" % (int(total_time)/60, int(total_time)%60))
00074 print("Total distance travelled: %.1f meters" % total_dist)


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