7#ifndef QGC_NO_SERIAL_LINK
17 , _commLostCheckTimer(new QTimer(this))
22 (void) connect(_commLostCheckTimer, &QTimer::timeout,
this, &VehicleLinkManager::_commLostCheck);
24 _commLostCheckTimer->setSingleShot(
false);
25 _commLostCheckTimer->setInterval(_commLostCheckTimeoutMSecs);
36 if (message.msgid == MAVLINK_MSG_ID_RADIO_STATUS) {
40 const int linkIndex = _containsLinkIndex(link);
41 if (linkIndex == -1) {
46 LinkInfo_t &linkInfo = _rgLinkInfo[linkIndex];
47 linkInfo.heartbeatElapsedTimer.restart();
48 if (_rgLinkInfo[linkIndex].commLost) {
49 _commRegainedOnLink(link);
53void VehicleLinkManager::_commRegainedOnLink(
LinkInterface *link)
56 const int linkIndex = _containsLinkIndex(link);
57 if (linkIndex == -1) {
61 _rgLinkInfo[linkIndex].commLost =
false;
64 QString commRegainedMessage;
65 const bool isPrimaryLink = link == _primaryLink.lock().get();
66 if (_rgLinkInfo.count() > 1) {
67 commRegainedMessage = tr(
"%1Communication regained on %2 link").arg(_vehicle->_vehicleIdSpeech()).arg(isPrimaryLink ? tr(
"primary") : tr(
"secondary"));
69 commRegainedMessage = tr(
"%1Communication regained").arg(_vehicle->_vehicleIdSpeech());
73 QString primarySwitchMessage;
74 if (_updatePrimaryLink()) {
75 primarySwitchMessage = tr(
"%1Switching communication to new primary link").arg(_vehicle->_vehicleIdSpeech());
78 if (!commRegainedMessage.isEmpty()) {
82 if (!primarySwitchMessage.isEmpty()) {
90 if (!_communicationLost) {
94 bool noCommunicationLoss =
true;
95 for (
const LinkInfo_t &linkInfo: _rgLinkInfo) {
96 if (linkInfo.commLost) {
97 noCommunicationLoss =
false;
102 if (noCommunicationLoss) {
103 _communicationLost =
false;
108void VehicleLinkManager::_commLostCheck()
110 if (!_communicationLostEnabled) {
117 bool linkStatusChange =
false;
118 for (LinkInfo_t &linkInfo: _rgLinkInfo) {
119 if (!linkInfo.commLost && !linkInfo.link->linkConfiguration()->isHighLatency() && (linkInfo.heartbeatElapsedTimer.elapsed() > heartbeatTimeout)) {
120 linkInfo.commLost =
true;
121 linkStatusChange =
true;
124 const bool isPrimaryLink = linkInfo.link.get() == _primaryLink.lock().get();
125 if (_rgLinkInfo.count() > 1) {
126 const QString msg = tr(
"%1Communication lost on %2 link.").arg(_vehicle->_vehicleIdSpeech()).arg(isPrimaryLink ? tr(
"primary") : tr(
"secondary"));
132 if (linkStatusChange) {
136 if (_updatePrimaryLink()) {
137 QString msg = tr(
"%1Switching communication to secondary link.").arg(_vehicle->_vehicleIdSpeech());
142 if (_communicationLost) {
146 bool totalCommunicationLoss =
true;
147 for (
const LinkInfo_t &linkInfo: _rgLinkInfo) {
148 if (!linkInfo.commLost) {
149 totalCommunicationLoss =
false;
154 if (totalCommunicationLoss) {
155 if (_autoDisconnect) {
163 _communicationLost =
true;
168int VehicleLinkManager::_containsLinkIndex(
const LinkInterface *link)
170 for (
int i = 0; i < _rgLinkInfo.count(); i++) {
171 if (_rgLinkInfo[i].link.get() == link) {
181 if (_containsLinkIndex(link) != -1) {
182 qCWarning(VehicleLinkManagerLog) <<
"_addLink call with link which is already in the list";
188 qCDebug(VehicleLinkManagerLog) <<
"_addLink stale link" << (
void*)link;
192 qCDebug(VehicleLinkManagerLog) <<
"_addLink:" << link->
linkConfiguration()->name() << QString(
"%1").arg((qulonglong)link, 0, 16);
194 link->addVehicleReference();
197 linkInfo.link = sharedLink;
198 if (!link->linkConfiguration()->isHighLatency()) {
199 linkInfo.heartbeatElapsedTimer.start();
201 _rgLinkInfo.append(linkInfo);
203 _updatePrimaryLink();
209 if (_rgLinkInfo.count() == 1) {
210 _commLostCheckTimer->start();
216 const int linkIndex = _containsLinkIndex(link);
217 if (linkIndex == -1) {
218 qCWarning(VehicleLinkManagerLog) <<
"_removeLink call with link which is already in the list";
222 qCDebug(VehicleLinkManagerLog) <<
"_removeLink:" << QString(
"%1").arg((qulonglong)link, 0, 16);
224 if (link == _primaryLink.lock().get()) {
225 _primaryLink.reset();
230 link->removeVehicleReference();
232 _rgLinkInfo.removeAt(linkIndex);
234 if (_rgLinkInfo.isEmpty()) {
235 _commLostCheckTimer->stop();
239void VehicleLinkManager::_linkDisconnected()
241 qCDebug(VehicleLinkManagerLog) << Q_FUNC_INFO <<
"linkCount" << _rgLinkInfo.count();
243 LinkInterface *link = qobject_cast<LinkInterface*>(sender());
249 _updatePrimaryLink();
250 if (_rgLinkInfo.isEmpty() && !_allLinksRemovedSignalledByCloseVehicle) {
251 qCDebug(VehicleLinkManagerLog) <<
"signalling allLinksRemoved";
254 _vehicle->_stopCommandProcessing();
261#ifndef QGC_NO_SERIAL_LINK
263 for (
const LinkInfo_t &linkInfo: _rgLinkInfo) {
264 if (linkInfo.commLost) {
269 auto linkInterface = candidateLink.get();
271 return candidateLink;
277 for (
const LinkInfo_t &linkInfo: _rgLinkInfo) {
278 if (linkInfo.commLost) {
284 if (config && !config->isHighLatency()) {
285 return candidateLink;
297 for (
const LinkInfo_t &linkInfo: _rgLinkInfo) {
298 if (linkInfo.commLost) {
304 if (config && config->isHighLatency()) {
305 return candidateLink;
312bool VehicleLinkManager::_updatePrimaryLink()
315 const int linkIndex = _containsLinkIndex(
primaryLink.get());
317 if ((linkIndex != -1) && !_rgLinkInfo[linkIndex].commLost && !
primaryLink->linkConfiguration()->isHighLatency()) {
323 if ((linkIndex != -1) && !bestActivePrimaryLink) {
334 MAV_COMP_ID_AUTOPILOT1,
335 MAV_CMD_CONTROL_HIGH_LATENCY,
341 _primaryLink = bestActivePrimaryLink;
344 if (bestActivePrimaryLink && bestActivePrimaryLink->linkConfiguration()->isHighLatency()) {
346 MAV_CMD_CONTROL_HIGH_LATENCY,
358 const QList<LinkInfo_t> rgLinkInfoCopy = _rgLinkInfo;
359 for (
const LinkInfo_t &linkInfo: rgLinkInfoCopy) {
360 _removeLink(linkInfo.link.get());
365 _allLinksRemovedSignalledByCloseVehicle =
true;
368 _vehicle->_stopCommandProcessing();
382 return (_containsLinkIndex(link) != -1);
387 if (!_primaryLink.expired()) {
388 return _primaryLink.lock()->linkConfiguration()->name();
396 for (
const LinkInfo_t& linkInfo: _rgLinkInfo) {
397 if (linkInfo.link->linkConfiguration()->name() == name) {
398 _primaryLink = linkInfo.link;
408 for (
const LinkInfo_t &linkInfo: _rgLinkInfo) {
409 rgNames.append(linkInfo.link->linkConfiguration()->name());
417 QStringList rgStatuses;
419 for (
const LinkInfo_t &linkInfo: _rgLinkInfo) {
420 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()
SharedLinkInterfacePtr sharedLinkInterfacePointerForLink(const LinkInterface *link)
static bool isLinkUSBDirect(const LinkInterface *link)
static LinkManager * instance()
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)
void showAppMessage(const QString &message, const QString &title)
Modal application message. Queued if the UI isn't ready yet.