Skip to content

Commit

Permalink
Revert "dynamic param load timeout"
Browse files Browse the repository at this point in the history
  • Loading branch information
DonLakeFlyer authored Mar 6, 2017
1 parent 891f893 commit a4e8b08
Show file tree
Hide file tree
Showing 2 changed files with 5 additions and 30 deletions.
31 changes: 5 additions & 26 deletions src/FactSystem/ParameterManager.cc
Original file line number Diff line number Diff line change
Expand Up @@ -63,8 +63,6 @@ ParameterManager::ParameterManager(Vehicle* vehicle)
{
_versionParam = vehicle->firmwarePlugin()->getVersionParam();

_intervalUpdateTimer.invalidate();

if (_vehicle->isOfflineEditingVehicle()) {
_loadOfflineEditingParams();
return;
Expand Down Expand Up @@ -140,6 +138,7 @@ void ParameterManager::_parameterUpdate(int vehicleId, int componentId, QString
return;
}

_initialRequestTimeoutTimer.stop();
_waitingParamTimeoutTimer.stop();

_dataMutex.lock();
Expand Down Expand Up @@ -222,21 +221,6 @@ 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();
Expand Down Expand Up @@ -405,8 +389,6 @@ void ParameterManager::refreshAllParameters(uint8_t componentId)

_dataMutex.unlock();

_intervalUpdateTimer.start();

MAVLinkProtocol* mavlink = qgcApp()->toolbox()->mavlinkProtocol();
Q_ASSERT(mavlink);

Expand Down Expand Up @@ -528,10 +510,9 @@ 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
Expand All @@ -543,7 +524,7 @@ void ParameterManager::_waitingParamTimeout(void)
}

foreach(int paramIndex, _waitingReadParamIndexMap[componentId].keys()) {
if (++batchCount > _maxBatchSize) {
if (++batchCount > maxBatchSize) {
goto Out;
}

Expand Down Expand Up @@ -582,7 +563,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 {
Expand All @@ -604,7 +585,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 {
Expand Down Expand Up @@ -800,8 +781,6 @@ 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
}
}

Expand Down
4 changes: 0 additions & 4 deletions src/FactSystem/ParameterManager.h
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,6 @@
#include <QMutex>
#include <QDir>
#include <QJsonObject>
#include <QElapsedTimer>

#include "FactSystem.h"
#include "MAVLinkProtocol.h"
Expand Down Expand Up @@ -197,9 +196,6 @@ class ParameterManager : public QObject
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
Expand Down

0 comments on commit a4e8b08

Please sign in to comment.