Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

PlanManager: Increase Timeouts for Mission Transfer #12184

Draft
wants to merge 2 commits into
base: master
Choose a base branch
from
Draft
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
3 changes: 0 additions & 3 deletions src/Comms/UDPLink.cc
Original file line number Diff line number Diff line change
Expand Up @@ -328,10 +328,7 @@ void UDPWorker::connectLink()
qCDebug(UDPLinkLog) << "Attempting to join multicast group:" << _multicastGroup.toString();
const bool joinSuccess = _socket->joinMulticastGroup(_multicastGroup);
if (!joinSuccess) {
emit errorOccurred(tr("Failed to join multicast group"));
qCWarning(UDPLinkLog) << "Failed to join multicast group" << _multicastGroup.toString();
_onSocketDisconnected();
return;
}

#ifdef QGC_ZEROCONF_ENABLED
Expand Down
9 changes: 5 additions & 4 deletions src/MissionManager/PlanManager.cc
Original file line number Diff line number Diff line change
Expand Up @@ -247,18 +247,19 @@ void PlanManager::_startAckTimeout(AckType_t ack)
switch (ack) {
case AckMissionItem:
// We are actively trying to get the mission item, so we don't want to wait as long.
_ackTimeoutTimer->setInterval(_retryTimeoutMilliseconds);
_ackTimeoutTimer->setInterval(_retryTimeoutDefaultMilliseconds);
break;
case AckMissionRequest:
_ackTimeoutTimer->setInterval(_ackTimeoutMissionRequestMilliseconds);
break;
case AckNone:
// FALLTHROUGH
case AckMissionCount:
// FALLTHROUGH
case AckMissionRequest:
// FALLTHROUGH
case AckMissionClearAll:
// FALLTHROUGH
case AckGuidedItem:
_ackTimeoutTimer->setInterval(_ackTimeoutMilliseconds);
_ackTimeoutTimer->setInterval(_ackTimeoutDefaultMilliseconds);
break;
}

Expand Down
7 changes: 5 additions & 2 deletions src/MissionManager/PlanManager.h
Original file line number Diff line number Diff line change
Expand Up @@ -68,9 +68,12 @@ class PlanManager : public QObject

// These values are public so the unit test can set appropriate signal wait times
// When passively waiting for a mission process, use a longer timeout.
static const int _ackTimeoutMilliseconds = 1500;
static const int _ackTimeoutDefaultMilliseconds = 1500;
// When uploading a mission plan, use a longer timeout to cope with low
// bandwidth links, i.e. ELRS 900Mhz.
static const int _ackTimeoutMissionRequestMilliseconds = 2500;
// When actively retrying to request mission items, use a shorter timeout instead.
static const int _retryTimeoutMilliseconds = 250;
static const int _retryTimeoutDefaultMilliseconds = 1500;
static const int _maxRetryCount = 5;

signals:
Expand Down
2 changes: 1 addition & 1 deletion test/MissionManager/MissionControllerManagerTest.h
Original file line number Diff line number Diff line change
Expand Up @@ -72,7 +72,7 @@ protected slots:
static const size_t _cMissionManagerSignals = maxSignalIndex;
const char* _rgMissionManagerSignals[_cMissionManagerSignals];

static const int _missionManagerSignalWaitTime = MissionManager::_ackTimeoutMilliseconds * MissionManager::_maxRetryCount * 2;
static const int _missionManagerSignalWaitTime = MissionManager::_ackTimeoutDefaultMilliseconds * MissionManager::_maxRetryCount * 2;
};

#endif
Loading