Skip to content

Commit

Permalink
PlanManager: Improve timeout behavior during Mission Transfer
Browse files Browse the repository at this point in the history
This patch fixes runtime issues which are observed
on 900MHz ELRS.

During mission download from the vehicle, repeat timeout
occurs, causing mixup of request-response pairs which
results in sequence errors of mission items.
The repeat timeout is therefore increased to 1.5 seconds.
GCS based message repetition eventually bites with ELRS
stubborn sender feature.

During mission upload to the vehicle, the regular timeout
of 1.5 seconds is too tight and causes reported errors about
not all mission items retrieved by vehicle.
Therefore a separate timeout for MISSION_REQUEST_INT service
is added with a value of 2.5 seconds which seems appropriate.

For clarity the word default is added to the name of the
original timeout values.
  • Loading branch information
menschel committed Dec 16, 2024
1 parent 4e142d1 commit 1c616ec
Show file tree
Hide file tree
Showing 3 changed files with 11 additions and 7 deletions.
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

0 comments on commit 1c616ec

Please sign in to comment.