From d40db15725eadd30fa0dc04e8d7c31d95dc37648 Mon Sep 17 00:00:00 2001 From: Don Gagne Date: Sun, 29 May 2016 13:28:27 -0700 Subject: [PATCH] Protocol no longer stays on single link --- src/FactSystem/ParameterLoader.cc | 9 ++++----- src/FactSystem/ParameterLoader.h | 2 -- 2 files changed, 4 insertions(+), 7 deletions(-) diff --git a/src/FactSystem/ParameterLoader.cc b/src/FactSystem/ParameterLoader.cc index a774fa99d..99b39253e 100644 --- a/src/FactSystem/ParameterLoader.cc +++ b/src/FactSystem/ParameterLoader.cc @@ -53,7 +53,6 @@ ParameterLoader::ParameterLoader(Vehicle* vehicle) : QObject(vehicle) , _vehicle(vehicle) , _mavlink(qgcApp()->toolbox()->mavlinkProtocol()) - , _dedicatedLink(_vehicle->priorityLink()) , _parametersReady(false) , _initialLoadComplete(false) , _waitingForDefaultComponent(false) @@ -364,7 +363,7 @@ void ParameterLoader::refreshAllParameters(uint8_t componentID) mavlink_message_t msg; mavlink_msg_param_request_list_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, _vehicle->id(), componentID); - _vehicle->sendMessageOnLink(_dedicatedLink, msg); + _vehicle->sendMessageOnLink(_vehicle->priorityLink(), msg); QString what = (componentID == MAV_COMP_ID_ALL) ? "MAV_COMP_ID_ALL" : QString::number(componentID); qCDebug(ParameterLoaderLog) << "Request to refresh all parameters for component ID:" << what; @@ -594,7 +593,7 @@ void ParameterLoader::_readParameterRaw(int componentId, const QString& paramNam componentId, // Target component id fixedParamName, // Named parameter being requested paramIndex); // Parameter index being requested, -1 for named - _vehicle->sendMessageOnLink(_dedicatedLink, msg); + _vehicle->sendMessageOnLink(_vehicle->priorityLink(), msg); } void ParameterLoader::_writeParameterRaw(int componentId, const QString& paramName, const QVariant& value) @@ -647,7 +646,7 @@ void ParameterLoader::_writeParameterRaw(int componentId, const QString& paramNa mavlink_message_t msg; mavlink_msg_param_set_encode(_mavlink->getSystemId(), _mavlink->getComponentId(), &msg, &p); - _vehicle->sendMessageOnLink(_dedicatedLink, msg); + _vehicle->sendMessageOnLink(_vehicle->priorityLink(), msg); } void ParameterLoader::_writeLocalParamCache(int uasId, int componentId) @@ -757,7 +756,7 @@ void ParameterLoader::_saveToEEPROM(void) if (_vehicle->firmwarePlugin()->isCapable(FirmwarePlugin::MavCmdPreflightStorageCapability)) { mavlink_message_t msg; mavlink_msg_command_long_pack(_mavlink->getSystemId(), _mavlink->getComponentId(), &msg, _vehicle->id(), 0, MAV_CMD_PREFLIGHT_STORAGE, 1, 1, -1, -1, -1, 0, 0, 0); - _vehicle->sendMessageOnLink(_dedicatedLink, msg); + _vehicle->sendMessageOnLink(_vehicle->priorityLink(), msg); qCDebug(ParameterLoaderLog) << "_saveToEEPROM"; } else { qCDebug(ParameterLoaderLog) << "_saveToEEPROM skipped due to FirmwarePlugin::isCapable"; diff --git a/src/FactSystem/ParameterLoader.h b/src/FactSystem/ParameterLoader.h index 6dbd25e15..b83bed060 100644 --- a/src/FactSystem/ParameterLoader.h +++ b/src/FactSystem/ParameterLoader.h @@ -144,8 +144,6 @@ private: void _saveToEEPROM(void); void _checkInitialLoadComplete(bool failIfNoDefaultComponent); - LinkInterface* _dedicatedLink; ///< Parameter protocol stays on this link - /// First mapping is by component id /// Second mapping is parameter name, to Fact* in QVariant QMap _mapParameterName2Variant; -- 2.22.0