Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
77 changes: 77 additions & 0 deletions src/Comms/LinkManager.cc
Original file line number Diff line number Diff line change
Expand Up @@ -107,6 +107,18 @@ void LinkManager::createConnectedLink(const LinkConfiguration *config)

bool LinkManager::createConnectedLink(SharedLinkConfigurationPtr &config)
{
#ifndef QGC_NO_SERIAL_LINK
// If we're creating a serial link, disconnect any existing autoconnect link on the same port first.
// This prevents "Access denied" errors on Windows when the user manually connects to a port
// that autoconnect has already opened.
if (config->type() == LinkConfiguration::TypeSerial) {
const SerialConfiguration *newSerialConfig = qobject_cast<const SerialConfiguration*>(config.get());
if (newSerialConfig && !config->isAutoConnect()) {
_disconnectAutoConnectLink(newSerialConfig->portName());
}
}
#endif

SharedLinkInterfacePtr link = nullptr;

switch(config->type()) {
Expand Down Expand Up @@ -915,6 +927,38 @@ void LinkManager::_addSerialAutoConnectLink()
continue;
}
if (_portAlreadyConnected(portInfo.systemLocation()) || (_autoConnectRTKPort == portInfo.systemLocation())) {
// Check for zombie autoconnect links: port is open but no MAVLink data received
if (_autoConnectRTKPort != portInfo.systemLocation()) {
SharedLinkInterfacePtr existingLink;
{
QMutexLocker locker(&_linksMutex);
const QString searchPort = portInfo.systemLocation().trimmed();
for (const SharedLinkInterfacePtr &linkInterface : _rgLinks) {
const SharedLinkConfigurationPtr linkConfig = linkInterface->linkConfiguration();
if (linkConfig && linkConfig->isAutoConnect()) {
const SerialConfiguration *serialConfig = qobject_cast<const SerialConfiguration*>(linkConfig.get());
if (serialConfig && (serialConfig->portName() == searchPort)) {
existingLink = linkInterface;
break;
}
}
}
}

if (existingLink && !existingLink->decodedFirstMavlinkPacket()) {
_autoconnectNoMavlinkCount[portInfo.systemLocation()] += _autoconnectUpdateTimerMSecs;
if (_autoconnectNoMavlinkCount[portInfo.systemLocation()] > _autoconnectNoMavlinkTimeoutMSecs) {
qCWarning(LinkManagerLog) << "Autoconnect link on" << portInfo.systemLocation()
<< "has not received MAVLink data - disconnecting to retry";
_autoconnectNoMavlinkCount.remove(portInfo.systemLocation());
existingLink->disconnect();
Comment on lines +932 to +954
Copy link

Copilot AI Feb 5, 2026

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Potential race condition: The existingLink shared pointer is obtained inside a mutex lock but then used outside the lock. While SharedLinkInterfacePtr holds a reference count that prevents object deletion, the link could be removed from _rgLinks by another thread between line 946 and line 948. This could lead to disconnecting a link that was already processed for removal by another thread. While disconnect() is documented as safe to call multiple times, consider adding a check to verify the link is still in _rgLinks before calling disconnect(), or hold the mutex for the entire zombie detection and disconnect operation to ensure atomicity.

Copilot uses AI. Check for mistakes.
continue;
}
} else {
// Link is communicating, clear any timeout counter
_autoconnectNoMavlinkCount.remove(portInfo.systemLocation());
}
}
qCDebug(LinkManagerVerboseLog) << "Skipping existing autoconnect" << portInfo.systemLocation();
} else if (!_autoconnectPortWaitList.contains(portInfo.systemLocation())) {
// We don't connect to the port the first time we see it. The ability to correctly detect whether we
Expand Down Expand Up @@ -999,6 +1043,32 @@ bool LinkManager::_allowAutoConnectToBoard(QGCSerialPortInfo::BoardType_t boardT
return false;
}

void LinkManager::_disconnectAutoConnectLink(const QString &portName)
{
const QString searchPort = portName.trimmed();
SharedLinkInterfacePtr linkToDisconnect;

{
QMutexLocker locker(&_linksMutex);
for (const SharedLinkInterfacePtr &linkInterface : _rgLinks) {
const SharedLinkConfigurationPtr linkConfig = linkInterface->linkConfiguration();
if (!linkConfig || !linkConfig->isAutoConnect()) {
continue;
}
const SerialConfiguration *serialConfig = qobject_cast<const SerialConfiguration*>(linkConfig.get());
if (serialConfig && (serialConfig->portName() == searchPort)) {
linkToDisconnect = linkInterface;
break;
}
}
}

if (linkToDisconnect) {
qCDebug(LinkManagerLog) << "Disconnecting existing autoconnect link on port" << searchPort << "to allow manual connection";
Copy link

Copilot AI Feb 5, 2026

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

When disconnecting an autoconnect link to allow manual connection, the _autoconnectNoMavlinkCount entry for the port is not cleared. If the manual connection later fails and autoconnect tries again, it will resume the timeout counter from where it left off, potentially causing the new autoconnect attempt to timeout prematurely.

Consider adding _autoconnectNoMavlinkCount.remove(portName) after successfully finding and disconnecting an autoconnect link to reset the timeout counter when the user manually intervenes.

Suggested change
qCDebug(LinkManagerLog) << "Disconnecting existing autoconnect link on port" << searchPort << "to allow manual connection";
qCDebug(LinkManagerLog) << "Disconnecting existing autoconnect link on port" << searchPort << "to allow manual connection";
_autoconnectNoMavlinkCount.remove(searchPort);

Copilot uses AI. Check for mistakes.
linkToDisconnect->disconnect();
}
}

bool LinkManager::_portAlreadyConnected(const QString &portName)
{
QMutexLocker locker(&_linksMutex);
Expand All @@ -1008,6 +1078,13 @@ bool LinkManager::_portAlreadyConnected(const QString &portName)
const SharedLinkConfigurationPtr linkConfig = linkInterface->linkConfiguration();
const SerialConfiguration* const serialConfig = qobject_cast<const SerialConfiguration*>(linkConfig.get());
if (serialConfig && (serialConfig->portName() == searchPort)) {
// Also verify the link is actually connected. The serial port open happens
// asynchronously, so the link may be in _rgLinks but not truly connected yet
// (or the connection may have failed). If not connected, allow autoconnect to retry.
if (!linkInterface->isConnected()) {
qCDebug(LinkManagerLog) << "Port in link list but not connected, allowing retry:" << searchPort;
return false;
}
return true;
}
}
Expand Down
4 changes: 4 additions & 0 deletions src/Comms/LinkManager.h
Original file line number Diff line number Diff line change
Expand Up @@ -161,6 +161,8 @@ private slots:
#else
static constexpr int _autoconnectConnectDelayMSecs = 1000;
#endif
// If an autoconnect serial link hasn't received any MAVLink data within this time, disconnect and retry
static constexpr int _autoconnectNoMavlinkTimeoutMSecs = 10000;

#ifndef QGC_NO_SERIAL_LINK
private:
Expand All @@ -183,10 +185,12 @@ private slots:
bool _allowAutoConnectToBoard(QGCSerialPortInfo::BoardType_t boardType) const;
void _addSerialAutoConnectLink();
bool _portAlreadyConnected(const QString &portName);
void _disconnectAutoConnectLink(const QString &portName);
void _filterCompositePorts(QList<QGCSerialPortInfo> &portList);

UdpIODevice *_nmeaSocket = nullptr;
QMap<QString, int> _autoconnectPortWaitList; ///< key: QGCSerialPortInfo::systemLocation, value: wait count
QMap<QString, int> _autoconnectNoMavlinkCount; ///< key: port systemLocation, value: seconds since autoconnect with no MAVLink data
Copy link

Copilot AI Feb 5, 2026

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

The comment states the value is in "seconds since autoconnect", but the code actually increments this by _autoconnectUpdateTimerMSecs (which is in milliseconds) at line 949. The value stored is actually in milliseconds, not seconds. The comment should be corrected to say "milliseconds since autoconnect with no MAVLink data" to match the implementation.

Suggested change
QMap<QString, int> _autoconnectNoMavlinkCount; ///< key: port systemLocation, value: seconds since autoconnect with no MAVLink data
QMap<QString, int> _autoconnectNoMavlinkCount; ///< key: port systemLocation, value: milliseconds since autoconnect with no MAVLink data

Copilot uses AI. Check for mistakes.
QList<SerialLink*> _activeLinkCheckList; ///< List of links we are waiting for a vehicle to show up on
QStringList _commPortList;
QStringList _commPortDisplayList;
Expand Down
4 changes: 4 additions & 0 deletions src/Comms/MAVLinkProtocol.cc
Original file line number Diff line number Diff line change
Expand Up @@ -102,6 +102,10 @@ void MAVLinkProtocol::receiveBytes(LinkInterface *link, const QByteArray &data)
continue;
}

if (!link->decodedFirstMavlinkPacket()) {
link->setDecodedFirstMavlinkPacket(true);
}

// It's ok to get v1 HEARTBEAT messages on a v2 link:
// PX4 defaults to sending V1 then switches to V2 after receiving a V2 message from GCS
// ArduPilot always sends both versions
Expand Down
Loading