diff --git a/src/FactSystem/ParameterLoader.cc b/src/FactSystem/ParameterLoader.cc index 47cc29a4b3d3954e05da2c16a4be37003382c4fa..c07f40e3e3d384dad866f964dc9d3c61e6ca0ade 100644 --- a/src/FactSystem/ParameterLoader.cc +++ b/src/FactSystem/ParameterLoader.cc @@ -72,10 +72,6 @@ ParameterLoader::ParameterLoader(AutoPilotPlugin* autopilot, Vehicle* vehicle, Q _waitingParamTimeoutTimer.setInterval(1000); connect(&_waitingParamTimeoutTimer, &QTimer::timeout, this, &ParameterLoader::_waitingParamTimeout); - _cacheTimeoutTimer.setSingleShot(true); - _cacheTimeoutTimer.setInterval(2500); - connect(&_cacheTimeoutTimer, &QTimer::timeout, this, &ParameterLoader::_timeoutRefreshAll); - connect(_vehicle->uas(), &UASInterface::parameterUpdate, this, &ParameterLoader::_parameterUpdate); // Ensure the cache directory exists @@ -120,7 +116,6 @@ void ParameterLoader::_parameterUpdate(int uasId, int componentId, QString param if (parameterName == "_HASH_CHECK") { /* we received a cache hash, potentially load from cache */ - _cacheTimeoutTimer.stop(); _tryCacheHashLoad(uasId, componentId, value); return; } @@ -523,19 +518,6 @@ Out: } } -void ParameterLoader::_tryCacheLookup() -{ - /* Start waiting for 2.5 seconds to get a cache hit and avoid loading all params over the radio */ - _cacheTimeoutTimer.start(); - - MAVLinkProtocol* mavlink = qgcApp()->toolbox()->mavlinkProtocol(); - Q_ASSERT(mavlink); - - mavlink_message_t msg; - mavlink_msg_param_request_read_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, _vehicle->id(), MAV_COMP_ID_ALL, "_HASH_CHECK", -1); - _vehicle->sendMessageOnLink(_dedicatedLink, msg); -} - void ParameterLoader::_readParameterRaw(int componentId, const QString& paramName, int paramIndex) { mavlink_message_t msg; @@ -913,9 +895,3 @@ void ParameterLoader::_initialRequestTimeout(void) refreshAllParameters(); _initialRequestTimeoutTimer.start(); } - -void ParameterLoader::_timeoutRefreshAll() -{ - refreshAllParameters(); -} - diff --git a/src/FactSystem/ParameterLoader.h b/src/FactSystem/ParameterLoader.h index cdd71b0f7d6dca05ebad66c5bd72d4ab695682ec..48638d51a0dfec41dfe7efb9faa4e5b4a70c47f0 100644 --- a/src/FactSystem/ParameterLoader.h +++ b/src/FactSystem/ParameterLoader.h @@ -112,9 +112,6 @@ protected: void _waitingParamTimeout(void); void _tryCacheLookup(void); void _initialRequestTimeout(void); - -private slots: - void _timeoutRefreshAll(); private: static QVariant _stringToTypedVariant(const QString& string, FactMetaData::ValueType_t type, bool failOk = false); @@ -160,7 +157,6 @@ private: QTimer _initialRequestTimeoutTimer; QTimer _waitingParamTimeoutTimer; - QTimer _cacheTimeoutTimer; QMutex _dataMutex;