4 extract one mode type from a log 6 from __future__
import print_function
11 from argparse
import ArgumentParser
12 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(
"--robust", action=
'store_true', help=
"Enable robust parsing (skip over bad data)")
16 parser.add_argument(
"--condition", default=
None, help=
"select packets by condition")
17 parser.add_argument(
"--mode", default=
'auto', help=
"mode to extract")
18 parser.add_argument(
"--link", default=
None, type=int, help=
"only extract specific comms link")
19 parser.add_argument(
"logs", metavar=
"LOG", nargs=
"+")
20 args = parser.parse_args()
22 from pymavlink
import mavutil
25 '''return true if m is older than lastm by timestamp''' 26 atts = {
'time_boot_ms' : 1.0e-3,
27 'time_unix_usec' : 1.0e-6,
29 for a
in list(atts.keys()):
32 t1 = m.getattr(a) * mul
33 t2 = lastm.getattr(a) * mul
34 if t2 >= t1
and t2 - t1 < 60:
39 '''process one logfile''' 40 print(
"Processing %s" % filename)
41 mlog = mavutil.mavlink_connection(filename, notimestamps=args.notimestamps,
42 robust_parsing=args.robust)
45 ext = os.path.splitext(filename)[1]
46 isbin = ext
in [
'.bin',
'.BIN']
47 islog = ext
in [
'.log',
'.LOG']
50 dirname = os.path.dirname(filename)
62 modes = args.mode.upper().split(
',')
69 if args.link
is not None and m._link != args.link:
78 if mtype ==
'HEARTBEAT' and m.get_srcComponent() != mavutil.mavlink.MAV_COMP_ID_GIMBAL
and m.type != mavutil.mavlink.MAV_TYPE_GCS:
79 flightmode = mavutil.mode_string_v10(m).upper()
81 flightmode = mlog.flightmode
83 if (isbin
or islog)
and m.get_type()
in [
"FMT",
"PARM",
"CMD"]:
84 file_header += m.get_msgbuf()
85 if (isbin
or islog)
and m.get_type() ==
'MSG' and m.Message.startswith(
"Ardu"):
86 file_header += m.get_msgbuf()
87 if m.get_type()
in [
'PARAM_VALUE',
'MISSION_ITEM']:
88 timestamp = getattr(m,
'_timestamp',
None)
89 file_header += struct.pack(
'>Q', timestamp*1.0e6) + m.get_msgbuf()
91 if not mavutil.evaluate_condition(args.condition, mlog.messages):
94 if flightmode
in modes:
96 path = os.path.join(dirname,
"%s%u.%s" % (modes[0], count, extension))
98 print(
"Creating %s" % path)
99 output = open(path, mode=
'wb')
100 output.write(file_header)
102 if output
is not None:
106 if output
and m.get_type() !=
'BAD_DATA':
107 timestamp = getattr(m,
'_timestamp',
None)
109 output.write(struct.pack(
'>Q', timestamp*1.0e6))
110 output.write(m.get_msgbuf())
112 for filename
in args.logs: