4 example program that dumps a Mavlink log file. The log file is 5 assumed to be in the format that qgroundcontrol uses, which consists 6 of a series of MAVLink packets, each with a 64 bit timestamp 7 header. The timestamp is in microseconds since 1970 (unix epoch) 9 from __future__
import print_function
21 print(
"WARNING: Numpy missing, mathematical notation will not be supported..")
23 from argparse
import ArgumentParser
24 parser = ArgumentParser(description=__doc__)
26 parser.add_argument(
"--no-timestamps", dest=
"notimestamps", action=
'store_true', help=
"Log doesn't have timestamps")
27 parser.add_argument(
"--planner", action=
'store_true', help=
"use planner file format")
28 parser.add_argument(
"--robust", action=
'store_true', help=
"Enable robust parsing (skip over bad data)")
29 parser.add_argument(
"-f",
"--follow", action=
'store_true', help=
"keep waiting for more data at end of file")
30 parser.add_argument(
"--condition", default=
None, help=
"select packets by condition")
31 parser.add_argument(
"-q",
"--quiet", action=
'store_true', help=
"don't display packets")
32 parser.add_argument(
"-o",
"--output", default=
None, help=
"output matching packets to give file")
33 parser.add_argument(
"-p",
"--parms", action=
'store_true', help=
"preserve parameters in output with -o")
34 parser.add_argument(
"--format", default=
None, help=
"Change the output format between 'standard', 'json', and 'csv'. For the CSV output, you must supply types that you want.")
35 parser.add_argument(
"--csv_sep", dest=
"csv_sep", default=
",", help=
"Select the delimiter between columns for the output CSV file. Use 'tab' to specify tabs. Only applies when --format=csv")
36 parser.add_argument(
"--types", default=
None, help=
"types of messages (comma separated with wildcard)")
37 parser.add_argument(
"--nottypes", default=
None, help=
"types of messages not to include (comma separated with wildcard)")
38 parser.add_argument(
"--dialect", default=
"ardupilotmega", help=
"MAVLink dialect")
39 parser.add_argument(
"--zero-time-base", action=
'store_true', help=
"use Z time base for DF logs")
40 parser.add_argument(
"--no-bad-data", action=
'store_true', help=
"Don't output corrupted messages")
41 parser.add_argument(
"--show-source", action=
'store_true', help=
"Show source system ID and component ID")
42 parser.add_argument(
"--show-seq", action=
'store_true', help=
"Show sequence numbers")
43 parser.add_argument(
"--show-types", action=
'store_true', help=
"Shows all message types available on opened log")
44 parser.add_argument(
"--source-system", type=int, default=
None, help=
"filter by source system ID")
45 parser.add_argument(
"--source-component", type=int, default=
None, help=
"filter by source component ID")
46 parser.add_argument(
"--link", type=int, default=
None, help=
"filter by comms link ID")
47 parser.add_argument(
"--mav10", action=
'store_true', help=
"parse as MAVLink1")
48 parser.add_argument(
"log", metavar=
"LOG")
49 args = parser.parse_args()
52 os.environ[
'MAVLINK20'] =
'1' 56 from pymavlink
import mavutil
61 mlog = mavutil.mavlink_connection(filename, planner_format=args.planner,
62 notimestamps=args.notimestamps,
63 robust_parsing=args.robust,
65 zero_time_base=args.zero_time_base)
69 output = open(args.output, mode=
'wb')
73 types = types.split(
',')
75 nottypes = args.nottypes
76 if nottypes
is not None:
77 nottypes = nottypes.split(
',')
79 ext = os.path.splitext(filename)[1]
80 isbin = ext
in [
'.bin',
'.BIN',
'.px4log']
81 islog = ext
in [
'.log',
'.LOG']
82 istlog = ext
in [
'.tlog',
'.TLOG']
84 if args.csv_sep ==
"tab":
88 '''return True if mtype matches pattern''' 90 if fnmatch.fnmatch(mtype, p):
95 fields = [
'timestamp']
97 if istlog
and args.format ==
'csv':
102 typeClass =
"MAVLink_{0}_message".format(type.lower())
103 fields += [type +
'.' + x
for x
in inspect.getargspec(getattr(mavutil.mavlink, typeClass).__init__).args[1:]]
104 offsets[type] = currentOffset
105 currentOffset += len(fields)
109 print(
"You must specify a list of message types if outputting CSV format via the --types argument.")
113 csv_out = [
"" for x
in fields]
114 print(args.csv_sep.join(fields))
116 if isbin
and args.format ==
'csv':
117 if types
is None or len(types) != 1:
118 print(
"Need exactly one type when dumping CSV from bin file")
122 last_timestamp =
None 125 available_types = set()
129 if types
is not None and hasattr(mlog,
'name_to_id'):
130 for k
in mlog.name_to_id.keys():
132 if nottypes
is not None and match_type(k, nottypes):
134 if match_types
is None:
136 match_types.append(k)
138 if isbin
and args.format ==
'csv':
140 match_types.append(
"FMT")
144 m = mlog.recv_match(blocking=args.follow, type=match_types)
148 available_types.add(m.get_type())
149 if isbin
and m.get_type() ==
"FMT" and args.format ==
'csv':
150 if m.Name == types[0]:
151 fields += m.Columns.split(
',')
152 csv_out = [
"" for x
in fields]
153 print(args.csv_sep.join(fields))
155 if output
is not None:
156 if (isbin
or islog)
and m.get_type() ==
"FMT":
157 output.write(m.get_msgbuf())
159 if (isbin
or islog)
and (m.get_type() ==
"PARM" and args.parms):
160 output.write(m.get_msgbuf())
162 if m.get_type() ==
'PARAM_VALUE' and args.parms:
163 timestamp = getattr(m,
'_timestamp',
None)
164 output.write(struct.pack(
'>Q',
int(timestamp*1.0e6)) + m.get_msgbuf())
167 if not mavutil.evaluate_condition(args.condition, mlog.messages):
169 if args.source_system
is not None and args.source_system != m.get_srcSystem():
171 if args.source_component
is not None and args.source_component != m.get_srcComponent():
173 if args.link
is not None and args.link != m._link:
176 if types
is not None and m.get_type() !=
'BAD_DATA' and not match_type(m.get_type(), types):
179 if nottypes
is not None and match_type(m.get_type(), nottypes):
184 if m.get_type() ==
'BAD_DATA' and (args.no_bad_data
is True or m.reason ==
"Bad prefix"):
188 timestamp = getattr(m,
'_timestamp', 0.0)
192 if not (isbin
or islog):
193 output.write(struct.pack(
'>Q',
int(timestamp*1.0e6)))
195 output.write(m.get_msgbuf())
196 except Exception
as ex:
197 print(
"Failed to write msg %s: %s" % (m.get_type(),
str(ex)))
204 if args.format ==
'json':
209 del data[
'mavpackettype']
212 if 'data' in data
and type(data[
'data'])
is not dict:
213 data[
'data'] = list(data[
'data'])
217 meta = {
"type": m.get_type(),
"timestamp": timestamp}
219 meta[
"srcSystem"] = m.get_srcSystem()
220 meta[
"srcComponent"] = m.get_srcComponent()
223 for key
in data.keys():
224 if type(data[key]) == array.array:
225 data[key] = list(data[key])
226 outMsg = {
"meta": meta,
"data": data}
229 print(json.dumps(outMsg))
231 elif args.format ==
'csv':
237 if timestamp == last_timestamp
or last_timestamp
is None:
239 newData = [
str(data[y])
if y !=
"timestamp" else "" for y
in fields]
241 newData = [
str(data[y.split(
'.')[-1]])
if y.split(
'.')[0] == type
and y.split(
'.')[-1]
in data
else "" for y
in fields]
243 for i, val
in enumerate(newData):
249 csv_out[0] =
"{:.8f}".format(last_timestamp)
250 print(args.csv_sep.join(csv_out))
252 csv_out = [
str(data[y])
if y !=
"timestamp" else "" for y
in fields]
254 csv_out = [
str(data[y.split(
'.')[-1]])
if y.split(
'.')[0] == type
and y.split(
'.')[-1]
in data
else "" for y
in fields]
257 s =
"%s.%02u: %s" % (time.strftime(
"%Y-%m-%d %H:%M:%S",
258 time.localtime(timestamp)),
259 int(timestamp*100.0)%100, m)
261 s +=
" srcSystem=%u srcComponent=%u" % (m.get_srcSystem(), m.get_srcComponent())
263 s +=
" seq=%u" % m.get_seq()
264 if not args.show_types:
268 last_timestamp = timestamp
271 for msgType
in available_types: