From d564a943ae23df029740dd8a6f09a0bce81de5ee Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Beat=20K=C3=BCng?= Date: Mon, 6 Mar 2017 06:29:35 +0100 Subject: [PATCH] ParameterManager: dynamically set retry timeout based on parameter rate --- src/FactSystem/ParameterManager.cc | 30 ++++++++++++++++++++++++++---- src/FactSystem/ParameterManager.h | 4 ++++ 2 files changed, 30 insertions(+), 4 deletions(-) diff --git a/src/FactSystem/ParameterManager.cc b/src/FactSystem/ParameterManager.cc index d81511870..63c17f5b6 100644 --- a/src/FactSystem/ParameterManager.cc +++ b/src/FactSystem/ParameterManager.cc @@ -63,6 +63,8 @@ ParameterManager::ParameterManager(Vehicle* vehicle) { _versionParam = vehicle->firmwarePlugin()->getVersionParam(); + _intervalUpdateTimer.invalidate(); + if (_vehicle->isOfflineEditingVehicle()) { _loadOfflineEditingParams(); return; @@ -221,6 +223,21 @@ void ParameterManager::_parameterUpdate(int vehicleId, int componentId, QString int readWaitingParamCount = waitingReadParamIndexCount + waitingReadParamNameCount; int totalWaitingParamCount = readWaitingParamCount + waitingWriteParamNameCount; + + // dynamically adjust the retry timeout according to the measured incoming parameter rate + if (_intervalUpdateTimer.isValid()) { + int numParamRead = _totalParamCount - readWaitingParamCount; + if (numParamRead > 10) { + const int multiplier = 5; // increase the timeout by this factor to account for jitter + const int timeout_ms = qMin(3000, (int)(_intervalUpdateTimer.nsecsElapsed() * _maxBatchSize * multiplier / numParamRead / 1000000)); + qCDebug(ParameterManagerVerbose1Log) << _logVehiclePrefix() << "Setting _waitingParamTimeoutTimer interval:" << timeout_ms; + _waitingParamTimeoutTimer.setInterval(timeout_ms); + } + if (totalWaitingParamCount == 0) { + _intervalUpdateTimer.invalidate(); // all params loaded, so don't update the interval anymore + } + } + if (totalWaitingParamCount) { // More params to wait for, restart timer _waitingParamTimeoutTimer.start(); @@ -389,6 +406,8 @@ void ParameterManager::refreshAllParameters(uint8_t componentId) _dataMutex.unlock(); + _intervalUpdateTimer.start(); + MAVLinkProtocol* mavlink = qgcApp()->toolbox()->mavlinkProtocol(); Q_ASSERT(mavlink); @@ -510,9 +529,10 @@ const QMap >& ParameterManager::getGroupMap(void void ParameterManager::_waitingParamTimeout(void) { bool paramsRequested = false; - const int maxBatchSize = 10; int batchCount = 0; + _intervalUpdateTimer.invalidate(); // don't update the interval anymore + qCDebug(ParameterManagerLog) << _logVehiclePrefix() << "_waitingParamTimeout"; // First check for any missing parameters from the initial index based load @@ -524,7 +544,7 @@ void ParameterManager::_waitingParamTimeout(void) } foreach(int paramIndex, _waitingReadParamIndexMap[componentId].keys()) { - if (++batchCount > maxBatchSize) { + if (++batchCount > _maxBatchSize) { goto Out; } @@ -563,7 +583,7 @@ void ParameterManager::_waitingParamTimeout(void) if (_waitingWriteParamNameMap[componentId][paramName] <= _maxReadWriteRetry) { _writeParameterRaw(componentId, paramName, getParameter(componentId, paramName)->rawValue()); qCDebug(ParameterManagerLog) << _logVehiclePrefix(componentId) << "Write resend for (paramName:" << paramName << "retryCount:" << _waitingWriteParamNameMap[componentId][paramName] << ")"; - if (++batchCount > maxBatchSize) { + if (++batchCount > _maxBatchSize) { goto Out; } } else { @@ -585,7 +605,7 @@ void ParameterManager::_waitingParamTimeout(void) if (_waitingReadParamNameMap[componentId][paramName] <= _maxReadWriteRetry) { _readParameterRaw(componentId, paramName, -1); qCDebug(ParameterManagerLog) << _logVehiclePrefix(componentId) << "Read re-request for (paramName:" << paramName << "retryCount:" << _waitingReadParamNameMap[componentId][paramName] << ")"; - if (++batchCount > maxBatchSize) { + if (++batchCount > _maxBatchSize) { goto Out; } } else { @@ -781,6 +801,8 @@ void ParameterManager::_tryCacheHashLoad(int vehicleId, int componentId, QVarian }); ani->start(QAbstractAnimation::DeleteWhenStopped); + + _intervalUpdateTimer.invalidate(); // don't change the interval since we loaded the params from cache } } diff --git a/src/FactSystem/ParameterManager.h b/src/FactSystem/ParameterManager.h index a2c65c015..e698b6227 100644 --- a/src/FactSystem/ParameterManager.h +++ b/src/FactSystem/ParameterManager.h @@ -18,6 +18,7 @@ #include #include #include +#include #include "FactSystem.h" #include "MAVLinkProtocol.h" @@ -196,6 +197,9 @@ private: QTimer _initialRequestTimeoutTimer; QTimer _waitingParamTimeoutTimer; + QElapsedTimer _intervalUpdateTimer; ///< measures the time since refreshAllParameters() was called + static constexpr int _maxBatchSize = 10; ///< maximum number of parameters retry requests at once + QMutex _dataMutex; static Fact _defaultFact; ///< Used to return default fact, when parameter not found -- 2.22.0