QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
MAVLinkChartController.cc
Go to the documentation of this file.
4#include "QGCApplication.h"
6
7#include <QtCharts/QAbstractSeries>
8#include <QtCore/QTimer>
9
10Q_DECLARE_METATYPE(QAbstractSeries*)
11
12QGC_LOGGING_CATEGORY(MAVLinkChartControllerLog, "AnalyzeView.MAVLinkChartController")
13
15 : QObject(parent)
16 , _updateSeriesTimer(new QTimer(this))
17{
18 // qCDebug(MAVLinkChartControllerLog) << Q_FUNC_INFO << this;
19
20 (void) qRegisterMetaType<QAbstractSeries*>("QAbstractSeries*");
21
22 (void) connect(_updateSeriesTimer, &QTimer::timeout, this, &MAVLinkChartController::_refreshSeries);
23}
24
25MAVLinkChartController::~MAVLinkChartController()
26{
27 // qCDebug(MAVLinkChartControllerLog) << Q_FUNC_INFO << this;
28}
29
30void MAVLinkChartController::setInspectorController(MAVLinkInspectorController *controller)
31{
32 if (_inspectorController == controller) {
33 return;
34 }
35
36 _inspectorController = controller;
37 updateXRange();
38}
39
40void MAVLinkChartController::setRangeYIndex(quint32 index)
41{
42 if (index == _rangeYIndex) {
43 return;
44 }
45
46 if (index >= static_cast<quint32>(_inspectorController->rangeSt().count())) {
47 return;
48 }
49
50 _rangeYIndex = index;
51 emit rangeYIndexChanged();
52
53 // If not Auto, use defined range
54 const qreal range = _inspectorController->rangeSt()[static_cast<int>(index)]->range;
55 if (_rangeYIndex > 0) {
56 _rangeYMin = -range;
57 emit rangeYMinChanged();
58
59 _rangeYMax = range;
60 emit rangeYMaxChanged();
61 }
62}
63
64void MAVLinkChartController::setRangeXIndex(quint32 index)
65{
66 if (index == _rangeXIndex) {
67 return;
68 }
69
70 _rangeXIndex = index;
71 emit rangeXIndexChanged();
72
73 updateXRange();
74}
75
76void MAVLinkChartController::updateXRange()
77{
78 if (_rangeXIndex >= static_cast<quint32>(_inspectorController->timeScaleSt().count())) {
79 return;
80 }
81
82 const qint64 bootTime = static_cast<qint64>(qgcApp()->msecsSinceBoot());
83 _rangeXMax = QDateTime::fromMSecsSinceEpoch(bootTime);
84 emit rangeXMaxChanged();
85
86 _rangeXMin = QDateTime::fromMSecsSinceEpoch(bootTime - _inspectorController->timeScaleSt()[static_cast<int>(_rangeXIndex)]->timeScale);
87 emit rangeXMinChanged();
88}
89
90void MAVLinkChartController::updateYRange()
91{
92 if (_chartFields.isEmpty()) {
93 return;
94 }
95
96 qreal vmin = std::numeric_limits<qreal>::max();
97 qreal vmax = std::numeric_limits<qreal>::min();
98 for (const QVariant &field : _chartFields) {
99 QObject *const object = qvariant_cast<QObject*>(field);
100 QGCMAVLinkMessageField *const pField = qobject_cast<QGCMAVLinkMessageField*>(object);
101 if (pField) {
102 if (vmax < pField->rangeMax()) {
103 vmax = pField->rangeMax();
104 }
105
106 if (vmin > pField->rangeMin()) {
107 vmin = pField->rangeMin();
108 }
109 }
110 }
111
112 if (qAbs(_rangeYMin - vmin) > 0.000001) {
113 _rangeYMin = vmin;
114 emit rangeYMinChanged();
115 }
116
117 if (qAbs(_rangeYMax - vmax) > 0.000001) {
118 _rangeYMax = vmax;
119 emit rangeYMaxChanged();
120 }
121}
122
123void MAVLinkChartController::_refreshSeries()
124{
125 updateXRange();
126
127 for (QVariant &field : _chartFields) {
128 QObject *const object = qvariant_cast<QObject*>(field);
129 QGCMAVLinkMessageField *const pField = qobject_cast<QGCMAVLinkMessageField*>(object);
130 if(pField) {
131 pField->updateSeries();
132 }
133 }
134}
135
136void MAVLinkChartController::addSeries(QGCMAVLinkMessageField *field, QAbstractSeries *series)
137{
138 if (!field || !series) {
139 return;
140 }
141
142 const QVariant f = QVariant::fromValue(field);
143 for (const QVariant &chartField : _chartFields) {
144 if (chartField == f) {
145 return;
146 }
147 }
148
149 _chartFields.append(f);
150 field->addSeries(this, series);
151 emit chartFieldsChanged();
152
153 _updateSeriesTimer->start(kUpdateFrequency);
154}
155
156void MAVLinkChartController::delSeries(QGCMAVLinkMessageField *field)
157{
158 if (!field) {
159 return;
160 }
161
162 field->delSeries();
163
164 const QVariant f = QVariant::fromValue(field);
165 const QList<QVariant>::const_iterator it = std::find(_chartFields.constBegin(), _chartFields.constEnd(), f);
166 if (it != _chartFields.constEnd()) {
167 (void) _chartFields.erase(it);
168 emit chartFieldsChanged();
169
170 if (_chartFields.isEmpty()) {
171 updateXRange();
172 _updateSeriesTimer->stop();
173 }
174 }
175}
#define qgcApp()
#define QGC_LOGGING_CATEGORY(name, categoryStr)
MAVLink message inspector controller (provides the logic for UI display)
const QList< TimeScale_st * > & timeScaleSt() const
const QList< Range_st * > & rangeSt() const
Q_DECLARE_METATYPE(satellite_info_s)