mavgraph.py 10 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317
  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. import datetime
  10. import matplotlib
  11. import os
  12. import re
  13. import sys
  14. import time
  15. from math import *
  16. try:
  17. from pymavlink.mavextra import *
  18. except:
  19. print("WARNING: Numpy missing, mathematical notation will not be supported.")
  20. # cope with rename of raw_input in python3
  21. try:
  22. input = raw_input
  23. except NameError:
  24. pass
  25. colourmap = {
  26. 'apm' : {
  27. 'MANUAL' : (1.0, 0, 0),
  28. 'AUTO' : ( 0, 1.0, 0),
  29. 'LOITER' : ( 0, 0, 1.0),
  30. 'FBWA' : (1.0, 0.5, 0),
  31. 'RTL' : ( 1, 0, 0.5),
  32. 'STABILIZE' : (0.5, 1.0, 0),
  33. 'LAND' : ( 0, 1.0, 0.5),
  34. 'STEERING' : (0.5, 0, 1.0),
  35. 'HOLD' : ( 0, 0.5, 1.0),
  36. 'ALT_HOLD' : (1.0, 0.5, 0.5),
  37. 'CIRCLE' : (0.5, 1.0, 0.5),
  38. 'POSITION' : (1.0, 0.0, 1.0),
  39. 'GUIDED' : (0.5, 0.5, 1.0),
  40. 'ACRO' : (1.0, 1.0, 0),
  41. 'CRUISE' : ( 0, 1.0, 1.0)
  42. },
  43. 'px4' : {
  44. 'MANUAL' : (1.0, 0, 0),
  45. 'SEATBELT' : ( 0.5, 0.5, 0),
  46. 'EASY' : ( 0, 1.0, 0),
  47. 'AUTO' : ( 0, 0, 1.0),
  48. 'UNKNOWN' : ( 1.0, 1.0, 1.0)
  49. }
  50. }
  51. edge_colour = (0.1, 0.1, 0.1)
  52. lowest_x = None
  53. highest_x = None
  54. def plotit(x, y, fields, colors=[]):
  55. '''plot a set of graphs using date for x axis'''
  56. global lowest_x, highest_x
  57. pylab.ion()
  58. fig = pylab.figure(num=1, figsize=(12,6))
  59. ax1 = fig.gca()
  60. ax2 = None
  61. xrange = 0.0
  62. for i in range(0, len(fields)):
  63. if len(x[i]) == 0: continue
  64. if lowest_x is None or x[i][0] < lowest_x:
  65. lowest_x = x[i][0]
  66. if highest_x is None or x[i][-1] > highest_x:
  67. highest_x = x[i][-1]
  68. if highest_x is None or lowest_x is None:
  69. return
  70. xrange = highest_x - lowest_x
  71. xrange *= 24 * 60 * 60
  72. formatter = matplotlib.dates.DateFormatter('%H:%M:%S')
  73. interval = 1
  74. intervals = [ 1, 2, 5, 10, 15, 30, 60, 120, 240, 300, 600,
  75. 900, 1800, 3600, 7200, 5*3600, 10*3600, 24*3600 ]
  76. for interval in intervals:
  77. if xrange / interval < 15:
  78. break
  79. locator = matplotlib.dates.SecondLocator(interval=interval)
  80. if not args.xaxis:
  81. ax1.xaxis.set_major_locator(locator)
  82. ax1.xaxis.set_major_formatter(formatter)
  83. empty = True
  84. ax1_labels = []
  85. ax2_labels = []
  86. for i in range(0, len(fields)):
  87. if len(x[i]) == 0:
  88. print("Failed to find any values for field %s" % fields[i])
  89. continue
  90. if i < len(colors):
  91. color = colors[i]
  92. else:
  93. color = 'red'
  94. (tz, tzdst) = time.tzname
  95. if axes[i] == 2:
  96. if ax2 is None:
  97. ax2 = ax1.twinx()
  98. ax = ax2
  99. if not args.xaxis:
  100. ax2.xaxis.set_major_locator(locator)
  101. ax2.xaxis.set_major_formatter(formatter)
  102. label = fields[i]
  103. if label.endswith(":2"):
  104. label = label[:-2]
  105. ax2_labels.append(label)
  106. else:
  107. ax1_labels.append(fields[i])
  108. ax = ax1
  109. if args.xaxis:
  110. if args.marker is not None:
  111. marker = args.marker
  112. else:
  113. marker = '+'
  114. if args.linestyle is not None:
  115. linestyle = args.linestyle
  116. else:
  117. linestyle = 'None'
  118. ax.plot(x[i], y[i], color=color, label=fields[i],
  119. linestyle=linestyle, marker=marker)
  120. else:
  121. if args.marker is not None:
  122. marker = args.marker
  123. else:
  124. marker = 'None'
  125. if args.linestyle is not None:
  126. linestyle = args.linestyle
  127. else:
  128. linestyle = '-'
  129. ax.plot_date(x[i], y[i], color=color, label=fields[i],
  130. linestyle=linestyle, marker=marker, tz=None)
  131. empty = False
  132. if args.flightmode is not None:
  133. for i in range(len(modes)-1):
  134. c = colourmap[args.flightmode].get(modes[i][1], edge_colour)
  135. ax1.axvspan(modes[i][0], modes[i+1][0], fc=c, ec=edge_colour, alpha=0.1)
  136. c = colourmap[args.flightmode].get(modes[-1][1], edge_colour)
  137. ax1.axvspan(modes[-1][0], ax1.get_xlim()[1], fc=c, ec=edge_colour, alpha=0.1)
  138. if ax1_labels != []:
  139. ax1.legend(ax1_labels,loc=args.legend)
  140. if ax2_labels != []:
  141. ax2.legend(ax2_labels,loc=args.legend2)
  142. if empty:
  143. print("No data to graph")
  144. return
  145. return fig
  146. from argparse import ArgumentParser
  147. parser = ArgumentParser(description=__doc__)
  148. parser.add_argument("--no-timestamps", dest="notimestamps", action='store_true', help="Log doesn't have timestamps")
  149. parser.add_argument("--planner", action='store_true', help="use planner file format")
  150. parser.add_argument("--condition", default=None, help="select packets by a condition")
  151. parser.add_argument("--labels", default=None, help="comma separated field labels")
  152. parser.add_argument("--legend", default='upper left', help="default legend position")
  153. parser.add_argument("--legend2", default='upper right', help="default legend2 position")
  154. parser.add_argument("--marker", default=None, help="point marker")
  155. parser.add_argument("--linestyle", default=None, help="line style")
  156. parser.add_argument("--xaxis", default=None, help="X axis expression")
  157. parser.add_argument("--multi", action='store_true', help="multiple files with same colours")
  158. parser.add_argument("--zero-time-base", action='store_true', help="use Z time base for DF logs")
  159. parser.add_argument("--flightmode", default=None,
  160. 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.")
  161. parser.add_argument("--dialect", default="ardupilotmega", help="MAVLink dialect")
  162. parser.add_argument("--output", default=None, help="provide an output format")
  163. parser.add_argument("--timeshift", type=float, default=0, help="shift time on first graph in seconds")
  164. parser.add_argument("logs_fields", metavar="<LOG or FIELD>", nargs="+")
  165. args = parser.parse_args()
  166. from pymavlink import mavutil
  167. if args.flightmode is not None and args.xaxis:
  168. print("Cannot request flightmode backgrounds with an x-axis expression")
  169. sys.exit(1)
  170. if args.flightmode is not None and args.flightmode not in colourmap:
  171. print("Unknown flight controller '%s' in specification of --flightmode" % args.flightmode)
  172. sys.exit(1)
  173. if args.output is not None:
  174. matplotlib.use('Agg')
  175. import pylab
  176. filenames = []
  177. fields = []
  178. for f in args.logs_fields:
  179. if os.path.exists(f):
  180. filenames.append(f)
  181. else:
  182. fields.append(f)
  183. msg_types = set()
  184. multiplier = []
  185. field_types = []
  186. colors = [ 'red', 'green', 'blue', 'orange', 'olive', 'black', 'grey', 'yellow', 'brown', 'darkcyan', 'cornflowerblue', 'darkmagenta', 'deeppink', 'darkred']
  187. # work out msg types we are interested in
  188. x = []
  189. y = []
  190. modes = []
  191. axes = []
  192. first_only = []
  193. re_caps = re.compile('[A-Z_][A-Z0-9_]+')
  194. for f in fields:
  195. caps = set(re.findall(re_caps, f))
  196. msg_types = msg_types.union(caps)
  197. field_types.append(caps)
  198. y.append([])
  199. x.append([])
  200. axes.append(1)
  201. first_only.append(False)
  202. def add_data(t, msg, vars, flightmode):
  203. '''add some data'''
  204. mtype = msg.get_type()
  205. if args.flightmode is not None and (len(modes) == 0 or modes[-1][1] != flightmode):
  206. modes.append((t, flightmode))
  207. if mtype not in msg_types:
  208. return
  209. for i in range(0, len(fields)):
  210. if mtype not in field_types[i]:
  211. continue
  212. f = fields[i]
  213. if f.endswith(":2"):
  214. axes[i] = 2
  215. f = f[:-2]
  216. if f.endswith(":1"):
  217. first_only[i] = True
  218. f = f[:-2]
  219. v = mavutil.evaluate_expression(f, vars)
  220. if v is None:
  221. continue
  222. if args.xaxis is None:
  223. xv = t
  224. else:
  225. xv = mavutil.evaluate_expression(args.xaxis, vars)
  226. if xv is None:
  227. continue
  228. y[i].append(v)
  229. x[i].append(xv)
  230. def process_file(filename, timeshift):
  231. '''process one file'''
  232. print("Processing %s" % filename)
  233. mlog = mavutil.mavlink_connection(filename, notimestamps=args.notimestamps, zero_time_base=args.zero_time_base, dialect=args.dialect)
  234. vars = {}
  235. while True:
  236. msg = mlog.recv_match(args.condition)
  237. if msg is None: break
  238. try:
  239. tdays = matplotlib.dates.date2num(datetime.datetime.fromtimestamp(msg._timestamp+timeshift))
  240. except ValueError:
  241. # this can happen if the log is corrupt
  242. # ValueError: year is out of range
  243. break
  244. add_data(tdays, msg, mlog.messages, mlog.flightmode)
  245. if len(filenames) == 0:
  246. print("No files to process")
  247. sys.exit(1)
  248. if args.labels is not None:
  249. labels = args.labels.split(',')
  250. if len(labels) != len(fields)*len(filenames):
  251. print("Number of labels (%u) must match number of fields (%u)" % (
  252. len(labels), len(fields)*len(filenames)))
  253. sys.exit(1)
  254. else:
  255. labels = None
  256. timeshift = args.timeshift
  257. for fi in range(0, len(filenames)):
  258. f = filenames[fi]
  259. process_file(f, timeshift)
  260. timeshift = 0
  261. for i in range(0, len(x)):
  262. if first_only[i] and fi != 0:
  263. x[i] = []
  264. y[i] = []
  265. if labels:
  266. lab = labels[fi*len(fields):(fi+1)*len(fields)]
  267. else:
  268. lab = fields[:]
  269. if args.multi:
  270. col = colors[:]
  271. else:
  272. col = colors[fi*len(fields):]
  273. fig = plotit(x, y, lab, colors=col)
  274. for i in range(0, len(x)):
  275. x[i] = []
  276. y[i] = []
  277. if args.output is None:
  278. pylab.show()
  279. pylab.draw()
  280. input('press enter to exit....')
  281. else:
  282. fname, fext = os.path.splitext(args.output)
  283. if fext == '.html':
  284. import mpld3
  285. html = mpld3.fig_to_html(fig)
  286. f_out = open(args.output, 'w')
  287. f_out.write(html)
  288. f_out.close()
  289. else:
  290. pylab.legend(loc=2,prop={'size':8})
  291. pylab.savefig(args.output, bbox_inches='tight', dpi=200)