forked from fschill/mavue
-
Notifications
You must be signed in to change notification settings - Fork 0
/
mavue.py
executable file
·330 lines (255 loc) · 12.3 KB
/
mavue.py
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
'''
MAVUE v0.1 (beta)
Graphical inspector for MAVLink enabled embedded systems.
Copyright (c) 2009-2014, Felix Schill
All rights reserved.
Refer to the file LICENSE.TXT which should be included in all distributions of this project.
mavue.py
This is the main file.
Usage: mavue.py [options]
Options:
-h, --help show this help message and exit
--baudrate=BAUDRATE master port baud rate
--device=DEVICE serial device
--dialect=DIALECT Mavlink dialect
--logfile=LOGFILE_RAW
output log file
--notimestamps=NOTIMESTAMPS
logfile format
--source-system=SOURCE_SYSTEM
MAVLink source system for this GCS
After startup, the message inspector window will show a tree of all received messages.
To plot values, click "add plot" and drag and drop message contents onto the plot window, or onto the "x" or "y" button of an existing plot item.
Message streams can be activated/deactivated by clicking the checkbox in front of them.
Double-clicking the frequency allows to edit the message stream frequency (only supported on the MAVRIC autopilot).
MAVlink parameters can be edited by double-clicking on the value behind the parameter message.
'''
#!/usr/bin/python
#from PyQt4 import QtCore, QtGui
from pyqtgraph.Qt import QtGui, QtCore
import numpy as np
import pyqtgraph as pg
import sys
import mavlink_receiver
import threading
import pickle
import time
import plugins as plugins
import gui_elements
import plugins.robotvis
import plugins.spectrogram
import plugins.flowchart
colors=[[1.0, 0.0, 0.0], [0.0, 1.0, 0.0], [0.0, 0.0, 1.0], [1.0, 1.0, 0.0], [0.0, 1.0, 1.0], [1.0, 0.0, 1.0]]
from plot_widget import *
from message_viewer import *
import bootloader
# define sorting order of MAVlink attributes (this controls the subtree structure of the message viewer).
key_attribute_list=('_header.srcSystem', '_header.srcComponent', 'name', 'param_id', 'stream_id', 'port', 'command')
class Update_Thread():
def __init__(self, parent, treeViewInstance):
self._treeViewInstance= treeViewInstance
self.mavlinkReceiver=mavlink_receiver.MAVlinkReceiver(threading=False)
self._parent = parent
self.running=True
self.lastTreeUpdate=time.time()
self.treeUpdateFrequency=5.0
self.t = QtCore.QTimer()
self.t.timeout.connect(self.update)
self.t.start(5)
self.mainDataRange=[-200, 0]
self.plugin_manager=plugins.plugin_manager(self.plugin_callback, self.mainDataRange)
self.timelinePlot = None
def plugin_callback(self, msg):
if msg!=None:
self._treeViewInstance.rootNode.updateContent(key_attribute_list, content=msg)
def update(self):
start_time = time.time()
for i in range(0,1000):
if time.time()-start_time>0.05:
#print "timeout!", i
break
if self.mavlinkReceiver.messagesAvailable():
msg_key=""
if self.mavlinkReceiver.threading:
try:
msg_key, msg=self.mavlinkReceiver.wait_message()
except:
print "error in wait_message"
else:
msg_key, msg=self.mavlinkReceiver.wait_message()
if msg_key!='':
#print "received message:", msg_key
#print "updating tree: ",msg_key
msgNode=self._treeViewInstance.rootNode.updateContent(key_attribute_list , content=msg)
if msgNode!=None:
if msg_key.__contains__('MAVLink_heartbeat_message'):
if self.timelinePlot is None:
self.timelinePlot = MainWindow.addTimeline(self._parent)
self.timelinePlot.widget.addSource(sourceY=msgNode.getValueByName("base_mode"))
self.timelinePlot.widget.addSource(sourceY=msgNode.getValueByName("system_status"))
#call plugins
self.plugin_manager.run_plugins(msgNode)
else:
break
#self._treeViewInstance.treeView.update()
if time.time()>self.lastTreeUpdate+1.0/(self.treeUpdateFrequency):
self._treeViewInstance.model.layoutChanged.emit()
self._treeViewInstance.rootNode.notifySubscribers()
self.lastTreeUpdate=time.time()
def reloadPlugins(self):
global plugins
reload(plugins)
import plugins
self.plugin_manager=plugins.plugin_manager(self.plugin_callback)
def stop(self):
self.t.stop()
self.mavlinkReceiver.close()
def reopen(self, device):
self.stop()
self.mavlinkReceiver.reopenDevice(device)
self.t.start()
class MainWindow(QtGui.QMainWindow):
def __init__(self):
QtGui.QMainWindow.__init__(self)
self.messageTreeView=MessageTreeView()
self.updater=Update_Thread(self, self.messageTreeView)
self.serialPorts= self.updater.mavlinkReceiver.scanForSerials()
print self.serialPorts
self.setWindowTitle('MavLink viewer')
self.resize(500,900)
cw = QtGui.QWidget()
self.setCentralWidget(cw)
self.l = QtGui.QGridLayout()
self.setCentralWidget(cw)
cw.setLayout(self.l)
self.menubar=QtGui.QWidget()
self.menubarLayout=QtGui.QHBoxLayout()
self.menubar.setLayout(self.menubarLayout)
self.widgetbar=QtGui.QWidget()
self.widgetbarLayout=QtGui.QHBoxLayout()
self.widgetbar.setLayout(self.widgetbarLayout)
self.serialSelect=gui_elements.PlainComboField(parent=self, label='Serial port', choices=['...','udp:localhost:14550']+[s.device for s in self.serialPorts], value=self.updater.mavlinkReceiver.opts.device, onOpenCallback = self.rescanForSerials)
self.connect(self.serialSelect, QtCore.SIGNAL("currentIndexChanged(const QString&)"), self.openConnection)
self.baudSelect=gui_elements.PlainComboField(parent=self, label='Baudrate', choices=[9600, 19200, 38400, 57600, 115200, 512000], value=self.updater.mavlinkReceiver.opts.baudrate)
self.connect(self.baudSelect, QtCore.SIGNAL("currentIndexChanged(const QString&)"), self.changeBaudrate)
self.menubarLayout.addWidget(self.serialSelect)
self.menubarLayout.addWidget(self.baudSelect)
self.refreshButton=QtGui.QPushButton("refresh")
self.menubarLayout.addWidget(self.refreshButton)
self.connect(self.refreshButton, QtCore.SIGNAL("clicked()"), self.updater.mavlinkReceiver.requestAllStreams)
#self.reloadPluginsButton=QtGui.QPushButton("reload plugins")
#self.menubarLayout.addWidget(self.reloadPluginsButton)
#self.connect(self.reloadPluginsButton, QtCore.SIGNAL("clicked()"), self.updater.reloadPlugins)
self.armButton=QtGui.QPushButton("Arm")
self.menubarLayout.addWidget(self.armButton)
self.connect(self.armButton, QtCore.SIGNAL("clicked()"), self.updater.mavlinkReceiver.sendArmCommand)
self.standbyButton=QtGui.QPushButton("Standby")
self.menubarLayout.addWidget(self.standbyButton)
self.connect(self.standbyButton, QtCore.SIGNAL("clicked()"), self.updater.mavlinkReceiver.sendStandbyCommand)
self.bootloaderButton=QtGui.QPushButton("Bootloader")
self.menubarLayout.addWidget(self.bootloaderButton)
self.connect(self.bootloaderButton, QtCore.SIGNAL("clicked()"), self.openBootloader)
self.l.addWidget(self.menubar, 0, 0)
self.l.addWidget(self.messageTreeView.treeView, 1, 0)
self.l.addWidget(self.widgetbar)
self.add2DButton=QtGui.QPushButton("2D plot")
self.connect(self.add2DButton, QtCore.SIGNAL("clicked()"), self.addPlot)
#self.add3DButton=QtGui.QPushButton("3D plot")
#self.connect(self.add3DButton, QtCore.SIGNAL("clicked()"), self.addPlot6D)
#self.add3DButton=QtGui.QPushButton("flowchart")
#self.connect(self.add3DButton, QtCore.SIGNAL("clicked()"), self.addFlowchart)
self.addSpecButton=QtGui.QPushButton("Spectrum")
self.connect(self.addSpecButton, QtCore.SIGNAL("clicked()"), self.addSpectrogram)
self.widgetbarLayout.addWidget(self.add2DButton)
#self.widgetbarLayout.addWidget(self.add3DButton)
self.widgetbarLayout.addWidget(self.addSpecButton)
self.addParamButton=QtGui.QPushButton("param-slider")
self.connect(self.addParamButton, QtCore.SIGNAL("clicked()"), self.addParamSlider)
self.widgetbarLayout.addWidget(self.addParamButton)
self.addTimelineButton=QtGui.QPushButton("timeline")
self.connect(self.addTimelineButton, QtCore.SIGNAL("clicked()"), self.addTimeline)
self.widgetbarLayout.addWidget(self.addTimelineButton)
#self.addPlot()
#self.addPlot()
self.show()
def rescanForSerials(self):
self.serialPorts= self.updater.mavlinkReceiver.scanForSerials()
print self.serialPorts
self.serialSelect.updateChoices(['...','udp:localhost:14550']+[s.device for s in self.serialPorts])
def addPlot(self):
pw1 = DropPlot(parent=self, data_range=self.updater.mainDataRange)
#self.l.addWidget(pw1, 0, 1)
dock1=DockPlot(title="2D Plot", parent=self, widget=pw1)
#self.addDockWidget(QtCore.Qt.NoDockWidgetArea, dock1)
dock1.show()
return dock1
def addSpectrogram(self):
pw1 = plugins.spectrogram.SpectrogramPlot(parent=self, data_range=self.updater.mainDataRange)
dock1=DockPlot(title="Spectrogram", parent=self, widget=pw1)
dock1.show()
return dock1
def addFlowchart(self):
pw1 = plugins.flowchart.FlowchartWidget(parent=self, data_range=self.updater.mainDataRange)
dock1=DockPlot(title="Spectrogram", parent=self, widget=pw1)
dock1.show()
return dock1
def addPlot6D(self):
pw1 = plugins.robotvis.DropPlot6D(parent=self, data_range=self.updater.mainDataRange)
#self.l.addWidget(pw1, 0, 1)
dock1=DockPlot(title="3D Plot", parent=self, widget=pw1)
#self.addDockWidget(QtCore.Qt.NoDockWidgetArea, dock1)
dock1.show()
return dock1
def addTimeline(self):
pw1 = TimeLinePlot(parent=self, dataRange=self.updater.mainDataRange)
dock1=DockPlot(title="Timeline", parent=self, widget=pw1)
dock1.show()
return dock1
def addParamSlider(self):
#self.l.addWidget(pw1, 0, 1)
slider=ParamSlider(title="Slider", parent=self)
slider.show()
def openBootloader(self):
self.bootloaderWindow=bootloader.Bootloader(self, self.updater.mavlinkReceiver)
self.updater.plugin_manager.active_plugins.append(self.bootloaderWindow)
self.bootloaderWindow.show()
def openConnection(self, index):
if index=="...":
filename=QtGui.QFileDialog.getOpenFileName(self, 'Open file', '', "MAVlink (*.mav);; RAW log (*.raw)")
if filename!=None:
index=filename
else:
return
try:
self.updater.stop
print "closed previous connection"
except:
print "no connection to close."
print "opening connection"
print index
self.updater.mavlinkReceiver.reopenDevice(str(index))
def changeBaudrate(self, baudrate):
print "changing baudrate to ", baudrate
self.updater.mavlinkReceiver.reopenDevice(baudrate=baudrate)
def closeEvent(self, event):
mw.updater.t.stop()
mw.messageTreeView.close()
try:
self.updater.mavlinkReceiver.master.close()
print "closed connection"
except:
print "no connection to close."
self.deleteLater()
print "shutting down."
sys.exit(0)
if __name__ == '__main__':
app = QtGui.QApplication(sys.argv)
print "creating main window"
mw = MainWindow()
print "starting app"
app.exec_()
print "shutting down"
mw.updater.t.stop()
print "updater stopped"
mw.messageTreeView.close()
print "tree closed"