Commit 6b449af3 authored by Michael Carpenter's avatar Michael Carpenter

Addition of new Raw Status display, and tabbed widget container for QuickView

parent 296a2b37
......@@ -229,7 +229,9 @@ FORMS += src/ui/MainWindow.ui \
src/ui/designer/QGCTextLabel.ui \
src/ui/uas/UASQuickView.ui \
src/ui/uas/UASQuickViewItemSelect.ui \
src/ui/uas/UASActionsWidget.ui
src/ui/uas/UASActionsWidget.ui \
src/ui/QGCTabbedInfoView.ui \
src/ui/UASRawStatusView.ui
INCLUDEPATH += src \
src/ui \
src/ui/linechart \
......@@ -381,7 +383,9 @@ HEADERS += src/MG.h \
src/ui/uas/UASQuickViewItem.h \
src/ui/uas/UASQuickViewItemSelect.h \
src/ui/uas/UASQuickViewTextItem.h \
src/ui/uas/UASActionsWidget.h
src/ui/uas/UASActionsWidget.h \
src/ui/QGCTabbedInfoView.h \
src/ui/UASRawStatusView.h
# Google Earth is only supported on Mac OS and Windows with Visual Studio Compiler
macx|macx-g++|macx-g++42|win32-msvc2008|win32-msvc2010|win32-msvc2012::HEADERS += src/ui/map3D/QGCGoogleEarthView.h
......@@ -552,7 +556,9 @@ SOURCES += src/main.cc \
src/ui/uas/UASQuickView.cc \
src/ui/uas/UASQuickViewTextItem.cc \
src/ui/uas/UASQuickViewItemSelect.cc \
src/ui/uas/UASActionsWidget.cpp
src/ui/uas/UASActionsWidget.cpp \
src/ui/QGCTabbedInfoView.cpp \
src/ui/UASRawStatusView.cpp
# Enable Google Earth only on Mac OS and Windows with Visual Studio compiler
macx|macx-g++|macx-g++42|win32-msvc2008|win32-msvc2010|win32-msvc2012::SOURCES += src/ui/map3D/QGCGoogleEarthView.cc
......
......@@ -394,7 +394,11 @@ void SerialLink::writeSettings()
void SerialLink::run()
{
// Initialize the connection
hardwareConnect();
if (!hardwareConnect())
{
//Need to error out here.
}
// Qt way to make clear what a while(1) loop does
quint64 msecs = QDateTime::currentMSecsSinceEpoch();
......
......@@ -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,7 +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"
#ifdef QGC_OSG_ENABLED
#include "Q3DWidgetFactory.h"
#endif
......@@ -575,14 +577,27 @@ void MainWindow::buildCommonWidgets()
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);
UASQuickView *quickview = new UASQuickView(this);
quickview->addSource(mavlinkDecoder);
createDockWidget(pilotView,quickview,tr("Quick View"),"UAS_INFO_QUICKVIEW_DOCKWIDGET",VIEW_FLIGHT,Qt::LeftDockWidgetArea);
//UASQuickView *quickview = new UASQuickView(this);
//quickview->addSource(mavlinkDecoder);
//createDockWidget(pilotView,quickview,tr("Quick View"),"UAS_INFO_QUICKVIEW_DOCKWIDGET",VIEW_FLIGHT,Qt::LeftDockWidgetArea);
QGCTabbedInfoView *infoview = new QGCTabbedInfoView(this);
createDockWidget(pilotView,infoview,tr("Info View"),"UAS_INFO_INFOVIEW_DOCKWIDGET",VIEW_FLIGHT,Qt::LeftDockWidgetArea);
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 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();
......
#include "QGCTabbedInfoView.h"
#include <UASActionsWidget.h>
#include <UASQuickView.h>
QGCTabbedInfoView::QGCTabbedInfoView(QWidget *parent) : QWidget(parent)
{
ui.setupUi(this);
ui.tabWidget->addTab(new UASQuickView(this),"Quick");
ui.tabWidget->addTab(new UASActionsWidget(this),"Actions");
}
QGCTabbedInfoView::~QGCTabbedInfoView()
{
}
#ifndef QGCTABBEDINFOVIEW_H
#define QGCTABBEDINFOVIEW_H
#include <QWidget>
#include "ui_QGCTabbedInfoView.h"
class QGCTabbedInfoView : public QWidget
{
Q_OBJECT
public:
explicit QGCTabbedInfoView(QWidget *parent = 0);
~QGCTabbedInfoView();
private:
Ui::QGCTabbedInfoView ui;
};
#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>
#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::setDecoder(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 setDecoder(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>
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