Commit b7f2d3b1 authored by Gus Grubba's avatar Gus Grubba Committed by GitHub

Merge pull request #4717 from bkueng/dynamic_param_load_timeout

dynamic param load timeout
parents 2ea6d950 26d2756c
......@@ -63,6 +63,8 @@ ParameterManager::ParameterManager(Vehicle* vehicle)
{
_versionParam = vehicle->firmwarePlugin()->getVersionParam();
_intervalUpdateTimer.invalidate();
if (_vehicle->isOfflineEditingVehicle()) {
_loadOfflineEditingParams();
return;
......@@ -138,7 +140,6 @@ void ParameterManager::_parameterUpdate(int vehicleId, int componentId, QString
return;
}
_initialRequestTimeoutTimer.stop();
_waitingParamTimeoutTimer.stop();
_dataMutex.lock();
......@@ -221,6 +222,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 +405,8 @@ void ParameterManager::refreshAllParameters(uint8_t componentId)
_dataMutex.unlock();
_intervalUpdateTimer.start();
MAVLinkProtocol* mavlink = qgcApp()->toolbox()->mavlinkProtocol();
Q_ASSERT(mavlink);
......@@ -510,9 +528,10 @@ const QMap<int, QMap<QString, QStringList> >& 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 +543,7 @@ void ParameterManager::_waitingParamTimeout(void)
}
foreach(int paramIndex, _waitingReadParamIndexMap[componentId].keys()) {
if (++batchCount > maxBatchSize) {
if (++batchCount > _maxBatchSize) {
goto Out;
}
......@@ -563,7 +582,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 +604,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 +800,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
}
}
......
......@@ -18,6 +18,7 @@
#include <QMutex>
#include <QDir>
#include <QJsonObject>
#include <QElapsedTimer>
#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
......
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment