Commit 3149ae76 authored by Lorenz Meier's avatar Lorenz Meier

Merge branch 'mp_merge' of https://github.com/diydrones/qgroundcontrol into integration_merge

parents 8cc94fc7 d06caab2
......@@ -227,7 +227,11 @@ FORMS += src/ui/MainWindow.ui \
src/ui/QGCHilXPlaneConfiguration.ui \
src/ui/designer/QGCComboBox.ui \
src/ui/designer/QGCTextLabel.ui \
src/ui/uas/UASQuickView.ui
src/ui/uas/UASQuickView.ui \
src/ui/uas/UASQuickViewItemSelect.ui \
src/ui/uas/UASActionsWidget.ui \
src/ui/QGCTabbedInfoView.ui \
src/ui/UASRawStatusView.ui
INCLUDEPATH += src \
src/ui \
src/ui/linechart \
......@@ -377,6 +381,12 @@ HEADERS += src/MG.h \
src/ui/dockwidgettitlebareventfilter.h \
src/ui/uas/UASQuickView.h \
src/ui/uas/UASQuickViewItem.h \
src/ui/uas/UASQuickViewItemSelect.h \
src/ui/uas/UASQuickViewTextItem.h \
src/ui/uas/UASActionsWidget.h \
src/ui/designer/QGCRadioChannelDisplay.h \
src/ui/QGCTabbedInfoView.h \
src/ui/UASRawStatusView.h \
src/ui/PrimaryFlightDisplay.h
# Google Earth is only supported on Mac OS and Windows with Visual Studio Compiler
......@@ -546,6 +556,12 @@ SOURCES += src/main.cc \
src/ui/dockwidgettitlebareventfilter.cpp \
src/ui/uas/UASQuickViewItem.cc \
src/ui/uas/UASQuickView.cc \
src/ui/uas/UASQuickViewTextItem.cc \
src/ui/uas/UASQuickViewItemSelect.cc \
src/ui/uas/UASActionsWidget.cpp \
src/ui/designer/QGCRadioChannelDisplay.cpp \
src/ui/QGCTabbedInfoView.cpp \
src/ui/UASRawStatusView.cpp \
src/ui/PrimaryFlightDisplay.cpp
# Enable Google Earth only on Mac OS and Windows with Visual Studio compiler
......
......@@ -203,7 +203,7 @@ QGCCore::QGCCore(int &argc, char* argv[]) : QApplication(argc, argv)
QGCCore::~QGCCore()
{
//mainWindow->storeSettings();
mainWindow->close();
//mainWindow->close();
//mainWindow->deleteLater();
// Delete singletons
// First systems
......@@ -211,7 +211,8 @@ QGCCore::~QGCCore()
// then links
delete LinkManager::instance();
// Finally the main window
delete MainWindow::instance();
//delete MainWindow::instance();
//The main window now autodeletes on close.
}
/**
......
......@@ -232,6 +232,8 @@ signals:
/** @brief Communication error occured */
void communicationError(const QString& linkname, const QString& error);
void communicationUpdate(const QString& linkname, const QString& text);
/** @brief destroying element */
void deleteLink(LinkInterface* const link);
......
......@@ -20,7 +20,6 @@
#ifdef _WIN32
#include "windows.h"
#endif
#ifdef _WIN32
#include <qextserialenumerator.h>
#endif
......@@ -394,7 +393,13 @@ void SerialLink::writeSettings()
void SerialLink::run()
{
// Initialize the connection
hardwareConnect();
if (!hardwareConnect())
{
//Need to error out here.
emit communicationError(getName(),"Error connecting: " + port->errorString());
return;
}
// Qt way to make clear what a while(1) loop does
quint64 msecs = QDateTime::currentMSecsSinceEpoch();
......@@ -402,7 +407,7 @@ void SerialLink::run()
quint64 bytes = 0;
bool triedreset = false;
bool triedDTR = false;
int timeout = 2500;
int timeout = 5000;
forever
{
{
......@@ -438,6 +443,7 @@ void SerialLink::run()
if (!triedDTR && triedreset)
{
triedDTR = true;
communicationUpdate(getName(),"No data to receive on COM port. Attempting to reset via DTR signal");
qDebug() << "No data!!! Attempting reset via DTR.";
port->setDtr(true);
this->msleep(250);
......@@ -446,11 +452,13 @@ void SerialLink::run()
else if (!triedreset)
{
qDebug() << "No data!!! Attempting reset via reboot command.";
communicationUpdate(getName(),"No data to receive on COM port. Assuming possible terminal mode, attempting to reset via \"reboot\" command");
port->write("reboot\r\n",8);
triedreset = true;
}
else
{
communicationUpdate(getName(),"No data to receive on COM port....");
qDebug() << "No data!!!";
}
}
......@@ -661,7 +669,14 @@ bool SerialLink::hardwareConnect()
port->setCommTimeouts(QSerialPort::CtScheme_NonBlockingRead);
connectionStartTime = MG::TIME::getGroundTimeNow();
port->open();
if (!port->open())
{
emit communicationUpdate(getName(),"Error opening port: " + port->errorString());
}
else
{
emit communicationUpdate(getName(),"Opened port!");
}
bool connectionUp = isConnected();
if(connectionUp) {
......
......@@ -850,6 +850,8 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
if (!globalEstimatorActive) {
if ((vel < 1000000) && !isnan(vel) && !isinf(vel))
{
//emit speedChanged(this, vel, 0.0, 0.0, time);
setGroundSpeed(vel);
// TODO: Other sources also? Actually this condition does not quite belong here.
emit gpsSpeedChanged(this, vel, time);
}
......
......@@ -102,6 +102,18 @@ public:
Q_PROPERTY(double pitch READ getPitch WRITE setPitch NOTIFY pitchChanged)
Q_PROPERTY(double yaw READ getYaw WRITE setYaw NOTIFY yawChanged)
Q_PROPERTY(double distToWaypoint READ getDistToWaypoint WRITE setDistToWaypoint NOTIFY distToWaypointChanged)
Q_PROPERTY(double groundSpeed READ getGroundSpeed WRITE setGroundSpeed NOTIFY groundSpeedChanged)
void setGroundSpeed(double val)
{
groundSpeed = val;
emit groundSpeedChanged(val,"groundSpeed");
emit valueChanged(this->uasId,"groundSpeed","m/s",QVariant(val),getUnixTime());
}
double getGroundSpeed() const
{
return groundSpeed;
}
Q_PROPERTY(double bearingToWaypoint READ getBearingToWaypoint WRITE setBearingToWaypoint NOTIFY bearingToWaypointChanged)
// dongfang: There is not only one altitude; there are at least (APM) GPS altitude, mix altitude and mix-altitude relative to home.
......@@ -427,6 +439,7 @@ protected: //COMMENTS FOR TEST UNIT
/// WAYPOINT NAVIGATION
double distToWaypoint; ///< Distance to next waypoint
double groundSpeed; ///< GPS Groundspeed
double bearingToWaypoint; ///< Bearing to next waypoint
UASWaypointManager waypointManager;
......@@ -850,6 +863,7 @@ signals:
void yawChanged(double val,QString name);
void satelliteCountChanged(double val,QString name);
void distToWaypointChanged(double val,QString name);
void groundSpeedChanged(double val, QString name);
void bearingToWaypointChanged(double val,QString name);
//void primaryAltitudeChanged(UASInterface*, double altitude, quint64 usec);
......
......@@ -215,6 +215,12 @@ void DebugConsole::removeLink(LinkInterface* const linkInterface)
}
if (linkInterface == currLink) currLink = NULL;
}
void DebugConsole::linkStatusUpdate(const QString& name,const QString& text)
{
m_ui->receiveText->appendPlainText(text);
// Ensure text area scrolls correctly
m_ui->receiveText->ensureCursorVisible();
}
void DebugConsole::linkSelected(int linkId)
{
......@@ -222,6 +228,7 @@ void DebugConsole::linkSelected(int linkId)
if (currLink) {
disconnect(currLink, SIGNAL(bytesReceived(LinkInterface*,QByteArray)), this, SLOT(receiveBytes(LinkInterface*, QByteArray)));
disconnect(currLink, SIGNAL(connected(bool)), this, SLOT(setConnectionState(bool)));
disconnect(currLink,SIGNAL(communicationUpdate(QString,QString)),this,SLOT(linkStatusUpdate(QString,QString)));
}
// Clear data
m_ui->receiveText->clear();
......@@ -230,6 +237,7 @@ void DebugConsole::linkSelected(int linkId)
currLink = links[linkId];
connect(currLink, SIGNAL(bytesReceived(LinkInterface*,QByteArray)), this, SLOT(receiveBytes(LinkInterface*, QByteArray)));
connect(currLink, SIGNAL(connected(bool)), this, SLOT(setConnectionState(bool)));
connect(currLink,SIGNAL(communicationUpdate(QString,QString)),this,SLOT(linkStatusUpdate(QString,QString)));
setConnectionState(currLink->isConnected());
}
......
......@@ -96,6 +96,8 @@ public slots:
/** @brief A new special symbol is selected */
void specialSymbolSelected(const QString& text);
void linkStatusUpdate(const QString& name,const QString& text);
protected slots:
/** @brief Draw information overlay */
void paintEvent(QPaintEvent *event);
......
......@@ -110,6 +110,9 @@
<height>50</height>
</size>
</property>
<property name="readOnly">
<bool>true</bool>
</property>
<property name="tabStopWidth">
<number>60</number>
</property>
......@@ -200,7 +203,7 @@
<string/>
</property>
<property name="icon">
<iconset resource="../../mavground.qrc">
<iconset resource="../../qgroundcontrol.qrc">
<normaloff>:/files/images/actions/list-add.svg</normaloff>:/files/images/actions/list-add.svg</iconset>
</property>
</widget>
......@@ -224,7 +227,7 @@
<string>Send</string>
</property>
<property name="icon">
<iconset resource="../../mavground.qrc">
<iconset resource="../../qgroundcontrol.qrc">
<normaloff>:/files/images/devices/network-wireless.svg</normaloff>:/files/images/devices/network-wireless.svg</iconset>
</property>
</widget>
......@@ -287,7 +290,7 @@
</layout>
</widget>
<resources>
<include location="../../mavground.qrc"/>
<include location="../../qgroundcontrol.qrc"/>
</resources>
<connections>
<connection>
......
......@@ -200,7 +200,7 @@ void MAVLinkDecoder::emitFieldValue(mavlink_message_t* msg, int fieldid, quint64
// Add field tree widget item
uint8_t msgid = msg->msgid;
if (messageFilter.contains(msgid)) return;
//if (messageFilter.contains(msgid)) return;
QString fieldName(messageInfo[msgid].fields[fieldid].name);
QString fieldType;
uint8_t* m = ((uint8_t*)(receivedMessages+msgid))+8;
......
......@@ -21,6 +21,7 @@ signals:
void valueChanged(const int uasId, const QString& name, const QString& unit, const quint64 value, const quint64 msec);
void valueChanged(const int uasId, const QString& name, const QString& unit, const qint64 value, const quint64 msec);
void valueChanged(const int uasId, const QString& name, const QString& unit, const double value, const quint64 msec);
//void valueChanged(const int uasId, const QString& name, const QString& unit, const QVariant value, const quint64 msec);
public slots:
......
......@@ -59,6 +59,9 @@ This file is part of the QGROUNDCONTROL project
#include "QGCFirmwareUpdate.h"
#include "QGCStatusBar.h"
#include "UASQuickView.h"
#include "UASActionsWidget.h"
#include "QGCTabbedInfoView.h"
#include "UASRawStatusView.h"
#include "PrimaryFlightDisplay.h"
#ifdef QGC_OSG_ENABLED
......@@ -105,6 +108,7 @@ MainWindow::MainWindow(QWidget *parent):
autoReconnect(false),
lowPowerMode(false)
{
this->setAttribute(Qt::WA_DeleteOnClose);
hide();
dockWidgetTitleBarEnabled = true;
isAdvancedMode = false;
......@@ -322,6 +326,16 @@ MainWindow::~MainWindow()
}
}
// Delete all UAS objects
if (debugConsole)
{
delete debugConsole;
}
for (int i=0;i<commsWidgetList.size();i++)
{
commsWidgetList[i]->deleteLater();
}
}
void MainWindow::resizeEvent(QResizeEvent * event)
......@@ -498,6 +512,7 @@ void MainWindow::buildCommonWidgets()
createDockWidget(simView,new UASControlWidget(this),tr("Control"),"UNMANNED_SYSTEM_CONTROL_DOCKWIDGET",VIEW_SIMULATION,Qt::LeftDockWidgetArea);
createDockWidget(plannerView,new UASListWidget(this),tr("Unmanned Systems"),"UNMANNED_SYSTEM_LIST_DOCKWIDGET",VIEW_MISSION,Qt::LeftDockWidgetArea);
createDockWidget(plannerView,new QGCWaypointListMulti(this),tr("Mission Plan"),"WAYPOINT_LIST_DOCKWIDGET",VIEW_MISSION,Qt::BottomDockWidgetArea);
{
//createDockWidget(plannerView,new QGCWaypointListMulti(this),tr("Mission Plan"),"WAYPOINT_LIST_DOCKWIDGET",VIEW_MISSION,Qt::BottomDockWidgetArea);
......@@ -521,10 +536,17 @@ void MainWindow::buildCommonWidgets()
connect(tempAction,SIGNAL(triggered(bool)),this, SLOT(showTool(bool)));
}
{
QAction* tempAction = ui.menuTools->addAction(tr("Communication Console"));
menuToDockNameMap[tempAction] = "COMMUNICATION_DEBUG_CONSOLE_DOCKWIDGET";
tempAction->setCheckable(true);
connect(tempAction,SIGNAL(triggered(bool)),this, SLOT(showTool(bool)));
if (!debugConsole)
{
debugConsole = new DebugConsole();
debugConsole->setWindowTitle("Communications Console");
debugConsole->hide();
QAction* tempAction = ui.menuTools->addAction(tr("Communication Console"));
//menuToDockNameMap[tempAction] = "COMMUNICATION_DEBUG_CONSOLE_DOCKWIDGET";
tempAction->setCheckable(true);
connect(tempAction,SIGNAL(triggered(bool)),debugConsole,SLOT(setShown(bool)));
}
}
createDockWidget(simView,new HSIDisplay(this),tr("Horizontal Situation"),"HORIZONTAL_SITUATION_INDICATOR_DOCKWIDGET",VIEW_SIMULATION,Qt::BottomDockWidgetArea);
......@@ -572,16 +594,39 @@ void MainWindow::buildCommonWidgets()
// createDockWidget(simView,new HUD(320,240,this),tr("Head Up Display"),"HEAD_UP_DISPLAY_DOCKWIDGET",VIEW_SIMULATION,Qt::RightDockWidgetArea,this->width()/1.5);
createDockWidget(simView,new PrimaryFlightDisplay(320,240,this),tr("Primary Flight Display"),"PRIMARY_FLIGHT_DISPLAY_DOCKWIDGET",VIEW_SIMULATION,Qt::RightDockWidgetArea,this->width()/1.5);
createDockWidget(pilotView,new UASListWidget(this),tr("Unmanned Systems"),"UNMANNED_SYSTEM_LIST_DOCKWIDGET",VIEW_FLIGHT,Qt::RightDockWidgetArea);
//createDockWidget(pilotView,new UASListWidget(this),tr("Unmanned Systems"),"UNMANNED_SYSTEM_LIST_DOCKWIDGET",VIEW_FLIGHT,Qt::RightDockWidgetArea);
// createDockWidget(pilotView,new HUD(320,240,this),tr("Head Up Display"),"HEAD_UP_DISPLAY_DOCKWIDGET",VIEW_FLIGHT,Qt::LeftDockWidgetArea,this->width()/1.8);
//createDockWidget(pilotView,new UASQuickView(this),tr("Quick View"),"UAS_INFO_QUICKVIEW_DOCKWIDGET",VIEW_FLIGHT,Qt::LeftDockWidgetArea);
//createDockWidget(pilotView,new HUD(320,240,this),tr("Head Up Display"),"HEAD_UP_DISPLAY_DOCKWIDGET",VIEW_FLIGHT,Qt::LeftDockWidgetArea,this->width()/1.8);
//UASQuickView *quickview = new UASQuickView(this);
//quickview->addSource(mavlinkDecoder);
//createDockWidget(pilotView,quickview,tr("Quick View"),"UAS_INFO_QUICKVIEW_DOCKWIDGET",VIEW_FLIGHT,Qt::LeftDockWidgetArea);
createDockWidget(pilotView,new PrimaryFlightDisplay(320,240,this),tr("Primary Flight Display"),"PRIMARY_FLIGHT_DISPLAY_DOCKWIDGET",VIEW_FLIGHT,Qt::LeftDockWidgetArea,this->width()/1.8);
createDockWidget(pilotView,new UASQuickView(this),tr("Quick View"),"UAS_INFO_QUICKVIEW_DOCKWIDGET",VIEW_FLIGHT,Qt::LeftDockWidgetArea);
createDockWidget(pilotView,new HSIDisplay(this),tr("Horizontal Situation"),"HORIZONTAL_SITUATION_INDICATOR_DOCKWIDGET",VIEW_FLIGHT,Qt::LeftDockWidgetArea);
pilotView->setTabPosition(Qt::LeftDockWidgetArea,QTabWidget::North);
pilotView->tabifyDockWidget((QDockWidget*)centralWidgetToDockWidgetsMap[VIEW_FLIGHT]["HORIZONTAL_SITUATION_INDICATOR_DOCKWIDGET"],(QDockWidget*)centralWidgetToDockWidgetsMap[VIEW_FLIGHT]["UAS_INFO_QUICKVIEW_DOCKWIDGET"]);
QGCTabbedInfoView *infoview = new QGCTabbedInfoView(this);
infoview->addSource(mavlinkDecoder);
createDockWidget(pilotView,infoview,tr("Info View"),"UAS_INFO_INFOVIEW_DOCKWIDGET",VIEW_FLIGHT,Qt::LeftDockWidgetArea);
//createDockWidget(pilotView,new HUD(320,240,this),tr("Head Up Display"),"HEAD_UP_DISPLAY_DOCKWIDGET",VIEW_FLIGHT,Qt::LeftDockWidgetArea,this->width()/1.8);
// createDockWidget(pilotView,new UASQuickView(this),tr("Quick View"),"UAS_INFO_QUICKVIEW_DOCKWIDGET",VIEW_FLIGHT,Qt::LeftDockWidgetArea);
// createDockWidget(pilotView,new HSIDisplay(this),tr("Horizontal Situation"),"HORIZONTAL_SITUATION_INDICATOR_DOCKWIDGET",VIEW_FLIGHT,Qt::LeftDockWidgetArea);
// pilotView->setTabPosition(Qt::LeftDockWidgetArea,QTabWidget::North);
// pilotView->tabifyDockWidget((QDockWidget*)centralWidgetToDockWidgetsMap[VIEW_FLIGHT]["HORIZONTAL_SITUATION_INDICATOR_DOCKWIDGET"],(QDockWidget*)centralWidgetToDockWidgetsMap[VIEW_FLIGHT]["UAS_INFO_QUICKVIEW_DOCKWIDGET"]);
//UASRawStatusView *view = new UASRawStatusView();
//view->setDecoder(mavlinkDecoder);
//view->show();
//hddisplay->addSource(mavlinkDecoder);
//createDockWidget(pilotView,new HSIDisplay(this),tr("Horizontal Situation"),"HORIZONTAL_SITUATION_INDICATOR_DOCKWIDGET",VIEW_FLIGHT,Qt::LeftDockWidgetArea);
//pilotView->setTabPosition(Qt::LeftDockWidgetArea,QTabWidget::North);
//pilotView->tabifyDockWidget((QDockWidget*)centralWidgetToDockWidgetsMap[VIEW_FLIGHT]["HORIZONTAL_SITUATION_INDICATOR_DOCKWIDGET"],(QDockWidget*)centralWidgetToDockWidgetsMap[VIEW_FLIGHT]["UAS_INFO_QUICKVIEW_DOCKWIDGET"]);
//createDockWidget(pilotView,new UASActionsWidget(this),tr("Actions"),"UNMANNED_SYSTEM_ACTION_DOCKWIDGET",VIEW_FLIGHT,Qt::RightDockWidgetArea);
// Custom widgets, added last to all menus and layouts
buildCustomWidget();
......@@ -760,7 +805,9 @@ void MainWindow::loadDockWidget(QString name)
}
else if (name == "COMMUNICATION_DEBUG_CONSOLE_DOCKWIDGET")
{
createDockWidget(centerStack->currentWidget(),new DebugConsole(this),tr("Communication Console"),"COMMUNICATION_DEBUG_CONSOLE_DOCKWIDGET",currentView,Qt::BottomDockWidgetArea);
//This is now a permanently detached window.
//centralWidgetToDockWidgetsMap[currentView][name] = console;
//createDockWidget(centerStack->currentWidget(),new DebugConsole(this),tr("Communication Console"),"COMMUNICATION_DEBUG_CONSOLE_DOCKWIDGET",currentView,Qt::BottomDockWidgetArea);
}
else if (name == "HORIZONTAL_SITUATION_INDICATOR_DOCKWIDGET")
{
......@@ -1606,6 +1653,8 @@ void MainWindow::addLink(LinkInterface *link)
if (!found)
{ // || udp
CommConfigurationWindow* commWidget = new CommConfigurationWindow(link, mavlink, this);
commsWidgetList.append(commWidget);
connect(commWidget,SIGNAL(destroyed(QObject*)),this,SLOT(commsWidgetDestroyed(QObject*)));
QAction* action = commWidget->getAction();
ui.menuNetwork->addAction(action);
......@@ -1619,6 +1668,13 @@ void MainWindow::addLink(LinkInterface *link)
}
}
}
void MainWindow::commsWidgetDestroyed(QObject *obj)
{
if (commsWidgetList.contains(obj))
{
commsWidgetList.removeOne(obj);
}
}
void MainWindow::setActiveUAS(UASInterface* uas)
{
......
......@@ -250,6 +250,8 @@ public slots:
/** @brief Update the window name */
void configureWindowName();
void commsWidgetDestroyed(QObject *obj);
signals:
void initStatusChanged(const QString& message);
#ifdef MOUSE_ENABLED_LINUX
......@@ -397,6 +399,8 @@ protected:
QPointer<QGCToolBar> toolBar;
QPointer<QGCStatusBar> customStatusBar;
QPointer<DebugConsole> debugConsole;
QPointer<QDockWidget> mavlinkInspectorWidget;
QPointer<MAVLinkDecoder> mavlinkDecoder;
QPointer<QDockWidget> mavlinkSenderWidget;
......@@ -441,6 +445,7 @@ protected:
QTimer windowNameUpdateTimer;
private:
QList<QObject*> commsWidgetList;
QMap<QString,QString> customWidgetNameToFilenameMap;
QMap<QAction*,QString > menuToDockNameMap;
QMap<QDockWidget*,QWidget*> dockToTitleBarMap;
......
......@@ -150,7 +150,7 @@ PrimaryFlightDisplay::PrimaryFlightDisplay(int width, int height, QWidget *paren
font("Bitstream Vera Sans"),
refreshTimer(new QTimer(this)),
navigationCrosstrackError(INFINITY),
navigationCrosstrackError(0),
navigationTargetBearing(UNKNOWN_ATTITUDE),
layout(COMPASS_INTEGRATED),
......@@ -673,7 +673,7 @@ void PrimaryFlightDisplay::drawPitchScale(
QTransform savedTransform = painter.transform();
// find the mark nearest center
int snap = round(pitch/PITCH_SCALE_RESOLUTION)*PITCH_SCALE_RESOLUTION;
int snap = qRound((double)(pitch/PITCH_SCALE_RESOLUTION))*PITCH_SCALE_RESOLUTION;
int _min = snap-PITCH_SCALE_HALFRANGE;
int _max = snap+PITCH_SCALE_HALFRANGE;
for (int degrees=_min; degrees<=_max; degrees+=PITCH_SCALE_RESOLUTION) {
......@@ -876,7 +876,7 @@ void PrimaryFlightDisplay::drawAICompassDisk(QPainter& painter, QRectF area, flo
painter.drawRoundedRect(digitalCompassRect, instrumentEdgePen.widthF()*2/3, instrumentEdgePen.widthF()*2/3);
/* final safeguard for really stupid systems */
int digitalCompassValue = static_cast<int>(round(heading)) % 360;
int digitalCompassValue = static_cast<int>(qRound((double)heading)) % 360;
QString s_digitalCompass;
s_digitalCompass.sprintf("%03d", digitalCompassValue);
......
#include "QGCTabbedInfoView.h"
QGCTabbedInfoView::QGCTabbedInfoView(QWidget *parent) : QWidget(parent)
{
ui.setupUi(this);
actionsWidget = new UASActionsWidget(this);
quickView = new UASQuickView(this);
rawView = new UASRawStatusView(this);
ui.tabWidget->addTab(quickView,"Quick");
ui.tabWidget->addTab(actionsWidget,"Actions");
ui.tabWidget->addTab(rawView,"Status");
}
void QGCTabbedInfoView::addSource(MAVLinkDecoder *decoder)
{
m_decoder = decoder;
rawView->addSource(decoder);
quickView->addSource(decoder);
}
QGCTabbedInfoView::~QGCTabbedInfoView()
{
}
#ifndef QGCTABBEDINFOVIEW_H
#define QGCTABBEDINFOVIEW_H
#include <QWidget>
#include "ui_QGCTabbedInfoView.h"
#include "MAVLinkDecoder.h"
#include "UASActionsWidget.h"
#include "UASQuickView.h"
#include "UASRawStatusView.h"
class QGCTabbedInfoView : public QWidget
{
Q_OBJECT
public:
explicit QGCTabbedInfoView(QWidget *parent = 0);
~QGCTabbedInfoView();
void addSource(MAVLinkDecoder *decoder);
private:
MAVLinkDecoder *m_decoder;
Ui::QGCTabbedInfoView ui;
UASActionsWidget *actionsWidget;
UASQuickView *quickView;
UASRawStatusView *rawView;
};
#endif // QGCTABBEDINFOVIEW_H
<?xml version="1.0" encoding="UTF-8"?>
<ui version="4.0">
<class>QGCTabbedInfoView</class>
<widget class="QWidget" name="QGCTabbedInfoView">
<property name="geometry">
<rect>
<x>0</x>
<y>0</y>
<width>571</width>
<height>457</height>
</rect>
</property>
<property name="windowTitle">
<string>Form</string>
</property>
<layout class="QVBoxLayout" name="verticalLayout">
<item>
<widget class="QTabWidget" name="tabWidget">
<property name="currentIndex">
<number>-1</number>
</property>
</widget>
</item>
</layout>
</widget>
<resources/>
<connections/>
</ui>
This diff is collapsed.
......@@ -26,7 +26,8 @@ public:
RC_MODE_1 = 1,
RC_MODE_2 = 2,
RC_MODE_3 = 3,
RC_MODE_4 = 4
RC_MODE_4 = 4,
RC_MODE_NONE = 5
};
public slots:
......@@ -56,6 +57,8 @@ public slots:
/** Render the data updated */
void updateView();
void updateMinMax();
/** Set the RC channel */
void setRollChan(int channel) {
rcMapping[0] = channel - 1;
......
This diff is collapsed.
#include "UASRawStatusView.h"
#include "MAVLinkDecoder.h"
#include "UASInterface.h"
#include "UAS.h"
#include <QTimer>
#include <QScrollBar>
UASRawStatusView::UASRawStatusView(QWidget *parent) : QWidget(parent)
{
ui.setupUi(this);
ui.tableWidget->setColumnCount(2);
ui.tableWidget->setHorizontalScrollBarPolicy(Qt::ScrollBarAlwaysOn);
ui.tableWidget->setShowGrid(false);
ui.tableWidget->setEditTriggers(QAbstractItemView::NoEditTriggers);
QTimer *timer = new QTimer(this);
connect(timer,SIGNAL(timeout()),this,SLOT(updateTableTimerTick()));
timer->start(2000);
}
void UASRawStatusView::addSource(MAVLinkDecoder *decoder)
{
connect(decoder,SIGNAL(valueChanged(int,QString,QString,double,quint64)),this,SLOT(valueChanged(int,QString,QString,double,quint64)));
connect(decoder,SIGNAL(valueChanged(int,QString,QString,qint8,quint64)),this,SLOT(valueChanged(int,QString,QString,qint8,quint64)));
connect(decoder,SIGNAL(valueChanged(int,QString,QString,qint16,quint64)),this,SLOT(valueChanged(int,QString,QString,qint16,quint64)));
connect(decoder,SIGNAL(valueChanged(int,QString,QString,qint32,quint64)),this,SLOT(valueChanged(int,QString,QString,qint32,quint64)));
connect(decoder,SIGNAL(valueChanged(int,QString,QString,qint64,quint64)),this,SLOT(valueChanged(int,QString,QString,qint64,quint64)));
connect(decoder,SIGNAL(valueChanged(int,QString,QString,quint8,quint64)),this,SLOT(valueChanged(int,QString,QString,quint8,quint64)));
connect(decoder,SIGNAL(valueChanged(int,QString,QString,qint16,quint64)),this,SLOT(valueChanged(int,QString,QString,qint16,quint64)));
connect(decoder,SIGNAL(valueChanged(int,QString,QString,quint32,quint64)),this,SLOT(valueChanged(int,QString,QString,quint32,quint64)));
connect(decoder,SIGNAL(valueChanged(int,QString,QString,quint64,quint64)),this,SLOT(valueChanged(int,QString,QString,quint64,quint64)));
}
void UASRawStatusView::valueChanged(const int uasId, const QString& name, const QString& unit, const quint8 value, const quint64 msec)
{
valueChanged(uasId,name,unit,(double)value,msec);
}
void UASRawStatusView::valueChanged(const int uasId, const QString& name, const QString& unit, const qint8 value, const quint64 msec)
{
valueChanged(uasId,name,unit,(double)value,msec);
}
void UASRawStatusView::valueChanged(const int uasId, const QString& name, const QString& unit, const quint16 value, const quint64 msec)
{
valueChanged(uasId,name,unit,(double)value,msec);
}
void UASRawStatusView::valueChanged(const int uasId, const QString& name, const QString& unit, const qint16 value, const quint64 msec)
{
valueChanged(uasId,name,unit,(double)value,msec);
}
void UASRawStatusView::valueChanged(const int uasId, const QString& name, const QString& unit, const quint32 value, const quint64 msec)
{
valueChanged(uasId,name,unit,(double)value,msec);
}
void UASRawStatusView::valueChanged(const int uasId, const QString& name, const QString& unit, const qint32 value, const quint64 msec)
{
valueChanged(uasId,name,unit,(double)value,msec);
}
void UASRawStatusView::valueChanged(const int uasId, const QString& name, const QString& unit, const quint64 value, const quint64 msec)
{
valueChanged(uasId,name,unit,(double)value,msec);
}
void UASRawStatusView::valueChanged(const int uasId, const QString& name, const QString& unit, const qint64 value, const quint64 msec)
{
valueChanged(uasId,name,unit,(double)value,msec);
}
void UASRawStatusView::valueChanged(const int uasId, const QString& name, const QString& unit, const double value, const quint64 msec)
{
valueMap[name] = value;
if (nameToUpdateWidgetMap.contains(name))
{
nameToUpdateWidgetMap[name]->setText(QString::number(value));
}
else
{
m_tableDirty = true;
}
return;
}
void UASRawStatusView::resizeEvent(QResizeEvent *event)
{
m_tableDirty = true;
}
void UASRawStatusView::updateTableTimerTick()
{
if (m_tableDirty)
{
m_tableDirty = false;
int columncount = 2;
bool good = false;
while (!good)
{
ui.tableWidget->clear();
ui.tableWidget->setRowCount(0);
ui.tableWidget->setColumnCount(columncount);
ui.tableWidget->horizontalHeader()->hide();
ui.tableWidget->verticalHeader()->hide();
int currcolumn = 0;
int currrow = 0;
int totalheight = 2 + ui.tableWidget->horizontalScrollBar()->height();
bool broke = false;
for (QMap<QString,double>::const_iterator i=valueMap.constBegin();i!=valueMap.constEnd();i++)
{
if (ui.tableWidget->rowCount() < currrow+1)
{
ui.tableWidget->setRowCount(currrow+1);
}
ui.tableWidget->setItem(currrow,currcolumn,new QTableWidgetItem(i.key().split(".")[1]));
QTableWidgetItem *item = new QTableWidgetItem(QString::number(i.value()));
nameToUpdateWidgetMap[i.key()] = item;
ui.tableWidget->setItem(currrow,currcolumn+1,item);
ui.tableWidget->resizeRowToContents(currrow);
totalheight += ui.tableWidget->rowHeight(currrow);
currrow++;
if ((totalheight + ui.tableWidget->rowHeight(currrow-1)) > ui.tableWidget->height())
{
currcolumn+=2;
totalheight = 2 + ui.tableWidget->horizontalScrollBar()->height();
currrow = 0;
if (currcolumn >= columncount)
{
//We're over what we can do. Add a column and continue.
columncount+=2;
broke = true;
break;
}
}
}
if (!broke)
{
good = true;
}
}
ui.tableWidget->resizeColumnsToContents();
//ui.tableWidget->columnCount()-2
}
}
UASRawStatusView::~UASRawStatusView()
{
}
#ifndef UASRAWSTATUSVIEW_H
#define UASRAWSTATUSVIEW_H
#include <QWidget>
#include "MAVLinkDecoder.h"
#include "ui_UASRawStatusView.h"
class UASRawStatusView : public QWidget
{
Q_OBJECT
public:
explicit UASRawStatusView(QWidget *parent = 0);
~UASRawStatusView();
void addSource(MAVLinkDecoder *decoder);
private slots:
void updateTableTimerTick();
void valueChanged(const int uasId, const QString& name, const QString& unit, const quint8 value, const quint64 msec);
void valueChanged(const int uasId, const QString& name, const QString& unit, const qint8 value, const quint64 msec);
void valueChanged(const int uasId, const QString& name, const QString& unit, const quint16 value, const quint64 msec);
void valueChanged(const int uasId, const QString& name, const QString& unit, const qint16 value, const quint64 msec);
void valueChanged(const int uasId, const QString& name, const QString& unit, const quint32 value, const quint64 msec);
void valueChanged(const int uasId, const QString& name, const QString& unit, const qint32 value, const quint64 msec);
void valueChanged(const int uasId, const QString& name, const QString& unit, const quint64 value, const quint64 msec);
void valueChanged(const int uasId, const QString& name, const QString& unit, const qint64 value, const quint64 msec);
void valueChanged(const int uasId, const QString& name, const QString& unit, const double value, const quint64 msec);
protected:
void resizeEvent(QResizeEvent *event);
private:
QMap<QString,double> valueMap;
QMap<QString,QTableWidgetItem*> nameToUpdateWidgetMap;
Ui::UASRawStatusView ui;
bool m_tableDirty;
};
#endif // UASRAWSTATUSVIEW_H
<?xml version="1.0" encoding="UTF-8"?>
<ui version="4.0">
<class>UASRawStatusView</class>
<widget class="QWidget" name="UASRawStatusView">
<property name="geometry">
<rect>
<x>0</x>
<y>0</y>
<width>400</width>
<height>300</height>
</rect>
</property>
<property name="windowTitle">
<string>Form</string>
</property>
<layout class="QVBoxLayout" name="verticalLayout">
<item>
<widget class="QTableWidget" name="tableWidget"/>
</item>
</layout>
</widget>
<resources/>
<connections/>
</ui>
#include "QGCRadioChannelDisplay.h"
#include <QPainter>
QGCRadioChannelDisplay::QGCRadioChannelDisplay(QWidget *parent) : QWidget(parent)
{
m_showMinMax = false;
m_min = 0;
m_max = 1;
m_value = 1500;
m_orientation = Qt::Vertical;
m_name = "Yaw";
}
void QGCRadioChannelDisplay::setName(QString name)
{
m_name = name;
update();
}
void QGCRadioChannelDisplay::setOrientation(Qt::Orientation orient)
{
m_orientation = orient;
update();
}
void QGCRadioChannelDisplay::paintEvent(QPaintEvent *event)
{
//Values range from 0-3000.
//1500 is the middle, static servo value.
QPainter painter(this);
int currval = m_value;
if (currval > m_max)
{
currval = m_max;
}
if (currval < m_min)
{
currval = m_min;
}
if (m_orientation == Qt::Vertical)
{
painter.drawRect(0,0,width()-1,(height()-1) - (painter.fontMetrics().height() * 2));
painter.setBrush(Qt::SolidPattern);
painter.setPen(QColor::fromRgb(50,255,50));
//m_value - m_min / m_max - m_min
if (!m_showMinMax)
{
int newval = (height()-2-(painter.fontMetrics().height() * 2)) * ((float)(currval - m_min) / ((m_max-m_min)+1));
int newvaly = (height()-2-(painter.fontMetrics().height() * 2)) - newval;
painter.drawRect(1,newvaly,width()-3,((height()-2) - newvaly - (painter.fontMetrics().height() * 2)));
}
else
{
int newval = (height()-2-(painter.fontMetrics().height() * 2)) * ((float)(currval / 3001.0));
int newvaly = (height()-2-(painter.fontMetrics().height() * 2)) - newval;
painter.drawRect(1,newvaly,width()-3,((height()-2) - newvaly - (painter.fontMetrics().height() * 2)));
}
QString valstr = QString::number(m_value);
painter.setPen(QColor::fromRgb(255,255,255));
painter.drawText((width()/2.0) - (painter.fontMetrics().width(m_name)/2.0),((height()-3) - (painter.fontMetrics().height()*1)),m_name);
painter.drawText((width()/2.0) - (painter.fontMetrics().width(valstr)/2.0),((height()-3) - (painter.fontMetrics().height() * 0)),valstr);
if (m_showMinMax)
{
painter.setBrush(Qt::NoBrush);
painter.setPen(QColor::fromRgb(255,0,0));
int maxyval = (height()-3 - (painter.fontMetrics().height() * 2)) - (((height()-3-(painter.fontMetrics().height() * 2)) * ((float)m_max / 3000.0)));
int minyval = (height()-3 - (painter.fontMetrics().height() * 2)) - (((height()-3-(painter.fontMetrics().height() * 2)) * ((float)m_min / 3000.0)));
painter.drawRect(2,maxyval,width()-3,minyval - maxyval);
QString minstr = QString::number(m_min);
painter.drawText((width() / 2.0) - (painter.fontMetrics().width("min")/2.0),minyval,"min");
painter.drawText((width() / 2.0) - (painter.fontMetrics().width(minstr)/2.0),minyval + painter.fontMetrics().height(),minstr);
QString maxstr = QString::number(m_max);
painter.drawText((width() / 2.0) - (painter.fontMetrics().width("max")/2.0),maxyval,"max");
painter.drawText((width() / 2.0) - (painter.fontMetrics().width(maxstr)/2.0),maxyval + painter.fontMetrics().height(),maxstr);
//painter.drawRect(width() * ,2,((width()-1) * ((float)m_max / 3000.0)) - (width() * ((float)m_min / 3000.0)),(height()-5) - (painter.fontMetrics().height() * 2));
}
}
else
{
painter.drawRect(0,0,width()-1,(height()-1) - (painter.fontMetrics().height() * 2));
painter.setBrush(Qt::SolidPattern);
painter.setPen(QColor::fromRgb(50,255,50));
if (!m_showMinMax)
{
painter.drawRect(1,1,(width()-3) * ((float)(currval-m_min) / (m_max-m_min)),(height()-3) - (painter.fontMetrics().height() * 2));
}
else
{
painter.drawRect(1,1,(width()-3) * ((float)currval / 3000.0),(height()-3) - (painter.fontMetrics().height() * 2));
}
painter.setPen(QColor::fromRgb(255,255,255));
QString valstr = QString::number(m_value);
painter.drawText((width()/2.0) - (painter.fontMetrics().width(m_name)/2.0),((height()-3) - (painter.fontMetrics().height()*1)),m_name);
painter.drawText((width()/2.0) - (painter.fontMetrics().width(valstr)/2.0),((height()-3) - (painter.fontMetrics().height() * 0)),valstr);
if (m_showMinMax)
{
painter.setBrush(Qt::NoBrush);
painter.setPen(QColor::fromRgb(255,0,0));
painter.drawRect(width() * ((float)m_min / 3000.0),2,((width()-1) * ((float)m_max / 3000.0)) - (width() * ((float)m_min / 3000.0)),(height()-5) - (painter.fontMetrics().height() * 2));
QString minstr = QString::number(m_min);
painter.drawText((width() * ((float)m_min / 3000.0)) - (painter.fontMetrics().width("min")/2.0),((height()-3) - (painter.fontMetrics().height()*1)),"min");
painter.drawText((width() * ((float)m_min / 3000.0)) - (painter.fontMetrics().width(minstr)/2.0),((height()-3) - (painter.fontMetrics().height() * 0)),minstr);
QString maxstr = QString::number(m_max);
painter.drawText((width() * ((float)m_max / 3000.0)) - (painter.fontMetrics().width("max")/2.0),((height()-3) - (painter.fontMetrics().height()*1)),"max");
painter.drawText((width() * ((float)m_max / 3000.0)) - (painter.fontMetrics().width(maxstr)/2.0),((height()-3) - (painter.fontMetrics().height() * 0)),maxstr);
}
}
}
void QGCRadioChannelDisplay::setValue(int value)
{
if (value < 0)
{
m_value = 0;
}
else if (value > 3000)
{
m_value = 3000;
}
else
{
m_value = value;
}
update();
}
void QGCRadioChannelDisplay::showMinMax()
{
m_showMinMax = true;
update();
}
void QGCRadioChannelDisplay::hideMinMax()
{
m_showMinMax = false;
update();
}
void QGCRadioChannelDisplay::setMin(int value)
{
m_min = value;
if (m_min == m_max)
{
m_min--;
}
update();
}
void QGCRadioChannelDisplay::setMax(int value)
{
m_max = value;
if (m_min == m_max)
{
m_max++;
}
update();
}
#ifndef QGCRADIOCHANNELDISPLAY_H
#define QGCRADIOCHANNELDISPLAY_H
#include <QWidget>
class QGCRadioChannelDisplay : public QWidget
{
Q_OBJECT
public:
explicit QGCRadioChannelDisplay(QWidget *parent = 0);
void setOrientation(Qt::Orientation orient);
void setValue(int value);
void showMinMax();
void hideMinMax();
void setMin(int value);
void setMax(int value);
void setName(QString name);
int value() { return m_value; }
int min() { return m_min; }
int max() { return m_max; }
protected:
void paintEvent(QPaintEvent *event);
private:
Qt::Orientation m_orientation;
int m_value;
int m_min;
int m_max;
bool m_showMinMax;
QString m_name;
signals:
public slots:
};
#endif // QGCRADIOCHANNELDISPLAY_H
#include "UASActionsWidget.h"
#include <QMessageBox>
#include <UAS.h>
UASActionsWidget::UASActionsWidget(QWidget *parent) : QWidget(parent)
{
m_uas = 0;
ui.setupUi(this);
connect(ui.changeAltitudeButton,SIGNAL(clicked()),this,SLOT(changeAltitudeClicked()));
connect(ui.changeSpeedButton,SIGNAL(clicked()),this,SLOT(changeSpeedClicked()));
connect(ui.goToWaypointButton,SIGNAL(clicked()),this,SLOT(goToWaypointClicked()));
connect(ui.armDisarmButton,SIGNAL(clicked()),this,SLOT(armButtonClicked()));
connect(UASManager::instance(),SIGNAL(activeUASSet(UASInterface*)),this,SLOT(activeUASSet(UASInterface*)));
if (UASManager::instance()->getActiveUAS())
{
activeUASSet(UASManager::instance()->getActiveUAS());
}
}
void UASActionsWidget::activeUASSet(UASInterface *uas)
{
m_uas = uas;
connect(m_uas->getWaypointManager(),SIGNAL(waypointEditableListChanged()),this,SLOT(updateWaypointList()));
connect(m_uas->getWaypointManager(),SIGNAL(currentWaypointChanged(quint16)),this,SLOT(currentWaypointChanged(quint16)));
connect(m_uas,SIGNAL(armingChanged(bool)),this,SLOT(armingChanged(bool)));
armingChanged(m_uas->isArmed());
updateWaypointList();
}
void UASActionsWidget::armButtonClicked()
{
if (m_uas)
{
if (m_uas->isArmed())
{
((UAS*)m_uas)->disarmSystem();
}
else
{
((UAS*)m_uas)->armSystem();
}
}
}
void UASActionsWidget::armingChanged(bool state)
{
//TODO:
//Figure out why arm/disarm is in UAS.h and not part of the interface, and fix.
if (state)
{
ui.armDisarmButton->setText("DISARM\nCurrently Armed");
}
else
{
ui.armDisarmButton->setText("ARM\nCurrently Disarmed");
}
}
void UASActionsWidget::currentWaypointChanged(quint16 wpid)
{
ui.currentWaypointLabel->setText("Current: " + QString::number(wpid));
}
void UASActionsWidget::updateWaypointList()
{
ui.waypointComboBox->clear();
for (int i=0;i<m_uas->getWaypointManager()->getWaypointEditableList().size();i++)
{
ui.waypointComboBox->addItem(QString::number(i));
}
}
UASActionsWidget::~UASActionsWidget()
{
}
void UASActionsWidget::goToWaypointClicked()
{
if (!m_uas)
{
return;
}
m_uas->getWaypointManager()->setCurrentWaypoint(ui.waypointComboBox->currentIndex());
}
void UASActionsWidget::changeAltitudeClicked()
{
QMessageBox::information(0,"Error","No implemented yet.");
}
void UASActionsWidget::changeSpeedClicked()
{
if (!m_uas)
{
return;
}
if (m_uas->getSystemType() == MAV_TYPE_QUADROTOR)
{
m_uas->setParameter(1,"WP_SPEED_MAX",QVariant(((float)ui.altitudeSpinBox->value() * 100)));
return;
}
else if (m_uas->getSystemType() == MAV_TYPE_FIXED_WING)
{
QVariant variant;
if (m_uas->getParamManager()->getParameterValue(1,"ARSPD_ENABLE",variant))
{
if (variant.toInt() == 1)
{
m_uas->setParameter(1,"TRIM_ARSPD_CN",QVariant(((float)ui.altitudeSpinBox->value() * 100)));
return;
}
}
m_uas->setParameter(1,"TRIM_ARSPD_CN",QVariant(((float)ui.altitudeSpinBox->value() * 100)));
}
}
#ifndef UASACTIONSWIDGET_H
#define UASACTIONSWIDGET_H
#include <QWidget>
#include "ui_UASActionsWidget.h"
#include <UASManager.h>
#include <UASInterface.h>
class UASActionsWidget : public QWidget
{
Q_OBJECT
public:
explicit UASActionsWidget(QWidget *parent = 0);
~UASActionsWidget();
private:
Ui::UASActionsWidget ui;
UASInterface *m_uas;
private slots:
void armButtonClicked();
void armingChanged(bool state);
void currentWaypointChanged(quint16 wpid);
void updateWaypointList();
void activeUASSet(UASInterface *uas);
void goToWaypointClicked();
void changeAltitudeClicked();
void changeSpeedClicked();
};
#endif // UASACTIONSWIDGET_H
<?xml version="1.0" encoding="UTF-8"?>
<ui version="4.0">
<class>UASActionsWidget</class>
<widget class="QWidget" name="UASActionsWidget">
<property name="geometry">
<rect>
<x>0</x>
<y>0</y>
<width>321</width>
<height>363</height>
</rect>
</property>
<property name="windowTitle">
<string>Form</string>
</property>
<widget class="QGroupBox" name="groupBox">
<property name="geometry">
<rect>
<x>10</x>
<y>10</y>
<width>241</width>
<height>161</height>
</rect>
</property>
<property name="title">
<string>Mission Controls</string>
</property>
<widget class="QPushButton" name="goToWaypointButton">
<property name="geometry">
<rect>
<x>10</x>
<y>50</y>
<width>131</width>
<height>23</height>
</rect>
</property>
<property name="text">
<string>Go To Waypoint</string>
</property>
</widget>
<widget class="QComboBox" name="waypointComboBox">
<property name="geometry">
<rect>
<x>10</x>
<y>20</y>
<width>131</width>
<height>22</height>
</rect>
</property>
</widget>
<widget class="QWidget" name="horizontalLayoutWidget">
<property name="geometry">
<rect>
<x>10</x>
<y>120</y>
<width>221</width>
<height>31</height>
</rect>
</property>
<layout class="QHBoxLayout" name="horizontalLayout">
<item>
<widget class="QSpinBox" name="speedSpinBox"/>
</item>
<item>
<widget class="QPushButton" name="changeSpeedButton">
<property name="text">
<string>Change Speed</string>
</property>
</widget>
</item>
</layout>
</widget>
<widget class="QWidget" name="horizontalLayoutWidget_2">
<property name="geometry">
<rect>
<x>10</x>
<y>81</y>
<width>221</width>
<height>31</height>
</rect>
</property>
<layout class="QHBoxLayout" name="horizontalLayout_2">
<item>
<widget class="QSpinBox" name="altitudeSpinBox"/>
</item>
<item>
<widget class="QPushButton" name="changeAltitudeButton">
<property name="text">
<string>Change Altitude</string>
</property>
</widget>
</item>
</layout>
</widget>
<widget class="QLabel" name="currentWaypointLabel">
<property name="geometry">
<rect>
<x>150</x>
<y>20</y>
<width>81</width>
<height>20</height>
</rect>
</property>
<property name="text">
<string>Current:</string>
</property>
</widget>
<widget class="QPushButton" name="pushButton_6">
<property name="geometry">
<rect>
<x>150</x>
<y>50</y>
<width>81</width>
<height>23</height>
</rect>
</property>
<property name="text">
<string>Restart Mission</string>
</property>
</widget>
</widget>
<widget class="QGroupBox" name="groupBox_2">
<property name="geometry">
<rect>
<x>0</x>
<y>180</y>
<width>311</width>
<height>161</height>
</rect>
</property>
<property name="title">
<string>Auto Actions</string>
</property>
<widget class="QComboBox" name="comboBox">
<property name="geometry">
<rect>
<x>10</x>
<y>20</y>
<width>141</width>
<height>22</height>
</rect>
</property>
</widget>
<widget class="QPushButton" name="pushButton_8">
<property name="geometry">
<rect>
<x>10</x>
<y>50</y>
<width>141</width>
<height>23</height>
</rect>
</property>
<property name="text">
<string>Execute Action</string>
</property>
</widget>
<widget class="QComboBox" name="comboBox_3">
<property name="geometry">
<rect>
<x>160</x>
<y>20</y>
<width>141</width>
<height>22</height>
</rect>
</property>
</widget>
<widget class="QPushButton" name="pushButton_5">
<property name="geometry">
<rect>
<x>160</x>
<y>50</y>
<width>141</width>
<height>23</height>
</rect>
</property>
<property name="text">
<string>Set Mode</string>
</property>
</widget>
<widget class="QPushButton" name="pushButton">
<property name="geometry">
<rect>
<x>10</x>
<y>80</y>
<width>91</width>
<height>23</height>
</rect>
</property>
<property name="text">
<string>Auto</string>
</property>
</widget>
<widget class="QPushButton" name="pushButton_2">
<property name="geometry">
<rect>
<x>110</x>
<y>80</y>
<width>91</width>
<height>23</height>
</rect>
</property>
<property name="text">
<string>Manual</string>
</property>
</widget>
<widget class="QPushButton" name="pushButton_4">
<property name="geometry">
<rect>
<x>210</x>
<y>80</y>
<width>91</width>
<height>23</height>
</rect>
</property>
<property name="text">
<string>RTL</string>
</property>
</widget>
<widget class="QPushButton" name="armDisarmButton">
<property name="geometry">
<rect>
<x>10</x>
<y>110</y>
<width>291</width>
<height>41</height>
</rect>
</property>
<property name="text">
<string>ARM</string>
</property>
</widget>
</widget>
</widget>
<resources/>
<connections/>
</ui>
This diff is collapsed.
......@@ -8,28 +8,62 @@
#include "uas/UASInterface.h"
#include "ui_UASQuickView.h"
#include "UASQuickViewItem.h"
#include "MAVLinkDecoder.h"
#include "UASQuickViewItemSelect.h"
class UASQuickView : public QWidget
{
Q_OBJECT
public:
UASQuickView(QWidget *parent = 0);
void addSource(MAVLinkDecoder *decoder);
private:
UASInterface *uas;
QList<QString> uasPropertyList;
/** List of enabled properties */
QList<QString> uasEnabledPropertyList;
/** Maps from the property name to the current value */
QMap<QString,double> uasPropertyValueMap;
/** Maps from property name to the display item */
QMap<QString,UASQuickViewItem*> uasPropertyToLabelMap;
/** Timer for updating the UI */
QTimer *updateTimer;
/** Selection dialog for selectin/deselecting gauge items */
UASQuickViewItemSelect *quickViewSelectDialog;
/** Saves gauge layout to settings file */
void saveSettings();
/** Loads gauge layout from settings file */
void loadSettings();
protected:
Ui::Form ui;
signals:
public slots:
void valueChanged(const int uasId, const QString& name, const QString& unit, const quint8 value, const quint64 msec);
void valueChanged(const int uasId, const QString& name, const QString& unit, const qint8 value, const quint64 msec);
void valueChanged(const int uasId, const QString& name, const QString& unit, const quint16 value, const quint64 msec);
void valueChanged(const int uasId, const QString& name, const QString& unit, const qint16 value, const quint64 msec);
void valueChanged(const int uasId, const QString& name, const QString& unit, const quint32 value, const quint64 msec);
void valueChanged(const int uasId, const QString& name, const QString& unit, const qint32 value, const quint64 msec);
void valueChanged(const int uasId, const QString& name, const QString& unit, const quint64 value, const quint64 msec);
void valueChanged(const int uasId, const QString& name, const QString& unit, const qint64 value, const quint64 msec);
void valueChanged(const int uasId, const QString& name, const QString& unit, const double value, const quint64 msec);
void valueChanged(const int uasid, const QString& name, const QString& unit, const QVariant value,const quint64 msecs);
void actionTriggered(bool checked);
void actionTriggered();
void updateTimerTick();
void addUAS(UASInterface* uas);
void setActiveUAS(UASInterface* uas);
void valChanged(double val,QString type);
void selectDialogClosed();
void valueEnabled(QString value);
void valueDisabled(QString value);
};
#endif // UASQUICKVIEW_H
......@@ -21,7 +21,11 @@
</property>
<layout class="QVBoxLayout" name="verticalLayout_2">
<item>
<layout class="QVBoxLayout" name="verticalLayout"/>
<layout class="QVBoxLayout" name="verticalLayout">
<property name="spacing">
<number>0</number>
</property>
</layout>
</item>
</layout>
</widget>
......
......@@ -3,24 +3,5 @@
UASQuickViewItem::UASQuickViewItem(QWidget *parent) : QWidget(parent)
{
QVBoxLayout *layout = new QVBoxLayout();
this->setLayout(layout);
titleLabel = new QLabel(this);
titleLabel->setAlignment(Qt::AlignHCenter);
this->layout()->addWidget(titleLabel);
valueLabel = new QLabel(this);
valueLabel->setAlignment(Qt::AlignHCenter);
valueLabel->setText("<h1>0.00</h1>");
this->layout()->addWidget(valueLabel);
layout->addSpacerItem(new QSpacerItem(20, 40, QSizePolicy::Minimum, QSizePolicy::Expanding));
}
void UASQuickViewItem::setValue(double value)
{
valueLabel->setText("<h1>" + QString::number(value,'f',4) + "</h1>");
}
void UASQuickViewItem::setTitle(QString title)
{
titleLabel->setText(title);
}
......@@ -8,15 +8,8 @@ class UASQuickViewItem : public QWidget
Q_OBJECT
public:
explicit UASQuickViewItem(QWidget *parent = 0);
void setValue(double value);
void setTitle(QString title);
private:
QLabel *titleLabel;
QLabel *valueLabel;
signals:
public slots:
virtual void setValue(double value)=0;
virtual void setTitle(QString title)=0;
};
#endif // UASQUICKVIEWITEM_H
#include "UASQuickViewItemSelect.h"
#include <QLabel>
#include <QCheckBox>
UASQuickViewItemSelect::UASQuickViewItemSelect(QWidget *parent) : QWidget(parent)
{
ui.setupUi(this);
currcol = 0;
currrow = 0;
}
void UASQuickViewItemSelect::addItem(QString item,bool enabled)
{
QCheckBox *label = new QCheckBox(this);
if (enabled)
{
label->setChecked(true);
}
connect(label,SIGNAL(clicked(bool)),this,SLOT(checkBoxClicked(bool)));
label->setText(item);
label->show();
ui.gridLayout->addWidget(label,currrow,currcol++);
if (currcol > 10)
{
currcol = 0;
currrow++;
}
}
void UASQuickViewItemSelect::checkBoxClicked(bool checked)
{
QCheckBox *check = qobject_cast<QCheckBox*>(sender());
if (!check)
{
return;
}
if (checked)
{
emit valueEnabled(check->text());
}
else
{
emit valueDisabled(check->text());
}
}
UASQuickViewItemSelect::~UASQuickViewItemSelect()
{
}
#ifndef UASQUICKVIEWITEMSELECT_H
#define UASQUICKVIEWITEMSELECT_H
#include <QWidget>
#include "ui_UASQuickViewItemSelect.h"
class UASQuickViewItemSelect : public QWidget
{
Q_OBJECT
public:
explicit UASQuickViewItemSelect(QWidget *parent = 0);
~UASQuickViewItemSelect();
void addItem(QString item,bool enabled = false);
int currrow;
int currcol;
private:
Ui::UASQuickViewItemSelect ui;
private slots:
void checkBoxClicked(bool checked);
signals:
void valueEnabled(QString value);
void valueDisabled(QString value);
};
#endif // UASQUICKVIEWITEMSELECT_H
<?xml version="1.0" encoding="UTF-8"?>
<ui version="4.0">
<class>UASQuickViewItemSelect</class>
<widget class="QWidget" name="UASQuickViewItemSelect">
<property name="geometry">
<rect>
<x>0</x>
<y>0</y>
<width>571</width>
<height>474</height>
</rect>
</property>
<property name="windowTitle">
<string>Form</string>
</property>
<layout class="QVBoxLayout" name="verticalLayout">
<item>
<widget class="QScrollArea" name="scrollArea">
<property name="widgetResizable">
<bool>true</bool>
</property>
<widget class="QWidget" name="scrollAreaWidgetContents">
<property name="geometry">
<rect>
<x>0</x>
<y>0</y>
<width>551</width>
<height>454</height>
</rect>
</property>
<layout class="QHBoxLayout" name="horizontalLayout">
<item>
<layout class="QGridLayout" name="gridLayout"/>
</item>
</layout>
</widget>
</widget>
</item>
</layout>
</widget>
<resources/>
<connections/>
</ui>
#include "UASQuickViewTextItem.h"
#include <QVBoxLayout>
UASQuickViewTextItem::UASQuickViewTextItem(QWidget *parent) : UASQuickViewItem(parent)
{
QVBoxLayout *layout = new QVBoxLayout();
this->setLayout(layout);
layout->setSpacing(0);
layout->setMargin(0);
titleLabel = new QLabel(this);
titleLabel->setAlignment(Qt::AlignHCenter);
this->layout()->addWidget(titleLabel);
valueLabel = new QLabel(this);
valueLabel->setAlignment(Qt::AlignHCenter);
valueLabel->setText("0.00");
this->layout()->addWidget(valueLabel);
layout->addSpacerItem(new QSpacerItem(20, 40, QSizePolicy::Minimum, QSizePolicy::Expanding));
QFont valuefont = valueLabel->font();
QFont titlefont = titleLabel->font();
valuefont.setPixelSize(this->height() / 2.0);
titlefont.setPixelSize(this->height() / 4.0);
valueLabel->setFont(valuefont);
titleLabel->setFont(titlefont);
}
void UASQuickViewTextItem::setValue(double value)
{
valueLabel->setText(QString::number(value,'f',4));
}
void UASQuickViewTextItem::setTitle(QString title)
{
titleLabel->setText(title);
}
void UASQuickViewTextItem::resizeEvent(QResizeEvent *event)
{
QFont valuefont = valueLabel->font();
QFont titlefont = titleLabel->font();
valuefont.setPixelSize(this->height() / 2.0);
titlefont.setPixelSize(this->height() / 4.0);
valueLabel->setFont(valuefont);
titleLabel->setFont(titlefont);
update();
}
#ifndef UASQUICKVIEWTEXTITEM_H
#define UASQUICKVIEWTEXTITEM_H
#include "UASQuickViewItem.h"
#include <QLabel>
class UASQuickViewTextItem : public UASQuickViewItem
{
public:
UASQuickViewTextItem(QWidget *parent=0);
void setValue(double value);
void setTitle(QString title);
protected:
void resizeEvent(QResizeEvent *event);
private:
QLabel *titleLabel;
QLabel *valueLabel;
};
#endif // UASQUICKVIEWTEXTITEM_H
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