Commit 2ecf982d authored by pixhawk's avatar pixhawk

Merge branch 'master' of git@pixhawk.ethz.ch:qgroundcontrol

parents 7e6365fb 95191d2e
......@@ -46,11 +46,12 @@ To build on Linux:
Windows
=======
**********************************************************************************************
* PLEASE NOTE: YOU NEED TO DOWNLOAD THE MAVLINK LIBRARY IN ORDER TO COMPILE THIS APPLICATION *
**********************************************************************************************
Windows XP:
1) Download and install the QT SDK for Windows from http://qt.nokia.com/downloads/.
2) Open qgroundcontrol.pro with QT to open the project.
3) Once the indexing is complete, you may build the project, which will compile and run the debug build.
To build on Windows:
<instructions to be written>
......@@ -83,7 +83,6 @@ HEADERS += src/MG.h \
src/ui/uas/UASInfoWidget.h \
src/ui/HUD.h \
src/ui/linechart/LinechartWidget.h \
src/ui/linechart/LinechartContainer.h \
src/ui/linechart/LinechartPlot.h \
src/ui/linechart/Scrollbar.h \
src/ui/linechart/ScrollZoomer.h \
......@@ -115,7 +114,8 @@ HEADERS += src/MG.h \
src/ui/param/ParamTreeItem.h \
src/ui/param/ParamTreeModel.h \
src/ui/QGCParamWidget.h \
src/ui/QGCSensorSettingsWidget.h
src/ui/QGCSensorSettingsWidget.h \
src/ui/linechart/Linecharts.h
SOURCES += src/main.cc \
src/Core.cc \
src/uas/UASManager.cc \
......@@ -133,7 +133,6 @@ SOURCES += src/main.cc \
src/ui/uas/UASInfoWidget.cc \
src/ui/HUD.cc \
src/ui/linechart/LinechartWidget.cc \
src/ui/linechart/LinechartContainer.cc \
src/ui/linechart/LinechartPlot.cc \
src/ui/linechart/Scrollbar.cc \
src/ui/linechart/ScrollZoomer.cc \
......@@ -164,5 +163,6 @@ SOURCES += src/main.cc \
src/ui/param/ParamTreeItem.cc \
src/ui/param/ParamTreeModel.cc \
src/ui/QGCParamWidget.cc \
src/ui/QGCSensorSettingsWidget.cc
src/ui/QGCSensorSettingsWidget.cc \
src/ui/linechart/Linecharts.cc
RESOURCES = mavground.qrc
......@@ -122,6 +122,13 @@ void MAVLinkProtocol::receiveBytes(LinkInterface* link)
// of its existence, as it only then can send and receive
// 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
uas = new UAS(this, message.sysid);
// Make UAS aware that this link can be used to communicate with the actual robot
......
......@@ -152,16 +152,18 @@ void SerialLink::checkForBytes() {
void SerialLink::writeBytes(const char* data, qint64 size) {
if(port->isOpen()) {
if(port->isOpen())
{
int b = port->write(data, size);
qDebug() << "Transmitted " << b << "bytes:";
/* Increase write counter */
// Increase write counter
bitsSentTotal += size * 8;
int i;
for (i=0; i<size; i++){
unsigned int v=data[i];
for (i=0; i<size; i++)
{
unsigned char v=data[i];
fprintf(stderr,"%02x ", v);
}
......
......@@ -143,6 +143,9 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
mavlink_sys_status_t state;
mavlink_msg_sys_status_decode(&message, &state);
// FIXME
qDebug() << "SYSTEM NAV MODE:" << state.nav_mode;
QString audiostring = "System " + QString::number(this->getUASID());
QString stateAudio = "";
QString modeAudio = "";
......@@ -158,13 +161,13 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
stateAudio = " changed status to " + uasState;
}
if (static_cast<int>(this->mode) != static_cast<int>(state.mode))
if (static_cast<unsigned int>(this->mode) != static_cast<unsigned int>(state.mode))
{
modechanged = true;
this->mode = state.mode;
QString mode;
switch (state.mode)
switch ((unsigned int)(state.mode))
{
case MAV_MODE_LOCKED:
mode = "LOCKED MODE";
......@@ -449,8 +452,9 @@ void UAS::setMode(int mode)
{
this->mode = mode;
mavlink_message_t msg;
mavlink_msg_set_mode_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, getUASID(), (unsigned char)mode);
mavlink_msg_set_mode_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, (unsigned char)mode);
sendMessage(msg);
qDebug() << "SENDING REQUEST TO SET MODE TO SYSTEM" << uasId << ", REQUEST TO SET MODE " << mode;
}
}
......
......@@ -83,6 +83,7 @@ void UASManager::addUAS(UASInterface* uas)
{
activeUAS = 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();
emit activeUASSet(uas);
emit activeUASSet(uas->getUASID());
}
}
......@@ -166,6 +166,7 @@ protected:
signals:
void UASCreated(UASInterface* UAS);
void activeUASSet(UASInterface* UAS);
void activeUASSet(int systemId);
};
......
......@@ -71,9 +71,10 @@ MainWindow::MainWindow(QWidget *parent) : QMainWindow(parent),
// Initialize views, NOT show them yet, only initialize model and controller
centerStack = new QStackedWidget(this);
linechart = new LinechartWidget(this);
linechart = new Linecharts(this);
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);
control = new UASControlWidget(this);
//controlDock = new QDockWidget(this);
......@@ -312,7 +313,7 @@ void MainWindow::addLink(LinkInterface *link)
MAVLinkSimulationLink* sim = dynamic_cast<MAVLinkSimulationLink*>(link);
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)));
}
}
......@@ -322,15 +323,6 @@ void MainWindow::UASCreated(UASInterface* uas)
// Connect the UAS to the full user interface
//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
connect(uas, SIGNAL(textMessageReceived(int,int,QString)), debugConsole, SLOT(receiveTextMessage(int,int,QString)));
......
......@@ -42,7 +42,7 @@ This file is part of the PIXHAWK project
#include "UASInterface.h"
#include "UASManager.h"
#include "UASControlWidget.h"
#include "LinechartWidget.h"
#include "Linecharts.h"
#include "UASInfoWidget.h"
#include "WaypointList.h"
#include "CameraView.h"
......@@ -132,7 +132,7 @@ protected:
QSettings settings;
UASControlWidget* control;
LinechartWidget* linechart;
Linecharts* linechart;
UASInfoWidget* info;
CameraView* camera;
UASListWidget* list;
......
......@@ -130,7 +130,15 @@ void QGCParamWidget::addParameter(int uas, int component, QString parameterName,
{
Q_UNUSED(uas);
// 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;
plist.append(parameterName);
plist.append(QString::number(value));
......
#include <QFileDialog>
#include <QTextBrowser>
#include <QMessageBox>
#include <QSettings>
#include "XMLCommProtocolWidget.h"
#include "ui_XMLCommProtocolWidget.h"
......@@ -23,10 +24,12 @@ XMLCommProtocolWidget::XMLCommProtocolWidget(QWidget *parent) :
void XMLCommProtocolWidget::selectXMLFile()
{
qDebug() << "OPENING XML FILE";
//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;
dialog.setDirectory(dirPath);
dialog.setFileMode(QFileDialog::AnyFile);
dialog.setFilter(tr("MAVLink XML (*.xml)"));
dialog.setViewMode(QFileDialog::Detail);
......@@ -40,6 +43,8 @@ void XMLCommProtocolWidget::selectXMLFile()
{
m_ui->fileNameLabel->setText(fileNames.first());
QFile file(fileNames.first());
// Store filename for next time
settings.setValue(mavlinkXML, fileNames.first());
if (file.open(QIODevice::ReadOnly | QIODevice::Text))
{
const QString instanceText(QString::fromUtf8(file.readAll()));
......@@ -80,7 +85,11 @@ void XMLCommProtocolWidget::setXML(const QString& xml)
void XMLCommProtocolWidget::selectOutputDirectory()
{
QSettings settings;
const QString mavlinkOutputDir = "MAVLINK_OUTPUT_DIR";
QString dirPath = settings.value(mavlinkOutputDir, QCoreApplication::applicationDirPath() + "../").toString();
QFileDialog dialog;
dialog.setDirectory(dirPath);
dialog.setFileMode(QFileDialog::Directory);
dialog.setFilter(tr("MAVLink XML (*.xml)"));
dialog.setViewMode(QFileDialog::Detail);
......@@ -93,6 +102,8 @@ void XMLCommProtocolWidget::selectOutputDirectory()
if (fileNames.size() > 0)
{
m_ui->outputDirNameLabel->setText(fileNames.first());
// Store directory for next time
settings.setValue(mavlinkOutputDir, fileNames.first());
//QFile file(fileName);
}
}
......
/*=====================================================================
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);
}
/*=====================================================================
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_ */
......@@ -55,9 +55,9 @@ maxTime(QUINT64_MIN),
maxInterval(MAX_STORAGE_INTERVAL),
timeScaleStep(DEFAULT_SCALE_INTERVAL), // 10 seconds
automaticScrollActive(false),
m_active(true),
d_data(NULL),
d_curve(NULL),
m_active(true)
d_curve(NULL)
{
this->plotid = plotid;
this->plotInterval = interval;
......@@ -158,6 +158,14 @@ int LinechartPlot::getPlotId()
return this->plotid;
}
/**
* @param id curve identifier
*/
double LinechartPlot::getCurrentValue(QString id)
{
return data.value(id)->getCurrentValue();
}
/**
* @param id curve identifier
*/
......@@ -280,7 +288,7 @@ void LinechartPlot::addCurve(QString id)
data.insert(id, dataset);
// Notify connected components about new curve
emit curveAdded(plotid, id);
emit curveAdded(id);
}
QColor LinechartPlot::getNextColor()
......@@ -337,7 +345,7 @@ void LinechartPlot::setCurveColor(QString id, QColor color)
QwtPlotCurve* curve = curves.value(id);
curve->setPen(color);
emit colorSet(plotid, id, color);
emit colorSet(id, color);
}
/**
......@@ -635,7 +643,7 @@ void LinechartPlot::removeAllData()
curve = NULL;
// Notify connected components about the removal
emit curveRemoved(plotid, i.key());
emit curveRemoved(i.key());
}
// Delete data
......@@ -814,6 +822,11 @@ double TimeSeriesData::getMedian()
return median;
}
double TimeSeriesData::getCurrentValue()
{
return ms.last();
}
/**
* @brief Get the zero (center) value in the data set
* The zero value is not a statistical value, but instead manually defined
......
......@@ -132,6 +132,8 @@ public:
double getMean();
/** @brief Get the short-term median */
double getMedian();
/** @brief Get the current value */
double getCurrentValue();
void setZeroValue(double zeroValue);
void setInterval(quint64 ms);
void setAverageWindowSize(int windowSize);
......@@ -203,6 +205,8 @@ public:
double getMean(QString id);
/** @brief Get the short-term median of a curve */
double getMedian(QString id);
/** @brief Get the last inserted value */
double getCurrentValue(QString id);
static const int SCALE_ABSOLUTE = 0;
static const int SCALE_BEST_FIT = 1;
......@@ -303,20 +307,20 @@ signals:
*
* @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
*
* @param idstring The id-string of the curve
* @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
*
* @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
*
......
This diff is collapsed.
......@@ -46,9 +46,9 @@ This file is part of the PIXHAWK project
#include <QLabel>
#include <QReadWriteLock>
#include <QToolButton>
#include <QTimer>
#include <qwt_plot_curve.h>
#include "LinechartContainer.h"
#include "LinechartPlot.h"
#include "UASInterface.h"
#include "ui_Linechart.h"
......@@ -63,81 +63,62 @@ class LinechartWidget : public QWidget {
Q_OBJECT
public:
LinechartWidget(QWidget *parent = 0);
LinechartWidget(int systemid, QWidget *parent = 0);
~LinechartWidget();
LinechartPlot* getPlot(int uasId);
static const int MIN_TIME_SCROLLBAR_VALUE = 0; ///< The minimum scrollbar value
static const int MAX_TIME_SCROLLBAR_VALUE = 16383; ///< The maximum scrollbar value
public slots:
void addCurve(int uasid, QString curve);
void removeCurve(int uasid, QString curve);
void appendData(int uasid, QString curve, double data, quint64 usec);
void addCurve(QString curve);
void removeCurve(QString curve);
void appendData(int sysId, QString curve, double data, quint64 usec);
void takeButtonClick(bool checked);
void setPlotWindowPosition(int scrollBarValue);
void setPlotWindowPosition(quint64 position);
void setPlotInterval(quint64 interval);
void setActivePlot(int uasid);
void setActivePlot(UASInterface* uas);
void setActive(bool active);
/** @brief Set the number of values to average over */
void setAverageWindow(int windowSize);
/** @brief Start logging to file */
void startLogging();
/** @brief Stop logging to file */
void stopLogging();
/** @brief Refresh the view */
void refresh();
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 removeCurveFromList(QString curve);
QWidget* createCurveItem(LinechartPlot* plot, QString curve);
QToolButton* createButton(QWidget* parent);
QWidget* createCurveItem(QString curve);
void createLayout();
QAction* setScalingLogarithmic; ///< Set logarithmic scaling
QAction* setScalingLinear; ///< Set linear scaling
QAction* addNewCurve; ///< Add curve candidate to the active curves
int sysid; ///< ID of the unmanned system this plot belongs to
LinechartPlot* activePlot; ///< Plot for this system
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 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 **/
int curveListCounter;
QAction* setScalingLogarithmic; ///< Set logarithmic scaling
QAction* setScalingLinear; ///< Set linear scaling
QAction* addNewCurve; ///< Add curve candidate to the active curves
QMenu* curveMenu;
QList<QString>* listedCurves;
QGridLayout* mainLayout;
void createLayout();
void setPlot(int uasId);
/* Factory methods */
LinechartContainer* plotContainer;
QToolButton* createButton(QWidget* parent);
QToolButton* scalingLinearButton;
QToolButton* scalingLogButton;
QToolButton* logButton;
......@@ -145,6 +126,7 @@ protected:
QFile* logFile;
unsigned int logindex;
bool logging;
QTimer* updateTimer;
LogCompressor* compressor;
static const int MAX_CURVE_MENUITEM_NUMBER = 8;
......
#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());
}
}
}
}
#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
......@@ -87,7 +87,11 @@ void UASListWidget::addUAS(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)
......
......@@ -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)
{
// double totalSpeed = sqrt((pow(x, 2) + pow(y, 2) + pow(z, 2)));
// m_ui->speedBar->setValue(totalSpeed);
}
void UASView::receiveValue(int uasid, QString id, double value, quint64 time)
{
Q_UNUSED(usec);
double totalSpeed = sqrt((pow(x, 2) + pow(y, 2) + pow(z, 2)));
QString speed;
speed = speed.sprintf("%02.2f m/s", totalSpeed);
m_ui->speedLabel->setText(speed);
}
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 (current)
......@@ -269,6 +277,7 @@ void UASView::updateThrust(UASInterface* uas, double thrust)
void UASView::updateBattery(UASInterface* uas, double voltage, double percent, int seconds)
{
Q_UNUSED(voltage);
if (this->uas == uas)
{
timeRemaining = seconds;
......
......@@ -23,7 +23,7 @@ This file is part of the PIXHAWK project
/**
* @file
* @brief Definition of one airstrip
* @brief Definition of class UASView
*
* @author Lorenz Meier <mavteam@student.ethz.ch>
*
......@@ -59,7 +59,7 @@ public slots:
/** @brief Update the MAV mode */
void updateMode(int sysId, QString status, QString description);
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();
/** @brief Receive new waypoint information */
void setWaypoint(int uasId, int id, double x, double y, double z, double yaw, bool autocontinue, bool current);
......
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