28 changed files with 2141 additions and 473 deletions
After Width: | Height: | Size: 346 B |
After Width: | Height: | Size: 295 B |
@ -0,0 +1,579 @@
@@ -0,0 +1,579 @@
|
||||
/*=====================================================================
|
||||
|
||||
QGroundControl Open Source Ground Control Station |
||||
|
||||
(c) 2009, 2015 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
|
||||
|
||||
This file is part of the QGROUNDCONTROL project |
||||
|
||||
QGROUNDCONTROL is free software: you can redistribute it and/or modify |
||||
it under the terms of the GNU General Public License as published by |
||||
the Free Software Foundation, either version 3 of the License, or |
||||
(at your option) any later version. |
||||
|
||||
QGROUNDCONTROL is distributed in the hope that it will be useful, |
||||
but WITHOUT ANY WARRANTY; without even the implied warranty of |
||||
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the |
||||
GNU General Public License for more details. |
||||
|
||||
You should have received a copy of the GNU General Public License |
||||
along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>.
|
||||
|
||||
======================================================================*/ |
||||
|
||||
/**
|
||||
* @file |
||||
* @brief QGC Main Tool Bar |
||||
* @author Gus Grubba <mavlink@grubba.com> |
||||
*/ |
||||
|
||||
#include <QQmlContext> |
||||
#include <QQmlEngine> |
||||
|
||||
#include "MainWindow.h" |
||||
#include "MainToolBar.h" |
||||
#include "UASMessageHandler.h" |
||||
#include "UASMessageView.h" |
||||
|
||||
MainToolBar::MainToolBar() |
||||
: _mav(NULL) |
||||
, _toolBar(NULL) |
||||
, _currentView(ViewNone) |
||||
, _batteryVoltage(0.0) |
||||
, _batteryPercent(0.0) |
||||
, _linkSelected(false) |
||||
, _connectionCount(0) |
||||
, _systemArmed(false) |
||||
, _currentHeartbeatTimeout(0) |
||||
, _waypointDistance(0.0) |
||||
, _currentWaypoint(0) |
||||
, _currentMessageCount(0) |
||||
, _currentErrorCount(0) |
||||
, _currentWarningCount(0) |
||||
, _currentNormalCount(0) |
||||
, _currentMessageType(MessageNone) |
||||
, _satelliteCount(-1) |
||||
, _dotsPerInch(72.0) |
||||
, _rollDownMessages(0) |
||||
{ |
||||
setSizePolicy(QSizePolicy::MinimumExpanding, QSizePolicy::MinimumExpanding); |
||||
setObjectName("MainToolBar"); |
||||
setMinimumHeight(40); |
||||
setMaximumHeight(40); |
||||
setMinimumWidth(MainWindow::instance()->minimumWidth()); |
||||
// Get rid of layout default margins
|
||||
QLayout* pl = layout(); |
||||
if(pl) { |
||||
pl->setContentsMargins(0,0,0,0); |
||||
} |
||||
// Get screen DPI to manage font sizes on different platforms
|
||||
QScreen *srn = QGuiApplication::screens().at(0); // TODO: Find current monitor as opposed to picking first one
|
||||
_dotsPerInch = (qreal)srn->logicalDotsPerInch(); // Font point sizes are based on Mac 72dpi
|
||||
|
||||
setContextPropertyObject("mainToolBar", this); |
||||
setSource(QUrl::fromUserInput("qrc:/qml/MainToolBar.qml")); |
||||
setVisible(true); |
||||
// Configure the toolbar for the current default UAS (which should be none as we just booted)
|
||||
_setActiveUAS(UASManager::instance()->getActiveUAS()); |
||||
emit configListChanged(); |
||||
emit heartbeatTimeoutChanged(_currentHeartbeatTimeout); |
||||
emit connectionCountChanged(_connectionCount); |
||||
// Link signals
|
||||
connect(UASManager::instance(), &UASManager::activeUASSet, this, &MainToolBar::_setActiveUAS); |
||||
connect(LinkManager::instance(), &LinkManager::linkConfigurationChanged, this, &MainToolBar::_updateConfigurations); |
||||
connect(LinkManager::instance(), &LinkManager::linkConnected, this, &MainToolBar::_linkConnected); |
||||
connect(LinkManager::instance(), &LinkManager::linkDisconnected, this, &MainToolBar::_linkDisconnected); |
||||
} |
||||
|
||||
MainToolBar::~MainToolBar() |
||||
{ |
||||
|
||||
} |
||||
|
||||
void MainToolBar::onSetupView() |
||||
{ |
||||
setCurrentView(ViewSetup); |
||||
MainWindow::instance()->loadSetupView(); |
||||
} |
||||
|
||||
void MainToolBar::onPlanView() |
||||
{ |
||||
setCurrentView(ViewPlan); |
||||
MainWindow::instance()->loadOperatorView(); |
||||
} |
||||
|
||||
void MainToolBar::onFlyView() |
||||
{ |
||||
setCurrentView(ViewFly); |
||||
MainWindow::instance()->loadPilotView(); |
||||
} |
||||
|
||||
void MainToolBar::onAnalyzeView() |
||||
{ |
||||
setCurrentView(ViewAnalyze); |
||||
MainWindow::instance()->loadEngineerView(); |
||||
} |
||||
|
||||
void MainToolBar::onConnect(QString conf) |
||||
{ |
||||
// If no connection, the role is "Connect"
|
||||
if(_connectionCount == 0) { |
||||
// Connect Link
|
||||
if(_currentConfig.isEmpty()) { |
||||
MainWindow::instance()->manageLinks(); |
||||
} else { |
||||
// We don't want the combo box updating under our feet
|
||||
LinkManager::instance()->suspendConfigurationUpdates(true); |
||||
// Create a link
|
||||
LinkInterface* link = LinkManager::instance()->createLink(_currentConfig); |
||||
if(link) { |
||||
// Connect it
|
||||
LinkManager::instance()->connectLink(link); |
||||
// Save last used connection
|
||||
MainWindow::instance()->saveLastUsedConnection(_currentConfig); |
||||
} |
||||
LinkManager::instance()->suspendConfigurationUpdates(false); |
||||
} |
||||
} else { |
||||
if(conf.isEmpty()) { |
||||
// Disconnect Only Connected Link
|
||||
int connectedCount = 0; |
||||
LinkInterface* connectedLink = NULL; |
||||
QList<LinkInterface*> links = LinkManager::instance()->getLinks(); |
||||
foreach(LinkInterface* link, links) { |
||||
if (link->isConnected()) { |
||||
connectedCount++; |
||||
connectedLink = link; |
||||
} |
||||
} |
||||
Q_ASSERT(connectedCount == 1); |
||||
Q_ASSERT(_connectionCount == 1); |
||||
Q_ASSERT(connectedLink); |
||||
LinkManager::instance()->disconnectLink(connectedLink); |
||||
} else { |
||||
// Disconnect Named Connected Link
|
||||
QList<LinkInterface*> links = LinkManager::instance()->getLinks(); |
||||
foreach(LinkInterface* link, links) { |
||||
if (link->isConnected()) { |
||||
if(link->getLinkConfiguration() && link->getLinkConfiguration()->name() == conf) { |
||||
LinkManager::instance()->disconnectLink(link); |
||||
} |
||||
} |
||||
} |
||||
} |
||||
} |
||||
} |
||||
|
||||
void MainToolBar::onLinkConfigurationChanged(const QString& config) |
||||
{ |
||||
// User selected a link configuration from the combobox
|
||||
if(_currentConfig != config) { |
||||
_currentConfig = config; |
||||
_linkSelected = true; |
||||
} |
||||
} |
||||
|
||||
void MainToolBar::onEnterMessageArea(int x, int y) |
||||
{ |
||||
// If not already there and messages are actually present
|
||||
if(!_rollDownMessages && UASMessageHandler::instance()->messages().count()) |
||||
{ |
||||
// Reset Counts
|
||||
int count = _currentMessageCount; |
||||
MessageType_t type = _currentMessageType; |
||||
_currentErrorCount = 0; |
||||
_currentWarningCount = 0; |
||||
_currentNormalCount = 0; |
||||
_currentMessageCount = 0; |
||||
_currentMessageType = MessageNone; |
||||
if(count != _currentMessageCount) { |
||||
emit messageCountChanged(0); |
||||
} |
||||
if(type != _currentMessageType) { |
||||
emit messageTypeChanged(MessageNone); |
||||
} |
||||
// Show messages
|
||||
int dialogWidth = 400; |
||||
x = x - (dialogWidth >> 1); |
||||
if(x < 0) x = 0; |
||||
y = height() / 3; |
||||
// Put dialog on top of the message alert icon
|
||||
QPoint p = mapToGlobal(QPoint(x,y)); |
||||
_rollDownMessages = new UASMessageViewRollDown(MainWindow::instance()); |
||||
_rollDownMessages->setAttribute(Qt::WA_DeleteOnClose); |
||||
_rollDownMessages->move(mapFromGlobal(p)); |
||||
_rollDownMessages->setMinimumSize(dialogWidth,200); |
||||
connect(_rollDownMessages, &UASMessageViewRollDown::closeWindow, this, &MainToolBar::_leaveMessageView); |
||||
_rollDownMessages->show(); |
||||
} |
||||
} |
||||
|
||||
QString MainToolBar::getMavIconColor() |
||||
{ |
||||
// TODO: Not using because not only the colors are ghastly, it doesn't respect dark/light palette
|
||||
if(_mav) |
||||
return _mav->getColor().name(); |
||||
else |
||||
return QString("black"); |
||||
} |
||||
|
||||
void MainToolBar::_leaveMessageView() |
||||
{ |
||||
// Mouse has left the message window area (and it has closed itself)
|
||||
_rollDownMessages = NULL; |
||||
} |
||||
|
||||
void MainToolBar::setCurrentView(int currentView) |
||||
{ |
||||
ViewType_t view = ViewNone; |
||||
switch((MainWindow::VIEW_SECTIONS)currentView) { |
||||
case MainWindow::VIEW_ENGINEER: |
||||
view = ViewAnalyze; |
||||
break; |
||||
case MainWindow::VIEW_MISSION: |
||||
view = ViewPlan; |
||||
break; |
||||
case MainWindow::VIEW_FLIGHT: |
||||
view = ViewFly; |
||||
break; |
||||
case MainWindow::VIEW_SETUP: |
||||
view = ViewSetup; |
||||
break; |
||||
default: |
||||
view = ViewNone; |
||||
break; |
||||
} |
||||
if(view != _currentView) { |
||||
_currentView = view; |
||||
emit currentViewChanged(); |
||||
} |
||||
} |
||||
|
||||
void MainToolBar::_setActiveUAS(UASInterface* active) |
||||
{ |
||||
// Do nothing if system is the same
|
||||
if (_mav == active) { |
||||
return; |
||||
} |
||||
// If switching the UAS, disconnect the existing one.
|
||||
if (_mav) |
||||
{ |
||||
disconnect(UASMessageHandler::instance(), &UASMessageHandler::textMessageReceived, this, &MainToolBar::_handleTextMessage); |
||||
disconnect(_mav, &UASInterface::heartbeatTimeout, this, &MainToolBar::_heartbeatTimeout); |
||||
disconnect(_mav, &UASInterface::batteryChanged, this, &MainToolBar::_updateBatteryRemaining); |
||||
disconnect(_mav, &UASInterface::modeChanged, this, &MainToolBar::_updateMode); |
||||
disconnect(_mav, &UASInterface::nameChanged, this, &MainToolBar::_updateName); |
||||
disconnect(_mav, &UASInterface::systemTypeSet, this, &MainToolBar::_setSystemType); |
||||
disconnect(_mav, SIGNAL(statusChanged(UASInterface*,QString,QString)), this, SLOT(_updateState(UASInterface*,QString,QString))); |
||||
disconnect(_mav, SIGNAL(armingChanged(bool)), this, SLOT(_updateArmingState(bool))); |
||||
if (_mav->getWaypointManager()) |
||||
{ |
||||
disconnect(_mav->getWaypointManager(), &UASWaypointManager::currentWaypointChanged, this, &MainToolBar::_updateCurrentWaypoint); |
||||
disconnect(_mav->getWaypointManager(), &UASWaypointManager::waypointDistanceChanged, this, &MainToolBar::_updateWaypointDistance); |
||||
} |
||||
UAS* pUas = dynamic_cast<UAS*>(_mav); |
||||
if(pUas) { |
||||
disconnect(pUas, &UAS::satelliteCountChanged, this, &MainToolBar::_setSatelliteCount); |
||||
} |
||||
} |
||||
// Connect new system
|
||||
_mav = active; |
||||
if (_mav) |
||||
{ |
||||
_setSystemType(_mav, _mav->getSystemType()); |
||||
_updateArmingState(_mav->isArmed()); |
||||
connect(UASMessageHandler::instance(), &UASMessageHandler::textMessageReceived, this, &MainToolBar::_handleTextMessage); |
||||
connect(_mav, &UASInterface::heartbeatTimeout, this, &MainToolBar::_heartbeatTimeout); |
||||
connect(_mav, &UASInterface::batteryChanged, this, &MainToolBar::_updateBatteryRemaining); |
||||
connect(_mav, &UASInterface::modeChanged, this, &MainToolBar::_updateMode); |
||||
connect(_mav, &UASInterface::nameChanged, this, &MainToolBar::_updateName); |
||||
connect(_mav, &UASInterface::systemTypeSet, this, &MainToolBar::_setSystemType); |
||||
connect(_mav, SIGNAL(statusChanged(UASInterface*,QString,QString)), this, SLOT(_updateState(UASInterface*, QString,QString))); |
||||
connect(_mav, SIGNAL(armingChanged(bool)), this, SLOT(_updateArmingState(bool))); |
||||
if (_mav->getWaypointManager()) |
||||
{ |
||||
connect(_mav->getWaypointManager(), &UASWaypointManager::currentWaypointChanged, this, &MainToolBar::_updateCurrentWaypoint); |
||||
connect(_mav->getWaypointManager(), &UASWaypointManager::waypointDistanceChanged, this, &MainToolBar::_updateWaypointDistance); |
||||
} |
||||
UAS* pUas = dynamic_cast<UAS*>(_mav); |
||||
if(pUas) { |
||||
_setSatelliteCount(pUas->getSatelliteCount(), QString("")); |
||||
connect(pUas, &UAS::satelliteCountChanged, this, &MainToolBar::_setSatelliteCount); |
||||
} |
||||
} |
||||
// Let toolbar know about it
|
||||
emit mavPresentChanged(_mav != NULL); |
||||
} |
||||
|
||||
void MainToolBar::_updateArmingState(bool armed) |
||||
{ |
||||
if(_systemArmed != armed) { |
||||
_systemArmed = armed; |
||||
emit systemArmedChanged(armed); |
||||
} |
||||
} |
||||
|
||||
void MainToolBar::_updateBatteryRemaining(UASInterface*, double voltage, double, double percent, int) |
||||
{ |
||||
if(percent < 0.0) { |
||||
percent = 0.0; |
||||
} |
||||
if(voltage < 0.0) { |
||||
voltage = 0.0; |
||||
} |
||||
if (_batteryVoltage != voltage) { |
||||
_batteryVoltage = voltage; |
||||
emit batteryVoltageChanged(voltage); |
||||
} |
||||
if (_batteryPercent != percent) { |
||||
_batteryPercent = percent; |
||||
emit batteryPercentChanged(voltage); |
||||
} |
||||
} |
||||
|
||||
void MainToolBar::_updateConfigurations() |
||||
{ |
||||
bool resetSelected = false; |
||||
QString selected = _currentConfig; |
||||
QStringList tmpList; |
||||
QList<LinkConfiguration*> configs = LinkManager::instance()->getLinkConfigurationList(); |
||||
foreach(LinkConfiguration* conf, configs) { |
||||
if(conf) { |
||||
tmpList << conf->name(); |
||||
if((!_linkSelected && conf->isPreferred()) || selected.isEmpty()) { |
||||
selected = conf->name(); |
||||
resetSelected = true; |
||||
} |
||||
} |
||||
} |
||||
// Any changes?
|
||||
if(tmpList != _linkConfigurations) { |
||||
_linkConfigurations = tmpList; |
||||
emit configListChanged(); |
||||
} |
||||
// Selection change?
|
||||
if((selected != _currentConfig && _linkConfigurations.contains(selected)) || |
||||
(selected.isEmpty())) { |
||||
_currentConfig = selected; |
||||
emit currentConfigChanged(_currentConfig); |
||||
} |
||||
if(resetSelected) { |
||||
_linkSelected = false; |
||||
} |
||||
} |
||||
|
||||
void MainToolBar::_linkConnected(LinkInterface*) |
||||
{ |
||||
_updateConnection(); |
||||
} |
||||
|
||||
void MainToolBar::_linkDisconnected(LinkInterface* link) |
||||
{ |
||||
_updateConnection(link); |
||||
} |
||||
|
||||
void MainToolBar::_updateConnection(LinkInterface *disconnectedLink) |
||||
{ |
||||
QStringList connList; |
||||
int oldCount = _connectionCount; |
||||
// If there are multiple connected links add/update the connect button menu
|
||||
_connectionCount = 0; |
||||
QList<LinkInterface*> links = LinkManager::instance()->getLinks(); |
||||
foreach(LinkInterface* link, links) { |
||||
if (disconnectedLink != link && link->isConnected()) { |
||||
_connectionCount++; |
||||
if(link->getLinkConfiguration()) { |
||||
connList << link->getLinkConfiguration()->name(); |
||||
} |
||||
} |
||||
} |
||||
if(oldCount != _connectionCount) { |
||||
emit connectionCountChanged(_connectionCount); |
||||
} |
||||
if(connList != _connectedList) { |
||||
_connectedList = connList; |
||||
emit connectedListChanged(_connectedList); |
||||
} |
||||
} |
||||
|
||||
void MainToolBar::_updateState(UASInterface*, QString name, QString) |
||||
{ |
||||
if (_currentState != name) { |
||||
_currentState = name; |
||||
emit currentStateChanged(_currentState); |
||||
} |
||||
} |
||||
|
||||
void MainToolBar::_updateMode(int, QString name, QString) |
||||
{ |
||||
if (name.size()) { |
||||
QString shortMode = name; |
||||
shortMode = shortMode.replace("D|", ""); |
||||
shortMode = shortMode.replace("A|", ""); |
||||
if (_currentMode != shortMode) { |
||||
_currentMode = shortMode; |
||||
emit currentModeChanged(); |
||||
} |
||||
} |
||||
} |
||||
|
||||
void MainToolBar::_updateName(const QString& name) |
||||
{ |
||||
if (_systemName != name) { |
||||
_systemName = name; |
||||
// TODO: emit signal and use it
|
||||
} |
||||
} |
||||
|
||||
/**
|
||||
* The current system type is represented through the system icon. |
||||
* |
||||
* @param uas Source system, has to be the same as this->uas |
||||
* @param systemType type ID, following the MAVLink system type conventions |
||||
* @see http://pixhawk.ethz.ch/software/mavlink
|
||||
*/ |
||||
void MainToolBar::_setSystemType(UASInterface*, unsigned int systemType) |
||||
{ |
||||
_systemPixmap = "qrc:/files/images/mavs/"; |
||||
switch (systemType) { |
||||
case MAV_TYPE_GENERIC: |
||||
_systemPixmap += "generic.svg"; |
||||
break; |
||||
case MAV_TYPE_FIXED_WING: |
||||
_systemPixmap += "fixed-wing.svg"; |
||||
break; |
||||
case MAV_TYPE_QUADROTOR: |
||||
_systemPixmap += "quadrotor.svg"; |
||||
break; |
||||
case MAV_TYPE_COAXIAL: |
||||
_systemPixmap += "coaxial.svg"; |
||||
break; |
||||
case MAV_TYPE_HELICOPTER: |
||||
_systemPixmap += "helicopter.svg"; |
||||
break; |
||||
case MAV_TYPE_ANTENNA_TRACKER: |
||||
_systemPixmap += "antenna-tracker.svg"; |
||||
break; |
||||
case MAV_TYPE_GCS: |
||||
_systemPixmap += "groundstation.svg"; |
||||
break; |
||||
case MAV_TYPE_AIRSHIP: |
||||
_systemPixmap += "airship.svg"; |
||||
break; |
||||
case MAV_TYPE_FREE_BALLOON: |
||||
_systemPixmap += "free-balloon.svg"; |
||||
break; |
||||
case MAV_TYPE_ROCKET: |
||||
_systemPixmap += "rocket.svg"; |
||||
break; |
||||
case MAV_TYPE_GROUND_ROVER: |
||||
_systemPixmap += "ground-rover.svg"; |
||||
break; |
||||
case MAV_TYPE_SURFACE_BOAT: |
||||
_systemPixmap += "surface-boat.svg"; |
||||
break; |
||||
case MAV_TYPE_SUBMARINE: |
||||
_systemPixmap += "submarine.svg"; |
||||
break; |
||||
case MAV_TYPE_HEXAROTOR: |
||||
_systemPixmap += "hexarotor.svg"; |
||||
break; |
||||
case MAV_TYPE_OCTOROTOR: |
||||
_systemPixmap += "octorotor.svg"; |
||||
break; |
||||
case MAV_TYPE_TRICOPTER: |
||||
_systemPixmap += "tricopter.svg"; |
||||
break; |
||||
case MAV_TYPE_FLAPPING_WING: |
||||
_systemPixmap += "flapping-wing.svg"; |
||||
break; |
||||
case MAV_TYPE_KITE: |
||||
_systemPixmap += "kite.svg"; |
||||
break; |
||||
default: |
||||
_systemPixmap += "unknown.svg"; |
||||
break; |
||||
} |
||||
emit systemPixmapChanged(_systemPixmap); |
||||
} |
||||
|
||||
void MainToolBar::_heartbeatTimeout(bool timeout, unsigned int ms) |
||||
{ |
||||
unsigned int elapsed = ms; |
||||
if (!timeout) |
||||
{ |
||||
elapsed = 0; |
||||
} |
||||
if(elapsed != _currentHeartbeatTimeout) { |
||||
_currentHeartbeatTimeout = elapsed; |
||||
emit heartbeatTimeoutChanged(_currentHeartbeatTimeout); |
||||
} |
||||
} |
||||
|
||||
void MainToolBar::_handleTextMessage(UASMessage*) |
||||
{ |
||||
UASMessageHandler* pMh = UASMessageHandler::instance(); |
||||
Q_ASSERT(pMh); |
||||
MessageType_t type = _currentMessageType; |
||||
int errorCount = _currentErrorCount; |
||||
int warnCount = _currentWarningCount; |
||||
int normalCount = _currentNormalCount; |
||||
//-- Add current message counts
|
||||
errorCount += pMh->getErrorCount(); |
||||
warnCount += pMh->getWarningCount(); |
||||
normalCount += pMh->getNormalCount(); |
||||
//-- See if we have a higher level
|
||||
if(errorCount != _currentErrorCount) { |
||||
_currentErrorCount = errorCount; |
||||
type = MessageError; |
||||
} |
||||
if(warnCount != _currentWarningCount) { |
||||
_currentWarningCount = warnCount; |
||||
if(_currentMessageType != MessageError) { |
||||
type = MessageWarning; |
||||
} |
||||
} |
||||
if(normalCount != _currentNormalCount) { |
||||
_currentNormalCount = normalCount; |
||||
if(_currentMessageType != MessageError && _currentMessageType != MessageWarning) { |
||||
type = MessageNormal; |
||||
} |
||||
} |
||||
int count = _currentErrorCount + _currentWarningCount + _currentNormalCount; |
||||
if(count != _currentMessageCount) { |
||||
_currentMessageCount = count; |
||||
// Display current total message count
|
||||
emit messageCountChanged(count); |
||||
} |
||||
if(type != _currentMessageType) { |
||||
_currentMessageType = type; |
||||
// Update message level
|
||||
emit messageTypeChanged(type); |
||||
} |
||||
} |
||||
|
||||
void MainToolBar::_updateWaypointDistance(double distance) |
||||
{ |
||||
if (_waypointDistance != distance) { |
||||
_waypointDistance = distance; |
||||
// TODO: emit signal and use it
|
||||
} |
||||
} |
||||
|
||||
void MainToolBar::_updateCurrentWaypoint(quint16 id) |
||||
{ |
||||
if (_currentWaypoint != id) { |
||||
_currentWaypoint = id; |
||||
// TODO: emit signal and use it
|
||||
} |
||||
} |
||||
|
||||
void MainToolBar::_setSatelliteCount(double val, QString) |
||||
{ |
||||
if(val < 0.0) val = 0.0; |
||||
if(val > 99.0) val = 99.0; |
||||
if(_satelliteCount != (int)val) { |
||||
_satelliteCount = (int)val; |
||||
emit satelliteCountChanged(_satelliteCount); |
||||
} |
||||
} |
@ -0,0 +1,180 @@
@@ -0,0 +1,180 @@
|
||||
/*=====================================================================
|
||||
|
||||
QGroundControl Open Source Ground Control Station |
||||
|
||||
(c) 2009, 2015 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
|
||||
|
||||
This file is part of the QGROUNDCONTROL project |
||||
|
||||
QGROUNDCONTROL is free software: you can redistribute it and/or modify |
||||
it under the terms of the GNU General Public License as published by |
||||
the Free Software Foundation, either version 3 of the License, or |
||||
(at your option) any later version. |
||||
|
||||
QGROUNDCONTROL is distributed in the hope that it will be useful, |
||||
but WITHOUT ANY WARRANTY; without even the implied warranty of |
||||
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the |
||||
GNU General Public License for more details. |
||||
|
||||
You should have received a copy of the GNU General Public License |
||||
along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>.
|
||||
|
||||
======================================================================*/ |
||||
|
||||
/**
|
||||
* @file |
||||
* @brief QGC Main Tool Bar |
||||
* @author Gus Grubba <mavlink@grubba.com> |
||||
*/ |
||||
|
||||
#ifndef MAINTOOLBAR_H |
||||
#define MAINTOOLBAR_H |
||||
|
||||
#include "QGCQmlWidgetHolder.h" |
||||
|
||||
class UASInterface; |
||||
class UASMessage; |
||||
class UASMessageViewRollDown; |
||||
|
||||
class MainToolBar : public QGCQmlWidgetHolder |
||||
{ |
||||
Q_OBJECT |
||||
Q_ENUMS(ViewType_t) |
||||
Q_ENUMS(MessageType_t) |
||||
public: |
||||
MainToolBar(); |
||||
~MainToolBar(); |
||||
|
||||
typedef enum { |
||||
ViewNone = -1, |
||||
ViewAnalyze, // MainWindow::VIEW_ENGINEER
|
||||
ViewPlan , // MainWindow::VIEW_MISSION
|
||||
ViewFly , // MainWindow::VIEW_FLIGHT
|
||||
ViewSetup , // MainWindow::VIEW_SETUP
|
||||
} ViewType_t; |
||||
|
||||
typedef enum { |
||||
MessageNone, |
||||
MessageNormal, |
||||
MessageWarning, |
||||
MessageError |
||||
} MessageType_t; |
||||
|
||||
Q_INVOKABLE void onSetupView(); |
||||
Q_INVOKABLE void onPlanView(); |
||||
Q_INVOKABLE void onFlyView(); |
||||
Q_INVOKABLE void onAnalyzeView(); |
||||
Q_INVOKABLE void onConnect(QString conf); |
||||
Q_INVOKABLE void onLinkConfigurationChanged(const QString& config); |
||||
Q_INVOKABLE void onEnterMessageArea(int x, int y); |
||||
Q_INVOKABLE QString getMavIconColor(); |
||||
|
||||
Q_PROPERTY(int connectionCount READ connectionCount NOTIFY connectionCountChanged) |
||||
Q_PROPERTY(double batteryVoltage READ batteryVoltage NOTIFY batteryVoltageChanged) |
||||
Q_PROPERTY(double batteryPercent READ batteryPercent NOTIFY batteryPercentChanged) |
||||
Q_PROPERTY(ViewType_t currentView READ currentView NOTIFY currentViewChanged) |
||||
Q_PROPERTY(QStringList configList READ configList NOTIFY configListChanged) |
||||
Q_PROPERTY(bool systemArmed READ systemArmed NOTIFY systemArmedChanged) |
||||
Q_PROPERTY(unsigned int heartbeatTimeout READ heartbeatTimeout NOTIFY heartbeatTimeoutChanged) |
||||
Q_PROPERTY(QString currentMode READ currentMode NOTIFY currentModeChanged) |
||||
Q_PROPERTY(MessageType_t messageType READ messageType NOTIFY messageTypeChanged) |
||||
Q_PROPERTY(int messageCount READ messageCount NOTIFY messageCountChanged) |
||||
Q_PROPERTY(QString currentConfig READ currentConfig NOTIFY currentConfigChanged) |
||||
Q_PROPERTY(QString systemPixmap READ systemPixmap NOTIFY systemPixmapChanged) |
||||
Q_PROPERTY(int satelliteCount READ satelliteCount NOTIFY satelliteCountChanged) |
||||
Q_PROPERTY(QStringList connectedList READ connectedList NOTIFY connectedListChanged) |
||||
Q_PROPERTY(bool mavPresent READ mavPresent NOTIFY mavPresentChanged) |
||||
Q_PROPERTY(QString currentState READ currentState NOTIFY currentStateChanged) |
||||
Q_PROPERTY(double dotsPerInch READ dotsPerInch NOTIFY dotsPerInchChanged) |
||||
|
||||
int connectionCount () { return _connectionCount; } |
||||
double batteryVoltage () { return _batteryVoltage; } |
||||
double batteryPercent () { return _batteryPercent; } |
||||
ViewType_t currentView () { return _currentView; } |
||||
QStringList configList () { return _linkConfigurations; } |
||||
bool systemArmed () { return _systemArmed; } |
||||
unsigned int heartbeatTimeout () { return _currentHeartbeatTimeout; } |
||||
QString currentMode () { return _currentMode; } |
||||
MessageType_t messageType () { return _currentMessageType; } |
||||
int messageCount () { return _currentMessageCount; } |
||||
QString currentConfig () { return _currentConfig; } |
||||
QString systemPixmap () { return _systemPixmap; } |
||||
int satelliteCount () { return _satelliteCount; } |
||||
QStringList connectedList () { return _connectedList; } |
||||
bool mavPresent () { return _mav != NULL; } |
||||
QString currentState () { return _currentState; } |
||||
double dotsPerInch () { return _dotsPerInch; } |
||||
|
||||
void setCurrentView (int currentView); |
||||
|
||||
signals: |
||||
void connectionCountChanged (int count); |
||||
void batteryVoltageChanged (double value); |
||||
void batteryPercentChanged (double value); |
||||
void currentViewChanged (); |
||||
void configListChanged (); |
||||
void systemArmedChanged (bool systemArmed); |
||||
void heartbeatTimeoutChanged (unsigned int hbTimeout); |
||||
void currentModeChanged (); |
||||
void messageTypeChanged (MessageType_t type); |
||||
void messageCountChanged (int count); |
||||
void currentConfigChanged (QString config); |
||||
void systemPixmapChanged (QPixmap pix); |
||||
void satelliteCountChanged (int count); |
||||
void connectedListChanged (QStringList connectedList); |
||||
void mavPresentChanged (bool present); |
||||
void currentStateChanged (QString state); |
||||
void dotsPerInchChanged (); |
||||
|
||||
private slots: |
||||
void _setActiveUAS (UASInterface* active); |
||||
void _updateBatteryRemaining (UASInterface*, double voltage, double, double percent, int); |
||||
void _updateArmingState (bool armed); |
||||
void _updateConfigurations (); |
||||
void _linkConnected (LinkInterface* link); |
||||
void _linkDisconnected (LinkInterface* link); |
||||
void _updateState (UASInterface* system, QString name, QString description); |
||||
void _updateMode (int system, QString name, QString description); |
||||
void _updateName (const QString& name); |
||||
void _setSystemType (UASInterface* uas, unsigned int systemType); |
||||
void _heartbeatTimeout (bool timeout, unsigned int ms); |
||||
void _handleTextMessage (UASMessage* message); |
||||
void _updateCurrentWaypoint (quint16 id); |
||||
void _updateWaypointDistance (double distance); |
||||
void _setSatelliteCount (double val, QString name); |
||||
void _leaveMessageView (); |
||||
|
||||
private: |
||||
void _updateConnection (LinkInterface *disconnectedLink = NULL); |
||||
|
||||
private: |
||||
UASInterface* _mav; |
||||
QQuickItem* _toolBar; |
||||
ViewType_t _currentView; |
||||
double _batteryVoltage; |
||||
double _batteryPercent; |
||||
QStringList _linkConfigurations; |
||||
QString _currentConfig; |
||||
bool _linkSelected; |
||||
int _connectionCount; |
||||
bool _systemArmed; |
||||
QString _currentState; |
||||
QString _currentMode; |
||||
QString _systemName; |
||||
QString _systemPixmap; |
||||
unsigned int _currentHeartbeatTimeout; |
||||
double _waypointDistance; |
||||
quint16 _currentWaypoint; |
||||
int _currentMessageCount; |
||||
int _currentErrorCount; |
||||
int _currentWarningCount; |
||||
int _currentNormalCount; |
||||
MessageType_t _currentMessageType; |
||||
int _satelliteCount; |
||||
QStringList _connectedList; |
||||
qreal _dotsPerInch; |
||||
|
||||
UASMessageViewRollDown* _rollDownMessages; |
||||
}; |
||||
|
||||
#endif // MAINTOOLBAR_H
|
@ -0,0 +1,489 @@
@@ -0,0 +1,489 @@
|
||||
/*===================================================================== |
||||
|
||||
QGroundControl Open Source Ground Control Station |
||||
|
||||
(c) 2009, 2015 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org> |
||||
|
||||
This file is part of the QGROUNDCONTROL project |
||||
|
||||
QGROUNDCONTROL is free software: you can redistribute it and/or modify |
||||
it under the terms of the GNU General Public License as published by |
||||
the Free Software Foundation, either version 3 of the License, or |
||||
(at your option) any later version. |
||||
|
||||
QGROUNDCONTROL is distributed in the hope that it will be useful, |
||||
but WITHOUT ANY WARRANTY; without even the implied warranty of |
||||
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the |
||||
GNU General Public License for more details. |
||||
|
||||
You should have received a copy of the GNU General Public License |
||||
along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>. |
||||
|
||||
======================================================================*/ |
||||
|
||||
/** |
||||
* @file |
||||
* @brief QGC Main Tool Bar |
||||
* @author Gus Grubba <mavlink@grubba.com> |
||||
*/ |
||||
|
||||
import QtQuick 2.3 |
||||
import QtQuick.Controls 1.2 |
||||
import QtQuick.Controls.Styles 1.2 |
||||
|
||||
import QGroundControl.Controls 1.0 |
||||
import QGroundControl.FactControls 1.0 |
||||
import QGroundControl.Palette 1.0 |
||||
import QGroundControl.MainToolBar 1.0 |
||||
|
||||
Rectangle { |
||||
|
||||
property var qgcPal: QGCPalette { id: palette; colorGroupEnabled: true } |
||||
property int cellSpacerSize: 4 |
||||
property int cellHeight: 30 |
||||
property int cellRadius: 3 |
||||
property double dpiFactor: (72.0 / mainToolBar.dotsPerInch); |
||||
|
||||
property var colorBlue: "#1a6eaa" |
||||
property var colorGreen: "#00d930" |
||||
property var colorRed: "#a81a1b" |
||||
property var colorOrange: "#a76f26" |
||||
property var colorWhite: "#f0f0f0" |
||||
|
||||
id: toolBarHolder |
||||
color: qgcPal.windowShade |
||||
|
||||
function getMessageColor() { |
||||
if(mainToolBar.messageType === MainToolBar.MessageNone) |
||||
return qgcPal.button; |
||||
if(mainToolBar.messageType === MainToolBar.MessageNormal) |
||||
return colorBlue; |
||||
if(mainToolBar.messageType === MainToolBar.MessageWarning) |
||||
return colorOrange; |
||||
if(mainToolBar.messageType === MainToolBar.MessageError) |
||||
return colorRed; |
||||
// Cannot be so make make it obnoxious to show error |
||||
return "purple"; |
||||
} |
||||
|
||||
function getMessageIcon() { |
||||
if(mainToolBar.messageType === MainToolBar.MessageNormal || mainToolBar.messageType === MainToolBar.MessageNone) |
||||
return "qrc:/files/images/status/message_megaphone.png"; |
||||
else |
||||
return "qrc:/files/images/status/message_triangle.png"; |
||||
} |
||||
|
||||
function getBatteryIcon() { |
||||
if(mainToolBar.batteryPercent < 20.0) |
||||
return "qrc:/files/images/status/battery_0.svg"; |
||||
else if(mainToolBar.batteryPercent < 40.0) |
||||
return "qrc:/files/images/status/battery_20.svg"; |
||||
else if(mainToolBar.batteryPercent < 60.0) |
||||
return "qrc:/files/images/status/battery_40.svg"; |
||||
else if(mainToolBar.batteryPercent < 80.0) |
||||
return "qrc:/files/images/status/battery_60.svg"; |
||||
else if(mainToolBar.batteryPercent < 90.0) |
||||
return "qrc:/files/images/status/battery_80.svg"; |
||||
else |
||||
return "qrc:/files/images/status/battery_100.svg"; |
||||
} |
||||
|
||||
function showMavStatus() { |
||||
return (mainToolBar.mavPresent && mainToolBar.heartbeatTimeout === 0 && mainToolBar.connectionCount > 0); |
||||
} |
||||
|
||||
Row { |
||||
id: row1 |
||||
height: cellHeight |
||||
anchors.left: parent.left |
||||
spacing: cellSpacerSize |
||||
anchors.verticalCenter: parent.verticalCenter |
||||
anchors.leftMargin: 10 |
||||
|
||||
ExclusiveGroup { id: mainActionGroup } |
||||
|
||||
QGCButton { |
||||
id: setupButton |
||||
width: 90 |
||||
height: cellHeight |
||||
exclusiveGroup: mainActionGroup |
||||
text: qsTr("1. Setup") |
||||
anchors.verticalCenter: parent.verticalCenter |
||||
checked: (mainToolBar.currentView === MainToolBar.ViewSetup) |
||||
onClicked: { |
||||
mainToolBar.onSetupView(); |
||||
} |
||||
} |
||||
|
||||
QGCButton { |
||||
id: planButton |
||||
width: 90 |
||||
height: cellHeight |
||||
exclusiveGroup: mainActionGroup |
||||
text: qsTr("2. Plan") |
||||
anchors.verticalCenter: parent.verticalCenter |
||||
checked: (mainToolBar.currentView === MainToolBar.ViewPlan) |
||||
onClicked: { |
||||
mainToolBar.onPlanView(); |
||||
} |
||||
} |
||||
|
||||
QGCButton { |
||||
id: flyButton |
||||
width: 90 |
||||
height: cellHeight |
||||
exclusiveGroup: mainActionGroup |
||||
text: qsTr("3. Fly") |
||||
anchors.verticalCenter: parent.verticalCenter |
||||
checked: (mainToolBar.currentView === MainToolBar.ViewFly) |
||||
onClicked: { |
||||
mainToolBar.onFlyView(); |
||||
} |
||||
} |
||||
|
||||
QGCButton { |
||||
id: analyzeButton |
||||
width: 90 |
||||
height: cellHeight |
||||
exclusiveGroup: mainActionGroup |
||||
text: qsTr("4. Analyze") |
||||
anchors.verticalCenter: parent.verticalCenter |
||||
checked: (mainToolBar.currentView === MainToolBar.ViewAnalyze) |
||||
onClicked: { |
||||
mainToolBar.onAnalyzeView(); |
||||
} |
||||
} |
||||
|
||||
Rectangle { |
||||
width: 4 |
||||
height: cellHeight |
||||
color: "#00000000" |
||||
border.color: "#00000000" |
||||
border.width: 0 |
||||
} |
||||
|
||||
Rectangle { |
||||
id: messages |
||||
width: (mainToolBar.messageCount > 99) ? 70 : 60 |
||||
height: cellHeight |
||||
visible: (mainToolBar.connectionCount > 0) |
||||
anchors.verticalCenter: parent.verticalCenter |
||||
color: getMessageColor() |
||||
radius: cellRadius |
||||
border.color: "#00000000" |
||||
border.width: 0 |
||||
property bool showTriangle: false |
||||
|
||||
Image { |
||||
id: messageIcon |
||||
source: getMessageIcon(); |
||||
height: 16 |
||||
fillMode: Image.PreserveAspectFit |
||||
anchors.verticalCenter: parent.verticalCenter |
||||
anchors.left: parent.left |
||||
anchors.leftMargin: 10 |
||||
} |
||||
|
||||
Rectangle { |
||||
id: messageTextRect |
||||
anchors.verticalCenter: parent.verticalCenter |
||||
anchors.right: parent.right |
||||
width: messages.width - messageIcon.width |
||||
Text { |
||||
id: messageText |
||||
text: (mainToolBar.messageCount > 0) ? mainToolBar.messageCount : '' |
||||
font.pointSize: 14 * dpiFactor |
||||
font.weight: Font.DemiBold |
||||
anchors.verticalCenter: parent.verticalCenter |
||||
anchors.horizontalCenter: parent.horizontalCenter |
||||
horizontalAlignment: Text.AlignHCenter |
||||
color: colorWhite |
||||
} |
||||
} |
||||
|
||||
Image { |
||||
id: dropDown |
||||
source: "QGroundControl/Controls/arrow-down.png" |
||||
visible: (messages.showTriangle) |
||||
anchors.bottom: parent.bottom |
||||
anchors.right: parent.right |
||||
anchors.bottomMargin: 3 |
||||
anchors.rightMargin: 3 |
||||
} |
||||
|
||||
Timer { |
||||
id: mouseOffTimer |
||||
interval: 2000; |
||||
running: false; |
||||
repeat: false |
||||
onTriggered: { |
||||
messages.showTriangle = false; |
||||
} |
||||
} |
||||
|
||||
MouseArea { |
||||
anchors.fill: parent |
||||
hoverEnabled: true |
||||
onEntered: { |
||||
messages.showTriangle = true; |
||||
mouseOffTimer.start(); |
||||
} |
||||
onExited: { |
||||
messages.showTriangle = false; |
||||
} |
||||
onClicked: { |
||||
var p = mapToItem(toolBarHolder, mouseX, mouseY); |
||||
mainToolBar.onEnterMessageArea(p.x, p.y); |
||||
} |
||||
} |
||||
|
||||
} |
||||
|
||||
Rectangle { |
||||
id: mavIcon |
||||
width: cellHeight |
||||
height: cellHeight |
||||
visible: showMavStatus() |
||||
anchors.verticalCenter: parent.verticalCenter |
||||
color: colorBlue |
||||
radius: cellRadius |
||||
border.color: "#00000000" |
||||
border.width: 0 |
||||
Image { |
||||
source: mainToolBar.systemPixmap |
||||
height: cellHeight * 0.75 |
||||
fillMode: Image.PreserveAspectFit |
||||
anchors.verticalCenter: parent.verticalCenter |
||||
anchors.horizontalCenter: parent.horizontalCenter |
||||
} |
||||
} |
||||
|
||||
Rectangle { |
||||
id: satelitte |
||||
width: 60 |
||||
height: cellHeight |
||||
visible: showMavStatus() |
||||
anchors.verticalCenter: parent.verticalCenter |
||||
color: (mainToolBar.satelliteCount < 3) ? colorRed : colorBlue |
||||
radius: cellRadius |
||||
border.color: "#00000000" |
||||
border.width: 0 |
||||
|
||||
Image { |
||||
source: "qrc:/files/images/status/gps.svg"; |
||||
height: 24 |
||||
fillMode: Image.PreserveAspectFit |
||||
anchors.verticalCenter: parent.verticalCenter |
||||
anchors.left: parent.left |
||||
anchors.leftMargin: 10 |
||||
mipmap: true |
||||
smooth: true |
||||
} |
||||
|
||||
Text { |
||||
id: satelitteText |
||||
text: mainToolBar.satelliteCount |
||||
font.pointSize: 14 * dpiFactor |
||||
font.weight: Font.DemiBold |
||||
anchors.verticalCenter: parent.verticalCenter |
||||
anchors.right: parent.right |
||||
anchors.rightMargin: 10 |
||||
horizontalAlignment: Text.AlignRight |
||||
color: colorWhite |
||||
} |
||||
} |
||||
|
||||
Rectangle { |
||||
id: battery |
||||
width: 80 |
||||
height: cellHeight |
||||
visible: showMavStatus() |
||||
anchors.verticalCenter: parent.verticalCenter |
||||
color: (mainToolBar.batteryPercent > 40.0 || mainToolBar.batteryPercent < 0.01) ? colorBlue : colorRed |
||||
radius: cellRadius |
||||
border.color: "#00000000" |
||||
border.width: 0 |
||||
|
||||
Image { |
||||
source: getBatteryIcon(); |
||||
height: 20 |
||||
fillMode: Image.PreserveAspectFit |
||||
anchors.verticalCenter: parent.verticalCenter |
||||
anchors.left: parent.left |
||||
anchors.leftMargin: 6 |
||||
mipmap: true |
||||
smooth: true |
||||
} |
||||
|
||||
Text { |
||||
id: batteryText |
||||
text: mainToolBar.batteryVoltage.toFixed(2) + ' V'; |
||||
font.pointSize: 14 * dpiFactor |
||||
font.weight: Font.DemiBold |
||||
anchors.verticalCenter: parent.verticalCenter |
||||
anchors.right: parent.right |
||||
anchors.rightMargin: 8 |
||||
horizontalAlignment: Text.AlignRight |
||||
color: colorWhite |
||||
} |
||||
} |
||||
|
||||
Column { |
||||
anchors.verticalCenter: parent.verticalCenter |
||||
spacing: cellSpacerSize |
||||
visible: showMavStatus() |
||||
height: cellHeight * 0.75 |
||||
width: 80 |
||||
|
||||
Rectangle { |
||||
id: armedStatus |
||||
width: parent.width |
||||
height: parent.height / 2 |
||||
anchors.horizontalCenter: parent.horizontalCenter |
||||
color: "#00000000" |
||||
border.color: "#00000000" |
||||
border.width: 0 |
||||
|
||||
Text { |
||||
id: armedStatusText |
||||
text: (mainToolBar.systemArmed) ? qsTr("ARMED") : qsTr("DISARMED") |
||||
font.pointSize: 12 * dpiFactor |
||||
font.weight: Font.DemiBold |
||||
anchors.horizontalCenter: parent.horizontalCenter |
||||
anchors.verticalCenter: parent.verticalCenter |
||||
color: (mainToolBar.systemArmed) ? colorRed : colorGreen |
||||
} |
||||
} |
||||
|
||||
Rectangle { |
||||
id: stateStatus |
||||
width: parent.width |
||||
height: parent.height / 2 |
||||
anchors.horizontalCenter: parent.horizontalCenter |
||||
color: "#00000000" |
||||
border.color: "#00000000" |
||||
border.width: 0 |
||||
|
||||
Text { |
||||
id: stateStatusText |
||||
text: mainToolBar.currentState |
||||
font.pointSize: 12 * dpiFactor |
||||
font.weight: Font.DemiBold |
||||
anchors.horizontalCenter: parent.horizontalCenter |
||||
anchors.verticalCenter: parent.verticalCenter |
||||
color: (mainToolBar.currentState === "STANDBY") ? colorGreen : colorRed |
||||
} |
||||
} |
||||
|
||||
} |
||||
|
||||
Rectangle { |
||||
id: modeStatus |
||||
width: 90 |
||||
height: cellHeight |
||||
visible: showMavStatus() |
||||
color: "#00000000" |
||||
border.color: "#00000000" |
||||
border.width: 0 |
||||
|
||||
Text { |
||||
id: modeStatusText |
||||
text: mainToolBar.currentMode |
||||
font.pointSize: 12 * dpiFactor |
||||
font.weight: Font.DemiBold |
||||
anchors.horizontalCenter: parent.horizontalCenter |
||||
anchors.verticalCenter: parent.verticalCenter |
||||
color: qgcPal.text |
||||
} |
||||
} |
||||
|
||||
Rectangle { |
||||
id: connectionStatus |
||||
width: 160 |
||||
height: cellHeight |
||||
visible: (mainToolBar.connectionCount > 0 && mainToolBar.mavPresent && mainToolBar.heartbeatTimeout != 0) |
||||
anchors.verticalCenter: parent.verticalCenter |
||||
color: "#00000000" |
||||
border.color: "#00000000" |
||||
border.width: 0 |
||||
|
||||
Text { |
||||
id: connectionStatusText |
||||
text: qsTr("CONNECTION LOST") |
||||
font.pointSize: 14 * dpiFactor |
||||
font.weight: Font.DemiBold |
||||
anchors.verticalCenter: parent.verticalCenter |
||||
anchors.horizontalCenter: parent.horizontalCenter |
||||
color: colorRed |
||||
} |
||||
} |
||||
} |
||||
|
||||
Row { |
||||
id: row2 |
||||
height: cellHeight |
||||
spacing: cellSpacerSize |
||||
anchors.right: parent.right |
||||
anchors.verticalCenter: parent.verticalCenter |
||||
anchors.leftMargin: 10 |
||||
anchors.rightMargin: 10 |
||||
|
||||
QGCComboBox { |
||||
id: configList |
||||
width: 200 |
||||
height: cellHeight |
||||
visible: (mainToolBar.connectionCount === 0 && mainToolBar.configList.length > 0) |
||||
anchors.verticalCenter: parent.verticalCenter |
||||
model: mainToolBar.configList |
||||
onCurrentIndexChanged: { |
||||
mainToolBar.onLinkConfigurationChanged(mainToolBar.configList[currentIndex]); |
||||
} |
||||
Component.onCompleted: { |
||||
mainToolBar.currentConfigChanged.connect(configList.onCurrentConfigChanged) |
||||
} |
||||
function onCurrentConfigChanged(config) { |
||||
var index = configList.find(config); |
||||
configList.currentIndex = index; |
||||
} |
||||
} |
||||
|
||||
QGCButton { |
||||
id: connectButton |
||||
width: 90 |
||||
height: cellHeight |
||||
visible: (mainToolBar.connectionCount === 0 || mainToolBar.connectionCount === 1) |
||||
text: (mainToolBar.configList.length > 0) ? (mainToolBar.connectionCount === 0) ? qsTr("Connect") : qsTr("Disconnect") : qsTr("Add Link") |
||||
anchors.verticalCenter: parent.verticalCenter |
||||
onClicked: { |
||||
mainToolBar.onConnect(""); |
||||
} |
||||
} |
||||
|
||||
Menu { |
||||
id: disconnectMenu |
||||
Component.onCompleted: { |
||||
mainToolBar.connectedListChanged.connect(disconnectMenu.onConnectedListChanged) |
||||
} |
||||
function onConnectedListChanged(conList) { |
||||
disconnectMenu.clear(); |
||||
for(var i = 0; i < conList.length; i++) { |
||||
var mItem = disconnectMenu.addItem(conList[i]); |
||||
var menuSlot = function() {mainToolBar.onConnect(mItem.text)}; |
||||
mItem.triggered.connect(menuSlot); |
||||
} |
||||
} |
||||
} |
||||
|
||||
QGCButton { |
||||
id: multidisconnectButton |
||||
width: 90 |
||||
height: cellHeight |
||||
text: qsTr("Disconnect") |
||||
visible: (mainToolBar.connectionCount > 1) |
||||
anchors.verticalCenter: parent.verticalCenter |
||||
menu: disconnectMenu |
||||
} |
||||
|
||||
} |
||||
} |
||||
|
Loading…
Reference in new issue