mavsummarize.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 
3 '''
4 Summarize MAVLink logs. Useful for identifying which log is of interest in a large set.
5 '''
6 from __future__ import print_function
7 from builtins import object
8 
9 import glob
10 import time
11 
12 from argparse import ArgumentParser
13 parser = ArgumentParser(description=__doc__)
14 parser.add_argument("--no-timestamps", dest="notimestamps", action='store_true', help="Log doesn't have timestamps")
15 parser.add_argument("--condition", default=None, help="condition for packets")
16 parser.add_argument("--dialect", default="ardupilotmega", help="MAVLink dialect")
17 parser.add_argument("logs", metavar="LOG", nargs="+")
18 
19 args = parser.parse_args()
20 
21 from pymavlink import mavutil
22 from pymavlink.mavextra import distance_two
23 
24 
25 class Totals(object):
26  def __init__(self):
27  self.time = 0
28  self.distance = 0
29  self.flights = 0
30 
31  def print_summary(self):
32  print("===============================")
33  print("Num Flights : %u" % self.flights)
34  print("Total distance : {:0.2f}m".format(self.distance))
35  print("Total time (mm:ss): {:3.0f}:{:02.0f}".format(self.time / 60, self.time % 60))
36 
37 
38 totals = Totals()
39 
40 def PrintSummary(logfile):
41  '''Calculate some interesting datapoints of the file'''
42  # Open the log file
43  mlog = mavutil.mavlink_connection(filename, notimestamps=args.notimestamps, dialect=args.dialect)
44 
45  autonomous_sections = 0 # How many different autonomous sections there are
46  autonomous = False # Whether the vehicle is currently autonomous at this point in the logfile
47  auto_time = 0.0 # The total time the vehicle was autonomous/guided (seconds)
48  start_time = None # The datetime of the first received message (seconds since epoch)
49  total_dist = 0.0 # The total ground distance travelled (meters)
50  last_gps_msg = None # The first GPS message received
51  first_gps_msg = None # The last GPS message received
52  true_time = None # Track the first timestamp found that corresponds to a UNIX timestamp
53 
54  types = set(['HEARTBEAT', 'GPS_RAW_INT'])
55 
56  while True:
57  m = mlog.recv_match(condition=args.condition, type=types)
58 
59  # If there's no match, it means we're done processing the log.
60  if m is None:
61  break
62 
63  # Ignore any failed messages
64  if m.get_type() == 'BAD_DATA':
65  continue
66 
67  # Keep track of the latest timestamp for various calculations
68  timestamp = getattr(m, '_timestamp', 0.0)
69 
70  # Log the first message time
71  if start_time is None:
72  start_time = timestamp
73 
74  # Log the first timestamp found that is a true timestamp. We first try
75  # to get the groundstation timestamp from the log directly. If that fails
76  # we try to find a message that outputs a Unix time-since-epoch.
77  if true_time is None:
78  if not args.notimestamps and timestamp >= 1230768000:
79  true_time = timestamp
80  elif 'time_unix_usec' in m.__dict__ and m.time_unix_usec >= 1230768000:
81  true_time = m.time_unix_usec * 1.0e-6
82  elif 'time_usec' in m.__dict__ and m.time_usec >= 1230768000:
83  true_time = m.time_usec * 1.0e-6
84 
85  # Track the vehicle's speed and status
86  if m.get_type() == 'GPS_RAW_INT':
87 
88  # Ignore GPS messages without a proper fix
89  if m.fix_type < 3 or m.lat == 0 or m.lon == 0:
90  continue
91 
92  # Log the first GPS location found, being sure to skip GPS fixes
93  # that are bad (at lat/lon of 0,0)
94  if first_gps_msg is None:
95  first_gps_msg = m
96 
97  # Track the distance travelled, being sure to skip GPS fixes
98  # that are bad (at lat/lon of 0,0)
99  if last_gps_msg is None or m.time_usec > last_gps_msg.time_usec or m.time_usec+30e6 < last_gps_msg.time_usec:
100  if last_gps_msg is not None:
101  total_dist += distance_two(last_gps_msg, m)
102 
103  # Save this GPS message to do simple distance calculations with
104  last_gps_msg = m
105 
106  elif m.get_type() == 'HEARTBEAT':
107  if m.type == mavutil.mavlink.MAV_TYPE_GCS:
108  continue
109  if (m.base_mode & mavutil.mavlink.MAV_MODE_FLAG_GUIDED_ENABLED or
110  m.base_mode & mavutil.mavlink.MAV_MODE_FLAG_AUTO_ENABLED) and not autonomous:
111  autonomous = True
112  autonomous_sections += 1
113  start_auto_time = timestamp
114  elif (not m.base_mode & mavutil.mavlink.MAV_MODE_FLAG_GUIDED_ENABLED and
115  not m.base_mode & mavutil.mavlink.MAV_MODE_FLAG_AUTO_ENABLED) and autonomous:
116  autonomous = False
117  auto_time += timestamp - start_auto_time
118 
119  # If there were no messages processed, say so
120  if start_time is None:
121  print("ERROR: No messages found.")
122  return
123 
124  # If the vehicle ends in autonomous mode, make sure we log the total time
125  if autonomous:
126  auto_time += timestamp - start_auto_time
127 
128  # Compute the total logtime, checking that timestamps are 2009 or newer for validity
129  # (MAVLink didn't exist until 2009)
130  if true_time:
131  start_time_str = time.strftime("%Y-%m-%d %H:%M:%S", time.localtime(true_time))
132  print("Log started at about {}".format(start_time_str))
133  else:
134  print("Warning: No absolute timestamp found in datastream. No starting time can be provided for this log.")
135 
136  # Print location data
137  if last_gps_msg is not None:
138  first_gps_position = (first_gps_msg.lat / 1e7, first_gps_msg.lon / 1e7)
139  last_gps_position = (last_gps_msg.lat / 1e7, last_gps_msg.lon / 1e7)
140  print("Travelled from ({0[0]}, {0[1]}) to ({1[0]}, {1[1]})".format(first_gps_position, last_gps_position))
141  print("Total distance : {:0.2f}m".format(total_dist))
142  else:
143  print("Warning: No GPS data found, can't give position summary.")
144 
145  # Print out the rest of the results.
146  total_time = timestamp - start_time
147  print("Total time (mm:ss): {:3.0f}:{:02.0f}".format(total_time / 60, total_time % 60))
148  # The autonomous time should be good, as a steady HEARTBEAT is required for MAVLink operation
149  print("Autonomous sections: {}".format(autonomous_sections))
150  if autonomous_sections > 0:
151  print("Autonomous time (mm:ss): {:3.0f}:{:02.0f}".format(auto_time / 60, auto_time % 60))
152 
153  totals.time += total_time
154  totals.distance += total_dist
155  totals.flights += 1
156 
157 for filename in args.logs:
158  for f in glob.glob(filename):
159  print("Processing log %s" % filename)
160  PrintSummary(f)
161 
162 totals.print_summary()


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