diff --git a/src/QGCApplication.cc b/src/QGCApplication.cc index 8bfd850b3d3e896e58d4101bbc6bbf7efedd432c..35dbde0ebd4d61f057de60c6fa182f87612bd8cf 100644 --- a/src/QGCApplication.cc +++ b/src/QGCApplication.cc @@ -361,6 +361,7 @@ void QGCApplication::_initCommon(void) qmlRegisterUncreatableType ("QGroundControl.Vehicle", 1, 0, "ParameterManager", "Reference only"); qmlRegisterUncreatableType ("QGroundControl.Vehicle", 1, 0, "QGCCameraManager", "Reference only"); qmlRegisterUncreatableType ("QGroundControl.Vehicle", 1, 0, "QGCCameraControl", "Reference only"); + qmlRegisterUncreatableType ("QGroundControl.Vehicle", 1, 0, "LinkInterface", "Reference only"); qmlRegisterUncreatableType ("QGroundControl.JoystickManager", 1, 0, "JoystickManager", "Reference only"); qmlRegisterUncreatableType ("QGroundControl.JoystickManager", 1, 0, "Joystick", "Reference only"); qmlRegisterUncreatableType ("QGroundControl.QGCPositionManager", 1, 0, "QGCPositionManager", "Reference only"); diff --git a/src/Settings/App.SettingsGroup.json b/src/Settings/App.SettingsGroup.json index 32906073ba0441341f457f2d0302382da3e79b20..32d51f2bb4437097208fce78c1eec822d599a445 100644 --- a/src/Settings/App.SettingsGroup.json +++ b/src/Settings/App.SettingsGroup.json @@ -124,13 +124,6 @@ "type": "bool", "defaultValue": false }, -{ - "name": "AdvancedLinkSettings", - "shortDescription": "Allow advanced link settings.", - "longDescription": "Allow the user to pick the priority link and adding the high latency property to a link.", - "type": "bool", - "defaultValue": false -}, { "name": "BaseDeviceFontPointSize", "shortDescription": "Application font size", diff --git a/src/Settings/AppSettings.cc b/src/Settings/AppSettings.cc index 0d22132538b234ba34964d22fc34eb115af7385c..264181c8fd8fea423b9ca33d41ef90cde1aa7174 100644 --- a/src/Settings/AppSettings.cc +++ b/src/Settings/AppSettings.cc @@ -34,7 +34,6 @@ const char* AppSettings::showLargeCompassName = "ShowLar const char* AppSettings::savePathName = "SavePath"; const char* AppSettings::autoLoadMissionsName = "AutoLoadMissions"; const char* AppSettings::useChecklistName = "UseChecklist"; -const char* AppSettings::advancedLinkSettingsName = "AdvancedLinkSettings"; const char* AppSettings::mapboxTokenName = "MapboxToken"; const char* AppSettings::esriTokenName = "EsriToken"; const char* AppSettings::defaultFirmwareTypeName = "DefaultFirmwareType"; @@ -78,7 +77,6 @@ AppSettings::AppSettings(QObject* parent) , _savePathFact (NULL) , _autoLoadMissionsFact (NULL) , _useChecklistFact (NULL) - , _advancedLinkSettingsFact (NULL) , _mapboxTokenFact (NULL) , _esriTokenFact (NULL) , _defaultFirmwareTypeFact (NULL) @@ -369,15 +367,6 @@ Fact* AppSettings::autoLoadMissions(void) return _autoLoadMissionsFact; } -Fact* AppSettings::advancedLinkSettings(void) -{ - if (!_advancedLinkSettingsFact) { - _advancedLinkSettingsFact = _createSettingsFact(advancedLinkSettingsName); - } - - return _advancedLinkSettingsFact; -} - Fact* AppSettings::mapboxToken(void) { if (!_mapboxTokenFact) { diff --git a/src/Settings/AppSettings.h b/src/Settings/AppSettings.h index bf260f38654dc7801d213ed4d1d935e219ffd949..3b7b88fa6b1afe6aa24129ab3c462212dc1282a7 100644 --- a/src/Settings/AppSettings.h +++ b/src/Settings/AppSettings.h @@ -38,7 +38,6 @@ public: Q_PROPERTY(Fact* savePath READ savePath CONSTANT) Q_PROPERTY(Fact* autoLoadMissions READ autoLoadMissions CONSTANT) Q_PROPERTY(Fact* useChecklist READ useChecklist CONSTANT) - Q_PROPERTY(Fact* advancedLinkSettings READ advancedLinkSettings CONSTANT) Q_PROPERTY(Fact* mapboxToken READ mapboxToken CONSTANT) Q_PROPERTY(Fact* esriToken READ esriToken CONSTANT) Q_PROPERTY(Fact* defaultFirmwareType READ defaultFirmwareType CONSTANT) @@ -78,7 +77,6 @@ public: Fact* savePath (void); Fact* autoLoadMissions (void); Fact* useChecklist (void); - Fact* advancedLinkSettings (void); Fact* mapboxToken (void); Fact* esriToken (void); Fact* defaultFirmwareType (void); @@ -115,7 +113,6 @@ public: static const char* savePathName; static const char* autoLoadMissionsName; static const char* useChecklistName; - static const char* advancedLinkSettingsName; static const char* mapboxTokenName; static const char* esriTokenName; static const char* defaultFirmwareTypeName; @@ -167,7 +164,6 @@ private: SettingsFact* _savePathFact; SettingsFact* _autoLoadMissionsFact; SettingsFact* _useChecklistFact; - SettingsFact* _advancedLinkSettingsFact; SettingsFact* _mapboxTokenFact; SettingsFact* _esriTokenFact; SettingsFact* _defaultFirmwareTypeFact; diff --git a/src/Vehicle/Vehicle.cc b/src/Vehicle/Vehicle.cc index 3382f78fd2cb8ccf8833b631fa9a256ecee824a4..29e1c9942122317e4eb169f94f5215b5b16b7269 100644 --- a/src/Vehicle/Vehicle.cc +++ b/src/Vehicle/Vehicle.cc @@ -1148,6 +1148,7 @@ void Vehicle::_handleCommandLong(mavlink_message_t& message) if (sl && sl->getSerialConfig()->usbDirect()) { qDebug() << "Disconnecting:" << _links.at(i)->getName(); qgcApp()->toolbox()->linkManager()->disconnectLink(_links.at(i)); + emit linksChanged(); } } } @@ -1681,11 +1682,11 @@ void Vehicle::_sendMessageOnLink(LinkInterface* link, mavlink_message_t message) void Vehicle::_updatePriorityLink(bool updateActive, bool sendCommand) { - emit linkNamesChanged(); + emit linksPropertiesChanged(); // if the priority link is commanded and still active don't change anything if (_priorityLinkCommanded) { - if (_priorityLink.data()->active(_id)) { + if (_priorityLink.data()->link_active(_id)) { return; } else { _priorityLinkCommanded = false; @@ -1704,7 +1705,7 @@ void Vehicle::_updatePriorityLink(bool updateActive, bool sendCommand) // Check for the existing priority link to still be valid for (int i=0; i<_links.count(); i++) { if (_priorityLink.data() == _links[i]) { - if (!_priorityLink.data()->highLatency() && _priorityLink->active(_id)) { + if (!_priorityLink.data()->highLatency() && _priorityLink->link_active(_id)) { // Link is still valid. Continue to use it unless it is high latency. In that case we still look for a better // link to use as priority link. return; @@ -1728,7 +1729,7 @@ void Vehicle::_updatePriorityLink(bool updateActive, bool sendCommand) if (config) { SerialConfiguration* pSerialConfig = qobject_cast(config); if (pSerialConfig && pSerialConfig->usbDirect()) { - if (_priorityLink.data() != link && link->active(_id)) { + if (_priorityLink.data() != link && link->link_active(_id)) { newPriorityLink = link; break; } @@ -1743,7 +1744,7 @@ void Vehicle::_updatePriorityLink(bool updateActive, bool sendCommand) // Search for an active non-high latency link for (int i=0; i<_links.count(); i++) { LinkInterface* link = _links[i]; - if (!link->highLatency() && link->active(_id)) { + if (!link->highLatency() && link->link_active(_id)) { newPriorityLink = link; break; } @@ -1754,7 +1755,7 @@ void Vehicle::_updatePriorityLink(bool updateActive, bool sendCommand) // Search for an active high latency link for (int i=0; i<_links.count(); i++) { LinkInterface* link = _links[i]; - if (link->highLatency() && link->active(_id)) { + if (link->highLatency() && link->link_active(_id)) { newPriorityLink = link; break; } @@ -1776,7 +1777,7 @@ void Vehicle::_updatePriorityLink(bool updateActive, bool sendCommand) emit priorityLinkNameChanged(_priorityLink->getName()); if (updateActive) { - _linkActiveChanged(_priorityLink.data(), _priorityLink->active(_id), _id); + _linkActiveChanged(_priorityLink.data(), _priorityLink->link_active(_id), _id); } } } @@ -2120,16 +2121,6 @@ void Vehicle::setFlightMode(const QString& flightMode) } } -QStringList Vehicle::linkNames(void) const -{ - QStringList names; - - for (int i=0; i<_links.count(); i++) { - names += _links[i]->getName(); - } - return names; -} - QString Vehicle::priorityLinkName(void) const { if (_priorityLink) { @@ -2139,6 +2130,15 @@ QString Vehicle::priorityLinkName(void) const return "none"; } +QVariantList Vehicle::links(void) const { + QVariantList ret; + + foreach( const auto &item, _links ) + ret << QVariant::fromValue(item); + + return ret; +} + void Vehicle::setPriorityLinkByName(const QString& priorityLinkName) { if (!_priorityLink) { @@ -2164,7 +2164,7 @@ void Vehicle::setPriorityLinkByName(const QString& priorityLinkName) _priorityLink = _toolbox->linkManager()->sharedLinkInterfacePointerForLink(newPriorityLink); _updateHighLatencyLink(true); emit priorityLinkNameChanged(_priorityLink->getName()); - _linkActiveChanged(_priorityLink.data(), _priorityLink->active(_id), _id); + _linkActiveChanged(_priorityLink.data(), _priorityLink->link_active(_id), _id); } } @@ -2412,7 +2412,6 @@ void Vehicle::disconnectInactiveVehicle(void) { // Vehicle is no longer communicating with us, disconnect all links - LinkManager* linkMgr = _toolbox->linkManager(); for (int i=0; i<_links.count(); i++) { // FIXME: This linkInUse check is a hack fix for multiple vehicles on the same link. @@ -2421,6 +2420,7 @@ void Vehicle::disconnectInactiveVehicle(void) linkMgr->disconnectLink(_links[i]); } } + emit linksChanged(); } void Vehicle::_imageReady(UASInterface*) @@ -2475,6 +2475,8 @@ void Vehicle::_linkActiveChanged(LinkInterface *link, bool active, int vehicleID return; } + emit linksPropertiesChanged(); + if (link == _priorityLink) { if (active && _connectionLost) { // communication to priority link regained @@ -2513,6 +2515,7 @@ void Vehicle::_linkActiveChanged(LinkInterface *link, bool active, int vehicleID for (int i = 0; i < _links.length(); i++) { _mavlink->resetMetadataForLink(_links.at(i)); } + disconnectInactiveVehicle(); } } diff --git a/src/Vehicle/Vehicle.h b/src/Vehicle/Vehicle.h index 44025338fef0496e6972e063a22678e8f2bb4e30..0f1265976a10c153c1ecaceb9d6f0fb8c0041c01 100644 --- a/src/Vehicle/Vehicle.h +++ b/src/Vehicle/Vehicle.h @@ -10,6 +10,7 @@ #pragma once #include +#include #include #include "FactGroup.h" @@ -493,8 +494,8 @@ public: Q_PROPERTY(bool vtolInFwdFlight READ vtolInFwdFlight WRITE setVtolInFwdFlight NOTIFY vtolInFwdFlightChanged) Q_PROPERTY(bool highLatencyLink READ highLatencyLink NOTIFY highLatencyLinkChanged) Q_PROPERTY(bool supportsTerrainFrame READ supportsTerrainFrame NOTIFY firmwareTypeChanged) - Q_PROPERTY(QStringList linkNames READ linkNames NOTIFY linkNamesChanged) Q_PROPERTY(QString priorityLinkName READ priorityLinkName WRITE setPriorityLinkByName NOTIFY priorityLinkNameChanged) + Q_PROPERTY(QVariantList links READ links NOTIFY linksChanged) // Vehicle state used for guided control Q_PROPERTY(bool flying READ flying NOTIFY flyingChanged) ///< Vehicle is flying @@ -503,7 +504,7 @@ public: Q_PROPERTY(bool guidedModeSupported READ guidedModeSupported CONSTANT) ///< Guided mode commands are supported by this vehicle Q_PROPERTY(bool pauseVehicleSupported READ pauseVehicleSupported CONSTANT) ///< Pause vehicle command is supported Q_PROPERTY(bool orbitModeSupported READ orbitModeSupported CONSTANT) ///< Orbit mode is supported by this vehicle - Q_PROPERTY(bool takeoffVehicleSupported READ takeoffVehicleSupported CONSTANT) ///< Guided takeoff supported + Q_PROPERTY(bool takeoffVehicleSupported READ takeoffVehicleSupported CONSTANT) ///< Guided takeoff supported Q_PROPERTY(ParameterManager* parameterManager READ parameterManager CONSTANT) @@ -694,8 +695,8 @@ public: QString flightMode(void) const; void setFlightMode(const QString& flightMode); - QStringList linkNames(void) const; QString priorityLinkName(void) const; + QVariantList links(void) const; void setPriorityLinkByName(const QString& priorityLinkName); bool hilMode(void); @@ -949,8 +950,9 @@ signals: void capabilityBitsChanged(uint64_t capabilityBits); void toolBarIndicatorsChanged(void); void highLatencyLinkChanged(bool highLatencyLink); - void linkNamesChanged(void); void priorityLinkNameChanged(const QString& priorityLinkName); + void linksChanged(void); + void linksPropertiesChanged(void); void messagesReceivedChanged (); void messagesSentChanged (); diff --git a/src/comm/LinkInterface.cc b/src/comm/LinkInterface.cc index 55b71a489fe7bd4c12656d35eaae3ed03aefed2b..49de99628c189dc2b511320e6a3b2d2fe792f39f 100644 --- a/src/comm/LinkInterface.cc +++ b/src/comm/LinkInterface.cc @@ -23,7 +23,7 @@ bool LinkInterface::active() const return false; } -bool LinkInterface::active(int vehicle_id) const +bool LinkInterface::link_active(int vehicle_id) const { if (_heartbeatTimers.contains(vehicle_id)) { return _heartbeatTimers.value(vehicle_id)->getActive(); @@ -50,6 +50,8 @@ LinkInterface::LinkInterface(SharedLinkConfigurationPointer& config) , _enableRateCollection (false) , _decodedFirstMavlinkPacket(false) { + QQmlEngine::setObjectOwnership(this, QQmlEngine::CppOwnership); + _config->setLink(this); // Initialize everything for the data rate calculation buffers. diff --git a/src/comm/LinkInterface.h b/src/comm/LinkInterface.h index 0c11c4ec95980362bfaaf1323a716c155aeb85f7..3455279fe7bc1c0bca45ed9c4b9c98b2ceeba2f0 100644 --- a/src/comm/LinkInterface.h +++ b/src/comm/LinkInterface.h @@ -47,7 +47,8 @@ public: // Property accessors bool active() const; - bool active(int vehicle_id) const; + Q_INVOKABLE bool link_active(int vehicle_id) const; + Q_INVOKABLE bool getHighLatency(void) const { return _highLatency; } LinkConfiguration* getLinkConfiguration(void) { return _config.data(); } @@ -56,7 +57,7 @@ public: /** * @brief Get the human readable name of this link */ - virtual QString getName() const = 0; + Q_INVOKABLE virtual QString getName() const = 0; virtual void requestReset() = 0; diff --git a/src/ui/preferences/GeneralSettings.qml b/src/ui/preferences/GeneralSettings.qml index 98fc7962bdc4582c04864e80538b8a4ce524f057..70aa6cb082c3aa9d0ae5b17cd66a5bac2ae4598d 100644 --- a/src/ui/preferences/GeneralSettings.qml +++ b/src/ui/preferences/GeneralSettings.qml @@ -378,16 +378,6 @@ QGCView { property Fact _autoLoad: QGroundControl.settingsManager.appSettings.autoLoadMissions } - //----------------------------------------------------------------- - //-- Advanced Link Settings - FactCheckBox { - text: qsTr("Advanced Link Settings") - fact: _advancedLinkSettings - visible: _advancedLinkSettings.visible - - property Fact _advancedLinkSettings: QGroundControl.settingsManager.appSettings.advancedLinkSettings - } - //----------------------------------------------------------------- //-- Save path RowLayout { diff --git a/src/ui/toolbar/LinkIndicator.qml b/src/ui/toolbar/LinkIndicator.qml index c02c8b2fe2e139abf1bcfc5a778a8b632352576e..a7238d44d6a85941ed1b92304d119ca03e973c88 100644 --- a/src/ui/toolbar/LinkIndicator.qml +++ b/src/ui/toolbar/LinkIndicator.qml @@ -16,6 +16,7 @@ import QGroundControl.Controls 1.0 import QGroundControl.MultiVehicleManager 1.0 import QGroundControl.ScreenTools 1.0 import QGroundControl.Palette 1.0 +import QGroundControl.Vehicle 1.0 //------------------------------------------------------------------------- //-- Link Indicator @@ -25,6 +26,7 @@ Item { width: priorityLinkSelector.width property var _activeVehicle: QGroundControl.multiVehicleManager.activeVehicle + property bool _visible: false QGCLabel { id: priorityLinkSelector @@ -32,7 +34,7 @@ Item { font.pointSize: ScreenTools.mediumFontPointSize color: qgcPal.buttonText anchors.verticalCenter: parent.verticalCenter - visible: QGroundControl.settingsManager.appSettings.advancedLinkSettings.rawValue + visible: _visible Menu { id: linkSelectionMenu } @@ -50,14 +52,24 @@ Item { linkSelectionMenu.removeItem(linkSelectionMenuItems[i]) } linkSelectionMenuItems.length = 0 + // Add new items - for (var i = 0; i < _activeVehicle.linkNames.length; i++) { - var menuItem = linkSelectionMenuItemComponent.createObject(null, { "text": _activeVehicle.linkNames[i] }) + var has_hl = false; + var links = _activeVehicle.links + for (var i = 0; i < links.length; i++) { + var menuItem = linkSelectionMenuItemComponent.createObject(null, { "text": links[i].getName(), "enabled": links[i].link_active(_activeVehicle.id)}) linkSelectionMenuItems.push(menuItem) linkSelectionMenu.insertItem(i, menuItem) + + if (links[i].getHighLatency()) { + has_hl = true + } } + + _visible = links.length > 1 && has_hl } } + Component.onCompleted: priorityLinkSelector.updatelinkSelectionMenu() Connections { @@ -67,8 +79,14 @@ Item { Connections { target: _activeVehicle - onLinkNamesChanged: priorityLinkSelector.updatelinkSelectionMenu() + onLinksChanged: priorityLinkSelector.updatelinkSelectionMenu() } + + Connections { + target: _activeVehicle + onLinksPropertiesChanged: priorityLinkSelector.updatelinkSelectionMenu() + } + MouseArea { visible: _activeVehicle anchors.fill: parent