Commit 8b0fe775 authored by Gus Grubba's avatar Gus Grubba Committed by Lorenz Meier

WIP - First stab at charting

parent d48bf56d
...@@ -15,33 +15,67 @@ ...@@ -15,33 +15,67 @@
#include <QObject> #include <QObject>
#include <QString> #include <QString>
#include <QDebug> #include <QDebug>
#include <QAbstractListModel> #include <QVariantList>
#include <QtCharts/QAbstractSeries>
Q_DECLARE_LOGGING_CATEGORY(MAVLinkInspectorLog) Q_DECLARE_LOGGING_CATEGORY(MAVLinkInspectorLog)
QT_CHARTS_USE_NAMESPACE
class QGCMAVLinkMessage;
class MAVLinkInspectorController;
//----------------------------------------------------------------------------- //-----------------------------------------------------------------------------
class QGCMAVLinkMessageField : public QObject { class QGCMAVLinkMessageField : public QObject {
Q_OBJECT Q_OBJECT
Q_PROPERTY(QString name READ name CONSTANT) Q_PROPERTY(QString name READ name CONSTANT)
Q_PROPERTY(QString type READ type CONSTANT) Q_PROPERTY(QString type READ type CONSTANT)
Q_PROPERTY(QString value READ value NOTIFY valueChanged) Q_PROPERTY(QString value READ value NOTIFY valueChanged)
Q_PROPERTY(qreal rangeMin READ rangeMin NOTIFY rangeMinChanged)
Q_PROPERTY(qreal rangeMax READ rangeMax NOTIFY rangeMaxChanged)
Q_PROPERTY(bool selectable READ selectable NOTIFY selectableChanged)
Q_PROPERTY(bool selected READ selected WRITE setSelected NOTIFY selectedChanged)
public: public:
QGCMAVLinkMessageField(QObject* parent, QString name, QString type); QGCMAVLinkMessageField(QGCMAVLinkMessage* parent, QString name, QString type);
QString name () { return _name; } QString name () { return _name; }
QString type () { return _type; } QString type () { return _type; }
QString value () { return _value; } QString value () { return _value; }
qreal rangeMin () { return _rangeMin; }
qreal rangeMax () { return _rangeMax; }
QList<QPointF> series () { return _series; }
bool selectable () { return _selectable; }
bool selected () { return _selected; }
void updateValue (QString newValue) { _value = newValue; emit valueChanged(); } void setSelectable (bool sel);
void setSelected (bool sel);
void updateValue (QString newValue, qreal v);
signals: signals:
void rangeMinChanged ();
void rangeMaxChanged ();
void seriesChanged ();
void selectableChanged ();
void selectedChanged ();
void valueChanged (); void valueChanged ();
private:
void _updateSeries ();
private: private:
QString _type; QString _type;
QString _name; QString _name;
QString _value; QString _value;
QGCMAVLinkMessage* _msg = nullptr;
bool _selectable = true;
bool _selected = false;
int _dataIndex = 0;
qreal _rangeMin = 0;
qreal _rangeMax = 0;
QVector<qreal> _values;
QVector<quint64> _times;
QList<QPointF> _series;
}; };
//----------------------------------------------------------------------------- //-----------------------------------------------------------------------------
...@@ -53,9 +87,10 @@ class QGCMAVLinkMessage : public QObject { ...@@ -53,9 +87,10 @@ class QGCMAVLinkMessage : public QObject {
Q_PROPERTY(qreal messageHz READ messageHz NOTIFY freqChanged) Q_PROPERTY(qreal messageHz READ messageHz NOTIFY freqChanged)
Q_PROPERTY(quint64 count READ count NOTIFY messageChanged) Q_PROPERTY(quint64 count READ count NOTIFY messageChanged)
Q_PROPERTY(QmlObjectListModel* fields READ fields NOTIFY indexChanged) Q_PROPERTY(QmlObjectListModel* fields READ fields NOTIFY indexChanged)
Q_PROPERTY(bool selected READ selected NOTIFY selectedChanged)
public: public:
QGCMAVLinkMessage(QObject* parent, mavlink_message_t* message); QGCMAVLinkMessage(MAVLinkInspectorController* parent, mavlink_message_t* message);
quint32 id () { return _message.msgid; } quint32 id () { return _message.msgid; }
quint8 cid () { return _message.compid; } quint8 cid () { return _message.compid; }
...@@ -64,7 +99,11 @@ public: ...@@ -64,7 +99,11 @@ public:
quint64 count () { return _count; } quint64 count () { return _count; }
quint64 lastCount () { return _lastCount; } quint64 lastCount () { return _lastCount; }
QmlObjectListModel* fields () { return &_fields; } QmlObjectListModel* fields () { return &_fields; }
bool selected () { return _selected; }
MAVLinkInspectorController* msgCtl () { return _msgCtl; }
void select ();
void update (mavlink_message_t* message); void update (mavlink_message_t* message);
void updateFreq (); void updateFreq ();
...@@ -72,6 +111,7 @@ signals: ...@@ -72,6 +111,7 @@ signals:
void messageChanged (); void messageChanged ();
void freqChanged (); void freqChanged ();
void indexChanged (); void indexChanged ();
void selectedChanged ();
private: private:
QmlObjectListModel _fields; QmlObjectListModel _fields;
...@@ -80,6 +120,8 @@ private: ...@@ -80,6 +120,8 @@ private:
uint64_t _count = 0; uint64_t _count = 0;
uint64_t _lastCount = 0; uint64_t _lastCount = 0;
mavlink_message_t _message; //-- List of QGCMAVLinkMessageField mavlink_message_t _message; //-- List of QGCMAVLinkMessageField
MAVLinkInspectorController* _msgCtl = nullptr;
bool _selected = false;
}; };
//----------------------------------------------------------------------------- //-----------------------------------------------------------------------------
...@@ -126,14 +168,36 @@ public: ...@@ -126,14 +168,36 @@ public:
Q_PROPERTY(QStringList vehicleNames READ vehicleNames NOTIFY vehiclesChanged) Q_PROPERTY(QStringList vehicleNames READ vehicleNames NOTIFY vehiclesChanged)
Q_PROPERTY(QmlObjectListModel* vehicles READ vehicles NOTIFY vehiclesChanged) Q_PROPERTY(QmlObjectListModel* vehicles READ vehicles NOTIFY vehiclesChanged)
Q_PROPERTY(QGCMAVLinkVehicle* activeVehicle READ activeVehicle NOTIFY activeVehiclesChanged) Q_PROPERTY(QGCMAVLinkVehicle* activeVehicle READ activeVehicle NOTIFY activeVehiclesChanged)
Q_PROPERTY(int chartFieldCount READ chartFieldCount NOTIFY chartFieldCountChanged)
Q_PROPERTY(QVariantList chartFields READ chartFields NOTIFY chartFieldCountChanged)
Q_PROPERTY(QDateTime rangeXMin READ rangeXMin NOTIFY rangeMinXChanged)
Q_PROPERTY(QDateTime rangeXMax READ rangeXMax NOTIFY rangeMaxXChanged)
Q_PROPERTY(quint32 timeScale READ timeScale WRITE setTimeScale NOTIFY timeScaleChanged)
Q_INVOKABLE void updateSeries (int index, QAbstractSeries *series);
QmlObjectListModel* vehicles () { return &_vehicles; } QmlObjectListModel* vehicles () { return &_vehicles; }
QGCMAVLinkVehicle* activeVehicle () { return _activeVehicle; } QGCMAVLinkVehicle* activeVehicle () { return _activeVehicle; }
QStringList vehicleNames () { return _vehicleNames; } QStringList vehicleNames () { return _vehicleNames; }
quint32 timeScale () { return _timeScale; }
QVariantList chartFields () { return _chartFields; }
QDateTime rangeXMin () { return _rangeXMin; }
QDateTime rangeXMax () { return _rangeXMax; }
void setTimeScale (quint32 t) { _timeScale = t; emit timeScaleChanged(); }
int chartFieldCount () { return _chartFields.count(); }
void addChartField (QGCMAVLinkMessageField* field);
void delChartField (QGCMAVLinkMessageField* field);
void updateXRange ();
signals: signals:
void vehiclesChanged (); void vehiclesChanged ();
void activeVehiclesChanged (); void activeVehiclesChanged ();
void chartFieldCountChanged ();
void timeScaleChanged ();
void rangeMinXChanged ();
void rangeMaxXChanged ();
private slots: private slots:
void _receiveMessage (LinkInterface* link, mavlink_message_t message); void _receiveMessage (LinkInterface* link, mavlink_message_t message);
...@@ -150,9 +214,13 @@ private: ...@@ -150,9 +214,13 @@ private:
private: private:
int _selectedSystemID = 0; ///< Currently selected system int _selectedSystemID = 0; ///< Currently selected system
int _selectedComponentID = 0; ///< Currently selected component int _selectedComponentID = 0; ///< Currently selected component
quint32 _timeScale = 10; ///< 10 Seconds
QDateTime _rangeXMin;
QDateTime _rangeXMax;
QGCMAVLinkVehicle* _activeVehicle = nullptr; QGCMAVLinkVehicle* _activeVehicle = nullptr;
QTimer _updateTimer; QTimer _updateTimer;
QStringList _vehicleNames; QStringList _vehicleNames;
QmlObjectListModel _vehicles; //-- List of QGCMAVLinkVehicle QmlObjectListModel _vehicles; //-- List of QGCMAVLinkVehicle
QVariantList _chartFields;
}; };
...@@ -11,6 +11,8 @@ import QtQuick 2.11 ...@@ -11,6 +11,8 @@ import QtQuick 2.11
import QtQuick.Controls 2.4 import QtQuick.Controls 2.4
import QtQuick.Layouts 1.11 import QtQuick.Layouts 1.11
import QtQuick.Dialogs 1.3 import QtQuick.Dialogs 1.3
import QtQuick.Window 2.2
import QtCharts 2.1
import QGroundControl 1.0 import QGroundControl 1.0
import QGroundControl.Palette 1.0 import QGroundControl.Palette 1.0
...@@ -33,6 +35,79 @@ AnalyzePage { ...@@ -33,6 +35,79 @@ AnalyzePage {
id: controller id: controller
} }
Window {
id: chartWindow
width: mainWindow.width * 0.5
height: mainWindow.height * 0.5
visible: true
title: "Chart"
Rectangle {
color: qgcPal.window
anchors.fill: parent
ChartView {
id: chartView
anchors.fill: parent
theme: ChartView.ChartThemeDark
antialiasing: true
animationOptions: ChartView.NoAnimation
ValueAxis {
id: axisY1
min: visible ? controller.chartFields[0].rangeMin : 0
max: visible ? controller.chartFields[0].rangeMax : 0
visible: controller.chartFieldCount > 0
}
ValueAxis {
id: axisY2
min: visible ? controller.chartFields[1].rangeMin : 0
max: visible ? controller.chartFields[1].rangeMax : 0
visible: controller.chartFieldCount > 1
}
DateTimeAxis {
id: axisX
min: visible ? controller.rangeXMin : new Date()
max: visible ? controller.rangeXMax : new Date()
format: "hh:mm:ss.zzz"
tickCount: 6
visible: controller.chartFieldCount > 0
}
LineSeries {
id: lineSeries1
name: controller.chartFieldCount ? controller.chartFields[0].name : ""
axisX: axisX
axisY: axisY1
useOpenGL: true
}
LineSeries {
id: lineSeries2
name: controller.chartFieldCount > 1 ? controller.chartFields[1].name : ""
axisX: axisX
axisYRight: axisY2
useOpenGL: true
}
}
Timer {
id: refreshTimer
interval: 1 / 30 * 1000 // 30 Hz
running: controller.chartFieldCount > 0
repeat: true
onTriggered: {
if(controller.chartFieldCount > 0) {
controller.updateSeries(0, lineSeries1)
}
if(controller.chartFieldCount > 1) {
controller.updateSeries(1, lineSeries2)
}
}
}
}
}
Component { Component {
id: headerComponent id: headerComponent
//-- Header //-- Header
...@@ -73,6 +148,7 @@ AnalyzePage { ...@@ -73,6 +148,7 @@ AnalyzePage {
RowLayout { RowLayout {
width: availableWidth width: availableWidth
height: availableHeight height: availableHeight
spacing: ScreenTools.defaultFontPixelWidth
//-- Messages (Buttons) //-- Messages (Buttons)
QGCFlickable { QGCFlickable {
id: buttonGrid id: buttonGrid
...@@ -90,7 +166,7 @@ AnalyzePage { ...@@ -90,7 +166,7 @@ AnalyzePage {
Repeater { Repeater {
model: curVehicle ? curVehicle.messages : [] model: curVehicle ? curVehicle.messages : []
delegate: MAVLinkMessageButton { delegate: MAVLinkMessageButton {
text: object.name text: object.name + (object.selected ? " *" : "")
compID: object.cid compID: object.cid
checked: curMessageIndex === index checked: curMessageIndex === index
messageHz: object.messageHz messageHz: object.messageHz
...@@ -151,7 +227,7 @@ AnalyzePage { ...@@ -151,7 +227,7 @@ AnalyzePage {
} }
Item { height: ScreenTools.defaultFontPixelHeight * 0.25; width: 1 } Item { height: ScreenTools.defaultFontPixelHeight * 0.25; width: 1 }
GridLayout { GridLayout {
columns: 3 columns: 4
columnSpacing: ScreenTools.defaultFontPixelWidth columnSpacing: ScreenTools.defaultFontPixelWidth
rowSpacing: ScreenTools.defaultFontPixelHeight * 0.25 rowSpacing: ScreenTools.defaultFontPixelHeight * 0.25
Repeater { Repeater {
...@@ -182,6 +258,16 @@ AnalyzePage { ...@@ -182,6 +258,16 @@ AnalyzePage {
text: object.type text: object.type
} }
} }
Repeater {
model: curMessage ? curMessage.fields : []
delegate: QGCCheckBox {
Layout.row: index
Layout.column: 3
enabled: object.selected || (object.selectable && controller.chartFieldCount < 2)
checked: enabled ? object.selected : false
onClicked: { if(enabled) object.selected = checked }
}
}
} }
} }
} }
......
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment