Browse Source

Fixed Parameter view, made linechart feasible for multiple systems

QGC4.4
pixhawk 15 years ago
parent
commit
32c8de2ee4
  1. 8
      qgroundcontrol.pro
  2. 7
      src/comm/MAVLinkProtocol.cc
  3. 2
      src/uas/UASManager.cc
  4. 1
      src/uas/UASManager.h
  5. 16
      src/ui/MainWindow.cc
  6. 4
      src/ui/MainWindow.h
  7. 10
      src/ui/QGCParamWidget.cc
  8. 15
      src/ui/XMLCommProtocolWidget.cc
  9. 59
      src/ui/linechart/LinechartContainer.cc
  10. 59
      src/ui/linechart/LinechartContainer.h
  11. 23
      src/ui/linechart/LinechartPlot.cc
  12. 10
      src/ui/linechart/LinechartPlot.h
  13. 191
      src/ui/linechart/LinechartWidget.cc
  14. 74
      src/ui/linechart/LinechartWidget.h
  15. 66
      src/ui/linechart/Linecharts.cc
  16. 31
      src/ui/linechart/Linecharts.h
  17. 6
      src/ui/uas/UASListWidget.cc
  18. 25
      src/ui/uas/UASView.cc
  19. 4
      src/ui/uas/UASView.h

8
qgroundcontrol.pro

@ -83,7 +83,6 @@ HEADERS += src/MG.h \
src/ui/uas/UASInfoWidget.h \ src/ui/uas/UASInfoWidget.h \
src/ui/HUD.h \ src/ui/HUD.h \
src/ui/linechart/LinechartWidget.h \ src/ui/linechart/LinechartWidget.h \
src/ui/linechart/LinechartContainer.h \
src/ui/linechart/LinechartPlot.h \ src/ui/linechart/LinechartPlot.h \
src/ui/linechart/Scrollbar.h \ src/ui/linechart/Scrollbar.h \
src/ui/linechart/ScrollZoomer.h \ src/ui/linechart/ScrollZoomer.h \
@ -115,7 +114,8 @@ HEADERS += src/MG.h \
src/ui/param/ParamTreeItem.h \ src/ui/param/ParamTreeItem.h \
src/ui/param/ParamTreeModel.h \ src/ui/param/ParamTreeModel.h \
src/ui/QGCParamWidget.h \ src/ui/QGCParamWidget.h \
src/ui/QGCSensorSettingsWidget.h src/ui/QGCSensorSettingsWidget.h \
src/ui/linechart/Linecharts.h
SOURCES += src/main.cc \ SOURCES += src/main.cc \
src/Core.cc \ src/Core.cc \
src/uas/UASManager.cc \ src/uas/UASManager.cc \
@ -133,7 +133,6 @@ SOURCES += src/main.cc \
src/ui/uas/UASInfoWidget.cc \ src/ui/uas/UASInfoWidget.cc \
src/ui/HUD.cc \ src/ui/HUD.cc \
src/ui/linechart/LinechartWidget.cc \ src/ui/linechart/LinechartWidget.cc \
src/ui/linechart/LinechartContainer.cc \
src/ui/linechart/LinechartPlot.cc \ src/ui/linechart/LinechartPlot.cc \
src/ui/linechart/Scrollbar.cc \ src/ui/linechart/Scrollbar.cc \
src/ui/linechart/ScrollZoomer.cc \ src/ui/linechart/ScrollZoomer.cc \
@ -164,5 +163,6 @@ SOURCES += src/main.cc \
src/ui/param/ParamTreeItem.cc \ src/ui/param/ParamTreeItem.cc \
src/ui/param/ParamTreeModel.cc \ src/ui/param/ParamTreeModel.cc \
src/ui/QGCParamWidget.cc \ src/ui/QGCParamWidget.cc \
src/ui/QGCSensorSettingsWidget.cc src/ui/QGCSensorSettingsWidget.cc \
src/ui/linechart/Linecharts.cc
RESOURCES = mavground.qrc RESOURCES = mavground.qrc

7
src/comm/MAVLinkProtocol.cc

@ -122,6 +122,13 @@ void MAVLinkProtocol::receiveBytes(LinkInterface* link)
// of its existence, as it only then can send and receive // of its existence, as it only then can send and receive
// it's first messages. // it's first messages.
// FIXME Current debugging
// check if the UAS has the same id like this system
if (message.sysid == getSystemId())
{
qDebug() << "WARNING\nWARNING\nWARNING\nWARNING\nWARNING\nWARNING\nWARNING\n\n RECEIVED MESSAGE FROM THIS SYSTEM WITH ID" << message.msgid << "FROM COMPONENT" << message.compid;
}
// First create new UAS object // First create new UAS object
uas = new UAS(this, message.sysid); uas = new UAS(this, message.sysid);
// Make UAS aware that this link can be used to communicate with the actual robot // Make UAS aware that this link can be used to communicate with the actual robot

2
src/uas/UASManager.cc

@ -83,6 +83,7 @@ void UASManager::addUAS(UASInterface* uas)
{ {
activeUAS = uas; activeUAS = uas;
emit activeUASSet(uas); emit activeUASSet(uas);
emit activeUASSet(uas->getUASID());
} }
} }
@ -170,6 +171,7 @@ void UASManager::setActiveUAS(UASInterface* uas)
qDebug() << __FILE__ << ":" << __LINE__ << " ACTIVE UAS SET TO: " << uas->getUASName(); qDebug() << __FILE__ << ":" << __LINE__ << " ACTIVE UAS SET TO: " << uas->getUASName();
emit activeUASSet(uas); emit activeUASSet(uas);
emit activeUASSet(uas->getUASID());
} }
} }

1
src/uas/UASManager.h

