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 <QtGraphs/QAbstractSeries>
8#include <QtCore/QTimer>
9
10static constexpr qreal kMinDelta = 1e-6;
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) connect(_updateSeriesTimer, &QTimer::timeout, this, &MAVLinkChartController::_refreshSeries);
21}
22
24{
25 // qCDebug(MAVLinkChartControllerLog) << Q_FUNC_INFO << this;
26}
27
29{
30 if (_inspectorController == controller) {
31 return;
32 }
33
34 _inspectorController = controller;
36}
37
39{
40 if (index == _rangeYIndex) {
41 return;
42 }
43
44 if (!_inspectorController || index >= static_cast<quint32>(_inspectorController->rangeSt().count())) {
45 return;
46 }
47
48 _rangeYIndex = index;
49 emit rangeYIndexChanged();
50
51 // If not Auto, use defined range
52 const qreal range = _inspectorController->rangeSt()[static_cast<int>(index)]->range;
53 if (_rangeYIndex > 0) {
54 _rangeYMin = -range;
55 emit rangeYMinChanged();
56
57 _rangeYMax = range;
58 emit rangeYMaxChanged();
59 }
60}
61
63{
64 if (!_inspectorController) {
65 return 5000.0;
66 }
67 if (_rangeXIndex < static_cast<quint32>(_inspectorController->timeScaleSt().count())) {
68 return static_cast<qreal>(_inspectorController->timeScaleSt()[static_cast<int>(_rangeXIndex)]->timeScale);
69 }
70 return 5000.0;
71}
72
74{
75 if (index == _rangeXIndex) {
76 return;
77 }
78
79 _rangeXIndex = index;
80 emit rangeXIndexChanged();
81
83 _resetFieldBucketing();
84}
85
87{
88 if (!_inspectorController) {
89 return;
90 }
91
92 if (_rangeXIndex >= static_cast<quint32>(_inspectorController->timeScaleSt().count())) {
93 return;
94 }
95
96 const qint64 bootTime = static_cast<qint64>(qgcApp()->msecsSinceBoot());
97 _rangeXMax = static_cast<qreal>(bootTime);
98 emit rangeXMaxChanged();
99
100 _rangeXMin = static_cast<qreal>(bootTime - _inspectorController->timeScaleSt()[static_cast<int>(_rangeXIndex)]->timeScale);
101 emit rangeXMinChanged();
102}
103
105{
106 if (_chartFields.isEmpty()) {
107 return;
108 }
109
110 qreal vmin = std::numeric_limits<qreal>::max();
111 qreal vmax = std::numeric_limits<qreal>::lowest();
112 for (const QVariant &field : _chartFields) {
113 QObject *const object = qvariant_cast<QObject*>(field);
114 QGCMAVLinkMessageField *const pField = qobject_cast<QGCMAVLinkMessageField*>(object);
115 if (pField) {
116 vmin = std::min(vmin, pField->rangeMin());
117 vmax = std::max(vmax, pField->rangeMax());
118 }
119 }
120
121 if (vmin > vmax) {
122 return; // No field has received data yet (sentinel values)
123 }
124
125 if (qAbs(vmax - vmin) < kMinDelta) {
126 vmin -= 1.0;
127 vmax += 1.0;
128 } else {
129 const qreal padding = (vmax - vmin) * 0.05;
130 vmin -= padding;
131 vmax += padding;
132 }
133
134 if (qAbs(_rangeYMin - vmin) > kMinDelta) {
135 _rangeYMin = vmin;
136 emit rangeYMinChanged();
137 }
138
139 if (qAbs(_rangeYMax - vmax) > kMinDelta) {
140 _rangeYMax = vmax;
141 emit rangeYMaxChanged();
142 }
143}
144
145void MAVLinkChartController::_refreshSeries()
146{
147 updateXRange();
148
149 for (QVariant &field : _chartFields) {
150 QObject *const object = qvariant_cast<QObject*>(field);
151 QGCMAVLinkMessageField *const pField = qobject_cast<QGCMAVLinkMessageField*>(object);
152 if(pField) {
153 pField->updateSeries();
154 }
155 }
156
157 if (_rangeYIndex == 0) {
158 updateYRange();
159 }
160}
161
163{
164 if (!field || !series) {
165 return;
166 }
167
168 const QVariant f = QVariant::fromValue(field);
169 for (const QVariant &chartField : _chartFields) {
170 if (chartField == f) {
171 return;
172 }
173 }
174
175 _chartFields.append(f);
176 field->addSeries(this, series);
177 emit chartFieldsChanged();
178
179 _updateSeriesTimer->start(kUpdateFrequency);
180}
181
183{
184 if (!field) {
185 return;
186 }
187
188 field->delSeries();
189
190 const QVariant f = QVariant::fromValue(field);
191 const QList<QVariant>::const_iterator it = std::find(_chartFields.constBegin(), _chartFields.constEnd(), f);
192 if (it != _chartFields.constEnd()) {
193 (void) _chartFields.erase(it);
194 emit chartFieldsChanged();
195
196 if (_chartFields.isEmpty()) {
197 updateXRange();
198 _updateSeriesTimer->stop();
199 }
200 }
201}
202
204{
205 if (width == _plotPixelWidth) {
206 return;
207 }
208
209 _plotPixelWidth = width;
211 _resetFieldBucketing();
212}
213
214void MAVLinkChartController::_resetFieldBucketing()
215{
216 if (_plotPixelWidth <= 0) {
217 return;
218 }
219
220 const qreal bucketWidthMs = rangeXMs() / _plotPixelWidth;
221 for (const QVariant &field : _chartFields) {
222 QObject *const object = qvariant_cast<QObject*>(field);
223 QGCMAVLinkMessageField *const pField = qobject_cast<QGCMAVLinkMessageField*>(object);
224 if (pField) {
225 pField->resetBucketing(_plotPixelWidth, bucketWidthMs);
226 }
227 }
228}
static constexpr qreal kMinDelta
#define qgcApp()
#define QGC_LOGGING_CATEGORY(name, categoryStr)
Q_INVOKABLE void delSeries(QGCMAVLinkMessageField *field)
void setRangeXIndex(quint32 index)
void setRangeYIndex(quint32 index)
Q_INVOKABLE void addSeries(QGCMAVLinkMessageField *field, QAbstractSeries *series)
void setInspectorController(MAVLinkInspectorController *inspectorController)
MAVLink message inspector controller (provides the logic for UI display)
const QList< TimeScale_st * > & timeScaleSt() const
const QList< Range_st * > & rangeSt() const
void addSeries(MAVLinkChartController *chartController, QAbstractSeries *series)
void resetBucketing(int bucketCount, qreal bucketWidthMs)