Commit 78283634 authored by treymarc's avatar treymarc

add option "time serie" option to xyplot custom widget

parent 6de98807
...@@ -33,23 +33,28 @@ public: ...@@ -33,23 +33,28 @@ public:
/** Append data, returning the number of removed items */ /** Append data, returning the number of removed items */
int appendData(const QPointF &data) { int appendData(const QPointF &data) {
if(!minMaxSet) { m_data.append(data);
int removed = 0;
while (m_data.size() > m_maxShowPoints) {
++removed;
m_data.removeFirst();
}
if (!minMaxSet) {
xmin = xmax = data.x(); xmin = xmax = data.x();
ymin = ymax = data.y(); ymin = ymax = data.y();
minMaxSet = true; minMaxSet = true;
} else if(m_autoScale) { previousTime =xmin;
xmin = qMin(qreal(xmin), data.x()); } else if (m_autoScale) {
if (m_autoScaleTime) {
xmin += removed * (data.x() - previousTime);
previousTime = data.x();
} else {
xmin = qMin(qreal(xmin), data.x());
}
xmax = qMax(qreal(xmax), data.x()); xmax = qMax(qreal(xmax), data.x());
ymin = qMin(qreal(ymin), data.y()); ymin = qMin(qreal(ymin), data.y());
ymax = qMax(qreal(ymax), data.y()); ymax = qMax(qreal(ymax), data.y());
} }
m_data.append(data);
int removed = 0;
while(m_data.size() > m_maxStorePoints) {
++removed;
m_data.removeFirst();
}
itemChanged(); itemChanged();
return removed; return removed;
} }
...@@ -61,6 +66,10 @@ public: ...@@ -61,6 +66,10 @@ public:
void setColor(const QColor &color) { void setColor(const QColor &color) {
m_color = color; m_color = color;
} }
void setTimeSerie(bool state) {
clear();
m_autoScaleTime = state;
}
void unsetMinMax() { void unsetMinMax() {
if(m_autoScale) if(m_autoScale)
return; return;
...@@ -70,7 +79,7 @@ public: ...@@ -70,7 +79,7 @@ public:
minMaxSet = false; minMaxSet = false;
else { else {
minMaxSet = true; minMaxSet = true;
xmax = xmin = m_data.at(0).x(); previousTime = xmax = xmin = m_data.at(0).x();
ymax = ymin = m_data.at(0).y(); ymax = ymin = m_data.at(0).y();
for(int i = 1; i < m_data.size(); i++) { for(int i = 1; i < m_data.size(); i++) {
xmin = qMin(qreal(xmin), m_data.at(i).x()); xmin = qMin(qreal(xmin), m_data.at(i).x());
...@@ -164,12 +173,14 @@ private: ...@@ -164,12 +173,14 @@ private:
int m_smoothPoints; /** Number of points to average across */ int m_smoothPoints; /** Number of points to average across */
mutable QColor m_color; mutable QColor m_color;
double previousTime;
double xmin; double xmin;
double xmax; double xmax;
double ymin; double ymin;
double ymax; double ymax;
bool minMaxSet; bool minMaxSet;
bool m_autoScale; bool m_autoScale;
bool m_autoScaleTime;
int m_startIndex; int m_startIndex;
}; };
...@@ -220,6 +231,7 @@ QGCXYPlot::QGCXYPlot(QWidget *parent) : ...@@ -220,6 +231,7 @@ QGCXYPlot::QGCXYPlot(QWidget *parent) :
connect(ui->minY, SIGNAL(valueChanged(double)),this, SLOT(updateMinMaxSettings())); connect(ui->minY, SIGNAL(valueChanged(double)),this, SLOT(updateMinMaxSettings()));
connect(ui->maxY, SIGNAL(valueChanged(double)),this, SLOT(updateMinMaxSettings())); connect(ui->maxY, SIGNAL(valueChanged(double)),this, SLOT(updateMinMaxSettings()));
connect(ui->automaticAxisRange, SIGNAL(toggled(bool)),this, SLOT(updateMinMaxSettings())); connect(ui->automaticAxisRange, SIGNAL(toggled(bool)),this, SLOT(updateMinMaxSettings()));
connect(ui->timeAxisRange, SIGNAL(toggled(bool)),this, SLOT(setTimeAxis()));
connect(ui->maxDataShowSpinBox, SIGNAL(valueChanged(int)),this, SLOT(updateMinMaxSettings())); connect(ui->maxDataShowSpinBox, SIGNAL(valueChanged(int)),this, SLOT(updateMinMaxSettings()));
connect(ui->maxDataStoreSpinBox, SIGNAL(valueChanged(int)),this, SLOT(updateMinMaxSettings())); connect(ui->maxDataStoreSpinBox, SIGNAL(valueChanged(int)),this, SLOT(updateMinMaxSettings()));
connect(ui->smoothSpinBox, SIGNAL(valueChanged(int)),this, SLOT(updateMinMaxSettings())); connect(ui->smoothSpinBox, SIGNAL(valueChanged(int)),this, SLOT(updateMinMaxSettings()));
...@@ -261,6 +273,7 @@ void QGCXYPlot::setEditMode(bool editMode) ...@@ -261,6 +273,7 @@ void QGCXYPlot::setEditMode(bool editMode)
ui->maxDataShowSpinBox->setVisible(editMode); ui->maxDataShowSpinBox->setVisible(editMode);
ui->maxDataStoreSpinBox->setVisible(editMode); ui->maxDataStoreSpinBox->setVisible(editMode);
ui->automaticAxisRange->setVisible(editMode); ui->automaticAxisRange->setVisible(editMode);
ui->timeAxisRange->setVisible(editMode);
ui->lblSmooth->setVisible(editMode); ui->lblSmooth->setVisible(editMode);
ui->smoothSpinBox->setVisible(editMode); ui->smoothSpinBox->setVisible(editMode);
...@@ -286,7 +299,7 @@ void QGCXYPlot::writeSettings(QSettings& settings) ...@@ -286,7 +299,7 @@ void QGCXYPlot::writeSettings(QSettings& settings)
settings.setValue("QGC_XYPLOT_MAXDATA_SHOW", ui->maxDataShowSpinBox->value()); settings.setValue("QGC_XYPLOT_MAXDATA_SHOW", ui->maxDataShowSpinBox->value());
settings.setValue("QGC_XYPLOT_AUTO", ui->automaticAxisRange->isChecked()); settings.setValue("QGC_XYPLOT_AUTO", ui->automaticAxisRange->isChecked());
settings.setValue("QGC_XYPLOT_SMOOTH", ui->smoothSpinBox->value()); settings.setValue("QGC_XYPLOT_SMOOTH", ui->smoothSpinBox->value());
settings.setValue("QGC_XYPLOT_TIME", ui->timeAxisRange->isChecked());
settings.sync(); settings.sync();
} }
void QGCXYPlot::readSettings(const QString& pre,const QVariantMap& settings) void QGCXYPlot::readSettings(const QString& pre,const QVariantMap& settings)
...@@ -301,6 +314,7 @@ void QGCXYPlot::readSettings(const QString& pre,const QVariantMap& settings) ...@@ -301,6 +314,7 @@ void QGCXYPlot::readSettings(const QString& pre,const QVariantMap& settings)
ui->maxDataStoreSpinBox->setValue(settings.value(pre + "QGC_XYPLOT_MAXDATA_STORE", 10000).toInt()); ui->maxDataStoreSpinBox->setValue(settings.value(pre + "QGC_XYPLOT_MAXDATA_STORE", 10000).toInt());
ui->maxDataShowSpinBox->setValue(settings.value(pre + "QGC_XYPLOT_MAXDATA_SHOW", 15).toInt()); ui->maxDataShowSpinBox->setValue(settings.value(pre + "QGC_XYPLOT_MAXDATA_SHOW", 15).toInt());
ui->smoothSpinBox->setValue(settings.value(pre + "QGC_XYPLOT_SMOOTH", 1).toInt()); ui->smoothSpinBox->setValue(settings.value(pre + "QGC_XYPLOT_SMOOTH", 1).toInt());
ui->timeAxisRange->setChecked(settings.value(pre + "QGC_XYPLOT_TIME", true).toBool());
plot->setAxisTitle(QwtPlot::xBottom, ui->editXParam->currentText()); plot->setAxisTitle(QwtPlot::xBottom, ui->editXParam->currentText());
plot->setAxisTitle(QwtPlot::yLeft, ui->editYParam->currentText()); plot->setAxisTitle(QwtPlot::yLeft, ui->editYParam->currentText());
updateMinMaxSettings(); updateMinMaxSettings();
...@@ -318,6 +332,7 @@ void QGCXYPlot::readSettings(const QSettings& settings) ...@@ -318,6 +332,7 @@ void QGCXYPlot::readSettings(const QSettings& settings)
ui->maxDataStoreSpinBox->setValue(settings.value("QGC_XYPLOT_MAXDATA_STORE", 10000).toInt()); ui->maxDataStoreSpinBox->setValue(settings.value("QGC_XYPLOT_MAXDATA_STORE", 10000).toInt());
ui->maxDataShowSpinBox->setValue(settings.value("QGC_XYPLOT_MAXDATA_SHOW", 15).toInt()); ui->maxDataShowSpinBox->setValue(settings.value("QGC_XYPLOT_MAXDATA_SHOW", 15).toInt());
ui->smoothSpinBox->setValue(settings.value("QGC_XYPLOT_SMOOTH", 1).toInt()); ui->smoothSpinBox->setValue(settings.value("QGC_XYPLOT_SMOOTH", 1).toInt());
ui->timeAxisRange->setChecked(settings.value("QGC_XYPLOT_TIME", true).toBool());
plot->setAxisTitle(QwtPlot::xBottom, ui->editXParam->currentText()); plot->setAxisTitle(QwtPlot::xBottom, ui->editXParam->currentText());
plot->setAxisTitle(QwtPlot::yLeft, ui->editYParam->currentText()); plot->setAxisTitle(QwtPlot::yLeft, ui->editYParam->currentText());
updateMinMaxSettings(); updateMinMaxSettings();
...@@ -412,6 +427,11 @@ void QGCXYPlot::updateMinMaxSettings() ...@@ -412,6 +427,11 @@ void QGCXYPlot::updateMinMaxSettings()
xycurve->setSmoothPoints(ui->smoothSpinBox->value()); xycurve->setSmoothPoints(ui->smoothSpinBox->value());
} }
void QGCXYPlot::setTimeAxis()
{
xycurve->setTimeSerie(ui->timeAxisRange->isChecked());
}
void QGCXYPlot::on_maxDataShowSpinBox_valueChanged(int value) void QGCXYPlot::on_maxDataShowSpinBox_valueChanged(int value)
{ {
ui->maxDataStoreSpinBox->setMinimum(value); ui->maxDataStoreSpinBox->setMinimum(value);
......
...@@ -31,10 +31,11 @@ public slots: ...@@ -31,10 +31,11 @@ public slots:
void styleChanged(MainWindow::QGC_MAINWINDOW_STYLE style); void styleChanged(MainWindow::QGC_MAINWINDOW_STYLE style);
void updateMinMaxSettings(); void updateMinMaxSettings();
private slots: private slots:
void on_maxDataShowSpinBox_valueChanged(int value); void on_maxDataShowSpinBox_valueChanged(int value);
void on_stopStartButton_toggled(bool checked); void on_stopStartButton_toggled(bool checked);
void setTimeAxis();
void on_timeScrollBar_valueChanged(int value); void on_timeScrollBar_valueChanged(int value);
private: private:
...@@ -42,6 +43,7 @@ private: ...@@ -42,6 +43,7 @@ private:
QwtPlot *plot; QwtPlot *plot;
XYPlotCurve* xycurve; XYPlotCurve* xycurve;
bool autoScaleTime;
double x; /**< Last unused value for the x-coordinate */ double x; /**< Last unused value for the x-coordinate */
quint64 x_timestamp_us; /**< Timestamp that we last recieved a value for x */ quint64 x_timestamp_us; /**< Timestamp that we last recieved a value for x */
bool x_valid; /**< Whether we have recieved an x value but so far no corresponding y value */ bool x_valid; /**< Whether we have recieved an x value but so far no corresponding y value */
......
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