Commit 1e77e295 authored by acfloria's avatar acfloria

Use again the heartbeat instead of bytes received to determine if a link is active

parent dd28d2a3
......@@ -2490,6 +2490,7 @@ void Vehicle::_linkActiveChanged(LinkInterface *link, bool active)
}
} else {
qgcApp()->showMessage((tr("communication to auxiliary link %2 %3")).arg(link->getName()).arg(active ? "regained" : "lost"));
_updatePriorityLink(false, true);
}
}
......
......@@ -28,7 +28,7 @@ LinkInterface::LinkInterface(SharedLinkConfigurationPointer& config)
, _active (false)
, _enableRateCollection (false)
, _decodedFirstMavlinkPacket(false)
, _bytesReceivedTimer(NULL)
, _heartbeatReceivedTimer(NULL)
{
_config->setLink(this);
......@@ -161,8 +161,7 @@ void LinkInterface::_setMavlinkChannel(uint8_t channel)
_mavlinkChannel = channel;
}
void LinkInterface::_bytesReceivedTimeout()
void LinkInterface::_heartbeatReceivedTimeout()
{
if (_active && !_highLatency) {
setActive(false);
......@@ -170,21 +169,21 @@ void LinkInterface::_bytesReceivedTimeout()
}
void LinkInterface::timerStart() {
if (_bytesReceivedTimer) {
_bytesReceivedTimer->start();
if (_heartbeatReceivedTimer) {
_heartbeatReceivedTimer->start();
} else {
_bytesReceivedTimer = new QTimer();
_bytesReceivedTimer->setInterval(_bytesReceivedTimeoutMSecs);
_bytesReceivedTimer->setSingleShot(true);
_bytesReceivedTimer->start();
QObject::connect(_bytesReceivedTimer, &QTimer::timeout, this, &LinkInterface::_bytesReceivedTimeout);
_heartbeatReceivedTimer = new QTimer();
_heartbeatReceivedTimer->setInterval(_heartbeatReceivedTimeoutMSecs);
_heartbeatReceivedTimer->setSingleShot(true);
_heartbeatReceivedTimer->start();
QObject::connect(_heartbeatReceivedTimer, &QTimer::timeout, this, &LinkInterface::_heartbeatReceivedTimeout);
}
}
void LinkInterface::timerStop() {
if (_bytesReceivedTimer) {
_bytesReceivedTimer->stop();
QObject::disconnect(_bytesReceivedTimer, &QTimer::timeout, this, &LinkInterface::_bytesReceivedTimeout);
delete _bytesReceivedTimer;
if (_heartbeatReceivedTimer) {
_heartbeatReceivedTimer->stop();
QObject::disconnect(_heartbeatReceivedTimer, &QTimer::timeout, this, &LinkInterface::_heartbeatReceivedTimeout);
delete _heartbeatReceivedTimer;
}
}
......@@ -154,7 +154,7 @@ public slots:
private slots:
virtual void _writeBytes(const QByteArray) = 0;
void _bytesReceivedTimeout(void);
void _heartbeatReceivedTimeout(void);
signals:
......@@ -298,8 +298,8 @@ private:
bool _enableRateCollection;
bool _decodedFirstMavlinkPacket; ///< true: link has correctly decoded it's first mavlink packet
static const int _bytesReceivedTimeoutMSecs = 3500; // Signal connection lost after 3.5 seconds of no messages
QTimer* _bytesReceivedTimer;
static const int _heartbeatReceivedTimeoutMSecs = 3500; // Signal connection lost after 3.5 seconds of no messages
QTimer* _heartbeatReceivedTimer;
};
typedef QSharedPointer<LinkInterface> SharedLinkInterfacePointer;
......
......@@ -80,6 +80,8 @@ void LinkManager::setToolbox(QGCToolbox *toolbox)
_autoConnectSettings = toolbox->settingsManager()->autoConnectSettings();
_mavlinkProtocol = _toolbox->mavlinkProtocol();
connect(_mavlinkProtocol, &MAVLinkProtocol::vehicleHeartbeatInfo, this, &LinkManager::_heartbeatReceived);
connect(&_portListTimer, &QTimer::timeout, this, &LinkManager::_updateAutoConnectLinks);
_portListTimer.start(_autoconnectUpdateTimerMSecs); // timeout must be long enough to get past bootloader on second pass
......@@ -195,7 +197,6 @@ void LinkManager::_addLink(LinkInterface* link)
connect(link, &LinkInterface::communicationError, _app, &QGCApplication::criticalMessageBoxOnMainThread);
connect(link, &LinkInterface::bytesReceived, _mavlinkProtocol, &MAVLinkProtocol::receiveBytes);
connect(link, &LinkInterface::bytesReceived, this, &LinkManager::_bytesReceived);
_mavlinkProtocol->resetMetadataForLink(link);
_mavlinkProtocol->setVersion(_mavlinkProtocol->getCurrentVersion());
......@@ -1005,8 +1006,11 @@ void LinkManager::_freeMavlinkChannel(int channel)
_mavlinkChannelsUsedBitMask &= ~(1 << channel);
}
void LinkManager::_bytesReceived(LinkInterface *link, QByteArray bytes) {
Q_UNUSED(bytes);
void LinkManager::_heartbeatReceived(LinkInterface* link, int vehicleId, int componentId, int vehicleFirmwareType, int vehicleType) {
Q_UNUSED(vehicleId);
Q_UNUSED(componentId);
Q_UNUSED(vehicleFirmwareType);
Q_UNUSED(vehicleType);
link->timerStart();
......
......@@ -204,7 +204,7 @@ private:
SerialConfiguration* _autoconnectConfigurationsContainsPort(const QString& portName);
#endif
void _bytesReceived(LinkInterface* link, QByteArray bytes);
void _heartbeatReceived(LinkInterface* link, int vehicleId, int componentId, int vehicleFirmwareType, int vehicleType);
bool _configUpdateSuspended; ///< true: stop updating configuration list
bool _configurationsLoaded; ///< true: Link configurations have been loaded
......
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