|
|
|
@ -53,7 +53,6 @@ ParameterLoader::ParameterLoader(Vehicle* vehicle)
@@ -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)
@@ -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
@@ -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
@@ -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)
@@ -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"; |
|
|
|
|