7#include <QtGraphs/QAbstractSeries>
8#include <QtCore/QTimer>
16 , _updateSeriesTimer(new QTimer(this))
20 (void) connect(_updateSeriesTimer, &QTimer::timeout,
this, &MAVLinkChartController::_refreshSeries);
30 if (_inspectorController == controller) {
34 _inspectorController = controller;
40 if (index == _rangeYIndex) {
44 if (!_inspectorController || index >=
static_cast<quint32
>(_inspectorController->
rangeSt().count())) {
52 const qreal range = _inspectorController->
rangeSt()[
static_cast<int>(index)]->range;
53 if (_rangeYIndex > 0) {
64 if (!_inspectorController) {
67 if (_rangeXIndex <
static_cast<quint32
>(_inspectorController->
timeScaleSt().count())) {
68 return static_cast<qreal
>(_inspectorController->
timeScaleSt()[
static_cast<int>(_rangeXIndex)]->timeScale);
75 if (index == _rangeXIndex) {
83 _resetFieldBucketing();
88 if (!_inspectorController) {
92 if (_rangeXIndex >=
static_cast<quint32
>(_inspectorController->
timeScaleSt().count())) {
96 const qint64 bootTime =
static_cast<qint64
>(
qgcApp()->msecsSinceBoot());
97 _rangeXMax =
static_cast<qreal
>(bootTime);
100 _rangeXMin =
static_cast<qreal
>(bootTime - _inspectorController->
timeScaleSt()[
static_cast<int>(_rangeXIndex)]->timeScale);
106 if (_chartFields.isEmpty()) {
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);
116 vmin = std::min(vmin, pField->
rangeMin());
117 vmax = std::max(vmax, pField->
rangeMax());
129 const qreal padding = (vmax - vmin) * 0.05;
134 if (qAbs(_rangeYMin - vmin) >
kMinDelta) {
139 if (qAbs(_rangeYMax - vmax) >
kMinDelta) {
145void MAVLinkChartController::_refreshSeries()
149 for (QVariant &field : _chartFields) {
150 QObject *
const object = qvariant_cast<QObject*>(field);
157 if (_rangeYIndex == 0) {
164 if (!field || !series) {
168 const QVariant f = QVariant::fromValue(field);
169 for (
const QVariant &chartField : _chartFields) {
170 if (chartField == f) {
175 _chartFields.append(f);
179 _updateSeriesTimer->start(kUpdateFrequency);
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);
196 if (_chartFields.isEmpty()) {
198 _updateSeriesTimer->stop();
205 if (width == _plotPixelWidth) {
209 _plotPixelWidth = width;
211 _resetFieldBucketing();
214void MAVLinkChartController::_resetFieldBucketing()
216 if (_plotPixelWidth <= 0) {
220 const qreal bucketWidthMs =
rangeXMs() / _plotPixelWidth;
221 for (
const QVariant &field : _chartFields) {
222 QObject *
const object = qvariant_cast<QObject*>(field);
static constexpr qreal kMinDelta
#define QGC_LOGGING_CATEGORY(name, categoryStr)
~MAVLinkChartController()
void rangeXIndexChanged()
Q_INVOKABLE void delSeries(QGCMAVLinkMessageField *field)
void setRangeXIndex(quint32 index)
void chartFieldsChanged()
void rangeYIndexChanged()
void setRangeYIndex(quint32 index)
void setPlotPixelWidth(int width)
void plotPixelWidthChanged()
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)