From f5c76056d0014ec533924e650c4edcd85d38a0ad Mon Sep 17 00:00:00 2001 From: Don Gagne Date: Mon, 14 Dec 2015 11:31:31 -0800 Subject: [PATCH] Retry initial param request if it fails Plus notify user --- src/FactSystem/ParameterLoader.cc | 17 +++++++++++++++++ src/FactSystem/ParameterLoader.h | 2 ++ 2 files changed, 19 insertions(+) diff --git a/src/FactSystem/ParameterLoader.cc b/src/FactSystem/ParameterLoader.cc index 587df5949..91d072602 100644 --- a/src/FactSystem/ParameterLoader.cc +++ b/src/FactSystem/ParameterLoader.cc @@ -62,6 +62,10 @@ ParameterLoader::ParameterLoader(AutoPilotPlugin* autopilot, Vehicle* vehicle, Q // We signal this to ouselves in order to start timer on our thread connect(this, &ParameterLoader::restartWaitingParamTimer, this, &ParameterLoader::_restartWaitingParamTimer); + _initialRequestTimeoutTimer.setSingleShot(true); + _initialRequestTimeoutTimer.setInterval(6000); + connect(&_initialRequestTimeoutTimer, &QTimer::timeout, this, &ParameterLoader::_initialRequestTimeout); + _waitingParamTimeoutTimer.setSingleShot(true); _waitingParamTimeoutTimer.setInterval(1000); connect(&_waitingParamTimeoutTimer, &QTimer::timeout, this, &ParameterLoader::_waitingParamTimeout); @@ -92,6 +96,8 @@ void ParameterLoader::_parameterUpdate(int uasId, int componentId, QString param return; } + _initialRequestTimeoutTimer.stop(); + qCDebug(ParameterLoaderLog) << "_parameterUpdate (usaId:" << uasId << "componentId:" << componentId << "name:" << parameterName << @@ -296,6 +302,10 @@ void ParameterLoader::refreshAllParameters(void) { _dataMutex.lock(); + if (!_initialLoadComplete) { + _initialRequestTimeoutTimer.start(); + } + // Reset index wait lists foreach (int componentId, _paramCountMap.keys()) { // Add/Update all indices to the wait list, parameter index is 0-based @@ -859,3 +869,10 @@ void ParameterLoader::_checkInitialLoadComplete(void) emit parametersReady(false); } } + +void ParameterLoader::_initialRequestTimeout(void) +{ + qgcApp()->showMessage("Vehicle did not respond to request for parameters, retrying"); + refreshAllParameters(); + _initialRequestTimeoutTimer.start(); +} diff --git a/src/FactSystem/ParameterLoader.h b/src/FactSystem/ParameterLoader.h index 5a82e81fd..74775d778 100644 --- a/src/FactSystem/ParameterLoader.h +++ b/src/FactSystem/ParameterLoader.h @@ -108,6 +108,7 @@ private slots: void _restartWaitingParamTimer(void); void _waitingParamTimeout(void); void _tryCacheLookup(void); + void _initialRequestTimeout(void); private: static QVariant _stringToTypedVariant(const QString& string, FactMetaData::ValueType_t type, bool failOk = false); @@ -148,6 +149,7 @@ private: int _totalParamCount; ///< Number of parameters across all components + QTimer _initialRequestTimeoutTimer; QTimer _waitingParamTimeoutTimer; QTimer _cacheTimeoutTimer; -- 2.22.0