mavgraph.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 '''
3 graph a MAVLink log file
4 Andrew Tridgell August 2011
5 '''
6 from __future__ import print_function
7 from builtins import input
8 from builtins import range
9 
10 import datetime
11 import matplotlib
12 import os
13 import re
14 import sys
15 import time
16 from math import *
17 
18 try:
19  from pymavlink.mavextra import *
20 except:
21  print("WARNING: Numpy missing, mathematical notation will not be supported.")
22 
23 # cope with rename of raw_input in python3
24 try:
25  input = raw_input
26 except NameError:
27  pass
28 
29 colourmap = {
30  'apm' : {
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),
35  'RTL' : ( 1, 0, 0.5),
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)
46  },
47  'px4' : {
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)
53  }
54  }
55 
56 edge_colour = (0.1, 0.1, 0.1)
57 
58 lowest_x = None
59 highest_x = None
60 
61 def plotit(x, y, fields, colors=[]):
62  '''plot a set of graphs using date for x axis'''
63  global lowest_x, highest_x
64  pylab.ion()
65  fig = pylab.figure(num=1, figsize=(12,6))
66  ax1 = fig.gca()
67  ax2 = None
68  xrange = 0.0
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:
72  lowest_x = x[i][0]
73  if highest_x is None or x[i][-1] > highest_x:
74  highest_x = x[i][-1]
75  if highest_x is None or lowest_x is None:
76  return
77  xrange = highest_x - lowest_x
78  xrange *= 24 * 60 * 60
79  formatter = matplotlib.dates.DateFormatter('%H:%M:%S')
80  interval = 1
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:
85  break
86  locator = matplotlib.dates.SecondLocator(interval=interval)
87  if not args.xaxis:
88  ax1.xaxis.set_major_locator(locator)
89  ax1.xaxis.set_major_formatter(formatter)
90  empty = True
91  ax1_labels = []
92  ax2_labels = []
93  for i in range(0, len(fields)):
94  if len(x[i]) == 0:
95  print("Failed to find any values for field %s" % fields[i])
96  continue
97  if i < len(colors):
98  color = colors[i]
99  else:
100  color = 'red'
101  (tz, tzdst) = time.tzname
102  if axes[i] == 2:
103  if ax2 is None:
104  ax2 = ax1.twinx()
105  ax = ax2
106  if not args.xaxis:
107  ax2.xaxis.set_major_locator(locator)
108  ax2.xaxis.set_major_formatter(formatter)
109  label = fields[i]
110  if label.endswith(":2"):
111  label = label[:-2]
112  ax2_labels.append(label)
113  else:
114  ax1_labels.append(fields[i])
115  ax = ax1
116  if args.xaxis:
117  if args.marker is not None:
118  marker = args.marker
119  else:
120  marker = '+'
121  if args.linestyle is not None:
122  linestyle = args.linestyle
123  else:
124  linestyle = 'None'
125  ax.plot(x[i], y[i], color=color, label=fields[i],
126  linestyle=linestyle, marker=marker)
127  else:
128  if args.marker is not None:
129  marker = args.marker
130  else:
131  marker = 'None'
132  if args.linestyle is not None:
133  linestyle = args.linestyle
134  else:
135  linestyle = '-'
136  ax.plot_date(x[i], y[i], color=color, label=fields[i],
137  linestyle=linestyle, marker=marker, tz=None)
138  empty = False
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)
145  if ax1_labels != []:
146  ax1.legend(ax1_labels,loc=args.legend)
147  if ax2_labels != []:
148  ax2.legend(ax2_labels,loc=args.legend2)
149  if empty:
150  print("No data to graph")
151  return
152  return fig
153 
154 
155 from argparse import ArgumentParser
156 parser = ArgumentParser(description=__doc__)
157 
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()
176 
177 from pymavlink import mavutil
178 
179 if args.flightmode is not None and args.xaxis:
180  print("Cannot request flightmode backgrounds with an x-axis expression")
181  sys.exit(1)
182 
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)
185  sys.exit(1)
186 
187 
188 if args.output is not None:
189  matplotlib.use('Agg')
190 
191 import pylab
192 
193 filenames = []
194 fields = []
195 for f in args.logs_fields:
196  if os.path.exists(f):
197  filenames.append(f)
198  else:
199  fields.append(f)
200 msg_types = set()
201 multiplier = []
202 field_types = []
203 
204 colors = [ 'red', 'green', 'blue', 'orange', 'olive', 'black', 'grey', 'yellow', 'brown', 'darkcyan', 'cornflowerblue', 'darkmagenta', 'deeppink', 'darkred']
205 
206 # work out msg types we are interested in
207 x = []
208 y = []
209 modes = []
210 axes = []
211 first_only = []
212 re_caps = re.compile('[A-Z_][A-Z0-9_]+')
213 for f in fields:
214  caps = set(re.findall(re_caps, f))
215  msg_types = msg_types.union(caps)
216  field_types.append(caps)
217  y.append([])
218  x.append([])
219  axes.append(1)
220  first_only.append(False)
221 
222 def add_data(t, msg, vars, flightmode):
223  '''add some data'''
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:
228  return
229  for i in range(0, len(fields)):
230  if mtype not in field_types[i]:
231  continue
232  f = fields[i]
233  if f.endswith(":2"):
234  axes[i] = 2
235  f = f[:-2]
236  if f.endswith(":1"):
237  first_only[i] = True
238  f = f[:-2]
239  v = mavutil.evaluate_expression(f, vars)
240  if v is None:
241  continue
242  if args.xaxis is None:
243  xv = t
244  else:
245  xv = mavutil.evaluate_expression(args.xaxis, vars)
246  if xv is None:
247  continue
248  y[i].append(v)
249  x[i].append(xv)
250 
251 def process_file(filename, timeshift):
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)
255  vars = {}
256 
257  while True:
258  msg = mlog.recv_match(args.condition)
259  if msg is None: break
260  try:
261  tdays = matplotlib.dates.date2num(datetime.datetime.fromtimestamp(msg._timestamp+timeshift))
262  except ValueError:
263  # this can happen if the log is corrupt
264  # ValueError: year is out of range
265  break
266  add_data(tdays, msg, mlog.messages, mlog.flightmode)
267 
268 if len(filenames) == 0:
269  print("No files to process")
270  sys.exit(1)
271 
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)))
277  sys.exit(1)
278 else:
279  labels = None
280 
281 timeshift = args.timeshift
282 
283 for fi in range(0, len(filenames)):
284  f = filenames[fi]
285  process_file(f, timeshift)
286  timeshift = 0
287  for i in range(0, len(x)):
288  if first_only[i] and fi != 0:
289  x[i] = []
290  y[i] = []
291  if labels:
292  lab = labels[fi*len(fields):(fi+1)*len(fields)]
293  else:
294  lab = fields[:]
295  if args.multi:
296  col = colors[:]
297  else:
298  col = colors[fi*len(fields):]
299  fig = plotit(x, y, lab, colors=col)
300  for i in range(0, len(x)):
301  x[i] = []
302  y[i] = []
303 if args.output is None:
304  pylab.show()
305  pylab.draw()
306  input('press enter to exit....')
307 else:
308  fname, fext = os.path.splitext(args.output)
309  if fext == '.html':
310  import mpld3
311  html = mpld3.fig_to_html(fig)
312  f_out = open(args.output, 'w')
313  f_out.write(html)
314  f_out.close()
315  else:
316  pylab.legend(loc=2,prop={'size':8})
317  pylab.savefig(args.output, bbox_inches='tight', dpi=200)


mavlink
Author(s): Lorenz Meier
autogenerated on Sun Apr 7 2019 02:06:02