From 18ee64462ed7fafcfebed6fe9a3a5cfa0ffc55fd Mon Sep 17 00:00:00 2001 From: Don Gagne Date: Sat, 9 Apr 2016 16:33:04 -0700 Subject: [PATCH] Notify user on read/write failures after retries --- src/FactSystem/ParameterLoader.cc | 32 +++++++++++++++++++++---------- src/FactSystem/ParameterLoader.h | 5 +++-- 2 files changed, 25 insertions(+), 12 deletions(-) diff --git a/src/FactSystem/ParameterLoader.cc b/src/FactSystem/ParameterLoader.cc index 22183d76b..0a350f46c 100644 --- a/src/FactSystem/ParameterLoader.cc +++ b/src/FactSystem/ParameterLoader.cc @@ -536,11 +536,16 @@ void ParameterLoader::_waitingParamTimeout(void) foreach(const QString ¶mName, _waitingWriteParamNameMap[componentId].keys()) { paramsRequested = true; _waitingWriteParamNameMap[componentId][paramName]++; // Bump retry count - _writeParameterRaw(componentId, paramName, _vehicle->autopilotPlugin()->getFact(FactSystem::ParameterProvider, componentId, paramName)->rawValue()); - qCDebug(ParameterLoaderLog) << "Write resend for (componentId:" << componentId << "paramName:" << paramName << "retryCount:" << _waitingWriteParamNameMap[componentId][paramName] << ")"; - - if (++batchCount > maxBatchSize) { - goto Out; + if (_waitingWriteParamNameMap[componentId][paramName] <= _maxReadWriteRetry) { + _writeParameterRaw(componentId, paramName, _vehicle->autopilotPlugin()->getFact(FactSystem::ParameterProvider, componentId, paramName)->rawValue()); + qCDebug(ParameterLoaderLog) << "Write resend for (componentId:" << componentId << "paramName:" << paramName << "retryCount:" << _waitingWriteParamNameMap[componentId][paramName] << ")"; + if (++batchCount > maxBatchSize) { + goto Out; + } + } else { + // Exceeded max retry count, notify user + _waitingWriteParamNameMap[componentId].remove(paramName); + qgcApp()->showMessage(tr("Parameter write failed: comp:%1 param:%2").arg(componentId).arg(paramName)); } } } @@ -551,11 +556,16 @@ void ParameterLoader::_waitingParamTimeout(void) foreach(const QString ¶mName, _waitingReadParamNameMap[componentId].keys()) { paramsRequested = true; _waitingReadParamNameMap[componentId][paramName]++; // Bump retry count - _readParameterRaw(componentId, paramName, -1); - qCDebug(ParameterLoaderLog) << "Read re-request for (componentId:" << componentId << "paramName:" << paramName << "retryCount:" << _waitingReadParamNameMap[componentId][paramName] << ")"; - - if (++batchCount > maxBatchSize) { - goto Out; + if (_waitingReadParamNameMap[componentId][paramName] <= _maxReadWriteRetry) { + _readParameterRaw(componentId, paramName, -1); + qCDebug(ParameterLoaderLog) << "Read re-request for (componentId:" << componentId << "paramName:" << paramName << "retryCount:" << _waitingReadParamNameMap[componentId][paramName] << ")"; + if (++batchCount > maxBatchSize) { + goto Out; + } + } else { + // Exceeded max retry count, notify user + _waitingReadParamNameMap[componentId].remove(paramName); + qgcApp()->showMessage(tr("Parameter read failed: comp:%1 param:%2").arg(componentId).arg(paramName)); } } } @@ -585,6 +595,8 @@ void ParameterLoader::_readParameterRaw(int componentId, const QString& paramNam void ParameterLoader::_writeParameterRaw(int componentId, const QString& paramName, const QVariant& value) { + return; + mavlink_param_set_t p; mavlink_param_union_t union_value; diff --git a/src/FactSystem/ParameterLoader.h b/src/FactSystem/ParameterLoader.h index 77e4d3fbf..43714083a 100644 --- a/src/FactSystem/ParameterLoader.h +++ b/src/FactSystem/ParameterLoader.h @@ -163,8 +163,9 @@ private: int _parameterSetMajorVersion; ///< Version for parameter set, -1 if not known QObject* _parameterMetaData; ///< Opaque data from FirmwarePlugin::loadParameterMetaDataCall - static const int _maxInitialLoadRetry = 10; ///< Maximum a retries on initial index based load - + static const int _maxInitialLoadRetry = 10; ///< Maximum retries for initial index based load + static const int _maxReadWriteRetry = 5; ///< Maximum retries read/write + QMap _paramCountMap; ///< Key: Component id, Value: count of parameters in this component QMap > _waitingReadParamIndexMap; ///< Key: Component id, Value: Map { Key: parameter index still waiting for, Value: retry count } QMap > _waitingReadParamNameMap; ///< Key: Component id, Value: Map { Key: parameter name still waiting for, Value: retry count } -- 2.22.0