7#include <QtCharts/QAbstractSeries>
8#include <QtCore/QTimer>
16 , _updateSeriesTimer(new QTimer(this))
20 (void) qRegisterMetaType<QAbstractSeries*>(
"QAbstractSeries*");
22 (void) connect(_updateSeriesTimer, &QTimer::timeout,
this, &MAVLinkChartController::_refreshSeries);
25MAVLinkChartController::~MAVLinkChartController()
32 if (_inspectorController == controller) {
36 _inspectorController = controller;
40void MAVLinkChartController::setRangeYIndex(quint32 index)
42 if (index == _rangeYIndex) {
46 if (index >=
static_cast<quint32
>(_inspectorController->
rangeSt().count())) {
54 const qreal range = _inspectorController->
rangeSt()[
static_cast<int>(index)]->range;
55 if (_rangeYIndex > 0) {
64void MAVLinkChartController::setRangeXIndex(quint32 index)
66 if (index == _rangeXIndex) {
76void MAVLinkChartController::updateXRange()
78 if (_rangeXIndex >=
static_cast<quint32
>(_inspectorController->
timeScaleSt().count())) {
82 const qint64 bootTime =
static_cast<qint64
>(
qgcApp()->msecsSinceBoot());
83 _rangeXMax = QDateTime::fromMSecsSinceEpoch(bootTime);
86 _rangeXMin = QDateTime::fromMSecsSinceEpoch(bootTime - _inspectorController->
timeScaleSt()[
static_cast<int>(_rangeXIndex)]->timeScale);
90void MAVLinkChartController::updateYRange()
92 if (_chartFields.isEmpty()) {
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);
102 if (vmax < pField->rangeMax()) {
103 vmax = pField->rangeMax();
106 if (vmin > pField->rangeMin()) {
107 vmin = pField->rangeMin();
112 if (qAbs(_rangeYMin - vmin) > 0.000001) {
117 if (qAbs(_rangeYMax - vmax) > 0.000001) {
123void MAVLinkChartController::_refreshSeries()
127 for (QVariant &field : _chartFields) {
128 QObject *
const object = qvariant_cast<QObject*>(field);
131 pField->updateSeries();
138 if (!field || !series) {
142 const QVariant f = QVariant::fromValue(field);
143 for (
const QVariant &chartField : _chartFields) {
144 if (chartField == f) {
149 _chartFields.append(f);
150 field->addSeries(
this, series);
153 _updateSeriesTimer->start(kUpdateFrequency);
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);
170 if (_chartFields.isEmpty()) {
172 _updateSeriesTimer->stop();
#define QGC_LOGGING_CATEGORY(name, categoryStr)
void rangeXIndexChanged()
void chartFieldsChanged()
void rangeYIndexChanged()
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)