diff --git a/src/MissionManager/PlanManager.cc b/src/MissionManager/PlanManager.cc index fbb34ac4aa9..862b9f1ef5b 100644 --- a/src/MissionManager/PlanManager.cc +++ b/src/MissionManager/PlanManager.cc @@ -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; } diff --git a/src/MissionManager/PlanManager.h b/src/MissionManager/PlanManager.h index bcf3502b450..13cc8391f4b 100644 --- a/src/MissionManager/PlanManager.h +++ b/src/MissionManager/PlanManager.h @@ -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: diff --git a/test/MissionManager/MissionControllerManagerTest.h b/test/MissionManager/MissionControllerManagerTest.h index 10e1e96a399..053f0e42c01 100644 --- a/test/MissionManager/MissionControllerManagerTest.h +++ b/test/MissionManager/MissionControllerManagerTest.h @@ -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