Go to the documentation of this file.00001
00002
00003 '''
00004 Summarize MAVLink logs. Useful for identifying which log is of interest in a large set.
00005 '''
00006
00007 import sys, time, os, glob
00008
00009 from argparse import ArgumentParser
00010 parser = ArgumentParser(description=__doc__)
00011 parser.add_argument("--no-timestamps", dest="notimestamps", action='store_true', help="Log doesn't have timestamps")
00012 parser.add_argument("--condition", default=None, help="condition for packets")
00013 parser.add_argument("--dialect", default="ardupilotmega", help="MAVLink dialect")
00014 parser.add_argument("logs", metavar="LOG", nargs="+")
00015
00016 args = parser.parse_args()
00017
00018 from pymavlink import mavutil
00019 from pymavlink.mavextra import distance_two
00020
00021
00022 def PrintSummary(logfile):
00023 '''Calculate some interesting datapoints of the file'''
00024
00025 mlog = mavutil.mavlink_connection(filename, notimestamps=args.notimestamps, dialect=args.dialect)
00026
00027 autonomous_sections = 0
00028 autonomous = False
00029 auto_time = 0.0
00030 start_time = None
00031 total_dist = 0.0
00032 last_gps_msg = None
00033 first_gps_msg = None
00034 true_time = None
00035
00036 while True:
00037 m = mlog.recv_match(condition=args.condition)
00038
00039
00040 if m is None:
00041 break
00042
00043
00044 if m.get_type() == 'BAD_DATA':
00045 continue
00046
00047
00048 timestamp = getattr(m, '_timestamp', 0.0)
00049
00050
00051 if start_time is None:
00052 start_time = timestamp
00053
00054
00055
00056
00057 if true_time is None:
00058 if not args.notimestamps and timestamp >= 1230768000:
00059 true_time = timestamp
00060 elif 'time_unix_usec' in m.__dict__ and m.time_unix_usec >= 1230768000:
00061 true_time = m.time_unix_usec * 1.0e-6
00062 elif 'time_usec' in m.__dict__ and m.time_usec >= 1230768000:
00063 true_time = m.time_usec * 1.0e-6
00064
00065
00066 if m.get_type() == 'GPS_RAW_INT':
00067
00068
00069 if m.fix_type < 3 or m.lat == 0 or m.lon == 0:
00070 continue
00071
00072
00073
00074 if first_gps_msg is None:
00075 first_gps_msg = m
00076
00077
00078
00079 if last_gps_msg is not None:
00080 total_dist += distance_two(last_gps_msg, m)
00081
00082
00083 last_gps_msg = m
00084
00085 elif m.get_type() == 'HEARTBEAT':
00086 if (m.base_mode & mavutil.mavlink.MAV_MODE_FLAG_GUIDED_ENABLED or
00087 m.base_mode & mavutil.mavlink.MAV_MODE_FLAG_AUTO_ENABLED) and autonomous == False:
00088 autonomous = True
00089 autonomous_sections += 1
00090 start_auto_time = timestamp
00091 elif (not m.base_mode & mavutil.mavlink.MAV_MODE_FLAG_GUIDED_ENABLED and
00092 not m.base_mode & mavutil.mavlink.MAV_MODE_FLAG_AUTO_ENABLED) and autonomous == True:
00093 autonomous = False
00094 auto_time += timestamp - start_auto_time
00095
00096
00097 if start_time is None:
00098 print("ERROR: No messages found.")
00099 return
00100
00101
00102 if autonomous == True:
00103 auto_time += timestamp - start_auto_time
00104
00105
00106
00107 if true_time:
00108 start_time_str = time.strftime("%Y-%m-%d %H:%M:%S", time.localtime(true_time))
00109 print("Log started at about {}".format(start_time_str))
00110 else:
00111 print("Warning: No absolute timestamp found in datastream. No starting time can be provided for this log.")
00112
00113
00114 if last_gps_msg is not None:
00115 first_gps_position = (first_gps_msg.lat / 1e7, first_gps_msg.lon / 1e7)
00116 last_gps_position = (last_gps_msg.lat / 1e7, last_gps_msg.lon / 1e7)
00117 print("Travelled from ({0[0]}, {0[1]}) to ({1[0]}, {1[1]})".format(first_gps_position, last_gps_position))
00118 print("Total distance : {:0.2f}m".format(total_dist))
00119 else:
00120 print("Warning: No GPS data found, can't give position summary.")
00121
00122
00123 total_time = timestamp - start_time
00124 print("Total time (mm:ss): {:3.0f}:{:02.0f}".format(total_time / 60, total_time % 60))
00125
00126 print("Autonomous sections: {}".format(autonomous_sections))
00127 if autonomous_sections > 0:
00128 print("Autonomous time (mm:ss): {:3.0f}:{:02.0f}".format(auto_time / 60, auto_time % 60))
00129
00130 for filename in args.logs:
00131 for f in glob.glob(filename):
00132 print("Processing log %s" % filename)
00133 PrintSummary(f)