@ -166,6 +166,7 @@ protected:
signals: signals:
void UASCreated(UASInterface* UAS); void UASCreated(UASInterface* UAS);
void activeUASSet(UASInterface* UAS); void activeUASSet(UASInterface* UAS);
void activeUASSet(int systemId);
}; };

16
src/ui/MainWindow.cc

@ -71,9 +71,10 @@ MainWindow::MainWindow(QWidget *parent) : QMainWindow(parent),
// Initialize views, NOT show them yet, only initialize model and controller // Initialize views, NOT show them yet, only initialize model and controller
centerStack = new QStackedWidget(this); centerStack = new QStackedWidget(this);
linechart = new LinechartWidget(this); linechart = new Linecharts(this);
linechart->setActive(false); linechart->setActive(false);
connect(UASManager::instance(), SIGNAL(activeUASSet(UASInterface*)), linechart, SLOT(setActivePlot(UASInterface*))); connect(UASManager::instance(), SIGNAL(UASCreated(UASInterface*)), linechart, SLOT(addSystem(UASInterface*)));
connect(UASManager::instance(), SIGNAL(activeUASSet(int)), linechart, SLOT(selectSystem(int)));
centerStack->addWidget(linechart); centerStack->addWidget(linechart);
control = new UASControlWidget(this); control = new UASControlWidget(this);
//controlDock = new QDockWidget(this); //controlDock = new QDockWidget(this);
@ -312,7 +313,7 @@ void MainWindow::addLink(LinkInterface *link)
MAVLinkSimulationLink* sim = dynamic_cast<MAVLinkSimulationLink*>(link); MAVLinkSimulationLink* sim = dynamic_cast<MAVLinkSimulationLink*>(link);
if (sim) if (sim)
{ {
connect(sim, SIGNAL(valueChanged(int,QString,double,quint64)), linechart, SLOT(appendData(int,QString,double,quint64))); //connect(sim, SIGNAL(valueChanged(int,QString,double,quint64)), linechart, SLOT(appendData(int,QString,double,quint64)));
connect(ui.actionSimulate, SIGNAL(triggered(bool)), sim, SLOT(connectLink(bool))); connect(ui.actionSimulate, SIGNAL(triggered(bool)), sim, SLOT(connectLink(bool)));
} }
} }
@ -322,15 +323,6 @@ void MainWindow::UASCreated(UASInterface* uas)
// Connect the UAS to the full user interface // Connect the UAS to the full user interface
//ui.menuConnected_Systems->addAction(QIcon(":/images/mavs/generic.svg"), tr("View ") + uas->getUASName(), uas, SLOT(setSelected())); //ui.menuConnected_Systems->addAction(QIcon(":/images/mavs/generic.svg"), tr("View ") + uas->getUASName(), uas, SLOT(setSelected()));
// Line chart
// FIXME DO THIS ONLY FOR THE FIRST CONNECTED SYSTEM
static bool sysPresent = false;
if (!sysPresent)
{
connect(uas, SIGNAL(valueChanged(int,QString,double,quint64)), linechart, SLOT(appendData(int,QString,double,quint64)), Qt::QueuedConnection);
sysPresent = true;
}
// FIXME Should be not inside the mainwindow // FIXME Should be not inside the mainwindow
connect(uas, SIGNAL(textMessageReceived(int,int,QString)), debugConsole, SLOT(receiveTextMessage(int,int,QString))); connect(uas, SIGNAL(textMessageReceived(int,int,QString)), debugConsole, SLOT(receiveTextMessage(int,int,QString)));

4
src/ui/MainWindow.h

@ -42,7 +42,7 @@ This file is part of the PIXHAWK project
#include "UASInterface.h" #include "UASInterface.h"
#include "UASManager.h" #include "UASManager.h"
#include "UASControlWidget.h" #include "UASControlWidget.h"
#include "LinechartWidget.h" #include "Linecharts.h"
#include "UASInfoWidget.h" #include "UASInfoWidget.h"
#include "WaypointList.h" #include "WaypointList.h"
#include "CameraView.h" #include "CameraView.h"
@ -132,7 +132,7 @@ protected:
QSettings settings; QSettings settings;
UASControlWidget* control; UASControlWidget* control;
LinechartWidget* linechart; Linecharts* linechart;
UASInfoWidget* info; UASInfoWidget* info;
CameraView* camera; CameraView* camera;
UASListWidget* list; UASListWidget* list;

10
src/ui/QGCParamWidget.cc

