Newer
Older
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
/*=====================================================================
PIXHAWK Micro Air Vehicle Flying Robotics Toolkit
(c) 2009, 2010 PIXHAWK PROJECT <http://pixhawk.ethz.ch>
This file is part of the PIXHAWK project
PIXHAWK is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
PIXHAWK is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with PIXHAWK. If not, see <http://www.gnu.org/licenses/>.
======================================================================*/
/**
* @file
* @brief Line chart plot widget
*
* @author Lorenz Meier <mavteam@student.ethz.ch>
*
*/
#include <QDebug>
#include <QWidget>
#include <QHBoxLayout>
#include <QGridLayout>
#include <QComboBox>
#include <QToolButton>
#include <QScrollBar>
#include <QLabel>
#include <QMenu>
#include <QSpinBox>
#include <QColor>
#include <QPalette>
#include <QFileDialog>
#include <QDesktopServices>
#include <QMessageBox>
#include "LinechartWidget.h"
#include "LinechartPlot.h"
#include "LogCompressor.h"
LinechartWidget::LinechartWidget(int systemid, QWidget *parent) : QWidget(parent),
sysid(systemid),
activePlot(NULL),
curvesLock(new QReadWriteLock()),
plotWindowLock(),
curveListIndex(0),
curveListCounter(0),
listedCurves(new QList<QString>()),
curveLabels(new QMap<QString, QLabel*>()),
curveMeans(new QMap<QString, QLabel*>()),
curveMedians(new QMap<QString, QLabel*>()),
curveVariances(new QMap<QString, QLabel*>()),
curveMenu(new QMenu(this)),
logFile(new QFile()),
logindex(1),
logging(false),
logStartTime(0),
updateTimer(new QTimer())
{
// Add elements defined in Qt Designer
ui.setupUi(this);
this->setMinimumSize(300, 200);
// Add and customize curve list elements (left side)
curvesWidget = new QWidget(ui.curveListWidget);
ui.curveListWidget->setWidget(curvesWidget);
curvesWidgetLayout = new QGridLayout(curvesWidget);
curvesWidgetLayout->setMargin(2);
curvesWidgetLayout->setSpacing(4);
//curvesWidgetLayout->setSizeConstraint(QSizePolicy::Expanding);
curvesWidgetLayout->setAlignment(Qt::AlignTop);
curvesWidgetLayout->setColumnStretch(0, 0);
curvesWidgetLayout->setColumnStretch(1, 0);
curvesWidgetLayout->setColumnStretch(2, 80);
curvesWidgetLayout->setColumnStretch(3, 50);
curvesWidgetLayout->setColumnStretch(4, 50);
curvesWidgetLayout->setColumnStretch(5, 50);
// horizontalLayout->setColumnStretch(median, 50);
curvesWidgetLayout->setColumnStretch(6, 50);
// Create curve list headings
QLabel* label;
QLabel* value;
QLabel* mean;
QLabel* variance;
//horizontalLayout->addWidget(checkBox);
int labelRow = curvesWidgetLayout->rowCount();
selectAllCheckBox = new QCheckBox("", this);
connect(selectAllCheckBox, SIGNAL(clicked(bool)), this, SLOT(selectAllCurves(bool)));
curvesWidgetLayout->addWidget(selectAllCheckBox, labelRow, 0, 1, 2);
label = new QLabel(this);
curvesWidgetLayout->addWidget(label, labelRow, 2);
curvesWidgetLayout->addWidget(value, labelRow, 3);
// Unit
//curvesWidgetLayout->addWidget(new QLabel(tr("Unit")), labelRow, 4);
curvesWidgetLayout->addWidget(mean, labelRow, 5);
variance = new QLabel(this);
curvesWidgetLayout->addWidget(variance, labelRow, 6);
// Add and customize plot elements (right side)
// Create the layout
createLayout();
//connect(this, SIGNAL(plotWindowPositionUpdated(int)), scrollbar, SLOT(setValue(int)));
//connect(scrollbar, SIGNAL(sliderMoved(int)), this, SLOT(setPlotWindowPosition(int)));
updateTimer->setInterval(300);
connect(updateTimer, SIGNAL(timeout()), this, SLOT(refresh()));
LinechartWidget::~LinechartWidget()
{
writeSettings();
stopLogging();
delete listedCurves;
listedCurves = NULL;
}
void LinechartWidget::selectAllCurves(bool all)
{
QMap<QString, QLabel*>::iterator i;
for (i = curveLabels->begin(); i != curveLabels->end(); ++i) {
activePlot->setVisible(i.key(), all);
}
}
void LinechartWidget::writeSettings()
{
QSettings settings;
settings.beginGroup("LINECHART");
if (timeButton) settings.setValue("ENFORCE_GROUNDTIME", timeButton->isChecked());
if (unitsCheckBox) settings.setValue("SHOW_UNITS", unitsCheckBox->isChecked());
settings.endGroup();
settings.sync();
}
void LinechartWidget::readSettings()
{
QSettings settings;
settings.sync();
settings.beginGroup("LINECHART");
timeButton->setChecked(settings.value("ENFORCE_GROUNDTIME", timeButton->isChecked()).toBool());
activePlot->enforceGroundTime(settings.value("ENFORCE_GROUNDTIME", timeButton->isChecked()).toBool());
}
if (unitsCheckBox) unitsCheckBox->setChecked(settings.value("SHOW_UNITS").toBool());
settings.endGroup();
}
void LinechartWidget::createLayout()
{
// Create actions
createActions();
// Setup the plot group box area layout
QGridLayout* layout = new QGridLayout(ui.diagramGroupBox);
mainLayout = layout;
layout->setSpacing(4);
layout->setMargin(2);
// Create plot container widget
activePlot = new LinechartPlot(this, sysid);
// Activate automatic scrolling
activePlot->setAutoScroll(true);
// TODO Proper Initialization needed
// activePlot = getPlot(0);
// plotContainer->setPlot(activePlot);
layout->addWidget(activePlot, 0, 0, 1, 6);
// Linear scaling button
scalingLinearButton = createButton(this);
scalingLinearButton->setDefaultAction(setScalingLinear);
scalingLinearButton->setCheckable(true);
scalingLinearButton->setToolTip(tr("Set linear scale for Y axis"));
scalingLinearButton->setWhatsThis(tr("Set linear scale for Y axis"));
layout->addWidget(scalingLinearButton, 1, 0);
layout->setColumnStretch(0, 0);
// Logarithmic scaling button
scalingLogButton = createButton(this);
scalingLogButton->setDefaultAction(setScalingLogarithmic);
scalingLogButton->setCheckable(true);
scalingLogButton->setToolTip(tr("Set logarithmic scale for Y axis"));
scalingLogButton->setWhatsThis(tr("Set logarithmic scale for Y axis"));
layout->addWidget(scalingLogButton, 1, 1);
layout->setColumnStretch(1, 0);
// Averaging spin box
averageSpinBox = new QSpinBox(this);
averageSpinBox->setToolTip(tr("Sliding window size to calculate mean and variance"));
averageSpinBox->setWhatsThis(tr("Sliding window size to calculate mean and variance"));
averageSpinBox->setValue(200);
setAverageWindow(200);
averageSpinBox->setMaximum(9999);
layout->addWidget(averageSpinBox, 1, 2);
layout->setColumnStretch(2, 0);
connect(averageSpinBox, SIGNAL(valueChanged(int)), this, SLOT(setAverageWindow(int)));
// Log Button
logButton = new QToolButton(this);
logButton->setToolTip(tr("Start to log curve data into a CSV or TXT file"));
logButton->setWhatsThis(tr("Start to log curve data into a CSV or TXT file"));
logButton->setText(tr("Start Logging"));
layout->addWidget(logButton, 1, 3);
layout->setColumnStretch(3, 0);
connect(logButton, SIGNAL(clicked()), this, SLOT(startLogging()));
timeButton = new QCheckBox(this);
timeButton->setText(tr("Ground Time"));
timeButton->setToolTip(tr("Overwrite timestamp of data from vehicle with ground receive time. Helps if the plots are not visible because of missing or invalid onboard time."));
timeButton->setWhatsThis(tr("Overwrite timestamp of data from vehicle with ground receive time. Helps if the plots are not visible because of missing or invalid onboard time."));
bool gTimeDefault = true;
if (activePlot) activePlot->enforceGroundTime(gTimeDefault);
timeButton->setChecked(gTimeDefault);
layout->addWidget(timeButton, 1, 4);
layout->setColumnStretch(4, 0);
connect(timeButton, SIGNAL(clicked(bool)), activePlot, SLOT(enforceGroundTime(bool)));
connect(timeButton, SIGNAL(clicked()), this, SLOT(writeSettings()));
unitsCheckBox = new QCheckBox(this);
unitsCheckBox->setText(tr("Show units"));
unitsCheckBox->setChecked(true);
unitsCheckBox->setToolTip(tr("Enable unit display in curve list"));
unitsCheckBox->setWhatsThis(tr("Enable unit display in curve list"));
layout->addWidget(unitsCheckBox, 1, 5);
connect(unitsCheckBox, SIGNAL(clicked()), this, SLOT(writeSettings()));
// Add actions
averageSpinBox->setValue(activePlot->getAverageWindow());
// Connect notifications from the user interface to the plot
connect(this, SIGNAL(curveRemoved(QString)), activePlot, SLOT(hideCurve(QString)));
// Update scrollbar when plot window changes (via translator method setPlotWindowPosition()
connect(activePlot, SIGNAL(windowPositionChanged(quint64)), this, SLOT(setPlotWindowPosition(quint64)));
// Update plot when scrollbar is moved (via translator method setPlotWindowPosition()
connect(this, SIGNAL(plotWindowPositionUpdated(quint64)), activePlot, SLOT(setWindowPosition(quint64)));
// Set scaling
connect(scalingLinearButton, SIGNAL(clicked()), activePlot, SLOT(setLinearScaling()));
connect(scalingLogButton, SIGNAL(clicked()), activePlot, SLOT(setLogarithmicScaling()));
}
void LinechartWidget::appendData(int uasId, QString curve, double value, quint64 usec)
{
static const QString unit("-");
// Order matters here, first append to plot, then update curve list
activePlot->appendData(curve+unit, usec, value);
// Store data
QLabel* label = curveLabels->value(curve+unit, NULL);
// Make sure the curve will be created if it does not yet exist
addCurve(curve, unit);
}
}
// Log data
if (logging) {
if (activePlot->isVisible(curve+unit)) {
if (logStartTime == 0) logStartTime = usec;
qint64 time = usec - logStartTime;
if (time < 0) time = 0;
logFile->write(QString(QString::number(time) + "\t" + QString::number(uasId) + "\t" + curve + "\t" + QString::number(value,'g',18) + "\n").toLatin1());
logFile->flush();
}
}
}
void LinechartWidget::appendData(int uasId, const QString& curve, const QString& unit, double value, quint64 usec)
{
// Order matters here, first append to plot, then update curve list
activePlot->appendData(curve+unit, usec, value);
// Store data
QLabel* label = curveLabels->value(curve+unit, NULL);
// Make sure the curve will be created if it does not yet exist
//qDebug() << "ADDING CURVE IN APPENDDATE DOUBLE";
addCurve(curve, unit);
}
}
// Log data
if (logging) {
if (activePlot->isVisible(curve+unit)) {
if (logStartTime == 0) logStartTime = usec;
qint64 time = usec - logStartTime;
if (time < 0) time = 0;
logFile->write(QString(QString::number(time) + "\t" + QString::number(uasId) + "\t" + curve + "\t" + QString::number(value,'g',18) + "\n").toLatin1());
logFile->flush();
}
}
}
void LinechartWidget::appendData(int uasId, const QString& curve, const QString& unit, int value, quint64 usec)
// Order matters here, first append to plot, then update curve list
activePlot->appendData(curve+unit, usec, value);
QLabel* label = curveLabels->value(curve+unit, NULL);
// Make sure the curve will be created if it does not yet exist
addCurve(curve, unit);
// Add int data
intData.insert(curve+unit, value);
if (logging) {
if (activePlot->isVisible(curve+unit)) {
if (logStartTime == 0) logStartTime = usec;
qint64 time = usec - logStartTime;
if (time < 0) time = 0;
logFile->write(QString(QString::number(time) + "\t" + QString::number(uasId) + "\t" + curve + "\t" + QString::number(value) + "\n").toLatin1());
void LinechartWidget::refresh()
{
QString str;
// Value
QMap<QString, QLabel*>::iterator i;
for (i = curveLabels->begin(); i != curveLabels->end(); ++i) {
if (intData.contains(i.key())) {
double val = activePlot->getCurrentValue(i.key());
int intval = static_cast<int>(val);
if (intval >= 100000 || intval <= -100000) {
} else if (intval >= 10000 || intval <= -10000) {
} else if (intval >= 1000 || intval <= -1000) {
// Value
i.value()->setText(str);
}
// Mean
QMap<QString, QLabel*>::iterator j;
for (j = curveMeans->begin(); j != curveMeans->end(); ++j) {
double val = activePlot->getMean(j.key());
if (intval >= 100000 || intval <= -100000) {
} else if (intval >= 10000 || intval <= -10000) {
str.sprintf("% 11.2f", val);
} else if (intval >= 1000 || intval <= -1000) {
str.sprintf("% 11.6f", val);
}
j.value()->setText(str);
}
// QMap<QString, QLabel*>::iterator k;
// for (k = curveMedians->begin(); k != curveMedians->end(); ++k)
// {
// // Median
// str.sprintf("%+.2f", activePlot->getMedian(k.key()));
// k.value()->setText(str);
// }
for (l = curveVariances->begin(); l != curveVariances->end(); ++l) {
// Variance
str.sprintf("% 8.3e", activePlot->getVariance(l.key()));
l.value()->setText(str);
}
void LinechartWidget::startLogging()
{
// Store reference to file
// Append correct file ending if needed
bool abort = false;
if (!activePlot->anyCurveVisible()) {
QMessageBox msgBox;
msgBox.setIcon(QMessageBox::Critical);
msgBox.setText("No curves selected for logging.");
msgBox.setInformativeText("Please check all curves you want to log. Currently no data would be logged, aborting the logging.");
msgBox.setStandardButtons(QMessageBox::Ok);
msgBox.setDefaultButton(QMessageBox::Ok);
msgBox.exec();
return;
}
// Let user select the log file name
// QString("./pixhawk-log-" + date.toString("yyyy-MM-dd") + "-" + QString::number(logindex) + ".log")
QString fileName = QFileDialog::getSaveFileName(this, tr("Specify log file name"), QDesktopServices::storageLocation(QDesktopServices::DesktopLocation), tr("Logfile (*.csv *.txt);;"));
while (!(fileName.endsWith(".txt") || fileName.endsWith(".csv")) && !abort && fileName != "") {
QMessageBox msgBox;
msgBox.setIcon(QMessageBox::Critical);
msgBox.setText("Unsuitable file extension for logfile");
msgBox.setInformativeText("Please choose .txt or .csv as file extension. Click OK to change the file extension, cancel to not start logging.");
msgBox.setStandardButtons(QMessageBox::Ok | QMessageBox::Cancel);
msgBox.setDefaultButton(QMessageBox::Ok);
abort = true;
break;
}
fileName = QFileDialog::getSaveFileName(this, tr("Specify log file name"), QDesktopServices::storageLocation(QDesktopServices::DesktopLocation), tr("Logfile (*.txt *.csv);;"));
// Check if the user did not abort the file save dialog
logFile = new QFile(fileName);
if (logFile->open(QIODevice::WriteOnly | QIODevice::Text)) {
logStartTime = 0;
curvesWidget->setEnabled(false);
logindex++;
logButton->setText(tr("Stop logging"));
disconnect(logButton, SIGNAL(clicked()), this, SLOT(startLogging()));
connect(logButton, SIGNAL(clicked()), this, SLOT(stopLogging()));
}
}
}
void LinechartWidget::stopLogging()
{
logging = false;
curvesWidget->setEnabled(true);
logFile->flush();
logFile->close();
// Postprocess log file
compressor = new LogCompressor(logFile->fileName(), logFile->fileName());
connect(compressor, SIGNAL(finishedFile(QString)), this, SIGNAL(logfileWritten(QString)));
connect(compressor, SIGNAL(logProcessingStatusChanged(QString)), MainWindow::instance(), SLOT(showStatusMessage(QString)));
QMessageBox msgBox;
msgBox.setIcon(QMessageBox::Question);
msgBox.setText(tr("Starting Log Compression"));
msgBox.setInformativeText(tr("Should empty fields (e.g. due to packet drops) be filled with the previous value of the same variable (zero order hold)?"));
msgBox.setStandardButtons(QMessageBox::Yes | QMessageBox::No);
msgBox.setDefaultButton(QMessageBox::No);
int ret = msgBox.exec();
bool fill;
if (ret == QMessageBox::Yes)
{
fill = true;
}
else
{
fill = false;
}
compressor->startCompression(fill);
518
519
520
521
522
523
524
525
526
527
528
529
530
531
532
533
534
535
536
537
538
539
540
541
542
543
544
545
546
}
logButton->setText(tr("Start logging"));
disconnect(logButton, SIGNAL(clicked()), this, SLOT(stopLogging()));
connect(logButton, SIGNAL(clicked()), this, SLOT(startLogging()));
}
/**
* The average window size defines the width of the sliding average
* filter. It also defines the width of the sliding median filter.
*
* @param windowSize with (in values) of the sliding average/median filter. Minimum is 2
*/
void LinechartWidget::setAverageWindow(int windowSize)
{
if (windowSize > 1) activePlot->setAverageWindow(windowSize);
}
void LinechartWidget::createActions()
{
setScalingLogarithmic = new QAction("LOG", this);
setScalingLinear = new QAction("LIN", this);
}
/**
* @brief Add a curve to the curve list
*
* @param curve The id-string of the curve
* @see removeCurve()
**/
void LinechartWidget::addCurve(const QString& curve, const QString& unit)
LinechartPlot* plot = activePlot;
// QHBoxLayout *horizontalLayout;
QLabel* unitLabel;
int labelRow = curvesWidgetLayout->rowCount();
checkBox = new QCheckBox(this);
checkBox->setObjectName(curve+unit);
checkBox->setToolTip(tr("Enable the curve in the graph window"));
checkBox->setWhatsThis(tr("Enable the curve in the graph window"));
curvesWidgetLayout->addWidget(checkBox, labelRow, 0);
QWidget* colorIcon = new QWidget(this);
colorIcon->setMinimumSize(QSize(5, 14));
colorIcon->setMaximumSize(4, 14);
curvesWidgetLayout->addWidget(colorIcon, labelRow, 1);
label = new QLabel(this);
curvesWidgetLayout->addWidget(label, labelRow, 2);
QColor color = plot->getColorForCurve(curve+unit);
if(color.isValid()) {
QString colorstyle;
colorstyle = colorstyle.sprintf("QWidget { background-color: #%X%X%X; }", color.red(), color.green(), color.blue());
colorIcon->setStyleSheet(colorstyle);
colorIcon->setAutoFillBackground(true);
}
// Value
value->setStyleSheet(QString("QLabel {font-family:\"Courier\"; font-weight: bold;}"));
value->setToolTip(tr("Current value of %1 in %2 units").arg(curve, unit));
value->setWhatsThis(tr("Current value of %1 in %2 units").arg(curve, unit));
curveLabels->insert(curve+unit, value);
curvesWidgetLayout->addWidget(value, labelRow, 3);
// Unit
unitLabel = new QLabel(this);
unitLabel->setText(unit);
unitLabel->setStyleSheet(QString("QLabel {color: %1;}").arg("#AAAAAA"));
//qDebug() << "UNIT" << unit;
unitLabel->setToolTip(tr("Unit of ") + curve);
unitLabel->setWhatsThis(tr("Unit of ") + curve);
curvesWidgetLayout->addWidget(unitLabel, labelRow, 4);
unitLabel->setVisible(unitsCheckBox->isChecked());
connect(unitsCheckBox, SIGNAL(clicked(bool)), unitLabel, SLOT(setVisible(bool)));
mean->setStyleSheet(QString("QLabel {font-family:\"Courier\"; font-weight: bold;}"));
mean->setToolTip(tr("Arithmetic mean of %1 in %2 units").arg(curve, unit));
mean->setWhatsThis(tr("Arithmetic mean of %1 in %2 units").arg(curve, unit));
curveMeans->insert(curve+unit, mean);
curvesWidgetLayout->addWidget(mean, labelRow, 5);
// // Median
// median = new QLabel(form);
// value->setNum(0.00);
// curveMedians->insert(curve, median);
// horizontalLayout->addWidget(median);
variance = new QLabel(this);
variance->setStyleSheet(QString("QLabel {font-family:\"Courier\"; font-weight: bold;}"));
variance->setToolTip(tr("Variance of %1 in (%2)^2 units").arg(curve, unit));
variance->setWhatsThis(tr("Variance of %1 in (%2)^2 units").arg(curve, unit));
curveVariances->insert(curve+unit, variance);
curvesWidgetLayout->addWidget(variance, labelRow, 6);
/* Color picker
QColor color = QColorDialog::getColor(Qt::green, this);
if (color.isValid()) {
colorLabel->setText(color.name());
colorLabel->setPalette(QPalette(color));
colorLabel->setAutoFillBackground(true);
}
*/
// Set stretch factors so that the label gets the whole space
// Load visibility settings
// TODO
connect(selectAllCheckBox, SIGNAL(clicked(bool)), checkBox, SLOT(setChecked(bool)));
QObject::connect(checkBox, SIGNAL(clicked(bool)), this, SLOT(takeButtonClick(bool)));
QObject::connect(this, SIGNAL(curveVisible(QString, bool)), plot, SLOT(setVisible(QString, bool)));
// Set UI components to initial state
checkBox->setChecked(false);
plot->setVisible(curve+unit, false);
}
/**
* @brief Remove the curve from the curve list.
*
* @param curve The curve to remove
* @see addCurve()
**/
void LinechartWidget::removeCurve(QString curve)
Q_UNUSED(curve)
//TODO @todo Ensure that the button for a curve gets deleted when the original curve is deleted
// Remove name
void LinechartWidget::showEvent(QShowEvent* event)
{
Q_UNUSED(event);
setActive(true);
}
void LinechartWidget::hideEvent(QHideEvent* event)
{
Q_UNUSED(event);
setActive(false);
void LinechartWidget::setActive(bool active)
{
activePlot->setActive(active);
}
updateTimer->start(updateInterval);
updateTimer->stop();
}
}
/**
* @brief Set the position of the plot window.
* The plot covers only a portion of the complete time series. The scrollbar
* allows to select a window of the time series. The right edge of the window is
* defined proportional to the position of the scrollbar.
*
* @param scrollBarValue The value of the scrollbar, in the range from MIN_TIME_SCROLLBAR_VALUE to MAX_TIME_SCROLLBAR_VALUE
**/
void LinechartWidget::setPlotWindowPosition(int scrollBarValue)
{
703
704
705
706
707
708
709
710
711
712
713
714
715
716
717
718
719
720
721
722
723
724
725
726
727
728
729
730
731
732
733
734
735
736
737
738
739
740
741
742
743
744
745
746
747
plotWindowLock.lockForWrite();
// Disable automatic scrolling immediately
int scrollBarRange = (MAX_TIME_SCROLLBAR_VALUE - MIN_TIME_SCROLLBAR_VALUE);
double position = (static_cast<double>(scrollBarValue) - MIN_TIME_SCROLLBAR_VALUE) / scrollBarRange;
quint64 scrollInterval;
// Activate automatic scrolling if scrollbar is at the right edge
if(scrollBarValue > MAX_TIME_SCROLLBAR_VALUE - (MAX_TIME_SCROLLBAR_VALUE - MIN_TIME_SCROLLBAR_VALUE) * 0.01f) {
activePlot->setAutoScroll(true);
} else {
activePlot->setAutoScroll(false);
quint64 rightPosition;
/* If the data exceeds the plot window, choose the position according to the scrollbar position */
if(activePlot->getDataInterval() > activePlot->getPlotInterval()) {
scrollInterval = activePlot->getDataInterval() - activePlot->getPlotInterval();
rightPosition = activePlot->getMinTime() + activePlot->getPlotInterval() + (scrollInterval * position);
} else {
/* If the data interval is smaller as the plot interval, clamp the scrollbar to the right */
rightPosition = activePlot->getMinTime() + activePlot->getPlotInterval();
}
emit plotWindowPositionUpdated(rightPosition);
}
// The slider position must be mapped onto an interval of datainterval - plotinterval,
// because the slider position defines the right edge of the plot window. The leftmost
// slider position must therefore map to the start of the data interval + plot interval
// to ensure that the plot is not empty
// start> |-- plot interval --||-- (data interval - plotinterval) --| <end
//@TODO Add notification of scrollbar here
//plot->setWindowPosition(rightPosition);
plotWindowLock.unlock();
}
/**
* @brief Receive an updated plot window position.
* The plot window can be changed by the arrival of new data or by
* other user interaction. The scrollbar and other UI components
* can be notified by calling this method.
*
* @param position The absolute position of the right edge of the plot window, in milliseconds
**/
void LinechartWidget::setPlotWindowPosition(quint64 position)
{
plotWindowLock.lockForWrite();
// Calculate the relative position
double pos;
// A relative position makes only sense if the plot is filled
if(activePlot->getDataInterval() > activePlot->getPlotInterval()) {
//TODO @todo Implement the scrollbar enabling in a more elegant way
quint64 scrollInterval = position - activePlot->getMinTime() - activePlot->getPlotInterval();
pos = (static_cast<double>(scrollInterval) / (activePlot->getDataInterval() - activePlot->getPlotInterval()));
} else {
pos = 1;
}
plotWindowLock.unlock();
emit plotWindowPositionUpdated(static_cast<int>(pos * (MAX_TIME_SCROLLBAR_VALUE - MIN_TIME_SCROLLBAR_VALUE)));
}
/**
* @brief Set the time interval the plot displays.
* The time interval of the plot can be adjusted by this method. If the
* data covers less time than the interval, the plot will be filled from
* the right to left
*
* @param interval The time interval to plot
**/
void LinechartWidget::setPlotInterval(quint64 interval)
{
activePlot->setPlotInterval(interval);
}
/**
* @brief Take the click of a curve activation / deactivation button.
* This method allows to map a button to a plot curve.The text of the
* button must equal the curve name to activate / deactivate.
*
* @param checked The visibility of the curve: true to display the curve, false otherwise
**/
void LinechartWidget::takeButtonClick(bool checked)
{
QCheckBox* button = qobject_cast<QCheckBox*>(QObject::sender());
activePlot->setVisible(button->objectName(), checked);
}
}
/**
* @brief Factory method to create a new button.
*
* @param imagename The name of the image (should be placed at the standard icon location)
* @param text The button text
* @param parent The parent object (to ensure that the memory is freed after the deletion of the button)
**/
QToolButton* LinechartWidget::createButton(QWidget* parent)
{