Commit 7b229e54 authored by Don Gagne's avatar Don Gagne

Merge pull request #2323 from DonLakeFlyer/ACFixes

Autoconnect fixes
parents ac81491c 8bad8c69
......@@ -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());
}
......@@ -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<QString, int> _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
......@@ -154,28 +154,30 @@ bool SerialLink::_connect(void)
qgcApp()->toolbox()->linkManager()->suspendConfigurationUpdates(true);
#endif
QSerialPort::SerialPortError error;
QString errorString;
// Initialize the connection
if (!_hardwareConnect(_type)) {
// Need to error out here.
QString err("Could not create port.");
if (_port) {
err = _port->errorString();
if (!_hardwareConnect(error, errorString)) {
if (qgcApp()->toolbox()->linkManager()->isAutoconnectLink(this)) {
// Be careful with spitting out open error related to trying to open a busy port using autoconnect
if (error == QSerialPort::PermissionError) {
// Device already open, ignore and fail connect
return false;
}
}
_emitLinkError("Error connecting: " + err);
_emitLinkError(QString("Error connecting: Could not create port. %1").arg(errorString));
return false;
}
return true;
}
/**
* @brief This function is called indirectly by the _connect() call.
*
* The _connect() function starts the thread and indirectly calls this method.
*
* @return True if the connection could be established, false otherwise
* @see _connect() For the right function to establish the connection.
**/
bool SerialLink::_hardwareConnect(QString &type)
/// Performs the actual hardware port connection.
/// @param[out] error if failed
/// @param[out] error string if failed
/// @return success/fail
bool SerialLink::_hardwareConnect(QSerialPort::SerialPortError& error, QString& errorString)
{
if (_port) {
qCDebug(SerialLinkLog) << "SerialLink:" << QString::number((long)this, 16) << "closing port";
......@@ -235,6 +237,9 @@ bool SerialLink::_hardwareConnect(QString &type)
}
#endif
if (!_port->isOpen() ) {
qDebug() << "open failed" << _port->errorString() << _port->error() << getName() << qgcApp()->toolbox()->linkManager()->isAutoconnectLink(this);
error = _port->error();
errorString = _port->errorString();
emit communicationUpdate(getName(),"Error opening port: " + _port->errorString());
_port->close();
delete _port;
......@@ -252,7 +257,7 @@ bool SerialLink::_hardwareConnect(QString &type)
emit communicationUpdate(getName(), "Opened port!");
emit connected();
qCDebug(SerialLinkLog) << "CONNECTING LINK: " << __FILE__ << __LINE__ << "type:" << type << "with settings" << _config->portName()
qCDebug(SerialLinkLog) << "Connection SeriaLink: " << "with settings" << _config->portName()
<< _config->baud() << _config->dataBits() << _config->parity() << _config->stopBits();
return true; // successful connection
......
......@@ -152,7 +152,6 @@ protected:
int _timeout;
QMutex _dataMutex; // Mutex for reading data from _port
QMutex _writeMutex; // Mutex for accessing the _transmitBuffer.
QString _type;
private slots:
void _readBytes(void);
......@@ -168,7 +167,7 @@ private:
// Internal methods
void _emitLinkError(const QString& errorMsg);
bool _hardwareConnect(QString &_type);
bool _hardwareConnect(QSerialPort::SerialPortError& error, QString& errorString);
bool _isBootloader();
void _resetConfiguration();
......
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