Commit 76ca1553 authored by Michael Carpenter's avatar Michael Carpenter

Temp commit of new UAS properties and UASQuickView for viewing UAS Properties

parent 56d6bc66
......@@ -226,7 +226,8 @@ FORMS += src/ui/MainWindow.ui \
src/ui/QGCHilJSBSimConfiguration.ui \
src/ui/QGCHilXPlaneConfiguration.ui \
src/ui/designer/QGCComboBox.ui \
src/ui/designer/QGCTextLabel.ui
src/ui/designer/QGCTextLabel.ui \
src/ui/uas/UASQuickView.ui
INCLUDEPATH += src \
src/ui \
src/ui/linechart \
......@@ -373,7 +374,9 @@ HEADERS += src/MG.h \
src/ui/designer/QGCComboBox.h \
src/ui/designer/QGCTextLabel.h \
src/ui/submainwindow.h \
src/ui/dockwidgettitlebareventfilter.h
src/ui/dockwidgettitlebareventfilter.h \
src/ui/uas/UASQuickView.h \
src/ui/uas/UASQuickViewItem.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
......@@ -539,7 +542,9 @@ SOURCES += src/main.cc \
src/ui/designer/QGCComboBox.cc \
src/ui/designer/QGCTextLabel.cc \
src/ui/submainwindow.cpp \
src/ui/dockwidgettitlebareventfilter.cpp
src/ui/dockwidgettitlebareventfilter.cpp \
src/ui/uas/UASQuickView.cpp \
src/ui/uas/UASQuickViewItem.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
......
......@@ -77,9 +77,6 @@ UAS::UAS(MAVLinkProtocol* protocol, int id) : UASInterface(),
localX(0.0),
localY(0.0),
localZ(0.0),
latitude(0.0),
longitude(0.0),
altitude(0.0),
globalEstimatorActive(false),
latitude_gps(0.0),
longitude_gps(0.0),
......@@ -737,14 +734,17 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
mavlink_global_position_int_t pos;
mavlink_msg_global_position_int_decode(&message, &pos);
quint64 time = getUnixTime();
latitude = pos.lat/(double)1E7;
longitude = pos.lon/(double)1E7;
altitude = pos.alt/1000.0;
//latitude = pos.lat/(double)1E7;
setLatitude(pos.lat/(double)1E7);
//longitude = pos.lon/(double)1E7;
setLongitude(pos.lon/(double)1E7);
//altitude = pos.alt/1000.0;
setAltitude(pos.alt/1000.0);
globalEstimatorActive = true;
speedX = pos.vx/100.0;
speedY = pos.vy/100.0;
speedZ = pos.vz/100.0;
emit globalPositionChanged(this, latitude, longitude, altitude, time);
emit globalPositionChanged(this, getLatitude(), getLongitude(), getAltitude(), time);
emit speedChanged(this, speedX, speedY, speedZ, time);
// Set internal state
......@@ -785,10 +785,13 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
altitude_gps = pos.alt/1000.0;
if (!globalEstimatorActive) {
latitude = latitude_gps;
longitude = longitude_gps;
altitude = altitude_gps;
emit globalPositionChanged(this, latitude, longitude, altitude, time);
//latitude = latitude_gps;
setLatitude(latitude_gps);
//longitude = longitude_gps;
setLongitude(longitude_gps);
//altitude = altitude_gps;
setAltitude(altitude_gps);
emit globalPositionChanged(this, getLatitude(), getLongitude(), getAltitude(), time);
}
positionLock = true;
......
......@@ -100,26 +100,74 @@ public:
/** @brief Get the links associated with this robot */
QList<LinkInterface*>* getLinks();
Q_PROPERTY(double localX READ getLocalX WRITE setLocalX NOTIFY localXChanged)
Q_PROPERTY(double localY READ getLocalY WRITE setLocalY NOTIFY localYChanged)
Q_PROPERTY(double localZ READ getLocalZ WRITE setLocalZ NOTIFY localZChanged)
Q_PROPERTY(double latitude READ getLatitude WRITE setLatitude NOTIFY latitudeChanged)
Q_PROPERTY(double longitude READ getLongitude WRITE setLongitude NOTIFY longitudeChanged)
Q_PROPERTY(double altitude READ getAltitude WRITE setAltitude NOTIFY altitudeChanged)
Q_PROPERTY(bool isLocalPositionKnown READ localPositionKnown)
Q_PROPERTY(bool isGlobalPositionKnown READ globalPositionKnown)
Q_PROPERTY(double roll READ getRoll)
Q_PROPERTY(double pitch READ getPitch)
Q_PROPERTY(double yaw READ getYaw)
void setLocalX(double val)
{
localX = val;
emit localXChanged(val,"localX");
}
double getLocalX() const
{
return localX;
}
void setLocalY(double val)
{
localY = val;
emit localYChanged(val,"localY");
}
double getLocalY() const
{
return localY;
}
void setLocalZ(double val)
{
localZ = val;
emit localZChanged(val,"localZ");
}
double getLocalZ() const
{
return localZ;
}
void setLatitude(double val)
{
latitude = val;
emit latitudeChanged(val,"latitude");
}
double getLatitude() const
{
return latitude;
}
void setLongitude(double val)
{
longitude = val;
emit longitudeChanged(val,"longitude");
}
double getLongitude() const
{
return longitude;
}
void setAltitude(double val)
{
altitude = val;
emit altitudeChanged(val,"altitude");
}
double getAltitude() const
{
return altitude;
......@@ -699,6 +747,14 @@ signals:
/** @brief HIL actuator outputs have changed */
void hilActuatorsChanged(uint64_t time, float act1, float act2, float act3, float act4, float act5, float act6, float act7, float act8);
void localXChanged(double val,QString name);
void localYChanged(double val,QString name);
void localZChanged(double val,QString name);
void longitudeChanged(double val,QString name);
void latitudeChanged(double val,QString name);
void altitudeChanged(double val,QString name);
void altitudeChanged(int uasid, double altitude);
protected:
/** @brief Get the UNIX timestamp in milliseconds, enter microseconds */
quint64 getUnixTime(quint64 time=0);
......
......@@ -58,6 +58,7 @@ This file is part of the QGROUNDCONTROL project
#include "QGCRGBDView.h"
#include "QGCFirmwareUpdate.h"
#include "QGCStatusBar.h"
#include "UASQuickView.h"
#ifdef QGC_OSG_ENABLED
#include "Q3DWidgetFactory.h"
......@@ -526,6 +527,13 @@ void MainWindow::buildCommonWidgets()
QAction* tempAction = ui.menuTools->addAction(tr("Radio Control"));
tempAction->setCheckable(true);
connect(tempAction,SIGNAL(triggered(bool)),this, SLOT(showTool(bool)));
}
{
QAction* tempAction = ui.menuTools->addAction(tr("Quick View"));
tempAction->setCheckable(true);
menuToDockNameMap[tempAction] = "UAS_INFO_QUICKVIEW_DOCKWIDGET";
connect(tempAction,SIGNAL(triggered(bool)),this, SLOT(showTool(bool)));
}
createDockWidget(simView,new HUD(320,240,this),tr("Head Up Display"),"HEAD_UP_DISPLAY_DOCKWIDGET",VIEW_SIMULATION,Qt::RightDockWidgetArea,this->width()/1.5);
......@@ -735,6 +743,10 @@ void MainWindow::loadDockWidget(QString name)
{
createDockWidget(centerStack->currentWidget(),new HUD(320,240,this),tr("Head Up Display"),"HEAD_UP_DISPLAY_DOCKWIDGET",currentView,Qt::RightDockWidgetArea);
}
else if (name == "UAS_INFO_QUICKVIEW_DOCKWIDGET")
{
createDockWidget(centerStack->currentWidget(),new UASQuickView(this),tr("Quick View"),"UAS_INFO_QUICKVIEW_DOCKWIDGET",currentView,Qt::LeftDockWidgetArea);
}
else
{
qDebug() << "Error loading window:" << name;
......
#include "UASQuickView.h"
#include <QMetaMethod>
#include <QDebug>
UASQuickView::UASQuickView(QWidget *parent) : QWidget(parent)
{
ui.setupUi(this);
connect(UASManager::instance(),SIGNAL(activeUASSet(UASInterface*)),this,SLOT(setActiveUAS(UASInterface*)));
connect(UASManager::instance(),SIGNAL(UASCreated(UASInterface*)),this,SLOT(addUAS(UASInterface*)));
if (UASManager::instance()->getActiveUAS())
{
addUAS(UASManager::instance()->getActiveUAS());
}
this->setContextMenuPolicy(Qt::ActionsContextMenu);
{
QAction *action = new QAction("latitude",this);
action->setCheckable(true);
action->setChecked(true);
connect(action,SIGNAL(toggled(bool)),this,SLOT(actionTriggered(bool)));
this->addAction(action);
UASQuickViewItem *item = new UASQuickViewItem(this);
item->setTitle("latitude");
ui.verticalLayout->addWidget(item);
uasPropertyToLabelMap["latitude"] = item;
}
{
QAction *action = new QAction("longitude",this);
action->setCheckable(true);
action->setChecked(true);
connect(action,SIGNAL(toggled(bool)),this,SLOT(actionTriggered(bool)));
this->addAction(action);
UASQuickViewItem *item = new UASQuickViewItem(this);
item->setTitle("longitude");
ui.verticalLayout->addWidget(item);
uasPropertyToLabelMap["longitude"] = item;
}
{
QAction *action = new QAction("altitude",this);
action->setCheckable(true);
action->setChecked(true);
connect(action,SIGNAL(toggled(bool)),this,SLOT(actionTriggered(bool)));
this->addAction(action);
UASQuickViewItem *item = new UASQuickViewItem(this);
item->setTitle("altitude");
ui.verticalLayout->addWidget(item);
uasPropertyToLabelMap["altitude"] = item;
}
updateTimer = new QTimer(this);
connect(updateTimer,SIGNAL(timeout()),this,SLOT(updateTimerTick()));
updateTimer->start(1000);
}
void UASQuickView::updateTimerTick()
{
for (int i=0;i<uasPropertyList.size();i++)
{
if (uasPropertyValueMap.contains(uasPropertyList[i]) && uasPropertyToLabelMap.contains(uasPropertyList[i]))
{
uasPropertyToLabelMap[uasPropertyList[i]]->setValue(uasPropertyValueMap.value(uasPropertyList[i],0));
}
}
}
void UASQuickView::addUAS(UASInterface* uas)
{
if (uas)
{
if (!this->uas)
{
setActiveUAS(uas);
}
}
}
void UASQuickView::setActiveUAS(UASInterface* uas)
{
if (!uas)
{
return;
}
this->uas = uas;
uasPropertyList.clear();
qDebug() << "UASInfoWidget property count:" << uas->metaObject()->propertyCount();
for (int i=0;i<uas->metaObject()->propertyCount();i++)
{
if (uas->metaObject()->property(i).hasNotifySignal())
{
qDebug() << "Property:" << i << uas->metaObject()->property(i).name();
uasPropertyList.append(uas->metaObject()->property(i).name());
if (!uasPropertyToLabelMap.contains(uas->metaObject()->property(i).name()))
{
QAction *action = new QAction(QString(uas->metaObject()->property(i).name()),this);
action->setCheckable(true);
connect(action,SIGNAL(toggled(bool)),this,SLOT(actionTriggered(bool)));
this->addAction(action);
}
qDebug() << "Signature:" << uas->metaObject()->property(i).notifySignal().signature();
int val = this->metaObject()->indexOfMethod("valChanged(double,QString)");
if (val != -1)
{
if (!connect(uas,uas->metaObject()->property(i).notifySignal(),this,this->metaObject()->method(val)))
{
qDebug() << "Error connecting signal";
}
}
}
}
}
void UASQuickView::actionTriggered(bool checked)
{
QAction *senderlabel = qobject_cast<QAction*>(sender());
if (!senderlabel)
{
return;
}
if (checked)
{
UASQuickViewItem *item = new UASQuickViewItem(this);
item->setTitle(senderlabel->text());
ui.verticalLayout->addWidget(item);
uasPropertyToLabelMap[senderlabel->text()] = item;
}
else
{
ui.verticalLayout->removeWidget(uasPropertyToLabelMap[senderlabel->text()]);
uasPropertyToLabelMap.remove(senderlabel->text());
uasPropertyToLabelMap[senderlabel->text()]->deleteLater();
}
}
void UASQuickView::valChanged(double val,QString type)
{
//qDebug() << "Value changed:" << type << val;
uasPropertyValueMap[type] = val;
}
#ifndef UASQUICKVIEW_H
#define UASQUICKVIEW_H
#include <QWidget>
#include <QTimer>
#include <QLabel>
#include "uas/UASManager.h"
#include "uas/UASInterface.h"
#include "ui_UASQuickView.h"
#include "UASQuickViewItem.h"
class UASQuickView : public QWidget
{
Q_OBJECT
public:
UASQuickView(QWidget *parent = 0);
private:
UASInterface *uas;
QList<QString> uasPropertyList;
QMap<QString,double> uasPropertyValueMap;
QMap<QString,UASQuickViewItem*> uasPropertyToLabelMap;
QTimer *updateTimer;
protected:
Ui::Form ui;
signals:
public slots:
void actionTriggered(bool checked);
void updateTimerTick();
void addUAS(UASInterface* uas);
void setActiveUAS(UASInterface* uas);
void valChanged(double val,QString type);
};
#endif // UASQUICKVIEW_H
<?xml version="1.0" encoding="UTF-8"?>
<ui version="4.0">
<class>Form</class>
<widget class="QWidget" name="Form">
<property name="geometry">
<rect>
<x>0</x>
<y>0</y>
<width>400</width>
<height>300</height>
</rect>
</property>
<property name="minimumSize">
<size>
<width>100</width>
<height>100</height>
</size>
</property>
<property name="windowTitle">
<string>Form</string>
</property>
<layout class="QVBoxLayout" name="verticalLayout_2">
<item>
<layout class="QVBoxLayout" name="verticalLayout"/>
</item>
</layout>
</widget>
<resources/>
<connections/>
</ui>
#include "UASQuickViewItem.h"
#include <QVBoxLayout>
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);
}
#ifndef UASQUICKVIEWITEM_H
#define UASQUICKVIEWITEM_H
#include <QWidget>
#include <QLabel>
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:
};
#endif // UASQUICKVIEWITEM_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