3 graph a MAVLink log file 4 Andrew Tridgell August 2011 6 from __future__
import print_function
7 from builtins
import input
8 from builtins
import range
21 print(
"WARNING: Numpy missing, mathematical notation will not be supported.")
31 'MANUAL' : (1.0, 0, 0),
32 'AUTO' : ( 0, 1.0, 0),
33 'LOITER' : ( 0, 0, 1.0),
34 'FBWA' : (1.0, 0.5, 0),
36 'STABILIZE' : (0.5, 1.0, 0),
37 'LAND' : ( 0, 1.0, 0.5),
38 'STEERING' : (0.5, 0, 1.0),
39 'HOLD' : ( 0, 0.5, 1.0),
40 'ALT_HOLD' : (1.0, 0.5, 0.5),
41 'CIRCLE' : (0.5, 1.0, 0.5),
42 'POSITION' : (1.0, 0.0, 1.0),
43 'GUIDED' : (0.5, 0.5, 1.0),
44 'ACRO' : (1.0, 1.0, 0),
45 'CRUISE' : ( 0, 1.0, 1.0)
48 'MANUAL' : (1.0, 0, 0),
49 'SEATBELT' : ( 0.5, 0.5, 0),
50 'EASY' : ( 0, 1.0, 0),
51 'AUTO' : ( 0, 0, 1.0),
52 'UNKNOWN' : ( 1.0, 1.0, 1.0)
56 edge_colour = (0.1, 0.1, 0.1)
62 '''plot a set of graphs using date for x axis''' 63 global lowest_x, highest_x
65 fig = pylab.figure(num=1, figsize=(12,6))
69 for i
in range(0, len(fields)):
70 if len(x[i]) == 0:
continue 71 if lowest_x
is None or x[i][0] < lowest_x:
73 if highest_x
is None or x[i][-1] > highest_x:
75 if highest_x
is None or lowest_x
is None:
77 xrange = highest_x - lowest_x
78 xrange *= 24 * 60 * 60
79 formatter = matplotlib.dates.DateFormatter(
'%H:%M:%S')
81 intervals = [ 1, 2, 5, 10, 15, 30, 60, 120, 240, 300, 600,
82 900, 1800, 3600, 7200, 5*3600, 10*3600, 24*3600 ]
83 for interval
in intervals:
84 if xrange / interval < 15:
86 locator = matplotlib.dates.SecondLocator(interval=interval)
88 ax1.xaxis.set_major_locator(locator)
89 ax1.xaxis.set_major_formatter(formatter)
93 for i
in range(0, len(fields)):
95 print(
"Failed to find any values for field %s" % fields[i])
101 (tz, tzdst) = time.tzname
107 ax2.xaxis.set_major_locator(locator)
108 ax2.xaxis.set_major_formatter(formatter)
110 if label.endswith(
":2"):
112 ax2_labels.append(label)
114 ax1_labels.append(fields[i])
117 if args.marker
is not None:
121 if args.linestyle
is not None:
122 linestyle = args.linestyle
125 ax.plot(x[i], y[i], color=color, label=fields[i],
126 linestyle=linestyle, marker=marker)
128 if args.marker
is not None:
132 if args.linestyle
is not None:
133 linestyle = args.linestyle
136 ax.plot_date(x[i], y[i], color=color, label=fields[i],
137 linestyle=linestyle, marker=marker, tz=
None)
139 if args.flightmode
is not None:
140 for i
in range(len(modes)-1):
141 c = colourmap[args.flightmode].get(modes[i][1], edge_colour)
142 ax1.axvspan(modes[i][0], modes[i+1][0], fc=c, ec=edge_colour, alpha=0.1)
143 c = colourmap[args.flightmode].get(modes[-1][1], edge_colour)
144 ax1.axvspan(modes[-1][0], ax1.get_xlim()[1], fc=c, ec=edge_colour, alpha=0.1)
146 ax1.legend(ax1_labels,loc=args.legend)
148 ax2.legend(ax2_labels,loc=args.legend2)
150 print(
"No data to graph")
155 from argparse
import ArgumentParser
156 parser = ArgumentParser(description=__doc__)
158 parser.add_argument(
"--no-timestamps", dest=
"notimestamps", action=
'store_true', help=
"Log doesn't have timestamps")
159 parser.add_argument(
"--planner", action=
'store_true', help=
"use planner file format")
160 parser.add_argument(
"--condition", default=
None, help=
"select packets by a condition")
161 parser.add_argument(
"--labels", default=
None, help=
"comma separated field labels")
162 parser.add_argument(
"--legend", default=
'upper left', help=
"default legend position")
163 parser.add_argument(
"--legend2", default=
'upper right', help=
"default legend2 position")
164 parser.add_argument(
"--marker", default=
None, help=
"point marker")
165 parser.add_argument(
"--linestyle", default=
None, help=
"line style")
166 parser.add_argument(
"--xaxis", default=
None, help=
"X axis expression")
167 parser.add_argument(
"--multi", action=
'store_true', help=
"multiple files with same colours")
168 parser.add_argument(
"--zero-time-base", action=
'store_true', help=
"use Z time base for DF logs")
169 parser.add_argument(
"--flightmode", default=
None,
170 help=
"Choose the plot background according to the active flight mode of the specified type, e.g. --flightmode=apm for ArduPilot or --flightmode=px4 for PX4 stack logs. Cannot be specified with --xaxis.")
171 parser.add_argument(
"--dialect", default=
"ardupilotmega", help=
"MAVLink dialect")
172 parser.add_argument(
"--output", default=
None, help=
"provide an output format")
173 parser.add_argument(
"--timeshift", type=float, default=0, help=
"shift time on first graph in seconds")
174 parser.add_argument(
"logs_fields", metavar=
"<LOG or FIELD>", nargs=
"+")
175 args = parser.parse_args()
177 from pymavlink
import mavutil
179 if args.flightmode
is not None and args.xaxis:
180 print(
"Cannot request flightmode backgrounds with an x-axis expression")
183 if args.flightmode
is not None and args.flightmode
not in colourmap:
184 print(
"Unknown flight controller '%s' in specification of --flightmode" % args.flightmode)
188 if args.output
is not None:
189 matplotlib.use(
'Agg')
195 for f
in args.logs_fields:
196 if os.path.exists(f):
204 colors = [
'red',
'green',
'blue',
'orange',
'olive',
'black',
'grey',
'yellow',
'brown',
'darkcyan',
'cornflowerblue',
'darkmagenta',
'deeppink',
'darkred']
212 re_caps = re.compile(
'[A-Z_][A-Z0-9_]+')
214 caps = set(re.findall(re_caps, f))
215 msg_types = msg_types.union(caps)
216 field_types.append(caps)
220 first_only.append(
False)
224 mtype = msg.get_type()
225 if args.flightmode
is not None and (len(modes) == 0
or modes[-1][1] != flightmode):
226 modes.append((t, flightmode))
227 if mtype
not in msg_types:
229 for i
in range(0, len(fields)):
230 if mtype
not in field_types[i]:
239 v = mavutil.evaluate_expression(f, vars)
242 if args.xaxis
is None:
245 xv = mavutil.evaluate_expression(args.xaxis, vars)
252 '''process one file''' 253 print(
"Processing %s" % filename)
254 mlog = mavutil.mavlink_connection(filename, notimestamps=args.notimestamps, zero_time_base=args.zero_time_base, dialect=args.dialect)
258 msg = mlog.recv_match(args.condition)
259 if msg
is None:
break 261 tdays = matplotlib.dates.date2num(datetime.datetime.fromtimestamp(msg._timestamp+timeshift))
266 add_data(tdays, msg, mlog.messages, mlog.flightmode)
268 if len(filenames) == 0:
269 print(
"No files to process")
272 if args.labels
is not None:
273 labels = args.labels.split(
',')
274 if len(labels) != len(fields)*len(filenames):
275 print(
"Number of labels (%u) must match number of fields (%u)" % (
276 len(labels), len(fields)*len(filenames)))
281 timeshift = args.timeshift
283 for fi
in range(0, len(filenames)):
287 for i
in range(0, len(x)):
288 if first_only[i]
and fi != 0:
292 lab = labels[fi*len(fields):(fi+1)*len(fields)]
298 col = colors[fi*len(fields):]
300 for i
in range(0, len(x)):
303 if args.output
is None:
306 input(
'press enter to exit....')
308 fname, fext = os.path.splitext(args.output)
311 html = mpld3.fig_to_html(fig)
312 f_out = open(args.output,
'w')
316 pylab.legend(loc=2,prop={
'size':8})
317 pylab.savefig(args.output, bbox_inches=
'tight', dpi=200)