4 Summarize MAVLink logs. Useful for identifying which log is of interest in a large set. 6 from __future__
import print_function
7 from builtins
import object
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=
"+")
19 args = parser.parse_args()
21 from pymavlink
import mavutil
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))
41 '''Calculate some interesting datapoints of the file''' 43 mlog = mavutil.mavlink_connection(filename, notimestamps=args.notimestamps, dialect=args.dialect)
45 autonomous_sections = 0
54 types = set([
'HEARTBEAT',
'GPS_RAW_INT'])
57 m = mlog.recv_match(condition=args.condition, type=types)
64 if m.get_type() ==
'BAD_DATA':
68 timestamp = getattr(m,
'_timestamp', 0.0)
71 if start_time
is None:
72 start_time = timestamp
78 if not args.notimestamps
and timestamp >= 1230768000:
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
86 if m.get_type() ==
'GPS_RAW_INT':
89 if m.fix_type < 3
or m.lat == 0
or m.lon == 0:
94 if first_gps_msg
is None:
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:
106 elif m.get_type() ==
'HEARTBEAT':
107 if m.type == mavutil.mavlink.MAV_TYPE_GCS:
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:
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:
117 auto_time += timestamp - start_auto_time
120 if start_time
is None:
121 print(
"ERROR: No messages found.")
126 auto_time += timestamp - start_auto_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))
134 print(
"Warning: No absolute timestamp found in datastream. No starting time can be provided for this log.")
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))
143 print(
"Warning: No GPS data found, can't give position summary.")
146 total_time = timestamp - start_time
147 print(
"Total time (mm:ss): {:3.0f}:{:02.0f}".format(total_time / 60, total_time % 60))
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))
153 totals.time += total_time
154 totals.distance += total_dist
157 for filename
in args.logs:
158 for f
in glob.glob(filename):
159 print(
"Processing log %s" % filename)
162 totals.print_summary()