Skip to content
Projects
Groups
Snippets
Help
Loading...
Help
Support
Submit feedback
Contribute to GitLab
Sign in
Toggle navigation
Q
qgroundcontrol
Project
Project
Details
Activity
Releases
Cycle Analytics
Repository
Repository
Files
Commits
Branches
Tags
Contributors
Graph
Compare
Charts
Issues
0
Issues
0
List
Boards
Labels
Milestones
Merge Requests
0
Merge Requests
0
CI / CD
CI / CD
Pipelines
Jobs
Schedules
Charts
Wiki
Wiki
Snippets
Snippets
Members
Members
Collapse sidebar
Close sidebar
Activity
Graph
Charts
Create a new issue
Jobs
Commits
Issue Boards
Open sidebar
Valentin Platzgummer
qgroundcontrol
Commits
6f370406
Commit
6f370406
authored
Feb 16, 2016
by
Don Gagne
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
Only save to eeprom when value changes
parent
68908488
Changes
2
Hide whitespace changes
Inline
Side-by-side
Showing
2 changed files
with
13 additions
and
7 deletions
+13
-7
ParameterLoader.cc
src/FactSystem/ParameterLoader.cc
+12
-7
ParameterLoader.h
src/FactSystem/ParameterLoader.h
+1
-0
No files found.
src/FactSystem/ParameterLoader.cc
View file @
6f370406
...
...
@@ -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"
;
}
}
}
...
...
src/FactSystem/ParameterLoader.h
View file @
6f370406
...
...
@@ -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
;
...
...
Write
Preview
Markdown
is supported
0%
Try again
or
attach a new file
Attach a file
Cancel
You are about to add
0
people
to the discussion. Proceed with caution.
Finish editing this message first!
Cancel
Please
register
or
sign in
to comment