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
aa2771bd
Commit
aa2771bd
authored
Dec 02, 2016
by
Don Gagne
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
Deal with ArduPilot 65536 index on PARAM_VALUE correctly
parent
e3a1f016
Changes
1
Hide whitespace changes
Inline
Side-by-side
Showing
1 changed file
with
17 additions
and
20 deletions
+17
-20
ParameterManager.cc
src/FactSystem/ParameterManager.cc
+17
-20
No files found.
src/FactSystem/ParameterManager.cc
View file @
aa2771bd
...
...
@@ -72,7 +72,7 @@ ParameterManager::ParameterManager(Vehicle* vehicle)
_mavlink
=
qgcApp
()
->
toolbox
()
->
mavlinkProtocol
();
_initialRequestTimeoutTimer
.
setSingleShot
(
true
);
_initialRequestTimeoutTimer
.
setInterval
(
20
000
);
_initialRequestTimeoutTimer
.
setInterval
(
5
000
);
connect
(
&
_initialRequestTimeoutTimer
,
&
QTimer
::
timeout
,
this
,
&
ParameterManager
::
_initialRequestTimeout
);
_waitingParamTimeoutTimer
.
setSingleShot
(
true
);
...
...
@@ -135,12 +135,8 @@ void ParameterManager::_parameterUpdate(int vehicleId, int componentId, QString
return
;
}
if
(
parameterId
>=
parameterCount
)
{
qCDebug
(
ParameterManagerLog
)
<<
_logVehiclePrefix
()
<<
"Discarding bogus update name:id:count"
<<
parameterName
<<
parameterId
<<
parameterCount
;
return
;
}
_initialRequestTimeoutTimer
.
stop
();
_waitingParamTimeoutTimer
.
stop
();
_dataMutex
.
lock
();
...
...
@@ -179,14 +175,9 @@ void ParameterManager::_parameterUpdate(int vehicleId, int componentId, QString
componentParamsComplete
=
true
;
}
if
(
_waitingReadParamIndexMap
[
componentId
].
contains
(
parameterId
)
||
_waitingReadParamNameMap
[
componentId
].
contains
(
parameterName
)
||
_waitingWriteParamNameMap
[
componentId
].
contains
(
parameterName
))
{
// We were waiting for this parameter, restart wait timer. Otherwise it is a spurious parameter update which
// means we should not reset the wait timer.
qCDebug
(
ParameterManagerVerbose1Log
)
<<
_logVehiclePrefix
()
<<
"Restarting _waitingParamTimeoutTimer (valid param received)"
;
_waitingParamTimeoutTimer
.
start
();
}
else
{
if
(
!
_waitingReadParamIndexMap
[
componentId
].
contains
(
parameterId
)
&&
!
_waitingReadParamNameMap
[
componentId
].
contains
(
parameterName
)
&&
!
_waitingWriteParamNameMap
[
componentId
].
contains
(
parameterName
))
{
qCDebug
(
ParameterManagerVerbose1Log
)
<<
_logVehiclePrefix
()
<<
"Unrequested param update"
<<
parameterName
;
}
...
...
@@ -234,12 +225,17 @@ void ParameterManager::_parameterUpdate(int vehicleId, int componentId, QString
int
readWaitingParamCount
=
waitingReadParamIndexCount
+
waitingReadParamNameCount
;
int
totalWaitingParamCount
=
readWaitingParamCount
+
waitingWriteParamNameCount
;
if
(
totalWaitingParamCount
)
{
qCDebug
(
ParameterManagerVerbose1Log
)
<<
_logVehiclePrefix
(
componentId
)
<<
"totalWaitingParamCount:"
<<
totalWaitingParamCount
;
}
else
if
(
_defaultComponentId
!=
MAV_COMP_ID_ALL
||
_defaultComponentIdParam
.
isEmpty
())
{
// No more parameters to wait for, stop the timeout. Be careful to not stop timer if we don't have the default
// component yet.
qCDebug
(
ParameterManagerVerbose1Log
)
<<
_logVehiclePrefix
()
<<
"Stopping _waitingParamTimeoutTimer (all requests satisfied)"
;
_waitingParamTimeoutTimer
.
stop
();
// More params to wait for, restart timer
_waitingParamTimeoutTimer
.
start
();
qCDebug
(
ParameterManagerVerbose1Log
)
<<
_logVehiclePrefix
()
<<
"Restarting _waitingParamTimeoutTimer: totalWaitingParamCount:"
<<
totalWaitingParamCount
;
}
else
{
if
(
_defaultComponentId
==
MAV_COMP_ID_ALL
&&
!
_defaultComponentIdParam
.
isEmpty
())
{
// Still waiting for default component id, restart timer
qCDebug
(
ParameterManagerVerbose1Log
)
<<
_logVehiclePrefix
()
<<
"Restarting _waitingParamTimeoutTimer (still waiting for default component)"
;
_waitingParamTimeoutTimer
.
start
();
}
else
{
qCDebug
(
ParameterManagerVerbose1Log
)
<<
_logVehiclePrefix
()
<<
"Not restarting _waitingParamTimeoutTimer (all requests satisfied)"
;
}
}
// Update progress bar for waiting reads
...
...
@@ -1064,6 +1060,7 @@ void ParameterManager::_checkInitialLoadComplete(bool failIfNoDefaultComponent)
void
ParameterManager
::
_initialRequestTimeout
(
void
)
{
if
(
!
_disableAllRetries
&&
++
_initialRequestRetryCount
<=
_maxInitialRequestListRetry
)
{
qCDebug
(
ParameterManagerLog
)
<<
_logVehiclePrefix
()
<<
"Retyring initial parameter request list"
;
refreshAllParameters
();
_initialRequestTimeoutTimer
.
start
();
}
else
{
...
...
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