@ -130,7 +130,15 @@ void QGCParamWidget::addParameter(int uas, int component, QString parameterName,
{ {
Q_UNUSED(uas); Q_UNUSED(uas);
// Insert parameter into map // Insert parameter into map
//tree->appendParam(component, parameterName, value);
QString splitToken = "_";
// Check if auto-grouping can work
/*
if (parameterName.contains(splitToken))
{
QString parent = parameterName.section(splitToken, 0, 0, QString::SectionSkipEmpty);
QString children = parameterName.section(splitToken, 1, -1, QString::SectionSkipEmpty);
}*/
QStringList plist; QStringList plist;
plist.append(parameterName); plist.append(parameterName);
plist.append(QString::number(value)); plist.append(QString::number(value));

15
src/ui/XMLCommProtocolWidget.cc

@ -1,6 +1,7 @@
#include <QFileDialog> #include <QFileDialog>
#include <QTextBrowser> #include <QTextBrowser>
#include <QMessageBox> #include <QMessageBox>
#include <QSettings>
#include "XMLCommProtocolWidget.h" #include "XMLCommProtocolWidget.h"
#include "ui_XMLCommProtocolWidget.h" #include "ui_XMLCommProtocolWidget.h"
@ -23,10 +24,12 @@ XMLCommProtocolWidget::XMLCommProtocolWidget(QWidget *parent) :
void XMLCommProtocolWidget::selectXMLFile() void XMLCommProtocolWidget::selectXMLFile()
{ {
qDebug() << "OPENING XML FILE";
//QString fileName = QFileDialog::getOpenFileName(this, tr("Load Protocol Definition File"), ".", "*.xml"); //QString fileName = QFileDialog::getOpenFileName(this, tr("Load Protocol Definition File"), ".", "*.xml");
QSettings settings;
const QString mavlinkXML = "MAVLINK_XML_FILE";
QString dirPath = settings.value(mavlinkXML, QCoreApplication::applicationDirPath() + "../").toString();
QFileDialog dialog; QFileDialog dialog;
dialog.setDirectory(dirPath);
dialog.setFileMode(QFileDialog::AnyFile); dialog.setFileMode(QFileDialog::AnyFile);
dialog.setFilter(tr("MAVLink XML (*.xml)")); dialog.setFilter(tr("MAVLink XML (*.xml)"));
dialog.setViewMode(QFileDialog::Detail); dialog.setViewMode(QFileDialog::Detail);
@ -40,6 +43,8 @@ void XMLCommProtocolWidget::selectXMLFile()
{ {
m_ui->fileNameLabel->setText(fileNames.first()); m_ui->fileNameLabel->setText(fileNames.first());
QFile file(fileNames.first()); QFile file(fileNames.first());
// Store filename for next time
settings.setValue(mavlinkXML, fileNames.first());
if (file.open(QIODevice::ReadOnly | QIODevice::Text)) if (file.open(QIODevice::ReadOnly | QIODevice::Text))
{ {
const QString instanceText(QString::fromUtf8(file.readAll())); const QString instanceText(QString::fromUtf8(file.readAll()));
@ -80,7 +85,11 @@ void XMLCommProtocolWidget::setXML(const QString& xml)
void XMLCommProtocolWidget::selectOutputDirectory() void XMLCommProtocolWidget::selectOutputDirectory()
{ {
QSettings settings;
const QString mavlinkOutputDir = "MAVLINK_OUTPUT_DIR";
QString dirPath = settings.value(mavlinkOutputDir, QCoreApplication::applicationDirPath() + "../").toString();
QFileDialog dialog; QFileDialog dialog;
dialog.setDirectory(dirPath);
dialog.setFileMode(QFileDialog::Directory); dialog.setFileMode(QFileDialog::Directory);
dialog.setFilter(tr("MAVLink XML (*.xml)")); dialog.setFilter(tr("MAVLink XML (*.xml)"));
dialog.setViewMode(QFileDialog::Detail); dialog.setViewMode(QFileDialog::Detail);
@ -93,6 +102,8 @@ void XMLCommProtocolWidget::selectOutputDirectory()
if (fileNames.size() > 0) if (fileNames.size() > 0)
{ {
m_ui->outputDirNameLabel->setText(fileNames.first()); m_ui->outputDirNameLabel->setText(fileNames.first());
// Store directory for next time
settings.setValue(mavlinkOutputDir, fileNames.first());
//QFile file(fileName); //QFile file(fileName);
} }
} }

59
src/ui/linechart/LinechartContainer.cc

@ -1,59 +0,0 @@
/*=====================================================================
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 Brief Description
*
* @author Lorenz Meier <mavteam@student.ethz.ch>
*
*/
#include <QHBoxLayout>
#include <LinechartContainer.h>
LinechartContainer::LinechartContainer(QWidget* parent) : QWidget(parent)
{
// setMinimumHeight(300);
// setMinimumWidth(450);
setContentsMargins(0, 0, 0, 0); // No margin around container content
}
LinechartContainer::~LinechartContainer()
{
}
LinechartPlot* LinechartContainer::getPlot()
{
return plot;
}
void LinechartContainer::setPlot(LinechartPlot* plot)
{
this->plot = plot;
delete layout();
QHBoxLayout* currentLayout = new QHBoxLayout(this);
currentLayout->addWidget(plot);
setLayout(currentLayout);
}

59
src/ui/linechart/LinechartContainer.h

@ -1,59 +0,0 @@
/*=====================================================================
PIXHAWK Micro Air Vehicle Flying Robotics Toolkit
(c) 2009 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 Brief Description
*
* @author Lorenz Meier <mavteam@student.ethz.ch>
*
*/
#ifndef _LINECHARTCONTAINER_H_
#define _LINECHARTCONTAINER_H_
#include <QWidget>
#include <LinechartPlot.h>
/**
* @brief Container for line chart plots
*
* @see LinechartPlot
* @see LinechartWidget
*/
class LinechartContainer : public QWidget {
Q_OBJECT
public:
LinechartContainer(QWidget *parent = NULL);
~LinechartContainer();
LinechartPlot* getPlot();
public slots:
void setPlot(LinechartPlot* plot);
private:
LinechartPlot* plot;
};
#endif /* _LINECHARTCONTAINER_H_ */

23
src/ui/linechart/LinechartPlot.cc

@ -55,9 +55,9 @@ maxTime(QUINT64_MIN),
maxInterval(MAX_STORAGE_INTERVAL), maxInterval(MAX_STORAGE_INTERVAL),
timeScaleStep(DEFAULT_SCALE_INTERVAL), // 10 seconds timeScaleStep(DEFAULT_SCALE_INTERVAL), // 10 seconds
automaticScrollActive(false), automaticScrollActive(false),
m_active(true),
d_data(NULL), d_data(NULL),
d_curve(NULL), d_curve(NULL)
m_active(true)
{ {
this->plotid = plotid; this->plotid = plotid;
this->plotInterval = interval; this->plotInterval = interval;
@ -161,6 +161,14 @@ int LinechartPlot::getPlotId()
/** /**
* @param id curve identifier * @param id curve identifier
*/ */
double LinechartPlot::getCurrentValue(QString id)
{
return data.value(id)->getCurrentValue();
}
/**
* @param id curve identifier
*/
double LinechartPlot::getMean(QString id) double LinechartPlot::getMean(QString id)
{ {
return data.value(id)->getMean(); return data.value(id)->getMean();
@ -280,7 +288,7 @@ void LinechartPlot::addCurve(QString id)
data.insert(id, dataset); data.insert(id, dataset);
// Notify connected components about new curve // Notify connected components about new curve
emit curveAdded(plotid, id); emit curveAdded(id);
} }
QColor LinechartPlot::getNextColor() QColor LinechartPlot::getNextColor()
@ -337,7 +345,7 @@ void LinechartPlot::setCurveColor(QString id, QColor color)
QwtPlotCurve* curve = curves.value(id); QwtPlotCurve* curve = curves.value(id);
curve->setPen(color); curve->setPen(color);
emit colorSet(plotid, id, color); emit colorSet(id, color);
} }
/** /**
@ -635,7 +643,7 @@ void LinechartPlot::removeAllData()
curve = NULL; curve = NULL;
// Notify connected components about the removal // Notify connected components about the removal
emit curveRemoved(plotid, i.key()); emit curveRemoved(i.key());
} }
// Delete data // Delete data
@ -814,6 +822,11 @@ double TimeSeriesData::getMedian()
return median; return median;
} }
double TimeSeriesData::getCurrentValue()
{
return ms.last();
}
/** /**
* @brief Get the zero (center) value in the data set * @brief Get the zero (center) value in the data set
* The zero value is not a statistical value, but instead manually defined * The zero value is not a statistical value, but instead manually defined

10
src/ui/linechart/LinechartPlot.h

@ -132,6 +132,8 @@ public:
double getMean(); double getMean();
/** @brief Get the short-term median */ /** @brief Get the short-term median */
double getMedian(); double getMedian();
/** @brief Get the current value */
double TimeSeriesData::getCurrentValue();
void setZeroValue(double zeroValue); void setZeroValue(double zeroValue);
void setInterval(quint64 ms); void setInterval(quint64 ms);
void setAverageWindowSize(int windowSize); void setAverageWindowSize(int windowSize);
@ -203,6 +205,8 @@ public:
double getMean(QString id); double getMean(QString id);
/** @brief Get the short-term median of a curve */ /** @brief Get the short-term median of a curve */
double getMedian(QString id); double getMedian(QString id);
/** @brief Get the last inserted value */
double getCurrentValue(QString id);
static const int SCALE_ABSOLUTE = 0; static const int SCALE_ABSOLUTE = 0;
static const int SCALE_BEST_FIT = 1; static const int SCALE_BEST_FIT = 1;
@ -303,20 +307,20 @@ signals:
* *
* @param color The curve color in the diagram * @param color The curve color in the diagram
**/ **/
void curveAdded(int uasid, QString idstring); void curveAdded(QString idstring);
/** /**
* @brief This signal is emitted when a curve gets assigned a color * @brief This signal is emitted when a curve gets assigned a color
* *
* @param idstring The id-string of the curve * @param idstring The id-string of the curve
* @param color The curve color in the diagram * @param color The curve color in the diagram
**/ **/
void colorSet(int uasid, QString idstring, QColor color); void colorSet(QString idstring, QColor color);
/** /**
* @brief This signal is emitted when a curve is removed * @brief This signal is emitted when a curve is removed
* *
* @param name The id-string of the curve * @param name The id-string of the curve
**/ **/
void curveRemoved(int uasid, QString name); void curveRemoved(QString name);
/** /**
* @brief This signal is emitted when the plot window position changes * @brief This signal is emitted when the plot window position changes
* *

191
src/ui/linechart/LinechartWidget.cc

@ -49,19 +49,22 @@ This file is part of the PIXHAWK project
#include "MG.h" #include "MG.h"
LinechartWidget::LinechartWidget(QWidget *parent) : QWidget(parent), LinechartWidget::LinechartWidget(int systemid, QWidget *parent) : QWidget(parent),
sysid(systemid),
activePlot(NULL),
curvesLock(new QReadWriteLock()), curvesLock(new QReadWriteLock()),
plotWindowLock(),
curveListIndex(0), curveListIndex(0),
curveListCounter(0), curveListCounter(0),
activePlot(NULL),
curveMenu(new QMenu(this)),
listedCurves(new QList<QString>()), listedCurves(new QList<QString>()),
curveLabels(new QMap<QString, QLabel*>()), curveLabels(new QMap<QString, QLabel*>()),
curveMeans(new QMap<QString, QLabel*>()), curveMeans(new QMap<QString, QLabel*>()),
curveMedians(new QMap<QString, QLabel*>()), curveMedians(new QMap<QString, QLabel*>()),
curveMenu(new QMenu(this)),
logFile(new QFile()), logFile(new QFile()),
logindex(1), logindex(1),
logging(false) logging(false),
updateTimer(new QTimer())
{ {
// Add elements defined in Qt Designer // Add elements defined in Qt Designer
ui.setupUi(this); ui.setupUi(this);
@ -78,15 +81,16 @@ logging(false)
// Add and customize plot elements (right side) // Add and customize plot elements (right side)
// Instantiate the actual plot for multiple vehicles
plots = QMap<int, LinechartPlot*>();
// Create the layout // Create the layout
createLayout(); createLayout();
// Add the last actions // Add the last actions
connect(this, SIGNAL(plotWindowPositionUpdated(int)), scrollbar, SLOT(setValue(int))); connect(this, SIGNAL(plotWindowPositionUpdated(int)), scrollbar, SLOT(setValue(int)));
connect(scrollbar, SIGNAL(sliderMoved(int)), this, SLOT(setPlotWindowPosition(int))); connect(scrollbar, SIGNAL(sliderMoved(int)), this, SLOT(setPlotWindowPosition(int)));
updateTimer->setInterval(100);
connect(updateTimer, SIGNAL(timeout()), this, SLOT(refresh()));
updateTimer->start();
} }
LinechartWidget::~LinechartWidget() { LinechartWidget::~LinechartWidget() {
@ -95,11 +99,6 @@ LinechartWidget::~LinechartWidget() {
listedCurves = NULL; listedCurves = NULL;
} }
void LinechartWidget::setPlot(int uasId)
{
setActivePlot(uasId);
}
void LinechartWidget::createLayout() void LinechartWidget::createLayout()
{ {
// Create actions // Create actions
@ -112,13 +111,15 @@ void LinechartWidget::createLayout()
layout->setMargin(2); layout->setMargin(2);
// Create plot container widget // Create plot container widget
plotContainer = new LinechartContainer(ui.diagramGroupBox); activePlot = new LinechartPlot(this, sysid);
// Activate automatic scrolling
activePlot->setAutoScroll(true);
// TODO Proper Initialization needed // TODO Proper Initialization needed
// activePlot = getPlot(0); // activePlot = getPlot(0);
// plotContainer->setPlot(activePlot); // plotContainer->setPlot(activePlot);
layout->addWidget(plotContainer, 0, 0, 1, 5); layout->addWidget(activePlot, 0, 0, 1, 5);
layout->setRowStretch(0, 10); layout->setRowStretch(0, 10);
layout->setRowStretch(1, 0); layout->setRowStretch(1, 0);
@ -167,35 +168,47 @@ void LinechartWidget::createLayout()
layout->setColumnStretch(4, 10); layout->setColumnStretch(4, 10);
ui.diagramGroupBox->setLayout(layout); ui.diagramGroupBox->setLayout(layout);
// Add actions
averageSpinBox->setValue(activePlot->getAverageWindow());
// Connect notifications from the user interface to the plot
connect(this, SIGNAL(curveRemoved(QString)), activePlot, SLOT(hideCurve(QString)));
connect(this, SIGNAL(curveSet(QString, int)), activePlot, SLOT(showCurve(QString, int)));
// Connect notifications from the plot to the user interface
connect(activePlot, SIGNAL(curveAdded(QString)), this, SLOT(addCurve(QString)));
connect(activePlot, SIGNAL(curveRemoved(QString)), this, SLOT(removeCurve(QString)));
// Scrollbar
// 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) void LinechartWidget::appendData(int uasId, QString curve, double value, quint64 usec)
{ {
// Order matters here, first append to plot, then update curve list // Order matters here, first append to plot, then update curve list
LinechartPlot* currPlot = getPlot(uasId); activePlot->appendData(curve, usec, value);
currPlot->appendData(curve, usec, value); // Store data
if(activePlot == NULL) setActivePlot(uasId);
QString str;
str.sprintf("%+.2f", value);
QLabel* label = curveLabels->value(curve, NULL); QLabel* label = curveLabels->value(curve, NULL);
// Make sure the curve will be created if it does not yet exist // Make sure the curve will be created if it does not yet exist
if(!label) if(!label)
{ {
addCurve(uasId, curve); addCurve(curve);
} }
// Value
curveLabels->value(curve)->setText(str);
// Mean
str.sprintf("%+.2f", currPlot->getMean(curve));
curveMeans->value(curve)->setText(str);
// Median
str.sprintf("%+.2f", currPlot->getMedian(curve));
curveMedians->value(curve)->setText(str);
// Log data // Log data
if (logging) if (logging)
{ {
if (currPlot->isVisible(curve)) if (activePlot->isVisible(curve))
{ {
logFile->write(QString(QString::number(usec) + "\t" + QString::number(uasId) + "\t" + curve + "\t" + QString::number(value) + "\n").toLatin1()); logFile->write(QString(QString::number(usec) + "\t" + QString::number(uasId) + "\t" + curve + "\t" + QString::number(value) + "\n").toLatin1());
logFile->flush(); logFile->flush();
@ -203,6 +216,33 @@ void LinechartWidget::appendData(int uasId, QString curve, double value, quint64
} }
} }
void LinechartWidget::refresh()
{
QString str;
QMap<QString, QLabel*>::iterator i;
for (i = curveLabels->begin(); i != curveLabels->end(); ++i)
{
str.sprintf("%+.2f", activePlot->getCurrentValue(i.key()));
// Value
i.value()->setText(str);
}
// Mean
QMap<QString, QLabel*>::iterator j;
for (j = curveMeans->begin(); j != curveMeans->end(); ++j)
{
str.sprintf("%+.2f", activePlot->getMean(j.key()));
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);
}
}
void LinechartWidget::startLogging() void LinechartWidget::startLogging()
{ {
@ -219,10 +259,6 @@ void LinechartWidget::startLogging()
logButton->setText(tr("Stop logging")); logButton->setText(tr("Stop logging"));
disconnect(logButton, SIGNAL(clicked()), this, SLOT(startLogging())); disconnect(logButton, SIGNAL(clicked()), this, SLOT(startLogging()));
connect(logButton, SIGNAL(clicked()), this, SLOT(stopLogging())); connect(logButton, SIGNAL(clicked()), this, SLOT(stopLogging()));
// Write file header
//logFile->write(QString("MILLISECONDS\tID\t\"NAME\"\tVALUE\n").toLatin1());
//logFile->flush();
} }
else else
{ {
@ -268,13 +304,14 @@ void LinechartWidget::createActions()
* @param curve The id-string of the curve * @param curve The id-string of the curve
* @see removeCurve() * @see removeCurve()
**/ **/
void LinechartWidget::addCurve(int uasid, QString curve) void LinechartWidget::addCurve(QString curve)
{ {
curvesWidgetLayout->addWidget(createCurveItem(getPlot(uasid), curve)); curvesWidgetLayout->addWidget(createCurveItem(curve));
} }
QWidget* LinechartWidget::createCurveItem(LinechartPlot* plot, QString curve) QWidget* LinechartWidget::createCurveItem(QString curve)
{ {
LinechartPlot* plot = activePlot;
QWidget* form = new QWidget(this); QWidget* form = new QWidget(this);
QHBoxLayout *horizontalLayout; QHBoxLayout *horizontalLayout;
QCheckBox *checkBox; QCheckBox *checkBox;
@ -366,22 +403,10 @@ QWidget* LinechartWidget::createCurveItem(LinechartPlot* plot, QString curve)
* @param curve The curve to remove * @param curve The curve to remove
* @see addCurve() * @see addCurve()
**/ **/
void LinechartWidget::removeCurve(int uasid, QString curve) void LinechartWidget::removeCurve(QString curve)
{ {
//TODO @todo Ensure that the button for a curve gets deleted when the original curve is deleted //TODO @todo Ensure that the button for a curve gets deleted when the original curve is deleted
} // Remove name
/**
* @brief Get the plot widget.
*
* @return The plot widget
**/
LinechartPlot* LinechartWidget::getPlot(int plotid) {
if(!plots.contains(plotid))
{
plots.insert(plotid, new LinechartPlot(ui.diagramGroupBox, plotid));
}
return plots.value(plotid);
} }
void LinechartWidget::setActive(bool active) void LinechartWidget::setActive(bool active)
@ -390,67 +415,13 @@ void LinechartWidget::setActive(bool active)
{ {
activePlot->setActive(active); activePlot->setActive(active);
} }
} if (active)
void LinechartWidget::setActivePlot(UASInterface* uas)
{
setActivePlot(uas->getUASID());
}
void LinechartWidget::setActivePlot(int uasId)
{
if (!activePlot || uasId != activePlot->getPlotId())
{ {
// Make sure there is an active plot, else the next updateTimer->start();
// if clause will access a null pointer }
if (!activePlot) else
{ {
// Get plot, if it does not exist yet it will be automatically created updateTimer->stop();
activePlot = getPlot(uasId);
}
// Remove current plot
disconnect(this, SIGNAL(curveRemoved(QString)), activePlot, SLOT(hideCurve(QString)));
disconnect(this, SIGNAL(curveSet(QString, int)), activePlot, SLOT(showCurve(QString, int)));
disconnect(activePlot, SIGNAL(curveAdded(int, QString)), this, SLOT(addCurve(int, QString)));
disconnect(activePlot, SIGNAL(curveRemoved(int, QString)), this, SLOT(removeCurve(int, QString)));
disconnect(activePlot, SIGNAL(windowPositionChanged(quint64)), this, SLOT(setPlotWindowPosition(quint64)));
disconnect(this, SIGNAL(plotWindowPositionUpdated(quint64)), activePlot, SLOT(setWindowPosition(quint64)));
disconnect(scalingLinearButton, SIGNAL(clicked()), activePlot, SLOT(setLinearScaling()));
disconnect(scalingLogButton, SIGNAL(clicked()), activePlot, SLOT(setLogarithmicScaling()));
// Get plot, if it does not exist yet it will be automatically created
activePlot = getPlot(uasId);
plotContainer->setPlot(activePlot);
qDebug() << "LinechartWidget::setPlot(): Setting plot to UAS ID:" << uasId;
// Activate automatic scrolling
activePlot->setAutoScroll(true);
// Add actions
averageSpinBox->setValue(activePlot->getAverageWindow());
// Connect notifications from the user interface to the plot
connect(this, SIGNAL(curveRemoved(QString)), activePlot, SLOT(hideCurve(QString)));
connect(this, SIGNAL(curveSet(QString, int)), activePlot, SLOT(showCurve(QString, int)));
// Connect notifications from the plot to the user interface
connect(activePlot, SIGNAL(curveAdded(int, QString)), this, SLOT(addCurve(int, QString)));
connect(activePlot, SIGNAL(curveRemoved(int, QString)), this, SLOT(removeCurve(int, QString)));
// Scrollbar
// 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()));
} }
} }

74
src/ui/linechart/LinechartWidget.h

@ -46,9 +46,9 @@ This file is part of the PIXHAWK project
#include <QLabel> #include <QLabel>
#include <QReadWriteLock> #include <QReadWriteLock>
#include <QToolButton> #include <QToolButton>
#include <QTimer>
#include <qwt_plot_curve.h> #include <qwt_plot_curve.h>
#include "LinechartContainer.h"
#include "LinechartPlot.h" #include "LinechartPlot.h"
#include "UASInterface.h" #include "UASInterface.h"
#include "ui_Linechart.h" #include "ui_Linechart.h"
@ -63,81 +63,62 @@ class LinechartWidget : public QWidget {
Q_OBJECT Q_OBJECT
public: public:
LinechartWidget(QWidget *parent = 0); LinechartWidget(int systemid, QWidget *parent = 0);
~LinechartWidget(); ~LinechartWidget();
LinechartPlot* getPlot(int uasId);
static const int MIN_TIME_SCROLLBAR_VALUE = 0; ///< The minimum scrollbar value static const int MIN_TIME_SCROLLBAR_VALUE = 0; ///< The minimum scrollbar value
static const int MAX_TIME_SCROLLBAR_VALUE = 16383; ///< The maximum scrollbar value static const int MAX_TIME_SCROLLBAR_VALUE = 16383; ///< The maximum scrollbar value
public slots: public slots:
void addCurve(int uasid, QString curve); void addCurve(QString curve);
void removeCurve(int uasid, QString curve); void removeCurve(QString curve);
void appendData(int uasid, QString curve, double data, quint64 usec); void appendData(int sysId, QString curve, double data, quint64 usec);
void takeButtonClick(bool checked); void takeButtonClick(bool checked);
void setPlotWindowPosition(int scrollBarValue); void setPlotWindowPosition(int scrollBarValue);
void setPlotWindowPosition(quint64 position); void setPlotWindowPosition(quint64 position);
void setPlotInterval(quint64 interval); void setPlotInterval(quint64 interval);
void setActivePlot(int uasid);
void setActivePlot(UASInterface* uas);
void setActive(bool active); void setActive(bool active);
/** @brief Set the number of values to average over */ /** @brief Set the number of values to average over */
void setAverageWindow(int windowSize); void setAverageWindow(int windowSize);
/** @brief Start logging to file */ /** @brief Start logging to file */
void startLogging(); void startLogging();
/** @brief Stop logging to file */ /** @brief Stop logging to file */
void stopLogging(); void stopLogging();
/** @brief Refresh the view */
void refresh();
protected: protected:
// The plot part (right side)
/** The widget which contains all or the single plot **/
QMap<int, LinechartPlot*> plots;
LinechartPlot* activePlot;
/** A lock (mutex) for the concurrent access on the curves **/
QReadWriteLock* curvesLock;
/** A lock (mutex) for the concurrent access on the window position **/
QReadWriteLock plotWindowLock;
QMap<QString, QLabel*>* curveLabels; ///< References to the curve labels
QMap<QString, QLabel*>* curveMeans; ///< References to the curve means
QMap<QString, QLabel*>* curveMedians; ///< References to the curve medians
// The combo box curve selection part (left side)
QWidget* curvesWidget; ///< The QWidget containing the curve selection button
QVBoxLayout* curvesWidgetLayout; ///< The layout for the curvesWidget QWidget
QScrollBar* scrollbar; ///< The plot window scroll bar
QSpinBox* averageSpinBox; ///< Spin box to setup average window filter size
void addCurveToList(QString curve); void addCurveToList(QString curve);
void removeCurveFromList(QString curve); void removeCurveFromList(QString curve);
QWidget* createCurveItem(LinechartPlot* plot, QString curve); QToolButton* createButton(QWidget* parent);
QWidget* createCurveItem(QString curve);
void createLayout();
QAction* setScalingLogarithmic; ///< Set logarithmic scaling int sysid; ///< ID of the unmanned system this plot belongs to
QAction* setScalingLinear; ///< Set linear scaling LinechartPlot* activePlot; ///< Plot for this system
QAction* addNewCurve; ///< Add curve candidate to the active curves QReadWriteLock* curvesLock; ///< A lock (mutex) for the concurrent access on the curves
QReadWriteLock plotWindowLock; ///< A lock (mutex) for the concurrent access on the window position
/** Order index of curves **/
int curveListIndex; int curveListIndex;
int curveListCounter; ///< Counter of curves in curve list
QList<QString>* listedCurves; ///< Curves listed
QMap<QString, QLabel*>* curveLabels; ///< References to the curve labels
QMap<QString, QLabel*>* curveMeans; ///< References to the curve means
QMap<QString, QLabel*>* curveMedians; ///< References to the curve medians
QWidget* curvesWidget; ///< The QWidget containing the curve selection button
QVBoxLayout* curvesWidgetLayout; ///< The layout for the curvesWidget QWidget
QScrollBar* scrollbar; ///< The plot window scroll bar
QSpinBox* averageSpinBox; ///< Spin box to setup average window filter size
/** Counter of curves in curve list **/ QAction* setScalingLogarithmic; ///< Set logarithmic scaling
int curveListCounter; QAction* setScalingLinear; ///< Set linear scaling
QAction* addNewCurve; ///< Add curve candidate to the active curves
QMenu* curveMenu; QMenu* curveMenu;
QList<QString>* listedCurves;
QGridLayout* mainLayout; QGridLayout* mainLayout;
void createLayout();
void setPlot(int uasId);
/* Factory methods */
LinechartContainer* plotContainer;
QToolButton* createButton(QWidget* parent);
QToolButton* scalingLinearButton; QToolButton* scalingLinearButton;
QToolButton* scalingLogButton; QToolButton* scalingLogButton;
QToolButton* logButton; QToolButton* logButton;
@ -145,6 +126,7 @@ protected:
QFile* logFile; QFile* logFile;
unsigned int logindex; unsigned int logindex;
bool logging; bool logging;
QTimer* updateTimer;
LogCompressor* compressor; LogCompressor* compressor;
static const int MAX_CURVE_MENUITEM_NUMBER = 8; static const int MAX_CURVE_MENUITEM_NUMBER = 8;

66
src/ui/linechart/Linecharts.cc

@ -0,0 +1,66 @@
#include "Linecharts.h"
Linecharts::Linecharts(QWidget *parent) :
QStackedWidget(parent),
plots(),
active(true)
{
}
void Linecharts::setActive(bool active)
{
this->active = active;
QWidget* prevWidget = currentWidget();
if (prevWidget)
{
LinechartWidget* chart = dynamic_cast<LinechartWidget*>(prevWidget);
if (chart)
{
chart->setActive(active);
}
}
}
void Linecharts::selectSystem(int systemid)
{
QWidget* prevWidget = currentWidget();
if (prevWidget)
{
LinechartWidget* chart = dynamic_cast<LinechartWidget*>(prevWidget);
if (chart)
{
chart->setActive(false);
}
}
QWidget* widget = plots.value(systemid, NULL);
if (widget)
{
setCurrentWidget(widget);
LinechartWidget* chart = dynamic_cast<LinechartWidget*>(widget);
if (chart)
{
chart->setActive(true);
}
}
}
void Linecharts::addSystem(UASInterface* uas)
{
if (!plots.contains(uas->getUASID()))
{
LinechartWidget* widget = new LinechartWidget(uas->getUASID(), this);
addWidget(widget);
plots.insert(uas->getUASID(), widget);
connect(uas, SIGNAL(valueChanged(int,QString,double,quint64)), widget, SLOT(appendData(int,QString,double,quint64)));
// Set system active if this is the only system
if (active)
{
if (plots.size() == 1)
{
selectSystem(uas->getUASID());
}
}
}
}

31
src/ui/linechart/Linecharts.h

@ -0,0 +1,31 @@
#ifndef LINECHARTS_H
#define LINECHARTS_H
#include <QStackedWidget>
#include <QMap>
#include "LinechartWidget.h"
#include "UASInterface.h"
class Linecharts : public QStackedWidget
{
Q_OBJECT
public:
explicit Linecharts(QWidget *parent = 0);
signals:
public slots:
/** @brief Set all plots active/inactive */
void setActive(bool active);
/** @brief Select plot for one system */
void selectSystem(int systemid);
/** @brief Add a new system to the list of plots */
void addSystem(UASInterface* uas);
protected:
QMap<int, LinechartWidget*> plots;
bool active;
};
#endif // LINECHARTS_H

6
src/ui/uas/UASListWidget.cc

@ -87,7 +87,11 @@ void UASListWidget::addUAS(UASInterface* uas)
void UASListWidget::activeUAS(UASInterface* uas) void UASListWidget::activeUAS(UASInterface* uas)
{ {
//uasViews.value(uas)->setUASasActive(true); UASView* view = uasViews.value(uas, NULL);
if (view)
{
view->setUASasActive(true);
}
} }
void UASListWidget::removeUAS(UASInterface* uas) void UASListWidget::removeUAS(UASInterface* uas)

25
src/ui/uas/UASView.cc

@ -225,23 +225,31 @@ void UASView::updateLocalPosition(UASInterface* uas, double x, double y, double
} }
} }
void UASView::updateGlobalPosition(UASInterface*, double lon, double lat, double alt, quint64 usec) void UASView::updateGlobalPosition(UASInterface* uas, double lon, double lat, double alt, quint64 usec)
{ {
Q_UNUSED(uas);
Q_UNUSED(usec);
QString position;
position = position.sprintf("%02.2f %02.2f %02.2f m", lon, lat, alt);
m_ui->positionLabel->setText(position);
} }
void UASView::updateSpeed(UASInterface*, double x, double y, double z, quint64 usec) void UASView::updateSpeed(UASInterface*, double x, double y, double z, quint64 usec)
{ {
// double totalSpeed = sqrt((pow(x, 2) + pow(y, 2) + pow(z, 2))); Q_UNUSED(usec);
// m_ui->speedBar->setValue(totalSpeed); double totalSpeed = sqrt((pow(x, 2) + pow(y, 2) + pow(z, 2)));
} QString speed;
speed = speed.sprintf("%02.2f m/s", totalSpeed);
void UASView::receiveValue(int uasid, QString id, double value, quint64 time) m_ui->speedLabel->setText(speed);
{
} }
void UASView::setWaypoint(int uasId, int id, double x, double y, double z, double yaw, bool autocontinue, bool current) void UASView::setWaypoint(int uasId, int id, double x, double y, double z, double yaw, bool autocontinue, bool current)
{ {
Q_UNUSED(x);
Q_UNUSED(y);
Q_UNUSED(z);
Q_UNUSED(yaw);
Q_UNUSED(autocontinue);
if (uasId == this->uas->getUASID()) if (uasId == this->uas->getUASID())
{ {
if (current) if (current)
@ -269,6 +277,7 @@ void UASView::updateThrust(UASInterface* uas, double thrust)
void UASView::updateBattery(UASInterface* uas, double voltage, double percent, int seconds) void UASView::updateBattery(UASInterface* uas, double voltage, double percent, int seconds)
{ {
Q_UNUSED(voltage);
if (this->uas == uas) if (this->uas == uas)
{ {
timeRemaining = seconds; timeRemaining = seconds;

4
src/ui/uas/UASView.h

@ -23,7 +23,7 @@ This file is part of the PIXHAWK project
/** /**
* @file * @file
* @brief Definition of one airstrip * @brief Definition of class UASView
* *
* @author Lorenz Meier <mavteam@student.ethz.ch> * @author Lorenz Meier <mavteam@student.ethz.ch>
* *
@ -59,7 +59,7 @@ public slots:
/** @brief Update the MAV mode */ /** @brief Update the MAV mode */
void updateMode(int sysId, QString status, QString description); void updateMode(int sysId, QString status, QString description);
void updateLoad(UASInterface* uas, double load); void updateLoad(UASInterface* uas, double load);
void receiveValue(int uasid, QString id, double value, quint64 time); //void receiveValue(int uasid, QString id, double value, quint64 time);
void refresh(); void refresh();
/** @brief Receive new waypoint information */ /** @brief Receive new waypoint information */
void setWaypoint(int uasId, int id, double x, double y, double z, double yaw, bool autocontinue, bool current); void setWaypoint(int uasId, int id, double x, double y, double z, double yaw, bool autocontinue, bool current);

Loading…
Cancel
Save