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
dae59cf7
Commit
dae59cf7
authored
Aug 09, 2013
by
tstellanova
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
workaround for premature timer firing bug
parent
6bc50564
Changes
2
Hide whitespace changes
Inline
Side-by-side
Showing
2 changed files
with
17 additions
and
14 deletions
+17
-14
UASParameterCommsMgr.cc
src/uas/UASParameterCommsMgr.cc
+16
-10
UASParameterCommsMgr.h
src/uas/UASParameterCommsMgr.h
+1
-4
No files found.
src/uas/UASParameterCommsMgr.cc
View file @
dae59cf7
...
...
@@ -234,23 +234,33 @@ void UASParameterCommsMgr::resetAfterListReceive()
void
UASParameterCommsMgr
::
retransmissionGuardTick
()
{
quint64
curTime
=
QGC
::
groundTimeMilliseconds
();
//Workaround for an apparent Qt bug that causes retransmission guard timer to fire prematurely (350ms)
quint64
elapsed
=
(
curTime
=
lastTimerReset
);
if
(
elapsed
<
transmissionTimeout
)
{
qDebug
()
<<
"retransmissionGuardTick elapsed:"
<<
(
curTime
-
lastTimerReset
);
//reset the guard timer: it fired prematurely
setRetransmissionGuardEnabled
(
true
);
return
;
}
if
(
transmissionActive
)
{
if
(
transmissionListMode
&&
transmissionListSizeKnown
.
isEmpty
()
)
{
//we are still waitin for the first parameter list response
if
(
QGC
::
groundTimeMilliseconds
()
>
this
->
listRecvTimeout
)
{
if
(
curTime
>
this
->
listRecvTimeout
)
{
//re-request parameters
setParameterStatusMsg
(
tr
(
"TIMEOUT: Re-requesting param list"
),
ParamCommsStatusLevel_Warning
);
listRecvTimeout
=
QGC
::
groundTimeMilliseconds
()
+
10000
;
listRecvTimeout
=
curTime
+
10000
;
mav
->
requestParameters
();
}
return
;
}
// Check for timeout
// stop retransmission attempts on timeout
if
(
QGC
::
groundTimeMilliseconds
()
>
transmissionTimeout
)
{
if
(
curTime
>
transmissionTimeout
)
{
setRetransmissionGuardEnabled
(
false
);
resetAfterListReceive
();
...
...
@@ -285,10 +295,9 @@ void UASParameterCommsMgr::retransmissionGuardTick()
void
UASParameterCommsMgr
::
setRetransmissionGuardEnabled
(
bool
enabled
)
{
// qDebug() << "setRetransmissionGuardEnabled: " << enabled;
if
(
enabled
)
{
retransmissionTimer
.
start
(
retransmissionTimeout
);
lastTimerReset
=
QGC
::
groundTimeMilliseconds
()
;
}
else
{
retransmissionTimer
.
stop
();
}
...
...
@@ -429,7 +438,7 @@ void UASParameterCommsMgr::receivedParameterUpdate(int uas, int compId, int para
transmissionListSizeKnown
.
insert
(
compId
,
true
);
qDebug
()
<<
"Mark all parameters as missing: "
<<
paramCount
;
for
(
int
i
=
1
;
i
<
paramCount
;
++
i
)
{
//TODO check: param Id 0 is "all parameters" ?
for
(
int
i
=
1
;
i
<
paramCount
;
++
i
)
{
//TODO check: param Id 0 is "all parameters"
and not valid
?
if
(
!
compXmitMissing
->
contains
(
i
))
{
compXmitMissing
->
append
(
i
);
}
...
...
@@ -444,9 +453,6 @@ void UASParameterCommsMgr::receivedParameterUpdate(int uas, int compId, int para
}
}
// Start retransmission guard
// or reset timer
setRetransmissionGuardEnabled
(
true
);
}
// Mark this parameter as received in read list
...
...
src/uas/UASParameterCommsMgr.h
View file @
dae59cf7
...
...
@@ -84,10 +84,6 @@ public slots:
virtual
void
receivedParameterUpdate
(
int
uas
,
int
compId
,
int
paramCount
,
int
paramId
,
QString
paramName
,
QVariant
value
);
//protected slots:
// void receivedParameterChange(int uas, int component, QString parameterName, QVariant value);
// void receivedParameterListChange(int uas, int component, int parameterCount, int parameterId, QString parameterName, QVariant value);
protected:
UASInterface
*
mav
;
///< The MAV we're talking to
...
...
@@ -103,6 +99,7 @@ protected:
bool
transmissionActive
;
///< Missing packets, working on list?
quint64
transmissionTimeout
;
///< Timeout
QTimer
retransmissionTimer
;
///< Timer handling parameter retransmission
quint64
lastTimerReset
;
///< Last time the guard timer was reset, to prevent premature firing
int
retransmissionTimeout
;
///< Retransmission request timeout, in milliseconds
int
rewriteTimeout
;
///< Write request timeout, in milliseconds
int
retransmissionBurstRequestSize
;
///< Number of packets requested for retransmission per burst
...
...
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