mavflighttime.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 
3 '''
4 work out total flight time for a mavlink log
5 '''
6 from __future__ import print_function
7 
8 import time
9 import glob
10 
11 from argparse import ArgumentParser
12 parser = ArgumentParser(description=__doc__)
13 parser.add_argument("--condition", default=None, help="condition for packets")
14 parser.add_argument("--groundspeed", type=float, default=3.0, help="groundspeed threshold")
15 parser.add_argument("logs", metavar="LOG", nargs="+")
16 
17 args = parser.parse_args()
18 
19 from pymavlink import mavutil
20 from pymavlink.mavextra import distance_two
21 
22 
23 def flight_time(logfile):
24  '''work out flight time for a log file'''
25  print("Processing log %s" % filename)
26  mlog = mavutil.mavlink_connection(filename)
27 
28  in_air = False
29  start_time = 0.0
30  total_time = 0.0
31  total_dist = 0.0
32  t = None
33  last_msg = None
34  last_time_usec = None
35 
36  while True:
37  m = mlog.recv_match(type=['GPS','GPS_RAW_INT'], condition=args.condition)
38  if m is None:
39  if in_air:
40  total_time += time.mktime(t) - start_time
41  if total_time > 0:
42  print("Flight time : %u:%02u" % (int(total_time)/60, int(total_time)%60))
43  return (total_time, total_dist)
44  if m.get_type() == 'GPS_RAW_INT':
45  groundspeed = m.vel*0.01
46  status = m.fix_type
47  time_usec = m.time_usec
48  else:
49  groundspeed = m.Spd
50  status = m.Status
51  time_usec = m.TimeUS
52  if status < 3:
53  continue
54  t = time.localtime(m._timestamp)
55  if groundspeed > args.groundspeed and not in_air:
56  print("In air at %s (percent %.0f%% groundspeed %.1f)" % (time.asctime(t), mlog.percent, groundspeed))
57  in_air = True
58  start_time = time.mktime(t)
59  elif groundspeed < args.groundspeed and in_air:
60  print("On ground at %s (percent %.1f%% groundspeed %.1f time=%.1f seconds)" % (
61  time.asctime(t), mlog.percent, groundspeed, time.mktime(t) - start_time))
62  in_air = False
63  total_time += time.mktime(t) - start_time
64 
65  if last_msg is None or time_usec > last_time_usec or time_usec+30e6 < last_time_usec:
66  if last_msg is not None:
67  total_dist += distance_two(last_msg, m)
68  last_msg = m
69  last_time_usec = time_usec
70  return (total_time, total_dist)
71 
72 total_time = 0.0
73 total_dist = 0.0
74 for filename in args.logs:
75  for f in glob.glob(filename):
76  (ftime, fdist) = flight_time(f)
77  total_time += ftime
78  total_dist += fdist
79 
80 print("Total time in air: %u:%02u" % (int(total_time)//60, int(total_time)%60))
81 print("Total distance travelled: %.1f meters" % total_dist)


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