6#ifndef QGC_NO_SERIAL_LINK
16 , _commLostCheckTimer(new QTimer(this))
21 (void) connect(_commLostCheckTimer, &QTimer::timeout,
this, &VehicleLinkManager::_commLostCheck);
23 _commLostCheckTimer->setSingleShot(
false);
24 _commLostCheckTimer->setInterval(_commLostCheckTimeoutMSecs);
35 if (message.msgid == MAVLINK_MSG_ID_RADIO_STATUS) {
39 const int linkIndex = _containsLinkIndex(link);
40 if (linkIndex == -1) {
45 LinkInfo_t &linkInfo = _rgLinkInfo[linkIndex];
46 linkInfo.heartbeatElapsedTimer.restart();
47 if (_rgLinkInfo[linkIndex].commLost) {
48 _commRegainedOnLink(link);
52void VehicleLinkManager::_commRegainedOnLink(
LinkInterface *link)
55 const int linkIndex = _containsLinkIndex(link);
56 if (linkIndex == -1) {
60 _rgLinkInfo[linkIndex].commLost =
false;
63 QString commRegainedMessage;
64 const bool isPrimaryLink = link == _primaryLink.lock().get();
65 if (_rgLinkInfo.count() > 1) {
66 commRegainedMessage = tr(
"%1Communication regained on %2 link").arg(_vehicle->_vehicleIdSpeech()).arg(isPrimaryLink ? tr(
"primary") : tr(
"secondary"));
68 commRegainedMessage = tr(
"%1Communication regained").arg(_vehicle->_vehicleIdSpeech());
72 QString primarySwitchMessage;
73 if (_updatePrimaryLink()) {
74 primarySwitchMessage = tr(
"%1Switching communication to new primary link").arg(_vehicle->_vehicleIdSpeech());
77 if (!commRegainedMessage.isEmpty()) {
81 if (!primarySwitchMessage.isEmpty()) {
83 qgcApp()->showAppMessage(primarySwitchMessage);
89 if (!_communicationLost) {
93 bool noCommunicationLoss =
true;
94 for (
const LinkInfo_t &linkInfo: _rgLinkInfo) {
95 if (linkInfo.commLost) {
96 noCommunicationLoss =
false;
101 if (noCommunicationLoss) {
102 _communicationLost =
false;
107void VehicleLinkManager::_commLostCheck()
109 if (!_communicationLostEnabled) {
116 bool linkStatusChange =
false;
117 for (LinkInfo_t &linkInfo: _rgLinkInfo) {
118 if (!linkInfo.commLost && !linkInfo.link->linkConfiguration()->isHighLatency() && (linkInfo.heartbeatElapsedTimer.elapsed() > heartbeatTimeout)) {
119 linkInfo.commLost =
true;
120 linkStatusChange =
true;
123 const bool isPrimaryLink = linkInfo.link.get() == _primaryLink.lock().get();
124 if (_rgLinkInfo.count() > 1) {
125 const QString msg = tr(
"%1Communication lost on %2 link.").arg(_vehicle->_vehicleIdSpeech()).arg(isPrimaryLink ? tr(
"primary") : tr(
"secondary"));
131 if (linkStatusChange) {
135 if (_updatePrimaryLink()) {
136 QString msg = tr(
"%1Switching communication to secondary link.").arg(_vehicle->_vehicleIdSpeech());
138 qgcApp()->showAppMessage(msg);
141 if (_communicationLost) {
145 bool totalCommunicationLoss =
true;
146 for (
const LinkInfo_t &linkInfo: _rgLinkInfo) {
147 if (!linkInfo.commLost) {
148 totalCommunicationLoss =
false;
153 if (totalCommunicationLoss) {
154 if (_autoDisconnect) {
162 _communicationLost =
true;
167int VehicleLinkManager::_containsLinkIndex(
const LinkInterface *link)
169 for (
int i = 0; i < _rgLinkInfo.count(); i++) {
170 if (_rgLinkInfo[i].link.get() == link) {
180 if (_containsLinkIndex(link) != -1) {
181 qCWarning(VehicleLinkManagerLog) <<
"_addLink call with link which is already in the list";
187 qCDebug(VehicleLinkManagerLog) <<
"_addLink stale link" << (
void*)link;
191 qCDebug(VehicleLinkManagerLog) <<
"_addLink:" << link->
linkConfiguration()->name() << QString(
"%1").arg((qulonglong)link, 0, 16);
193 link->addVehicleReference();
196 linkInfo.link = sharedLink;
197 if (!link->linkConfiguration()->isHighLatency()) {
198 linkInfo.heartbeatElapsedTimer.start();
200 _rgLinkInfo.append(linkInfo);
202 _updatePrimaryLink();
208 if (_rgLinkInfo.count() == 1) {
209 _commLostCheckTimer->start();
215 const int linkIndex = _containsLinkIndex(link);
216 if (linkIndex == -1) {
217 qCWarning(VehicleLinkManagerLog) <<
"_removeLink call with link which is already in the list";
221 qCDebug(VehicleLinkManagerLog) <<
"_removeLink:" << QString(
"%1").arg((qulonglong)link, 0, 16);
223 if (link == _primaryLink.lock().get()) {
224 _primaryLink.reset();
229 link->removeVehicleReference();
231 _rgLinkInfo.removeAt(linkIndex);
233 if (_rgLinkInfo.isEmpty()) {
234 _commLostCheckTimer->stop();
238void VehicleLinkManager::_linkDisconnected()
240 qCDebug(VehicleLog) << Q_FUNC_INFO <<
"linkCount" << _rgLinkInfo.count();
242 LinkInterface *link = qobject_cast<LinkInterface*>(sender());
248 _updatePrimaryLink();
249 if (_rgLinkInfo.isEmpty() && !_allLinksRemovedSignalledByCloseVehicle) {
250 qCDebug(VehicleLog) <<
"signalling allLinksRemoved";
253 _vehicle->_stopCommandProcessing();
260#ifndef QGC_NO_SERIAL_LINK
262 for (
const LinkInfo_t &linkInfo: _rgLinkInfo) {
263 if (linkInfo.commLost) {
268 auto linkInterface = candidateLink.get();
269 if (linkInterface && LinkManager::isLinkUSBDirect(linkInterface)) {
270 return candidateLink;
276 for (
const LinkInfo_t &linkInfo: _rgLinkInfo) {
277 if (linkInfo.commLost) {
283 if (config && !config->isHighLatency()) {
284 return candidateLink;
296 for (
const LinkInfo_t &linkInfo: _rgLinkInfo) {
297 if (linkInfo.commLost) {
303 if (config && config->isHighLatency()) {
304 return candidateLink;
311bool VehicleLinkManager::_updatePrimaryLink()
314 const int linkIndex = _containsLinkIndex(
primaryLink.get());
316 if ((linkIndex != -1) && !_rgLinkInfo[linkIndex].commLost && !
primaryLink->linkConfiguration()->isHighLatency()) {
322 if ((linkIndex != -1) && !bestActivePrimaryLink) {
333 MAV_COMP_ID_AUTOPILOT1,
334 MAV_CMD_CONTROL_HIGH_LATENCY,
340 _primaryLink = bestActivePrimaryLink;
343 if (bestActivePrimaryLink && bestActivePrimaryLink->linkConfiguration()->isHighLatency()) {
345 MAV_CMD_CONTROL_HIGH_LATENCY,
357 const QList<LinkInfo_t> rgLinkInfoCopy = _rgLinkInfo;
358 for (
const LinkInfo_t &linkInfo: rgLinkInfoCopy) {
359 _removeLink(linkInfo.link.get());
364 _allLinksRemovedSignalledByCloseVehicle =
true;
367 _vehicle->_stopCommandProcessing();
381 return (_containsLinkIndex(link) != -1);
386 if (!_primaryLink.expired()) {
387 return _primaryLink.lock()->linkConfiguration()->name();
395 for (
const LinkInfo_t& linkInfo: _rgLinkInfo) {
396 if (linkInfo.link->linkConfiguration()->name() == name) {
397 _primaryLink = linkInfo.link;
407 for (
const LinkInfo_t &linkInfo: _rgLinkInfo) {
408 rgNames.append(linkInfo.link->linkConfiguration()->name());
416 QStringList rgStatuses;
418 for (
const LinkInfo_t &linkInfo: _rgLinkInfo) {
419 rgStatuses.append(linkInfo.commLost ? tr(
"Comm Lost") :
"");
std::shared_ptr< LinkConfiguration > SharedLinkConfigurationPtr
std::shared_ptr< LinkInterface > SharedLinkInterfacePtr
struct __mavlink_message mavlink_message_t
#define QGC_LOGGING_CATEGORY(name, categoryStr)
void say(const QString &text, TextMods textMods=TextMod::None)
static AudioOutput * instance()
The link interface defines the interface for all links used to communicate with the ground station ap...
SharedLinkConfigurationPtr linkConfiguration()
void communicationLostEnabledChanged(bool communicationLostEnabled)
void primaryLinkChanged()
QStringList linkNames() const
WeakLinkInterfacePtr primaryLink() const
void allLinksRemoved(Vehicle *vehicle)
QStringList linkStatuses() const
void setPrimaryLinkByName(const QString &name)
void mavlinkMessageReceived(LinkInterface *link, const mavlink_message_t &message)
void setCommunicationLostEnabled(bool communicationLostEnabled)
bool containsLink(LinkInterface *link)
void communicationLostChanged(bool communicationLost)
static constexpr int kTestHeartbeatTimeoutMs
Heartbeat timeout used in unit tests (much shorter for faster tests)
void linkStatusesChanged()
bool communicationLostEnabled() const
QString primaryLinkName() const
void sendMavCommand(int compId, MAV_CMD command, bool showError, float param1=0.0f, float param2=0.0f, float param3=0.0f, float param4=0.0f, float param5=0.0f, float param6=0.0f, float param7=0.0f)