Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
170 changes: 90 additions & 80 deletions MAVProxy/modules/lib/live_graph_ui.py
Original file line number Diff line number Diff line change
@@ -1,22 +1,25 @@
from MAVProxy.modules.lib.live_graph import LiveGraph
from MAVProxy.modules.lib.wx_loader import wx
from MAVProxy.modules.lib import icon
import time
import numpy, pylab
from matplotlib.backends.backend_wxagg import FigureCanvasWxAgg as FigCanvas
from matplotlib.figure import Figure

class GraphFrame(wx.Frame):
""" The main frame of the application
"""

def __init__(self, state):
def __init__(self, state: LiveGraph):
wx.Frame.__init__(self, None, -1, state.title)
try:
self.SetIcon(icon.SimpleIcon().get_ico())
except Exception:
pass
self.state = state
self.data = []
for i in range(len(state.fields)):
self.data.append([])
self.sample_dt = float(getattr(state, "sample_dt", state.tickresolution))
self.refresh_dt = float(getattr(state, "refresh_dt", state.tickresolution)) * 10

self.paused = False
self.clear_data = False

Expand All @@ -26,23 +29,16 @@ def __init__(self, state):

self.redraw_timer = wx.Timer(self)
self.Bind(wx.EVT_TIMER, self.on_redraw_timer, self.redraw_timer)
self.redraw_timer.Start(int(1000*self.state.tickresolution))
self.redraw_timer.Start(int(1000*self.refresh_dt))

self.last_yrange = (None, None)

def create_main_panel(self):
import platform
if platform.system() == 'Darwin':
from MAVProxy.modules.lib.MacOS import backend_wxagg
FigCanvas = backend_wxagg.FigureCanvasWxAgg
else:
from matplotlib.backends.backend_wxagg import FigureCanvasWxAgg as FigCanvas
self.panel = wx.Panel(self)

self.init_plot()
self.canvas = FigCanvas(self.panel, -1, self.fig)


self.close_button = wx.Button(self.panel, -1, "Close")
self.Bind(wx.EVT_BUTTON, self.on_close_button, self.close_button)

Expand Down Expand Up @@ -72,94 +68,88 @@ def create_main_panel(self):

def init_plot(self):
self.dpi = 100
from matplotlib.figure import Figure
self.fig = Figure((6.0, 3.0), dpi=self.dpi)

self.axes = self.fig.add_subplot(111)
try:
self.axes.set_facecolor('white')
except AttributeError as e:
# this was removed in matplotlib 2.2.0:
self.axes.set_axis_bgcolor('white')

self.axes.set_facecolor('white')

pylab.setp(self.axes.get_xticklabels(), fontsize=8)
pylab.setp(self.axes.get_yticklabels(), fontsize=8)

# create X data
self.max_points = int(self.state.timespan / self.sample_dt)
self.half_points = self.max_points // 2
self.write_idx = 0
self.xdata = numpy.arange(-self.state.timespan / 2, self.state.timespan / 2, self.sample_dt)[:self.max_points]
self.axes.set_xbound(lower=self.xdata[0], upper=self.xdata[-1])

self.ybuf = [numpy.full(self.max_points, numpy.nan) for _ in range(len(self.state.fields))]

# plot the data as a line series, and save the reference
# to the plotted line series
#
self.plot_data = []
if len(self.data[0]) == 0:
if len(self.ybuf[0]) == 0:
max_y = min_y = 0
else:
max_y = min_y = self.data[0][0]
max_y = min_y = self.ybuf[0][0]
num_labels = 0 if not self.state.labels else len(self.state.labels)
labels = []
for i in range(len(self.data)):
if i < num_labels and self.state.labels[i] is not None:
for i in range(len(self.ybuf)):
if i < num_labels and self.state.labels and self.state.labels[i] is not None:
label = self.state.labels[i]
else:
label = self.state.fields[i]
labels.append(label)
p = self.axes.plot(
self.data[i],
self.xdata, self.ybuf[i],
linewidth=1,
color=self.state.colors[i%len(self.state.colors)],
label=label
)[0]
self.plot_data.append(p)
if len(self.data[i]) != 0:
min_y = min(min_y, min(self.data[i]))
max_y = max(max_y, max(self.data[i]))
if len(self.ybuf[i]) != 0:
min_y = min(min_y, min(self.ybuf[i]))
max_y = max(max_y, max(self.ybuf[i]))

# create X data
self.xdata = numpy.arange(-self.state.timespan, 0, self.state.tickresolution)
self.axes.set_xbound(lower=self.xdata[0], upper=0)
if min_y == max_y:
self.axes.set_ybound(min_y, max_y+0.1)
self.axes.legend(labels, loc='upper left', bbox_to_anchor=(0, 1.1))

