Commit d564a943 authored by Beat Küng's avatar Beat Küng

ParameterManager: dynamically set retry timeout based on parameter rate

parent 25ca15d1
...@@ -63,6 +63,8 @@ ParameterManager::ParameterManager(Vehicle* vehicle) ...@@ -63,6 +63,8 @@ ParameterManager::ParameterManager(Vehicle* vehicle)
{ {
_versionParam = vehicle->firmwarePlugin()->getVersionParam(); _versionParam = vehicle->firmwarePlugin()->getVersionParam();
_intervalUpdateTimer.invalidate();
if (_vehicle->isOfflineEditingVehicle()) { if (_vehicle->isOfflineEditingVehicle()) {
_loadOfflineEditingParams(); _loadOfflineEditingParams();
return; return;
...@@ -221,6 +223,21 @@ void ParameterManager::_parameterUpdate(int vehicleId, int componentId, QString ...@@ -221,6 +223,21 @@ void ParameterManager::_parameterUpdate(int vehicleId, int componentId, QString
int readWaitingParamCount = waitingReadParamIndexCount + waitingReadParamNameCount; int readWaitingParamCount = waitingReadParamIndexCount + waitingReadParamNameCount;
int totalWaitingParamCount = readWaitingParamCount + waitingWriteParamNameCount; 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) { if (totalWaitingParamCount) {
// More params to wait for, restart timer // More params to wait for, restart timer
_waitingParamTimeoutTimer.start(); _waitingParamTimeoutTimer.start();
...@@ -389,6 +406,8 @@ void ParameterManager::refreshAllParameters(uint8_t componentId) ...@@ -389,6 +406,8 @@ void ParameterManager::refreshAllParameters(uint8_t componentId)
_dataMutex.unlock(); _dataMutex.unlock();
_intervalUpdateTimer.start();
MAVLinkProtocol* mavlink = qgcApp()->toolbox()->mavlinkProtocol(); MAVLinkProtocol* mavlink = qgcApp()->toolbox()->mavlinkProtocol();
Q_ASSERT(mavlink); Q_ASSERT(mavlink);
...@@ -510,9 +529,10 @@ const QMap<int, QMap<QString, QStringList> >& ParameterManager::getGroupMap(void ...@@ -510,9 +529,10 @@ const QMap<int, QMap<QString, QStringList> >& ParameterManager::getGroupMap(void
void ParameterManager::_waitingParamTimeout(void) void ParameterManager::_waitingParamTimeout(void)
{ {
bool paramsRequested = false; bool paramsRequested = false;
const int maxBatchSize = 10;
int batchCount = 0; int batchCount = 0;
_intervalUpdateTimer.invalidate(); // don't update the interval anymore
qCDebug(ParameterManagerLog) << _logVehiclePrefix() << "_waitingParamTimeout"; qCDebug(ParameterManagerLog) << _logVehiclePrefix() << "_waitingParamTimeout";
// First check for any missing parameters from the initial index based load // First check for any missing parameters from the initial index based load
...@@ -524,7 +544,7 @@ void ParameterManager::_waitingParamTimeout(void) ...@@ -524,7 +544,7 @@ void ParameterManager::_waitingParamTimeout(void)
} }
foreach(int paramIndex, _waitingReadParamIndexMap[componentId].keys()) { foreach(int paramIndex, _waitingReadParamIndexMap[componentId].keys()) {
if (++batchCount > maxBatchSize) { if (++batchCount > _maxBatchSize) {
goto Out; goto Out;
} }
...@@ -563,7 +583,7 @@ void ParameterManager::_waitingParamTimeout(void) ...@@ -563,7 +583,7 @@ void ParameterManager::_waitingParamTimeout(void)
if (_waitingWriteParamNameMap[componentId][paramName] <= _maxReadWriteRetry) { if (_waitingWriteParamNameMap[componentId][paramName] <= _maxReadWriteRetry) {
_writeParameterRaw(componentId, paramName, getParameter(componentId, paramName)->rawValue()); _writeParameterRaw(componentId, paramName, getParameter(componentId, paramName)->rawValue());
qCDebug(ParameterManagerLog) << _logVehiclePrefix(componentId) << "Write resend for (paramName:" << paramName << "retryCount:" << _waitingWriteParamNameMap[componentId][paramName] << ")"; qCDebug(ParameterManagerLog) << _logVehiclePrefix(componentId) << "Write resend for (paramName:" << paramName << "retryCount:" << _waitingWriteParamNameMap[componentId][paramName] << ")";
if (++batchCount > maxBatchSize) { if (++batchCount > _maxBatchSize) {
goto Out; goto Out;
} }
} else { } else {
...@@ -585,7 +605,7 @@ void ParameterManager::_waitingParamTimeout(void) ...@@ -585,7 +605,7 @@ void ParameterManager::_waitingParamTimeout(void)
if (_waitingReadParamNameMap[componentId][paramName] <= _maxReadWriteRetry) { if (_waitingReadParamNameMap[componentId][paramName] <= _maxReadWriteRetry) {
_readParameterRaw(componentId, paramName, -1); _readParameterRaw(componentId, paramName, -1);
qCDebug(ParameterManagerLog) << _logVehiclePrefix(componentId) << "Read re-request for (paramName:" << paramName << "retryCount:" << _waitingReadParamNameMap[componentId][paramName] << ")"; qCDebug(ParameterManagerLog) << _logVehiclePrefix(componentId) << "Read re-request for (paramName:" << paramName << "retryCount:" << _waitingReadParamNameMap[componentId][paramName] << ")";
if (++batchCount > maxBatchSize) { if (++batchCount > _maxBatchSize) {
goto Out; goto Out;
} }
} else { } else {
...@@ -781,6 +801,8 @@ void ParameterManager::_tryCacheHashLoad(int vehicleId, int componentId, QVarian ...@@ -781,6 +801,8 @@ void ParameterManager::_tryCacheHashLoad(int vehicleId, int componentId, QVarian
}); });
ani->start(QAbstractAnimation::DeleteWhenStopped); ani->start(QAbstractAnimation::DeleteWhenStopped);
_intervalUpdateTimer.invalidate(); // don't change the interval since we loaded the params from cache
} }
} }
......
...@@ -18,6 +18,7 @@ ...@@ -18,6 +18,7 @@
#include <QMutex> #include <QMutex>
#include <QDir> #include <QDir>
#include <QJsonObject> #include <QJsonObject>
#include <QElapsedTimer>
#include "FactSystem.h" #include "FactSystem.h"
#include "MAVLinkProtocol.h" #include "MAVLinkProtocol.h"
...@@ -196,6 +197,9 @@ private: ...@@ -196,6 +197,9 @@ private:
QTimer _initialRequestTimeoutTimer; QTimer _initialRequestTimeoutTimer;
QTimer _waitingParamTimeoutTimer; 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; QMutex _dataMutex;
static Fact _defaultFact; ///< Used to return default fact, when parameter not found 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