Commit 6c4f6de7 authored by Gus Grubba's avatar Gus Grubba Committed by Lorenz Meier

Make the chart a control

parent 78620bd1
......@@ -89,6 +89,7 @@
<file alias="QGroundControl/Controls/KMLOrSHPFileDialog.qml">src/QmlControls/KMLOrSHPFileDialog.qml</file>
<file alias="QGroundControl/Controls/LogReplayStatusBar.qml">src/QmlControls/LogReplayStatusBar.qml</file>
<file alias="QGroundControl/Controls/MainWindowSavedState.qml">src/QmlControls/MainWindowSavedState.qml</file>
<file alias="QGroundControl/Controls/MAVLinkChart.qml">src/QmlControls/MAVLinkChart.qml</file>
<file alias="QGroundControl/Controls/MAVLinkMessageButton.qml">src/QmlControls/MAVLinkMessageButton.qml</file>
<file alias="QGroundControl/Controls/MissionCommandDialog.qml">src/QmlControls/MissionCommandDialog.qml</file>
<file alias="QGroundControl/Controls/MissionItemEditor.qml">src/PlanView/MissionItemEditor.qml</file>
......
......@@ -18,6 +18,8 @@ QT_CHARTS_USE_NAMESPACE
Q_DECLARE_METATYPE(QAbstractSeries*)
#define UPDATE_FREQUENCY (1000 / 15) // 15Hz
//-----------------------------------------------------------------------------
QGCMAVLinkMessageField::QGCMAVLinkMessageField(QGCMAVLinkMessage *parent, QString name, QString type)
: QObject(parent)
......@@ -118,19 +120,25 @@ QGCMAVLinkMessageField::updateValue(QString newValue, qreal v)
_msg->msgCtl()->updateYRange(_left);
}
}
_msg->msgCtl()->updateXRange();
_updateSeries();
}
}
//-----------------------------------------------------------------------------
void
QGCMAVLinkMessageField::_updateSeries()
QGCMAVLinkMessageField::updateSeries()
{
int count = _values.count();
if (count > 1) {
QList<QPointF> s;
s.reserve(count);
int idx = _dataIndex;
for(int i = 0; i < count; i++, idx++) {
if(idx >= count) idx = 0;
QPointF p(_values[idx]);
s.append(p);
}
QLineSeries* lineSeries = static_cast<QLineSeries*>(_pSeries);
lineSeries->replace(_values);
lineSeries->replace(s);
}
}
......@@ -512,8 +520,10 @@ MAVLinkInspectorController::MAVLinkInspectorController()
connect(multiVehicleManager, &MultiVehicleManager::vehicleRemoved, this, &MAVLinkInspectorController::_vehicleRemoved);
MAVLinkProtocol* mavlinkProtocol = qgcApp()->toolbox()->mavlinkProtocol();
connect(mavlinkProtocol, &MAVLinkProtocol::messageReceived, this, &MAVLinkInspectorController::_receiveMessage);
connect(&_updateTimer, &QTimer::timeout, this, &MAVLinkInspectorController::_refreshFrequency);
_updateTimer.start(1000);
connect(&_updateFrequencyTimer, &QTimer::timeout, this, &MAVLinkInspectorController::_refreshFrequency);
connect(&_updateSeriesTimer, &QTimer::timeout, this, &MAVLinkInspectorController::_refreshSeries);
_updateFrequencyTimer.start(1000);
_updateSeriesTimer.start(UPDATE_FREQUENCY);
MultiVehicleManager *manager = qgcApp()->toolbox()->multiVehicleManager();
connect(manager, &MultiVehicleManager::activeVehicleChanged, this, &MAVLinkInspectorController::_setActiveVehicle);
_timeScaleSt.append(new TimeScale_st(this, tr("5 Sec"), 5 * 1000));
......@@ -570,13 +580,13 @@ MAVLinkInspectorController::setLeftRangeIdx(quint32 r)
{
if(r < static_cast<quint32>(_rangeSt.count())) {
_leftRangeIndex = r;
_timeRange = _rangeSt[static_cast<int>(r)]->range;
qreal range = _rangeSt[static_cast<int>(r)]->range;
emit leftRangeChanged();
//-- If not Auto, use defined range
if(_leftRangeIndex > 0) {
_leftRangeMin = -_timeRange;
_leftRangeMin = -range;
emit leftRangeMinChanged();
_leftRangeMax = _timeRange;
_leftRangeMax = range;
emit leftRangeMaxChanged();
}
}
......@@ -588,13 +598,13 @@ MAVLinkInspectorController::setRightRangeIdx(quint32 r)
{
if(r < static_cast<quint32>(_rangeSt.count())) {
_rightRangeIndex = r;
_timeRange = _rangeSt[static_cast<int>(r)]->range;
qreal range = _rangeSt[static_cast<int>(r)]->range;
emit rightRangeChanged();
//-- If not Auto, use defined range
if(_rightRangeIndex > 0) {
_rightRangeMin = -_timeRange;
_rightRangeMin = -range;
emit rightRangeMinChanged();
_rightRangeMax = _timeRange;
_rightRangeMax = range;
emit rightRangeMaxChanged();
}
}
......@@ -826,6 +836,7 @@ MAVLinkInspectorController::addSeries(QGCMAVLinkMessageField* field, QAbstractSe
{
if(field) {
field->addSeries(series, left);
_updateSeriesTimer.start(UPDATE_FREQUENCY);
}
}
......@@ -836,19 +847,29 @@ MAVLinkInspectorController::delSeries(QGCMAVLinkMessageField* field)
if(field) {
field->delSeries();
}
if(_leftChartFields.count() == 0) {
_leftRangeMin = 0;
_leftRangeMax = 1;
emit leftRangeMinChanged();
emit leftRangeMaxChanged();
}
if(_rightChartFields.count() == 0) {
_rightRangeMin = 0;
_rightRangeMax = 1;
emit rightRangeMinChanged();
emit rightRangeMaxChanged();
}
if(_leftChartFields.count() == 0 && _rightChartFields.count() == 0) {
updateXRange();
_updateSeriesTimer.stop();
}
}
//-----------------------------------------------------------------------------
void
MAVLinkInspectorController::_refreshSeries()
{
updateXRange();
for(int i = 0; i < _leftChartFields.count(); i++) {
QObject* object = qvariant_cast<QObject*>(_leftChartFields.at(i));
QGCMAVLinkMessageField* pField = qobject_cast<QGCMAVLinkMessageField*>(object);
if(pField) {
pField->updateSeries();
}
}
for(int i = 0; i < _rightChartFields.count(); i++) {
QObject* object = qvariant_cast<QObject*>(_rightChartFields.at(i));
QGCMAVLinkMessageField* pField = qobject_cast<QGCMAVLinkMessageField*>(object);
if(pField) {
pField->updateSeries();
}
}
}
......@@ -56,6 +56,7 @@ public:
void addSeries (QAbstractSeries* series, bool left);
void delSeries ();
void updateSeries ();
signals:
void seriesChanged ();
......@@ -63,10 +64,6 @@ signals:
void valueChanged ();
private:
void _updateSeries ();
private:
QString _type;
QString _name;
QString _value;
......@@ -242,6 +239,7 @@ private slots:
void _vehicleRemoved (Vehicle* vehicle);
void _setActiveVehicle (Vehicle* vehicle);
void _refreshFrequency ();
void _refreshSeries ();
private:
QGCMAVLinkVehicle* _findVehicle (uint8_t id);
......@@ -275,9 +273,9 @@ private:
qreal _rightRangeMin = 0;
qreal _rightRangeMax = 1;
quint32 _rightRangeIndex = 0; ///> Auto Range
qreal _timeRange = 0;
QGCMAVLinkVehicle* _activeVehicle = nullptr;
QTimer _updateTimer;
QTimer _updateFrequencyTimer;
QTimer _updateSeriesTimer;
QStringList _vehicleNames;
QmlObjectListModel _vehicles; ///< List of QGCMAVLinkVehicle
QVariantList _rightChartFields;
......
This diff is collapsed.
import QtQuick 2.11
import QtQuick.Controls 2.4
import QtQuick.Layouts 1.11
import QtCharts 2.3
import QGroundControl 1.0
import QGroundControl.Palette 1.0
import QGroundControl.Controls 1.0
import QGroundControl.Controllers 1.0
import QGroundControl.ScreenTools 1.0
ChartView {
id: chartView
theme: ChartView.ChartThemeDark
antialiasing: true
animationOptions: ChartView.NoAnimation
legend.visible: false
backgroundColor: qgcPal.window
backgroundRoundness: 0
margins.bottom: ScreenTools.defaultFontPixelHeight * 1.5
margins.top: chartHeader.height + (ScreenTools.defaultFontPixelHeight * 2)
property int maxSeriesCount: seriesColors.length
property var seriesColors: ["chartreuse", "chocolate", "yellowgreen", "thistle", "silver", "darkturquoise", "blue", "green"]
property alias max: axisY.max
property alias min: axisY.min
function addDimension(field, left) {
console.log(field.name + ' AxisY: ' + axisY)
console.log(chartView.count + ' ' + chartView.seriesColors[chartView.count])
var serie = createSeries(ChartView.SeriesTypeLine, field.label)
serie.axisX = axisX
serie.axisY = axisY
serie.useOpenGL = true
serie.color = chartView.seriesColors[chartView.count]
serie.width = 1
controller.addSeries(field, serie, left)
}
function delDimension(field) {
chartView.removeSeries(field.series)
controller.delSeries(field)
console.log('Remove: ' + chartView.count + ' ' + field.name)
}
DateTimeAxis {
id: axisX
min: controller.rangeXMin
max: controller.rangeXMax
format: "mm:ss.zzz"
tickCount: 5
gridVisible: true
labelsFont.family: "Fixed"
labelsFont.pixelSize: ScreenTools.smallFontPointSize
}
ValueAxis {
id: axisY
lineVisible: false
labelsFont.family: "Fixed"
labelsFont.pixelSize: ScreenTools.smallFontPointSize
}
RowLayout {
id: chartHeader
anchors.left: parent.left
anchors.leftMargin: ScreenTools.defaultFontPixelWidth * 4
anchors.right: parent.right
anchors.rightMargin: ScreenTools.defaultFontPixelWidth * 4
anchors.top: parent.top
anchors.topMargin: ScreenTools.defaultFontPixelHeight * 1.5
spacing: 0
QGCLabel {
text: qsTr("Scale:");
font.pixelSize: ScreenTools.smallFontPointSize
Layout.alignment: Qt.AlignVCenter
}
QGCComboBox {
id: timeScaleSelector
width: ScreenTools.defaultFontPixelWidth * 10
height: ScreenTools.defaultFontPixelHeight
model: controller.timeScales
currentIndex: controller.timeScale
onActivated: controller.timeScale = index
font.pixelSize: ScreenTools.smallFontPointSize
Layout.alignment: Qt.AlignVCenter
}
GridLayout {
columns: 2
columnSpacing: ScreenTools.defaultFontPixelWidth
rowSpacing: ScreenTools.defaultFontPixelHeight * 0.25
Layout.alignment: Qt.AlignRight | Qt.AlignVCenter
Layout.fillWidth: true
QGCLabel {
text: qsTr("Range Left:");
font.pixelSize: ScreenTools.smallFontPointSize
Layout.alignment: Qt.AlignVCenter
}
QGCComboBox {
Layout.minimumWidth: ScreenTools.defaultFontPixelWidth * 8
height: ScreenTools.defaultFontPixelHeight * 1.5
model: controller.rangeList
currentIndex: controller.leftRangeIdx
onActivated: controller.leftRangeIdx = index
font.pixelSize: ScreenTools.smallFontPointSize
Layout.alignment: Qt.AlignVCenter
}
QGCLabel {
text: qsTr("Range Right:");
font.pixelSize: ScreenTools.smallFontPointSize
Layout.alignment: Qt.AlignVCenter
}
QGCComboBox {
Layout.minimumWidth: ScreenTools.defaultFontPixelWidth * 8
height: ScreenTools.defaultFontPixelHeight * 1.5
model: controller.rangeList
currentIndex: controller.rightRangeIdx
onActivated: controller.rightRangeIdx = index
font.pixelSize: ScreenTools.smallFontPointSize
Layout.alignment: Qt.AlignVCenter
}
}
}
}
......@@ -93,3 +93,4 @@ VehicleRotationCal 1.0 VehicleRotationCal.qml
VehicleSummaryRow 1.0 VehicleSummaryRow.qml
ViewWidget 1.0 ViewWidget.qml
QGCHoverButton 1.0 QGCHoverButton.qml
MAVLinkChart 1.0 MAVLinkChart.qml
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