def draw_plot(self):
""" Redraws the plot
"""
state = self.state

if len(self.data[0]) == 0:
print("no data to plot")
# gather finite values to auto-scale Y
finite_vals = []
for arr in self.ybuf:
vals = arr[~numpy.isnan(arr)]
if vals.size:
finite_vals.append((vals.min(), vals.max()))
if not finite_vals:
# nothing to show yet
return
vhigh = max(self.data[0])
vlow = min(self.data[0])

for i in range(1,len(self.plot_data)):
vhigh = max(vhigh, max(self.data[i]))
vlow = min(vlow, min(self.data[i]))
ymin = vlow - 0.05*(vhigh-vlow)
ymax = vhigh + 0.05*(vhigh-vlow)

if ymin == ymax:
ymax = ymin + 0.1 * ymin
ymin = ymin - 0.1 * ymin

if (ymin, ymax) != self.last_yrange:
self.last_yrange = (ymin, ymax)

if ymax == ymin:
ymin = ymin-0.5
ymax = ymin+1
vlow = min(lo for lo, hi in finite_vals)
vhigh = max(hi for lo, hi in finite_vals)
if vlow == vhigh:
pad = 0.1 * (abs(vlow) if vlow != 0 else 1.0)
vlow -= pad
vhigh += pad
else:
pad = 0.05 * (vhigh - vlow)
vlow -= pad
vhigh += pad

self.axes.set_ybound(lower=ymin, upper=ymax)
#self.axes.ticklabel_format(useOffset=False, style='plain')
if (vlow, vhigh) != self.last_yrange:
self.last_yrange = (vlow, vhigh)
self.axes.set_ybound(lower=vlow, upper=vhigh)
self.axes.grid(True, color='gray')
pylab.setp(self.axes.get_xticklabels(), visible=True)
pylab.setp(self.axes.get_legend().get_texts(), fontsize='small')
leg = self.axes.get_legend()
if leg:
pylab.setp(leg.get_texts(), fontsize='small')

for i in range(len(self.plot_data)):
ydata = numpy.array(self.data[i])
xdata = self.xdata
if len(ydata) < len(self.xdata):
xdata = xdata[-len(ydata):]
self.plot_data[i].set_xdata(xdata)
self.plot_data[i].set_ydata(ydata)
# update lines in place
for i, line in enumerate(self.plot_data):
line.set_ydata(self.ybuf[i])

self.canvas.draw()
self.canvas.Refresh()
Expand All @@ -182,41 +172,61 @@ def on_close_button(self, event):
self.Destroy()

def on_idle(self, event):
time.sleep(self.state.tickresolution*0.5)
time.sleep(self.refresh_dt*0.5)

def on_redraw_timer(self, event):
# if paused do not add data, but still redraw the plot
# (to respond to scale modifications, grid change, etc.)
#
# print("redraw")
state = self.state
if state.close_graph.wait(0.001):
self.redraw_timer.Stop()
self.Destroy()
return

batch = []
while state.child_pipe.poll():
state.values = state.child_pipe.recv()
batch.append(state.child_pipe.recv())

if self.paused:
return

if self.clear_data:
self.clear_data = False
for i in range(len(self.ybuf)):
self.ybuf[i].fill(numpy.nan)
self.write_idx = 0

for msg in batch:
if msg is None:
print("msg is none")
continue

if self.write_idx >= self.max_points:
# shift the right half to the left half, clear the right half
for i in range(len(self.ybuf)):
self.ybuf[i][:self.half_points] = self.ybuf[i][self.half_points:]
self.ybuf[i][self.half_points:] = numpy.nan
self.write_idx = self.half_points

for i in range(len(self.plot_data)):
if state.values[i] is not None:
while len(self.data[i]):
self.data[i].pop(0)
val = msg[i] if i < len(msg) else None
if isinstance(val, list):
print("ERROR: Cannot plot array of length %d. Use 'graph %s[index]' instead"%(len(val), state.fields[i]))
self.redraw_timer.Stop()
self.Destroy()
return
if val is not None:
self.ybuf[i][self.write_idx] = val

# write once per message, not once per field
self.write_idx += 1

for i in range(len(self.plot_data)):
if (type(state.values[i]) == list):
print("ERROR: Cannot plot array of length %d. Use 'graph %s[index]' instead"%(len(state.values[i]), state.fields[i]))
self.redraw_timer.Stop()
self.Destroy()
return
if state.values[i] is not None:
self.data[i].append(state.values[i])
while len(self.data[i]) > len(self.xdata):
self.data[i].pop(0)

for i in range(len(self.plot_data)):
if state.values[i] is None or len(self.data[i]) < 2:
if len(self.ybuf[i]) < 2:
print("return from here")
return

self.draw_plot()
Loading