Commit f5c76056 authored by Don Gagne's avatar Don Gagne

Retry initial param request if it fails

Plus notify user
parent 781997b2
...@@ -62,6 +62,10 @@ ParameterLoader::ParameterLoader(AutoPilotPlugin* autopilot, Vehicle* vehicle, Q ...@@ -62,6 +62,10 @@ ParameterLoader::ParameterLoader(AutoPilotPlugin* autopilot, Vehicle* vehicle, Q
// We signal this to ouselves in order to start timer on our thread // We signal this to ouselves in order to start timer on our thread
connect(this, &ParameterLoader::restartWaitingParamTimer, this, &ParameterLoader::_restartWaitingParamTimer); connect(this, &ParameterLoader::restartWaitingParamTimer, this, &ParameterLoader::_restartWaitingParamTimer);
_initialRequestTimeoutTimer.setSingleShot(true);
_initialRequestTimeoutTimer.setInterval(6000);
connect(&_initialRequestTimeoutTimer, &QTimer::timeout, this, &ParameterLoader::_initialRequestTimeout);
_waitingParamTimeoutTimer.setSingleShot(true); _waitingParamTimeoutTimer.setSingleShot(true);
_waitingParamTimeoutTimer.setInterval(1000); _waitingParamTimeoutTimer.setInterval(1000);
connect(&_waitingParamTimeoutTimer, &QTimer::timeout, this, &ParameterLoader::_waitingParamTimeout); connect(&_waitingParamTimeoutTimer, &QTimer::timeout, this, &ParameterLoader::_waitingParamTimeout);
...@@ -92,6 +96,8 @@ void ParameterLoader::_parameterUpdate(int uasId, int componentId, QString param ...@@ -92,6 +96,8 @@ void ParameterLoader::_parameterUpdate(int uasId, int componentId, QString param
return; return;
} }
_initialRequestTimeoutTimer.stop();
qCDebug(ParameterLoaderLog) << "_parameterUpdate (usaId:" << uasId << qCDebug(ParameterLoaderLog) << "_parameterUpdate (usaId:" << uasId <<
"componentId:" << componentId << "componentId:" << componentId <<
"name:" << parameterName << "name:" << parameterName <<
...@@ -296,6 +302,10 @@ void ParameterLoader::refreshAllParameters(void) ...@@ -296,6 +302,10 @@ void ParameterLoader::refreshAllParameters(void)
{ {
_dataMutex.lock(); _dataMutex.lock();
if (!_initialLoadComplete) {
_initialRequestTimeoutTimer.start();
}
// Reset index wait lists // Reset index wait lists
foreach (int componentId, _paramCountMap.keys()) { foreach (int componentId, _paramCountMap.keys()) {
// Add/Update all indices to the wait list, parameter index is 0-based // Add/Update all indices to the wait list, parameter index is 0-based
...@@ -859,3 +869,10 @@ void ParameterLoader::_checkInitialLoadComplete(void) ...@@ -859,3 +869,10 @@ void ParameterLoader::_checkInitialLoadComplete(void)
emit parametersReady(false); emit parametersReady(false);
} }
} }
void ParameterLoader::_initialRequestTimeout(void)
{
qgcApp()->showMessage("Vehicle did not respond to request for parameters, retrying");
refreshAllParameters();
_initialRequestTimeoutTimer.start();
}
...@@ -108,6 +108,7 @@ private slots: ...@@ -108,6 +108,7 @@ private slots:
void _restartWaitingParamTimer(void); void _restartWaitingParamTimer(void);
void _waitingParamTimeout(void); void _waitingParamTimeout(void);
void _tryCacheLookup(void); void _tryCacheLookup(void);
void _initialRequestTimeout(void);
private: private:
static QVariant _stringToTypedVariant(const QString& string, FactMetaData::ValueType_t type, bool failOk = false); static QVariant _stringToTypedVariant(const QString& string, FactMetaData::ValueType_t type, bool failOk = false);
...@@ -148,6 +149,7 @@ private: ...@@ -148,6 +149,7 @@ private:
int _totalParamCount; ///< Number of parameters across all components int _totalParamCount; ///< Number of parameters across all components
QTimer _initialRequestTimeoutTimer;
QTimer _waitingParamTimeoutTimer; QTimer _waitingParamTimeoutTimer;
QTimer _cacheTimeoutTimer; QTimer _cacheTimeoutTimer;
......
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