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

WIP - First stab at charting

parent d48bf56d
......@@ -10,21 +10,118 @@
#include "MAVLinkInspectorController.h"
#include "QGCApplication.h"
#include "MultiVehicleManager.h"
#include <QtCharts/QLineSeries>
QGC_LOGGING_CATEGORY(MAVLinkInspectorLog, "MAVLinkInspectorLog")
QT_CHARTS_USE_NAMESPACE
Q_DECLARE_METATYPE(QAbstractSeries*)
//-----------------------------------------------------------------------------
QGCMAVLinkMessageField::QGCMAVLinkMessageField(QObject* parent, QString name, QString type)
QGCMAVLinkMessageField::QGCMAVLinkMessageField(QGCMAVLinkMessage *parent, QString name, QString type)
: QObject(parent)
, _type(type)
, _name(name)
, _msg(parent)
{
qCDebug(MAVLinkInspectorLog) << "Field:" << name << type;
}
//-----------------------------------------------------------------------------
QGCMAVLinkMessage::QGCMAVLinkMessage(QObject* parent, mavlink_message_t* message)
void
QGCMAVLinkMessageField::setSelectable(bool sel)
{
if(_selectable != sel) {
_selectable = sel;
emit selectableChanged();
}
}
//-----------------------------------------------------------------------------
void
QGCMAVLinkMessageField::setSelected(bool sel)
{
if(_selected != sel) {
_selected = sel;
emit selectedChanged();
_values.clear();
_times.clear();
_rangeMin = 0;
_rangeMax = 0;
_dataIndex = 0;
emit rangeMinChanged();
emit rangeMaxChanged();
if(_selected) {
_msg->msgCtl()->addChartField(this);
} else {
_msg->msgCtl()->delChartField(this);
}
_msg->select();
}
}
//-----------------------------------------------------------------------------
void
QGCMAVLinkMessageField::updateValue(QString newValue, qreal v)
{
if(_value != newValue) {
_value = newValue;
emit valueChanged();
}
if(_selected) {
int count = _values.count();
//-- Arbitrary limit of 1 minute of data at 50Hz for now
if(count < (50 * 60)) {
_values.append(v);
_times.append(QGC::groundTimeMilliseconds());
} else {
if(_dataIndex >= count) _dataIndex = 0;
_values[_dataIndex] = v;
_times[_dataIndex] = QGC::groundTimeMilliseconds();
_dataIndex++;
}
qreal vmin = std::numeric_limits<qreal>::max();
qreal vmax = std::numeric_limits<qreal>::min();
for(int i = 0; i < _values.count(); i++) {
qreal v = _values[i];
if(vmax < v) vmax = v;
if(vmin > v) vmin = v;
}
if(std::abs(_rangeMin - vmin) > 0.000001) {
_rangeMin = vmin;
emit rangeMinChanged();
}
if(std::abs(_rangeMax - vmax) > 0.000001) {
_rangeMax = vmax;
emit rangeMaxChanged();
}
_msg->msgCtl()->updateXRange();
_updateSeries();
}
}
//-----------------------------------------------------------------------------
void
QGCMAVLinkMessageField::_updateSeries()
{
int count = _values.count();
if (count > 1) {
_series.clear();
int idx = _dataIndex;
for(int i = 0; i < count; i++, idx++) {
if(idx >= count) idx = 0;
QPointF p(_times[idx], _values[idx]);
_series.append(p);
}
emit seriesChanged();
}
}
//-----------------------------------------------------------------------------
QGCMAVLinkMessage::QGCMAVLinkMessage(MAVLinkInspectorController *parent, mavlink_message_t* message)
: QObject(parent)
, _msgCtl(parent)
{
_message = *message;
const mavlink_message_info_t* msgInfo = mavlink_get_message_info(message);
......@@ -54,6 +151,26 @@ QGCMAVLinkMessage::QGCMAVLinkMessage(QObject* parent, mavlink_message_t* message
}
}
//-----------------------------------------------------------------------------
void
QGCMAVLinkMessage::select()
{
bool sel = false;
for (int i = 0; i < _fields.count(); ++i) {
QGCMAVLinkMessageField* f = qobject_cast<QGCMAVLinkMessageField*>(_fields.get(i));
if(f) {
if(f->selected()) {
sel = true;
break;
}
}
}
if(sel != _selected) {
_selected = sel;
emit selectedChanged();
}
}
//-----------------------------------------------------------------------------
void
QGCMAVLinkMessage::updateFreq()
......@@ -85,17 +202,18 @@ QGCMAVLinkMessage::update(mavlink_message_t* message)
if(f) {
switch (msgInfo->fields[i].type) {
case MAVLINK_TYPE_CHAR:
f->setSelectable(false);
if (msgInfo->fields[i].array_length > 0) {
char* str = reinterpret_cast<char*>(m+ msgInfo->fields[i].wire_offset);
// Enforce null termination
str[msgInfo->fields[i].array_length - 1] = '\0';
QString v(str);
f->updateValue(v);
f->updateValue(v, 0);
} else {
// Single char
char b = *(reinterpret_cast<char*>(m + msgInfo->fields[i].wire_offset));
QString v(b);
f->updateValue(v);
f->updateValue(v, 0);
}
break;
case MAVLINK_TYPE_UINT8_T:
......@@ -104,14 +222,15 @@ QGCMAVLinkMessage::update(mavlink_message_t* message)
// Enforce null termination
QString tmp("%1, ");
QString string;
for (unsigned int j = 0; j < msgInfo->fields[i].array_length; ++j) {
for (unsigned int j = 0; j < msgInfo->fields[i].array_length - 1; ++j) {
string += tmp.arg(nums[j]);
}
f->updateValue(string);
string += QString::number(nums[msgInfo->fields[i].array_length - 1]);
f->updateValue(string, static_cast<qreal>(nums[0]));
} else {
// Single value
uint8_t u = *(m+msgInfo->fields[i].wire_offset);
f->updateValue(QString::number(u));
f->updateValue(QString::number(u), static_cast<qreal>(u));
}
break;
case MAVLINK_TYPE_INT8_T:
......@@ -120,14 +239,15 @@ QGCMAVLinkMessage::update(mavlink_message_t* message)
// Enforce null termination
QString tmp("%1, ");
QString string;
for (unsigned int j = 0; j < msgInfo->fields[i].array_length; ++j) {
for (unsigned int j = 0; j < msgInfo->fields[i].array_length - 1; ++j) {
string += tmp.arg(nums[j]);
}
f->updateValue(string);
string += QString::number(nums[msgInfo->fields[i].array_length - 1]);
f->updateValue(string, static_cast<qreal>(nums[0]));
} else {
// Single value
int8_t n = *(reinterpret_cast<int8_t*>(m+msgInfo->fields[i].wire_offset));
f->updateValue(QString::number(n));
f->updateValue(QString::number(n), static_cast<qreal>(n));
}
break;
case MAVLINK_TYPE_UINT16_T:
......@@ -136,14 +256,15 @@ QGCMAVLinkMessage::update(mavlink_message_t* message)
// Enforce null termination
QString tmp("%1, ");
QString string;
for (unsigned int j = 0; j < msgInfo->fields[i].array_length; ++j) {
for (unsigned int j = 0; j < msgInfo->fields[i].array_length - 1; ++j) {
string += tmp.arg(nums[j]);
}
f->updateValue(string);
string += QString::number(nums[msgInfo->fields[i].array_length - 1]);
f->updateValue(string, static_cast<qreal>(nums[0]));
} else {
// Single value
uint16_t n = *(reinterpret_cast<uint16_t*>(m + msgInfo->fields[i].wire_offset));
f->updateValue(QString::number(n));
f->updateValue(QString::number(n), static_cast<qreal>(n));
}
break;
case MAVLINK_TYPE_INT16_T:
......@@ -152,14 +273,15 @@ QGCMAVLinkMessage::update(mavlink_message_t* message)
// Enforce null termination
QString tmp("%1, ");
QString string;
for (unsigned int j = 0; j < msgInfo->fields[i].array_length; ++j) {
for (unsigned int j = 0; j < msgInfo->fields[i].array_length - 1; ++j) {
string += tmp.arg(nums[j]);
}
f->updateValue(string);
string += QString::number(nums[msgInfo->fields[i].array_length - 1]);
f->updateValue(string, static_cast<qreal>(nums[0]));
} else {
// Single value
int16_t n = *(reinterpret_cast<int16_t*>(m + msgInfo->fields[i].wire_offset));
f->updateValue(QString::number(n));
f->updateValue(QString::number(n), static_cast<qreal>(n));
}
break;
case MAVLINK_TYPE_UINT32_T:
......@@ -168,19 +290,20 @@ QGCMAVLinkMessage::update(mavlink_message_t* message)
// Enforce null termination
QString tmp("%1, ");
QString string;
for (unsigned int j = 0; j < msgInfo->fields[i].array_length; ++j) {
for (unsigned int j = 0; j < msgInfo->fields[i].array_length - 1; ++j) {
string += tmp.arg(nums[j]);
}
f->updateValue(string);
string += QString::number(nums[msgInfo->fields[i].array_length - 1]);
f->updateValue(string, static_cast<qreal>(nums[0]));
} else {
// Single value
uint32_t n = *(reinterpret_cast<uint32_t*>(m + msgInfo->fields[i].wire_offset));
//-- Special case
if(_message.msgid == MAVLINK_MSG_ID_SYSTEM_TIME) {
QDateTime d = QDateTime::fromMSecsSinceEpoch(static_cast<qint64>(n),Qt::UTC,0);
f->updateValue(d.toString("HH:mm:ss"));
f->updateValue(d.toString("HH:mm:ss"), static_cast<qreal>(n));
} else {
f->updateValue(QString::number(n));
f->updateValue(QString::number(n), static_cast<qreal>(n));
}
}
break;
......@@ -190,14 +313,15 @@ QGCMAVLinkMessage::update(mavlink_message_t* message)
// Enforce null termination
QString tmp("%1, ");
QString string;
for (unsigned int j = 0; j < msgInfo->fields[i].array_length; ++j) {
for (unsigned int j = 0; j < msgInfo->fields[i].array_length - 1; ++j) {
string += tmp.arg(nums[j]);
}
f->updateValue(string);
string += QString::number(nums[msgInfo->fields[i].array_length - 1]);
f->updateValue(string, static_cast<qreal>(nums[0]));
} else {
// Single value
int32_t n = *(reinterpret_cast<int32_t*>(m + msgInfo->fields[i].wire_offset));
f->updateValue(QString::number(n));
f->updateValue(QString::number(n), static_cast<qreal>(n));
}
break;
case MAVLINK_TYPE_FLOAT:
......@@ -206,14 +330,15 @@ QGCMAVLinkMessage::update(mavlink_message_t* message)
// Enforce null termination
QString tmp("%1, ");
QString string;
for (unsigned int j = 0; j < msgInfo->fields[i].array_length; ++j) {
for (unsigned int j = 0; j < msgInfo->fields[i].array_length - 1; ++j) {
string += tmp.arg(static_cast<double>(nums[j]));
}
f->updateValue(string);
string += QString::number(static_cast<double>(nums[msgInfo->fields[i].array_length - 1]));
f->updateValue(string, static_cast<qreal>(nums[0]));
} else {
// Single value
float fv = *(reinterpret_cast<float*>(m + msgInfo->fields[i].wire_offset));
f->updateValue(QString::number(static_cast<double>(fv)));
f->updateValue(QString::number(static_cast<double>(fv)), static_cast<qreal>(fv));
}
break;
case MAVLINK_TYPE_DOUBLE:
......@@ -222,14 +347,15 @@ QGCMAVLinkMessage::update(mavlink_message_t* message)
// Enforce null termination
QString tmp("%1, ");
QString string;
for (unsigned int j = 0; j < msgInfo->fields[i].array_length; ++j) {
for (unsigned int j = 0; j < msgInfo->fields[i].array_length - 1; ++j) {
string += tmp.arg(nums[j]);
}
f->updateValue(string);
string += QString::number(static_cast<double>(nums[msgInfo->fields[i].array_length - 1]));
f->updateValue(string, static_cast<qreal>(nums[0]));
} else {
// Single value
double d = *(reinterpret_cast<double*>(m + msgInfo->fields[i].wire_offset));
f->updateValue(QString::number(d));
f->updateValue(QString::number(d), static_cast<qreal>(d));
}
break;
case MAVLINK_TYPE_UINT64_T:
......@@ -238,19 +364,20 @@ QGCMAVLinkMessage::update(mavlink_message_t* message)
// Enforce null termination
QString tmp("%1, ");
QString string;
for (unsigned int j = 0; j < msgInfo->fields[i].array_length; ++j) {
for (unsigned int j = 0; j < msgInfo->fields[i].array_length - 1; ++j) {
string += tmp.arg(nums[j]);
}
f->updateValue(string);
string += QString::number(nums[msgInfo->fields[i].array_length - 1]);
f->updateValue(string, static_cast<qreal>(nums[0]));
} else {
// Single value
uint64_t n = *(reinterpret_cast<uint64_t*>(m + msgInfo->fields[i].wire_offset));
//-- Special case
if(_message.msgid == MAVLINK_MSG_ID_SYSTEM_TIME) {
QDateTime d = QDateTime::fromMSecsSinceEpoch(n/1000,Qt::UTC,0);
f->updateValue(d.toString("yyyy MM dd HH:mm:ss"));
f->updateValue(d.toString("yyyy MM dd HH:mm:ss"), static_cast<qreal>(n));
} else {
f->updateValue(QString::number(n));
f->updateValue(QString::number(n), static_cast<qreal>(n));
}
}
break;
......@@ -260,14 +387,15 @@ QGCMAVLinkMessage::update(mavlink_message_t* message)
// Enforce null termination
QString tmp("%1, ");
QString string;
for (unsigned int j = 0; j < msgInfo->fields[i].array_length; ++j) {
for (unsigned int j = 0; j < msgInfo->fields[i].array_length - 1; ++j) {
string += tmp.arg(nums[j]);
}
f->updateValue(string);
string += QString::number(nums[msgInfo->fields[i].array_length - 1]);
f->updateValue(string, static_cast<qreal>(nums[0]));
} else {
// Single value
int64_t n = *(reinterpret_cast<int64_t*>(m + msgInfo->fields[i].wire_offset));
f->updateValue(QString::number(n));
f->updateValue(QString::number(n), static_cast<qreal>(n));
}
break;
}
......@@ -356,6 +484,8 @@ MAVLinkInspectorController::MAVLinkInspectorController()
_updateTimer.start(1000);
MultiVehicleManager *manager = qgcApp()->toolbox()->multiVehicleManager();
connect(manager, &MultiVehicleManager::activeVehicleChanged, this, &MAVLinkInspectorController::_setActiveVehicle);
_rangeXMax = QDateTime::fromMSecsSinceEpoch(0);
_rangeXMin = QDateTime::fromMSecsSinceEpoch(std::numeric_limits<qint64>::max());
}
//-----------------------------------------------------------------------------
......@@ -475,3 +605,57 @@ void
MAVLinkInspectorController::_reset()
{
}
//-----------------------------------------------------------------------------
void
MAVLinkInspectorController::addChartField(QGCMAVLinkMessageField* field)
{
QVariant f = QVariant::fromValue(field);
for(int i = 0; i < _chartFields.count(); i++) {
if(_chartFields.at(i) == f) {
return;
}
}
_chartFields.append(f);
emit chartFieldCountChanged();
}
//-----------------------------------------------------------------------------
void
MAVLinkInspectorController::delChartField(QGCMAVLinkMessageField* field)
{
QVariant f = QVariant::fromValue(field);
for(int i = 0; i < _chartFields.count(); i++) {
if(_chartFields.at(i) == f) {
_chartFields.removeAt(i);
emit chartFieldCountChanged();
if(_chartFields.count() == 0) {
_rangeXMax = QDateTime::fromMSecsSinceEpoch(0);
_rangeXMin = QDateTime::fromMSecsSinceEpoch(std::numeric_limits<qint64>::max());
}
return;
}
}
}
//-----------------------------------------------------------------------------
void
MAVLinkInspectorController::updateSeries(int index, QAbstractSeries* series)
{
if(index < _chartFields.count() && series) {
QGCMAVLinkMessageField* f = qvariant_cast<QGCMAVLinkMessageField*>(_chartFields.at(index));
QLineSeries* lineSeries = static_cast<QLineSeries*>(series);
lineSeries->replace(f->series());
}
}
//-----------------------------------------------------------------------------
void
MAVLinkInspectorController::updateXRange()
{
qint64 t = static_cast<qint64>(QGC::groundTimeMilliseconds());
_rangeXMax = QDateTime::fromMSecsSinceEpoch(t);
_rangeXMin = QDateTime::fromMSecsSinceEpoch(t - (60 * 1000));
emit rangeMinXChanged();
emit rangeMaxXChanged();
}
......@@ -15,33 +15,67 @@
#include <QObject>
#include <QString>
#include <QDebug>
#include <QAbstractListModel>
#include <QVariantList>
#include <QtCharts/QAbstractSeries>
Q_DECLARE_LOGGING_CATEGORY(MAVLinkInspectorLog)
QT_CHARTS_USE_NAMESPACE
class QGCMAVLinkMessage;
class MAVLinkInspectorController;
//-----------------------------------------------------------------------------
class QGCMAVLinkMessageField : public QObject {
Q_OBJECT
Q_PROPERTY(QString name READ name CONSTANT)
Q_PROPERTY(QString type READ type CONSTANT)
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:
QGCMAVLinkMessageField(QObject* parent, QString name, QString type);
QGCMAVLinkMessageField(QGCMAVLinkMessage* parent, QString name, QString type);
QString name () { return _name; }
QString type () { return _type; }
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:
void valueChanged ();
void rangeMinChanged ();
void rangeMaxChanged ();
void seriesChanged ();
void selectableChanged ();
void selectedChanged ();
void valueChanged ();
private:
void _updateSeries ();
private:
QString _type;
QString _name;
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 {
Q_PROPERTY(qreal messageHz READ messageHz NOTIFY freqChanged)
Q_PROPERTY(quint64 count READ count NOTIFY messageChanged)
Q_PROPERTY(QmlObjectListModel* fields READ fields NOTIFY indexChanged)
Q_PROPERTY(bool selected READ selected NOTIFY selectedChanged)
public:
QGCMAVLinkMessage(QObject* parent, mavlink_message_t* message);
QGCMAVLinkMessage(MAVLinkInspectorController* parent, mavlink_message_t* message);
quint32 id () { return _message.msgid; }
quint8 cid () { return _message.compid; }
......@@ -64,7 +99,11 @@ public:
quint64 count () { return _count; }
quint64 lastCount () { return _lastCount; }
QmlObjectListModel* fields () { return &_fields; }
bool selected () { return _selected; }
MAVLinkInspectorController* msgCtl () { return _msgCtl; }
void select ();
void update (mavlink_message_t* message);
void updateFreq ();
......@@ -72,6 +111,7 @@ signals:
void messageChanged ();
void freqChanged ();
void indexChanged ();
void selectedChanged ();
private:
QmlObjectListModel _fields;
......@@ -80,6 +120,8 @@ private:
uint64_t _count = 0;
uint64_t _lastCount = 0;
mavlink_message_t _message; //-- List of QGCMAVLinkMessageField
MAVLinkInspectorController* _msgCtl = nullptr;
bool _selected = false;
};
//-----------------------------------------------------------------------------
......@@ -123,17 +165,39 @@ public:
MAVLinkInspectorController();
~MAVLinkInspectorController();
Q_PROPERTY(QStringList vehicleNames READ vehicleNames NOTIFY vehiclesChanged)
Q_PROPERTY(QmlObjectListModel* vehicles READ vehicles NOTIFY vehiclesChanged)
Q_PROPERTY(QGCMAVLinkVehicle* activeVehicle READ activeVehicle NOTIFY activeVehiclesChanged)
Q_PROPERTY(QStringList vehicleNames READ vehicleNames NOTIFY vehiclesChanged)
Q_PROPERTY(QmlObjectListModel* vehicles READ vehicles NOTIFY vehiclesChanged)
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; }
QGCMAVLinkVehicle* activeVehicle () { return _activeVehicle; }
QStringList vehicleNames () { return _vehicleNames; }
quint32 timeScale () { return _timeScale; }
QVariantList chartFields () { return _chartFields; }
QDateTime rangeXMin () { return _rangeXMin; }
QDateTime rangeXMax () { return _rangeXMax; }
QmlObjectListModel* vehicles () { return &_vehicles; }
QGCMAVLinkVehicle* activeVehicle () { return _activeVehicle; }
QStringList vehicleNames () { return _vehicleNames; }
void setTimeScale (quint32 t) { _timeScale = t; emit timeScaleChanged(); }
int chartFieldCount () { return _chartFields.count(); }
void addChartField (QGCMAVLinkMessageField* field);
void delChartField (QGCMAVLinkMessageField* field);
void updateXRange ();
signals:
void vehiclesChanged ();
void activeVehiclesChanged ();
void chartFieldCountChanged ();
void timeScaleChanged ();
void rangeMinXChanged ();
void rangeMaxXChanged ();
private slots:
void _receiveMessage (LinkInterface* link, mavlink_message_t message);
......@@ -150,9 +214,13 @@ private:
private:
int _selectedSystemID = 0; ///< Currently selected system
int _selectedComponentID = 0; ///< Currently selected component
quint32 _timeScale = 10; ///< 10 Seconds
QDateTime _rangeXMin;
QDateTime _rangeXMax;
QGCMAVLinkVehicle* _activeVehicle = nullptr;
QTimer _updateTimer;
QStringList _vehicleNames;
QmlObjectListModel _vehicles; //-- List of QGCMAVLinkVehicle
QmlObjectListModel _vehicles; //-- List of QGCMAVLinkVehicle
QVariantList _chartFields;
};
......@@ -11,6 +11,8 @@ import QtQuick 2.11
import QtQuick.Controls 2.4
import QtQuick.Layouts 1.11
import QtQuick.Dialogs 1.3
import QtQuick.Window 2.2
import QtCharts 2.1
import QGroundControl 1.0
import QGroundControl.Palette 1.0
......@@ -33,6 +35,79 @@ AnalyzePage {
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 {
id: headerComponent
//-- Header
......@@ -73,6 +148,7 @@ AnalyzePage {
RowLayout {
width: availableWidth
height: availableHeight
spacing: ScreenTools.defaultFontPixelWidth
//-- Messages (Buttons)
QGCFlickable {
id: buttonGrid
......@@ -90,7 +166,7 @@ AnalyzePage {
Repeater {
model: curVehicle ? curVehicle.messages : []
delegate: MAVLinkMessageButton {
text: object.name
text: object.name + (object.selected ? " *" : "")
compID: object.cid
checked: curMessageIndex === index
messageHz: object.messageHz
......@@ -151,7 +227,7 @@ AnalyzePage {
}
Item { height: ScreenTools.defaultFontPixelHeight * 0.25; width: 1 }
GridLayout {
columns: 3
columns: 4
columnSpacing: ScreenTools.defaultFontPixelWidth
rowSpacing: ScreenTools.defaultFontPixelHeight * 0.25
Repeater {
......@@ -182,6 +258,16 @@ AnalyzePage {
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