|
|
@ -35,7 +35,6 @@ This file is part of the PIXHAWK project |
|
|
|
#include <QInputDialog> |
|
|
|
#include <QInputDialog> |
|
|
|
|
|
|
|
|
|
|
|
#include "QGC.h" |
|
|
|
#include "QGC.h" |
|
|
|
#include "MG.h" |
|
|
|
|
|
|
|
#include "UASManager.h" |
|
|
|
#include "UASManager.h" |
|
|
|
#include "UASView.h" |
|
|
|
#include "UASView.h" |
|
|
|
#include "UASWaypointManager.h" |
|
|
|
#include "UASWaypointManager.h" |
|
|
@ -65,6 +64,7 @@ UASView::UASView(UASInterface* uas, QWidget *parent) : |
|
|
|
alt(0), |
|
|
|
alt(0), |
|
|
|
groundDistance(0), |
|
|
|
groundDistance(0), |
|
|
|
localFrame(false), |
|
|
|
localFrame(false), |
|
|
|
|
|
|
|
globalFrameKnown(false), |
|
|
|
removeAction(new QAction("Delete this system", this)), |
|
|
|
removeAction(new QAction("Delete this system", this)), |
|
|
|
renameAction(new QAction("Rename..", this)), |
|
|
|
renameAction(new QAction("Rename..", this)), |
|
|
|
selectAction(new QAction("Control this system", this )), |
|
|
|
selectAction(new QAction("Control this system", this )), |
|
|
@ -72,6 +72,8 @@ UASView::UASView(UASInterface* uas, QWidget *parent) : |
|
|
|
selectAirframeAction(new QAction("Choose Airframe", this)), |
|
|
|
selectAirframeAction(new QAction("Choose Airframe", this)), |
|
|
|
setBatterySpecsAction(new QAction("Set Battery Options", this)), |
|
|
|
setBatterySpecsAction(new QAction("Set Battery Options", this)), |
|
|
|
lowPowerModeEnabled(true), |
|
|
|
lowPowerModeEnabled(true), |
|
|
|
|
|
|
|
generalUpdateCount(0), |
|
|
|
|
|
|
|
filterTime(0), |
|
|
|
m_ui(new Ui::UASView) |
|
|
|
m_ui(new Ui::UASView) |
|
|
|
{ |
|
|
|
{ |
|
|
|
// FIXME XXX
|
|
|
|
// FIXME XXX
|
|
|
@ -127,9 +129,12 @@ UASView::UASView(UASInterface* uas, QWidget *parent) : |
|
|
|
// Set static values
|
|
|
|
// Set static values
|
|
|
|
|
|
|
|
|
|
|
|
// Name
|
|
|
|
// Name
|
|
|
|
if (uas->getUASName() == "") { |
|
|
|
if (uas->getUASName() == "") |
|
|
|
|
|
|
|
{ |
|
|
|
m_ui->nameLabel->setText(tr("UAS") + QString::number(uas->getUASID())); |
|
|
|
m_ui->nameLabel->setText(tr("UAS") + QString::number(uas->getUASID())); |
|
|
|
} else { |
|
|
|
} |
|
|
|
|
|
|
|
else |
|
|
|
|
|
|
|
{ |
|
|
|
m_ui->nameLabel->setText(uas->getUASName()); |
|
|
|
m_ui->nameLabel->setText(uas->getUASName()); |
|
|
|
} |
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
@ -141,7 +146,9 @@ UASView::UASView(UASInterface* uas, QWidget *parent) : |
|
|
|
if (lowPowerModeEnabled) |
|
|
|
if (lowPowerModeEnabled) |
|
|
|
{ |
|
|
|
{ |
|
|
|
refreshTimer->start(updateInterval*3); |
|
|
|
refreshTimer->start(updateInterval*3); |
|
|
|
} else { |
|
|
|
} |
|
|
|
|
|
|
|
else |
|
|
|
|
|
|
|
{ |
|
|
|
refreshTimer->start(updateInterval); |
|
|
|
refreshTimer->start(updateInterval); |
|
|
|
} |
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
@ -194,10 +201,13 @@ void UASView::setBackgroundColor() |
|
|
|
QColor uasColor = uas->getColor(); |
|
|
|
QColor uasColor = uas->getColor(); |
|
|
|
QString colorstyle; |
|
|
|
QString colorstyle; |
|
|
|
QString borderColor = "#4A4A4F"; |
|
|
|
QString borderColor = "#4A4A4F"; |
|
|
|
if (isActive) { |
|
|
|
if (isActive) |
|
|
|
|
|
|
|
{ |
|
|
|
borderColor = "#FA4A4F"; |
|
|
|
borderColor = "#FA4A4F"; |
|
|
|
uasColor = uasColor.darker(475); |
|
|
|
uasColor = uasColor.darker(475); |
|
|
|
} else { |
|
|
|
} |
|
|
|
|
|
|
|
else |
|
|
|
|
|
|
|
{ |
|
|
|
uasColor = uasColor.darker(675); |
|
|
|
uasColor = uasColor.darker(675); |
|
|
|
} |
|
|
|
} |
|
|
|
colorstyle = colorstyle.sprintf("QGroupBox { border-radius: 12px; padding: 0px; margin: 0px; background-color: #%02X%02X%02X; border: 2px solid %s; }", |
|
|
|
colorstyle = colorstyle.sprintf("QGroupBox { border-radius: 12px; padding: 0px; margin: 0px; background-color: #%02X%02X%02X; border: 2px solid %s; }", |
|
|
@ -207,14 +217,16 @@ void UASView::setBackgroundColor() |
|
|
|
|
|
|
|
|
|
|
|
void UASView::setUASasActive(bool active) |
|
|
|
void UASView::setUASasActive(bool active) |
|
|
|
{ |
|
|
|
{ |
|
|
|
if (active) { |
|
|
|
if (active) |
|
|
|
|
|
|
|
{ |
|
|
|
UASManager::instance()->setActiveUAS(this->uas); |
|
|
|
UASManager::instance()->setActiveUAS(this->uas); |
|
|
|
} |
|
|
|
} |
|
|
|
} |
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
void UASView::updateActiveUAS(UASInterface* uas, bool active) |
|
|
|
void UASView::updateActiveUAS(UASInterface* uas, bool active) |
|
|
|
{ |
|
|
|
{ |
|
|
|
if (uas == this->uas) { |
|
|
|
if (uas == this->uas) |
|
|
|
|
|
|
|
{ |
|
|
|
this->isActive = active; |
|
|
|
this->isActive = active; |
|
|
|
setBackgroundColor(); |
|
|
|
setBackgroundColor(); |
|
|
|
} |
|
|
|
} |
|
|
@ -239,22 +251,25 @@ void UASView::mouseDoubleClickEvent (QMouseEvent * event) |
|
|
|
|
|
|
|
|
|
|
|
void UASView::enterEvent(QEvent* event) |
|
|
|
void UASView::enterEvent(QEvent* event) |
|
|
|
{ |
|
|
|
{ |
|
|
|
if (event->type() == QEvent::MouseMove) { |
|
|
|
if (event->type() == QEvent::MouseMove) |
|
|
|
|
|
|
|
{ |
|
|
|
emit uasInFocus(uas); |
|
|
|
emit uasInFocus(uas); |
|
|
|
if (uas != UASManager::instance()->getActiveUAS()) { |
|
|
|
if (uas != UASManager::instance()->getActiveUAS()) |
|
|
|
|
|
|
|
{ |
|
|
|
grabMouse(QCursor(Qt::PointingHandCursor)); |
|
|
|
grabMouse(QCursor(Qt::PointingHandCursor)); |
|
|
|
} |
|
|
|
} |
|
|
|
} |
|
|
|
} |
|
|
|
// qDebug() << __FILE__ << __LINE__ << "IN FOCUS";
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
if (event->type() == QEvent::MouseButtonDblClick) { |
|
|
|
if (event->type() == QEvent::MouseButtonDblClick) |
|
|
|
|
|
|
|
{ |
|
|
|
// qDebug() << __FILE__ << __LINE__ << "UAS CLICKED!";
|
|
|
|
// qDebug() << __FILE__ << __LINE__ << "UAS CLICKED!";
|
|
|
|
} |
|
|
|
} |
|
|
|
} |
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
void UASView::leaveEvent(QEvent* event) |
|
|
|
void UASView::leaveEvent(QEvent* event) |
|
|
|
{ |
|
|
|
{ |
|
|
|
if (event->type() == QEvent::MouseMove) { |
|
|
|
if (event->type() == QEvent::MouseMove) |
|
|
|
|
|
|
|
{ |
|
|
|
emit uasOutFocus(uas); |
|
|
|
emit uasOutFocus(uas); |
|
|
|
releaseMouse(); |
|
|
|
releaseMouse(); |
|
|
|
} |
|
|
|
} |
|
|
@ -300,9 +315,11 @@ void UASView::updateName(const QString& name) |
|
|
|
*/ |
|
|
|
*/ |
|
|
|
void UASView::setSystemType(UASInterface* uas, unsigned int systemType) |
|
|
|
void UASView::setSystemType(UASInterface* uas, unsigned int systemType) |
|
|
|
{ |
|
|
|
{ |
|
|
|
if (uas == this->uas) { |
|
|
|
if (uas == this->uas) |
|
|
|
|
|
|
|
{ |
|
|
|
// Set matching icon
|
|
|
|
// Set matching icon
|
|
|
|
switch (systemType) { |
|
|
|
switch (systemType) |
|
|
|
|
|
|
|
{ |
|
|
|
case 0: |
|
|
|
case 0: |
|
|
|
m_ui->typeButton->setIcon(QIcon(":/images/mavs/generic.svg")); |
|
|
|
m_ui->typeButton->setIcon(QIcon(":/images/mavs/generic.svg")); |
|
|
|
break; |
|
|
|
break; |
|
|
@ -354,10 +371,8 @@ void UASView::updateLocalPosition(UASInterface* uas, double x, double y, double |
|
|
|
this->x = x; |
|
|
|
this->x = x; |
|
|
|
this->y = y; |
|
|
|
this->y = y; |
|
|
|
this->z = z; |
|
|
|
this->z = z; |
|
|
|
if (!localFrame) { |
|
|
|
|
|
|
|
localFrame = true; |
|
|
|
localFrame = true; |
|
|
|
} |
|
|
|
} |
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
void UASView::updateGlobalPosition(UASInterface* uas, double lon, double lat, double alt, quint64 usec) |
|
|
|
void UASView::updateGlobalPosition(UASInterface* uas, double lon, double lat, double alt, quint64 usec) |
|
|
|
{ |
|
|
|
{ |
|
|
@ -366,6 +381,7 @@ void UASView::updateGlobalPosition(UASInterface* uas, double lon, double lat, do |
|
|
|
this->lon = lon; |
|
|
|
this->lon = lon; |
|
|
|
this->lat = lat; |
|
|
|
this->lat = lat; |
|
|
|
this->alt = alt; |
|
|
|
this->alt = alt; |
|
|
|
|
|
|
|
globalFrameKnown = true; |
|
|
|
} |
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
void UASView::updateSpeed(UASInterface*, double x, double y, double z, quint64 usec) |
|
|
|
void UASView::updateSpeed(UASInterface*, double x, double y, double z, quint64 usec) |
|
|
@ -386,8 +402,10 @@ void UASView::setWaypoint(int uasId, int id, double x, double y, double z, doubl |
|
|
|
Q_UNUSED(z); |
|
|
|
Q_UNUSED(z); |
|
|
|
Q_UNUSED(yaw); |
|
|
|
Q_UNUSED(yaw); |
|
|
|
Q_UNUSED(autocontinue); |
|
|
|
Q_UNUSED(autocontinue); |
|
|
|
if (uasId == this->uas->getUASID()) { |
|
|
|
if (uasId == this->uas->getUASID()) |
|
|
|
if (current) { |
|
|
|
{ |
|
|
|
|
|
|
|
if (current) |
|
|
|
|
|
|
|
{ |
|
|
|
m_ui->waypointLabel->setText(tr("WP") + QString::number(id)); |
|
|
|
m_ui->waypointLabel->setText(tr("WP") + QString::number(id)); |
|
|
|
} |
|
|
|
} |
|
|
|
} |
|
|
|
} |
|
|
@ -395,14 +413,16 @@ void UASView::setWaypoint(int uasId, int id, double x, double y, double z, doubl |
|
|
|
|
|
|
|
|
|
|
|
void UASView::selectWaypoint(int uasId, int id) |
|
|
|
void UASView::selectWaypoint(int uasId, int id) |
|
|
|
{ |
|
|
|
{ |
|
|
|
if (uasId == this->uas->getUASID()) { |
|
|
|
if (uasId == this->uas->getUASID()) |
|
|
|
|
|
|
|
{ |
|
|
|
m_ui->waypointLabel->setText(tr("WP") + QString::number(id)); |
|
|
|
m_ui->waypointLabel->setText(tr("WP") + QString::number(id)); |
|
|
|
} |
|
|
|
} |
|
|
|
} |
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
void UASView::updateThrust(UASInterface* uas, double thrust) |
|
|
|
void UASView::updateThrust(UASInterface* uas, double thrust) |
|
|
|
{ |
|
|
|
{ |
|
|
|
if (this->uas == uas) { |
|
|
|
if (this->uas == uas) |
|
|
|
|
|
|
|
{ |
|
|
|
this->thrust = thrust; |
|
|
|
this->thrust = thrust; |
|
|
|
} |
|
|
|
} |
|
|
|
} |
|
|
|
} |
|
|
@ -410,7 +430,8 @@ void UASView::updateThrust(UASInterface* uas, double thrust) |
|
|
|
void UASView::updateBattery(UASInterface* uas, double voltage, double percent, int seconds) |
|
|
|
void UASView::updateBattery(UASInterface* uas, double voltage, double percent, int seconds) |
|
|
|
{ |
|
|
|
{ |
|
|
|
Q_UNUSED(voltage); |
|
|
|
Q_UNUSED(voltage); |
|
|
|
if (this->uas == uas) { |
|
|
|
if (this->uas == uas) |
|
|
|
|
|
|
|
{ |
|
|
|
timeRemaining = seconds; |
|
|
|
timeRemaining = seconds; |
|
|
|
chargeLevel = percent; |
|
|
|
chargeLevel = percent; |
|
|
|
} |
|
|
|
} |
|
|
@ -418,7 +439,8 @@ void UASView::updateBattery(UASInterface* uas, double voltage, double percent, i |
|
|
|
|
|
|
|
|
|
|
|
void UASView::updateState(UASInterface* uas, QString uasState, QString stateDescription) |
|
|
|
void UASView::updateState(UASInterface* uas, QString uasState, QString stateDescription) |
|
|
|
{ |
|
|
|
{ |
|
|
|
if (this->uas == uas) { |
|
|
|
if (this->uas == uas) |
|
|
|
|
|
|
|
{ |
|
|
|
state = uasState; |
|
|
|
state = uasState; |
|
|
|
stateDesc = stateDescription; |
|
|
|
stateDesc = stateDescription; |
|
|
|
} |
|
|
|
} |
|
|
@ -426,7 +448,8 @@ void UASView::updateState(UASInterface* uas, QString uasState, QString stateDesc |
|
|
|
|
|
|
|
|
|
|
|
void UASView::updateLoad(UASInterface* uas, double load) |
|
|
|
void UASView::updateLoad(UASInterface* uas, double load) |
|
|
|
{ |
|
|
|
{ |
|
|
|
if (this->uas == uas) { |
|
|
|
if (this->uas == uas) |
|
|
|
|
|
|
|
{ |
|
|
|
this->load = load; |
|
|
|
this->load = load; |
|
|
|
} |
|
|
|
} |
|
|
|
} |
|
|
|
} |
|
|
@ -437,7 +460,8 @@ void UASView::contextMenuEvent (QContextMenuEvent* event) |
|
|
|
menu.addAction(selectAction); |
|
|
|
menu.addAction(selectAction); |
|
|
|
menu.addSeparator(); |
|
|
|
menu.addSeparator(); |
|
|
|
menu.addAction(renameAction); |
|
|
|
menu.addAction(renameAction); |
|
|
|
if (timeout) { |
|
|
|
if (timeout) |
|
|
|
|
|
|
|
{ |
|
|
|
menu.addAction(removeAction); |
|
|
|
menu.addAction(removeAction); |
|
|
|
} |
|
|
|
} |
|
|
|
menu.addAction(hilAction); |
|
|
|
menu.addAction(hilAction); |
|
|
@ -448,7 +472,8 @@ void UASView::contextMenuEvent (QContextMenuEvent* event) |
|
|
|
|
|
|
|
|
|
|
|
void UASView::setBatterySpecs() |
|
|
|
void UASView::setBatterySpecs() |
|
|
|
{ |
|
|
|
{ |
|
|
|
if (uas) { |
|
|
|
if (uas) |
|
|
|
|
|
|
|
{ |
|
|
|
bool ok; |
|
|
|
bool ok; |
|
|
|
QString newName = QInputDialog::getText(this, tr("Set Battery Specifications for %1").arg(uas->getUASName()), |
|
|
|
QString newName = QInputDialog::getText(this, tr("Set Battery Specifications for %1").arg(uas->getUASName()), |
|
|
|
tr("Specs: (empty,warn,full), e.g. (9V,9.5V,12.6V) or just warn level in percent (e.g. 15%) to use estimate from MAV"), QLineEdit::Normal, |
|
|
|
tr("Specs: (empty,warn,full), e.g. (9V,9.5V,12.6V) or just warn level in percent (e.g. 15%) to use estimate from MAV"), QLineEdit::Normal, |
|
|
@ -460,7 +485,8 @@ void UASView::setBatterySpecs() |
|
|
|
|
|
|
|
|
|
|
|
void UASView::rename() |
|
|
|
void UASView::rename() |
|
|
|
{ |
|
|
|
{ |
|
|
|
if (uas) { |
|
|
|
if (uas) |
|
|
|
|
|
|
|
{ |
|
|
|
bool ok; |
|
|
|
bool ok; |
|
|
|
QString newName = QInputDialog::getText(this, tr("Rename System %1").arg(uas->getUASName()), |
|
|
|
QString newName = QInputDialog::getText(this, tr("Rename System %1").arg(uas->getUASName()), |
|
|
|
tr("System Name:"), QLineEdit::Normal, |
|
|
|
tr("System Name:"), QLineEdit::Normal, |
|
|
@ -472,7 +498,8 @@ void UASView::rename() |
|
|
|
|
|
|
|
|
|
|
|
void UASView::selectAirframe() |
|
|
|
void UASView::selectAirframe() |
|
|
|
{ |
|
|
|
{ |
|
|
|
if (uas) { |
|
|
|
if (uas) |
|
|
|
|
|
|
|
{ |
|
|
|
// Get list of airframes from UAS
|
|
|
|
// Get list of airframes from UAS
|
|
|
|
QStringList airframes; |
|
|
|
QStringList airframes; |
|
|
|
airframes << "Generic" |
|
|
|
airframes << "Generic" |
|
|
@ -484,12 +511,14 @@ void UASView::selectAirframe() |
|
|
|
<< "Reaper" |
|
|
|
<< "Reaper" |
|
|
|
<< "Predator" |
|
|
|
<< "Predator" |
|
|
|
<< "Coaxial" |
|
|
|
<< "Coaxial" |
|
|
|
<< "Pteryx"; |
|
|
|
<< "Pteryx" |
|
|
|
|
|
|
|
<< "Asctec Firefly"; |
|
|
|
|
|
|
|
|
|
|
|
bool ok; |
|
|
|
bool ok; |
|
|
|
QString item = QInputDialog::getItem(this, tr("Select Airframe for %1").arg(uas->getUASName()), |
|
|
|
QString item = QInputDialog::getItem(this, tr("Select Airframe for %1").arg(uas->getUASName()), |
|
|
|
tr("Airframe"), airframes, uas->getAirframe(), false, &ok); |
|
|
|
tr("Airframe"), airframes, uas->getAirframe(), false, &ok); |
|
|
|
if (ok && !item.isEmpty()) { |
|
|
|
if (ok && !item.isEmpty()) |
|
|
|
|
|
|
|
{ |
|
|
|
// Set this airframe as UAS airframe
|
|
|
|
// Set this airframe as UAS airframe
|
|
|
|
uas->setAirframe(airframes.indexOf(item)); |
|
|
|
uas->setAirframe(airframes.indexOf(item)); |
|
|
|
} |
|
|
|
} |
|
|
@ -501,15 +530,15 @@ void UASView::refresh() |
|
|
|
//setUpdatesEnabled(false);
|
|
|
|
//setUpdatesEnabled(false);
|
|
|
|
//setUpdatesEnabled(true);
|
|
|
|
//setUpdatesEnabled(true);
|
|
|
|
//repaint();
|
|
|
|
//repaint();
|
|
|
|
|
|
|
|
//qDebug() << "UPDATING UAS WIDGET!" << uas->getUASName();
|
|
|
|
|
|
|
|
|
|
|
|
static quint64 lastupdate = 0; |
|
|
|
|
|
|
|
//// qDebug() << "UASVIEW update diff: " << MG::TIME::getGroundTimeNow() - lastupdate;
|
|
|
|
|
|
|
|
lastupdate = MG::TIME::getGroundTimeNow(); |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
// FIXME
|
|
|
|
quint64 lastupdate = 0; |
|
|
|
static int generalUpdateCount = 0; |
|
|
|
//// qDebug() << "UASVIEW update diff: " << MG::TIME::getGroundTimeNow() - lastupdate;
|
|
|
|
|
|
|
|
lastupdate = QGC::groundTimeMilliseconds(); |
|
|
|
|
|
|
|
|
|
|
|
if (generalUpdateCount == 4) { |
|
|
|
if (generalUpdateCount == 4) |
|
|
|
|
|
|
|
{ |
|
|
|
#if (QGC_EVENTLOOP_DEBUG) |
|
|
|
#if (QGC_EVENTLOOP_DEBUG) |
|
|
|
// qDebug() << "EVENTLOOP:" << __FILE__ << __LINE__;
|
|
|
|
// qDebug() << "EVENTLOOP:" << __FILE__ << __LINE__;
|
|
|
|
#endif |
|
|
|
#endif |
|
|
@ -525,29 +554,48 @@ void UASView::refresh() |
|
|
|
m_ui->thrustBar->setValue(this->thrust); |
|
|
|
m_ui->thrustBar->setValue(this->thrust); |
|
|
|
|
|
|
|
|
|
|
|
// Position
|
|
|
|
// Position
|
|
|
|
|
|
|
|
// If global position is known, prefer it over local coordinates
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
if (!globalFrameKnown && localFrame) |
|
|
|
|
|
|
|
{ |
|
|
|
QString position; |
|
|
|
QString position; |
|
|
|
position = position.sprintf("%05.1f %05.1f %06.1f m", x, y, z); |
|
|
|
position = position.sprintf("%05.1f %05.1f %06.1f m", x, y, z); |
|
|
|
m_ui->positionLabel->setText(position); |
|
|
|
m_ui->positionLabel->setText(position); |
|
|
|
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
if (globalFrameKnown) |
|
|
|
|
|
|
|
{ |
|
|
|
QString globalPosition; |
|
|
|
QString globalPosition; |
|
|
|
QString latIndicator; |
|
|
|
QString latIndicator; |
|
|
|
if (lat > 0) { |
|
|
|
if (lat > 0) |
|
|
|
|
|
|
|
{ |
|
|
|
latIndicator = "N"; |
|
|
|
latIndicator = "N"; |
|
|
|
} else { |
|
|
|
} |
|
|
|
|
|
|
|
else |
|
|
|
|
|
|
|
{ |
|
|
|
latIndicator = "S"; |
|
|
|
latIndicator = "S"; |
|
|
|
} |
|
|
|
} |
|
|
|
QString lonIndicator; |
|
|
|
QString lonIndicator; |
|
|
|
if (lon > 0) { |
|
|
|
if (lon > 0) |
|
|
|
|
|
|
|
{ |
|
|
|
lonIndicator = "E"; |
|
|
|
lonIndicator = "E"; |
|
|
|
} else { |
|
|
|
} |
|
|
|
|
|
|
|
else |
|
|
|
|
|
|
|
{ |
|
|
|
lonIndicator = "W"; |
|
|
|
lonIndicator = "W"; |
|
|
|
} |
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
globalPosition = globalPosition.sprintf("%05.1f%s %05.1f%s %06.1f m", lon, lonIndicator.toStdString().c_str(), lat, latIndicator.toStdString().c_str(), alt); |
|
|
|
globalPosition = globalPosition.sprintf("%05.1f%s %05.1f%s %06.1f m", lon, lonIndicator.toStdString().c_str(), lat, latIndicator.toStdString().c_str(), alt); |
|
|
|
m_ui->positionLabel->setText(globalPosition); |
|
|
|
m_ui->positionLabel->setText(globalPosition); |
|
|
|
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
// Altitude
|
|
|
|
// Altitude
|
|
|
|
if (groundDistance == 0 && alt != 0) { |
|
|
|
if (groundDistance == 0 && alt != 0) |
|
|
|
|
|
|
|
{ |
|
|
|
m_ui->groundDistanceLabel->setText(QString("%1 m").arg(alt, 6, 'f', 1, '0')); |
|
|
|
m_ui->groundDistanceLabel->setText(QString("%1 m").arg(alt, 6, 'f', 1, '0')); |
|
|
|
} else { |
|
|
|
} |
|
|
|
|
|
|
|
else |
|
|
|
|
|
|
|
{ |
|
|
|
m_ui->groundDistanceLabel->setText(QString("%1 m").arg(groundDistance, 6, 'f', 1, '0')); |
|
|
|
m_ui->groundDistanceLabel->setText(QString("%1 m").arg(groundDistance, 6, 'f', 1, '0')); |
|
|
|
} |
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
@ -558,9 +606,10 @@ void UASView::refresh() |
|
|
|
// Thrust
|
|
|
|
// Thrust
|
|
|
|
m_ui->thrustBar->setValue(thrust * 100); |
|
|
|
m_ui->thrustBar->setValue(thrust * 100); |
|
|
|
|
|
|
|
|
|
|
|
if(this->timeRemaining > 1 && this->timeRemaining < QGC::MAX_FLIGHT_TIME) { |
|
|
|
if(this->timeRemaining > 1 && this->timeRemaining < QGC::MAX_FLIGHT_TIME) |
|
|
|
|
|
|
|
{ |
|
|
|
// Filter output to get a higher stability
|
|
|
|
// Filter output to get a higher stability
|
|
|
|
static double filterTime = static_cast<int>(this->timeRemaining); |
|
|
|
filterTime = static_cast<int>(this->timeRemaining); |
|
|
|
filterTime = 0.8 * filterTime + 0.2 * static_cast<int>(this->timeRemaining); |
|
|
|
filterTime = 0.8 * filterTime + 0.2 * static_cast<int>(this->timeRemaining); |
|
|
|
int sec = static_cast<int>(filterTime - static_cast<int>(filterTime / 60.0f) * 60); |
|
|
|
int sec = static_cast<int>(filterTime - static_cast<int>(filterTime / 60.0f) * 60); |
|
|
|
int min = static_cast<int>(filterTime / 60); |
|
|
|
int min = static_cast<int>(filterTime / 60); |
|
|
@ -569,7 +618,9 @@ void UASView::refresh() |
|
|
|
QString timeText; |
|
|
|
QString timeText; |
|
|
|
timeText = timeText.sprintf("%02d:%02d:%02d", hours, min, sec); |
|
|
|
timeText = timeText.sprintf("%02d:%02d:%02d", hours, min, sec); |
|
|
|
m_ui->timeRemainingLabel->setText(timeText); |
|
|
|
m_ui->timeRemainingLabel->setText(timeText); |
|
|
|
} else { |
|
|
|
} |
|
|
|
|
|
|
|
else |
|
|
|
|
|
|
|
{ |
|
|
|
m_ui->timeRemainingLabel->setText(tr("Calc..")); |
|
|
|
m_ui->timeRemainingLabel->setText(tr("Calc..")); |
|
|
|
} |
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
@ -588,29 +639,37 @@ void UASView::refresh() |
|
|
|
|
|
|
|
|
|
|
|
QString colorstyle("QGroupBox { border-radius: 5px; padding: 2px; margin: 0px; border: 0px; background-color: %1; }"); |
|
|
|
QString colorstyle("QGroupBox { border-radius: 5px; padding: 2px; margin: 0px; border: 0px; background-color: %1; }"); |
|
|
|
|
|
|
|
|
|
|
|
if (timeout) { |
|
|
|
if (timeout) |
|
|
|
|
|
|
|
{ |
|
|
|
// CRITICAL CONDITION, NO HEARTBEAT
|
|
|
|
// CRITICAL CONDITION, NO HEARTBEAT
|
|
|
|
|
|
|
|
|
|
|
|
QString borderColor = "#FFFF00"; |
|
|
|
QString borderColor = "#FFFF00"; |
|
|
|
if (isActive) { |
|
|
|
if (isActive) |
|
|
|
|
|
|
|
{ |
|
|
|
borderColor = "#FA4A4F"; |
|
|
|
borderColor = "#FA4A4F"; |
|
|
|
} |
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
if (iconIsRed) { |
|
|
|
if (iconIsRed) |
|
|
|
|
|
|
|
{ |
|
|
|
QColor warnColor(Qt::red); |
|
|
|
QColor warnColor(Qt::red); |
|
|
|
m_ui->heartbeatIcon->setStyleSheet(colorstyle.arg(warnColor.name())); |
|
|
|
m_ui->heartbeatIcon->setStyleSheet(colorstyle.arg(warnColor.name())); |
|
|
|
QString style = QString("QGroupBox { border-radius: 12px; padding: 0px; margin: 0px; border: 2px solid %1; background-color: %2; }").arg(borderColor, warnColor.name()); |
|
|
|
QString style = QString("QGroupBox { border-radius: 12px; padding: 0px; margin: 0px; border: 2px solid %1; background-color: %2; }").arg(borderColor, warnColor.name()); |
|
|
|
m_ui->uasViewFrame->setStyleSheet(style); |
|
|
|
m_ui->uasViewFrame->setStyleSheet(style); |
|
|
|
} else { |
|
|
|
} |
|
|
|
|
|
|
|
else |
|
|
|
|
|
|
|
{ |
|
|
|
QColor warnColor(Qt::black); |
|
|
|
QColor warnColor(Qt::black); |
|
|
|
m_ui->heartbeatIcon->setStyleSheet(colorstyle.arg(warnColor.name())); |
|
|
|
m_ui->heartbeatIcon->setStyleSheet(colorstyle.arg(warnColor.name())); |
|
|
|
QString style = QString("QGroupBox { border-radius: 12px; padding: 0px; margin: 0px; border: 2px solid %1; background-color: %2; }").arg(borderColor, warnColor.name()); |
|
|
|
QString style = QString("QGroupBox { border-radius: 12px; padding: 0px; margin: 0px; border: 2px solid %1; background-color: %2; }").arg(borderColor, warnColor.name()); |
|
|
|
m_ui->uasViewFrame->setStyleSheet(style); |
|
|
|
m_ui->uasViewFrame->setStyleSheet(style); |
|
|
|
|
|
|
|
|
|
|
|
refreshTimer->setInterval(errorUpdateInterval); |
|
|
|
refreshTimer->setInterval(errorUpdateInterval); |
|
|
|
|
|
|
|
refreshTimer->start(); |
|
|
|
} |
|
|
|
} |
|
|
|
iconIsRed = !iconIsRed; |
|
|
|
iconIsRed = !iconIsRed; |
|
|
|
} else { |
|
|
|
} |
|
|
|
|
|
|
|
else |
|
|
|
|
|
|
|
{ |
|
|
|
if (!lowPowerModeEnabled) |
|
|
|
if (!lowPowerModeEnabled) |
|
|
|
{ |
|
|
|
{ |
|
|
|
// Fade heartbeat icon
|
|
|
|
// Fade heartbeat icon
|
|
|
@ -620,6 +679,7 @@ void UASView::refresh() |
|
|
|
//m_ui->heartbeatIcon->setAutoFillBackground(true);
|
|
|
|
//m_ui->heartbeatIcon->setAutoFillBackground(true);
|
|
|
|
m_ui->heartbeatIcon->setStyleSheet(colorstyle.arg(heartbeatColor.name())); |
|
|
|
m_ui->heartbeatIcon->setStyleSheet(colorstyle.arg(heartbeatColor.name())); |
|
|
|
refreshTimer->setInterval(updateInterval); |
|
|
|
refreshTimer->setInterval(updateInterval); |
|
|
|
|
|
|
|
refreshTimer->start(); |
|
|
|
} |
|
|
|
} |
|
|
|
} |
|
|
|
} |
|
|
|
//setUpdatesEnabled(true);
|
|
|
|
//setUpdatesEnabled(true);
|
|
|
@ -630,7 +690,8 @@ void UASView::refresh() |
|
|
|
void UASView::changeEvent(QEvent *e) |
|
|
|
void UASView::changeEvent(QEvent *e) |
|
|
|
{ |
|
|
|
{ |
|
|
|
QWidget::changeEvent(e); |
|
|
|
QWidget::changeEvent(e); |
|
|
|
switch (e->type()) { |
|
|
|
switch (e->type()) |
|
|
|
|
|
|
|
{ |
|
|
|
case QEvent::LanguageChange: |
|
|
|
case QEvent::LanguageChange: |
|
|
|
m_ui->retranslateUi(this); |
|
|
|
m_ui->retranslateUi(this); |
|
|
|
break; |
|
|
|
break; |
|
|
|