From 8bad8c69c3d367318df1a4b14bab70976e0f024b Mon Sep 17 00:00:00 2001 From: Don Gagne Date: Tue, 1 Dec 2015 12:14:52 -0800 Subject: [PATCH] Fix autoconnect/re-autoconnect, plus windows connect --- src/comm/LinkManager.cc | 31 +++++++++++++++++++++++++------ src/comm/LinkManager.h | 19 ++++++++++++------- 2 files changed, 37 insertions(+), 13 deletions(-) diff --git a/src/comm/LinkManager.cc b/src/comm/LinkManager.cc index f8d4771c2..f7116385e 100644 --- a/src/comm/LinkManager.cc +++ b/src/comm/LinkManager.cc @@ -55,6 +55,14 @@ const char* LinkManager::_autoconnect3DRRadioKey = "Autoconnect3DRRadio"; const char* LinkManager::_autoconnectPX4FlowKey = "AutoconnectPX4Flow"; const char* LinkManager::_defaultUPDLinkName = "Default UDP Link"; +const int LinkManager::_autoconnectUpdateTimerMSecs = 1000; +#ifdef Q_OS_WIN +// Have to manually let the bootloader go by on Windows to get a working connect +const int LinkManager::_autoconnectConnectDelayMSecs = 6000; +#else +const int LinkManager::_autoconnectConnectDelayMSecs = 1000; +#endif + LinkManager::LinkManager(QGCApplication* app) : QGCTool(app) , _configUpdateSuspended(false) @@ -96,7 +104,7 @@ void LinkManager::setToolbox(QGCToolbox *toolbox) connect(_mavlinkProtocol, &MAVLinkProtocol::vehicleHeartbeatInfo, this, &LinkManager::_vehicleHeartbeatInfo); connect(&_portListTimer, &QTimer::timeout, this, &LinkManager::_updateAutoConnectLinks); - _portListTimer.start(6000); // timeout must be long enough to get past bootloader on second pass + _portListTimer.start(_autoconnectUpdateTimerMSecs); // timeout must be long enough to get past bootloader on second pass } @@ -220,10 +228,16 @@ void LinkManager::disconnectLink(LinkInterface* link) link->_disconnect(); LinkConfiguration* config = link->getLinkConfiguration(); - if(config) { - config->setLink(NULL); + if (config) { + if (_autoconnectConfigurations.contains(config)) { + config->setLink(NULL); + } } _deleteLink(link); + if (_autoconnectConfigurations.contains(config)) { + _autoconnectConfigurations.removeOne(config); + delete config; + } } void LinkManager::_deleteLink(LinkInterface* link) @@ -465,11 +479,11 @@ void LinkManager::_updateAutoConnectLinks(void) // are in the bootloader is flaky from a cross-platform standpoint. So by putting it on a wait list // and only connect on the second pass we leave enough time for the board to boot up. qCDebug(LinkManagerLog) << "Waiting for next autoconnect pass" << portInfo.systemLocation(); - _autoconnectWaitList.append(portInfo.systemLocation()); - } else { + _autoconnectWaitList[portInfo.systemLocation()] = 1; + } else if (++_autoconnectWaitList[portInfo.systemLocation()] * _autoconnectUpdateTimerMSecs > _autoconnectConnectDelayMSecs) { SerialConfiguration* pSerialConfig = NULL; - _autoconnectWaitList.removeOne(portInfo.systemLocation()); + _autoconnectWaitList.remove(portInfo.systemLocation()); switch (boardType) { case QGCSerialPortInfo::BoardTypePX4FMUV1: @@ -707,3 +721,8 @@ QStringList LinkManager::serialBaudRates(void) return SerialConfiguration::supportedBaudRates(); #endif } + +bool LinkManager::isAutoconnectLink(LinkInterface* link) +{ + return _autoconnectConfigurations.contains(link->getLinkConfiguration()); +} diff --git a/src/comm/LinkManager.h b/src/comm/LinkManager.h index a93fa1988..f38a4085c 100644 --- a/src/comm/LinkManager.h +++ b/src/comm/LinkManager.h @@ -158,6 +158,9 @@ public: // Called to signal app shutdown. Disconnects all links while turning off auto-connect. void shutdown(void); + /// @return true: specified link is an autoconnect link + bool isAutoconnectLink(LinkInterface* link); + // Override from QGCTool virtual void setToolbox(QGCToolbox *toolbox); @@ -216,7 +219,7 @@ private: QmlObjectListModel _linkConfigurations; QmlObjectListModel _autoconnectConfigurations; - QStringList _autoconnectWaitList; + QMap _autoconnectWaitList; ///< key: QGCSerialPortInfo.systemLocation, value: wait count QStringList _commPortList; bool _autoconnectUDP; @@ -224,12 +227,14 @@ private: bool _autoconnect3DRRadio; bool _autoconnectPX4Flow; - static const char* _settingsGroup; - static const char* _autoconnectUDPKey; - static const char* _autoconnectPixhawkKey; - static const char* _autoconnect3DRRadioKey; - static const char* _autoconnectPX4FlowKey; - static const char* _defaultUPDLinkName; + static const char* _settingsGroup; + static const char* _autoconnectUDPKey; + static const char* _autoconnectPixhawkKey; + static const char* _autoconnect3DRRadioKey; + static const char* _autoconnectPX4FlowKey; + static const char* _defaultUPDLinkName; + static const int _autoconnectUpdateTimerMSecs; + static const int _autoconnectConnectDelayMSecs; }; #endif -- 2.22.0