Commit 6f370406 authored by Don Gagne's avatar Don Gagne

Only save to eeprom when value changes

parent 68908488
......@@ -52,6 +52,7 @@ ParameterLoader::ParameterLoader(AutoPilotPlugin* autopilot, Vehicle* vehicle, Q
, _mavlink(qgcApp()->toolbox()->mavlinkProtocol())
, _parametersReady(false)
, _initialLoadComplete(false)
, _saveRequired(false)
, _defaultComponentId(FactSystem::defaultComponentId)
, _totalParamCount(0)
{
......@@ -290,6 +291,7 @@ void ParameterLoader::_valueUpdated(const QVariant& value)
_waitingWriteParamNameMap[componentId].remove(name); // Remove any old entry
_waitingWriteParamNameMap[componentId][name] = 0; // Add new entry and set retry count
_waitingParamTimeoutTimer.start();
_saveRequired = true;
_dataMutex.unlock();
......@@ -672,13 +674,16 @@ void ParameterLoader::_tryCacheHashLoad(int uasId, QVariant hash_value)
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(_vehicle->priorityLink(), msg);
qCDebug(ParameterLoaderLog) << "_saveToEEPROM";
} else {
qCDebug(ParameterLoaderLog) << "_saveToEEPROM skipped due to FirmwarePlugin::isCapable";
if (_saveRequired) {
_saveRequired = false;
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(_vehicle->priorityLink(), msg);
qCDebug(ParameterLoaderLog) << "_saveToEEPROM";
} else {
qCDebug(ParameterLoaderLog) << "_saveToEEPROM skipped due to FirmwarePlugin::isCapable";
}
}
}
......
......@@ -139,6 +139,7 @@ private:
bool _parametersReady; ///< true: full set of parameters correctly loaded
bool _initialLoadComplete; ///< true: Initial load of all parameters complete, whether succesful or not
bool _saveRequired; ///< true: _saveToEEPROM should be called
int _defaultComponentId;
QString _defaultComponentIdParam;
......
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