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
708096b5
Commit
708096b5
authored
Feb 18, 2016
by
Nate Weibley
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
Remove dead parameter cache code
Conflicts: src/FactSystem/ParameterLoader.cc
parent
823b9a6d
Changes
2
Hide whitespace changes
Inline
Side-by-side
Showing
2 changed files
with
0 additions
and
28 deletions
+0
-28
ParameterLoader.cc
src/FactSystem/ParameterLoader.cc
+0
-24
ParameterLoader.h
src/FactSystem/ParameterLoader.h
+0
-4
No files found.
src/FactSystem/ParameterLoader.cc
View file @
708096b5
...
...
@@ -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
();
}
src/FactSystem/ParameterLoader.h
View file @
708096b5
...
...
@@ -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
;
...
...
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