Commit 1bc43cab authored by tstellanova's avatar tstellanova

workaround for premature timer firing bug

parent 5d23be2e
...@@ -234,23 +234,33 @@ void UASParameterCommsMgr::resetAfterListReceive() ...@@ -234,23 +234,33 @@ void UASParameterCommsMgr::resetAfterListReceive()
void UASParameterCommsMgr::retransmissionGuardTick() 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 (transmissionActive) {
if (transmissionListMode && transmissionListSizeKnown.isEmpty() ) { if (transmissionListMode && transmissionListSizeKnown.isEmpty() ) {
//we are still waitin for the first parameter list response //we are still waitin for the first parameter list response
if (QGC::groundTimeMilliseconds() > this->listRecvTimeout) { if (curTime > this->listRecvTimeout) {
//re-request parameters //re-request parameters
setParameterStatusMsg(tr("TIMEOUT: Re-requesting param list"),ParamCommsStatusLevel_Warning); setParameterStatusMsg(tr("TIMEOUT: Re-requesting param list"),ParamCommsStatusLevel_Warning);
listRecvTimeout = QGC::groundTimeMilliseconds() + 10000; listRecvTimeout = curTime + 10000;
mav->requestParameters(); mav->requestParameters();
} }
return; return;
} }
// Check for timeout // Check for timeout
// stop retransmission attempts on timeout // stop retransmission attempts on timeout
if (QGC::groundTimeMilliseconds() > transmissionTimeout) { if (curTime > transmissionTimeout) {
setRetransmissionGuardEnabled(false); setRetransmissionGuardEnabled(false);
resetAfterListReceive(); resetAfterListReceive();
...@@ -285,10 +295,9 @@ void UASParameterCommsMgr::retransmissionGuardTick() ...@@ -285,10 +295,9 @@ void UASParameterCommsMgr::retransmissionGuardTick()
void UASParameterCommsMgr::setRetransmissionGuardEnabled(bool enabled) void UASParameterCommsMgr::setRetransmissionGuardEnabled(bool enabled)
{ {
// qDebug() << "setRetransmissionGuardEnabled: " << enabled;
if (enabled) { if (enabled) {
retransmissionTimer.start(retransmissionTimeout); retransmissionTimer.start(retransmissionTimeout);
lastTimerReset = QGC::groundTimeMilliseconds() ;
} else { } else {
retransmissionTimer.stop(); retransmissionTimer.stop();
} }
...@@ -429,7 +438,7 @@ void UASParameterCommsMgr::receivedParameterUpdate(int uas, int compId, int para ...@@ -429,7 +438,7 @@ void UASParameterCommsMgr::receivedParameterUpdate(int uas, int compId, int para
transmissionListSizeKnown.insert(compId, true); transmissionListSizeKnown.insert(compId, true);
qDebug() << "Mark all parameters as missing: " << paramCount; 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)) { if (!compXmitMissing->contains(i)) {
compXmitMissing->append(i); compXmitMissing->append(i);
} }
...@@ -444,9 +453,6 @@ void UASParameterCommsMgr::receivedParameterUpdate(int uas, int compId, int para ...@@ -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 // Mark this parameter as received in read list
......
...@@ -84,10 +84,6 @@ public slots: ...@@ -84,10 +84,6 @@ public slots:
virtual void receivedParameterUpdate(int uas, int compId, int paramCount, int paramId, QString paramName, QVariant value); 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: protected:
UASInterface* mav; ///< The MAV we're talking to UASInterface* mav; ///< The MAV we're talking to
...@@ -103,6 +99,7 @@ protected: ...@@ -103,6 +99,7 @@ protected:
bool transmissionActive; ///< Missing packets, working on list? bool transmissionActive; ///< Missing packets, working on list?
quint64 transmissionTimeout; ///< Timeout quint64 transmissionTimeout; ///< Timeout
QTimer retransmissionTimer; ///< Timer handling parameter retransmission 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 retransmissionTimeout; ///< Retransmission request timeout, in milliseconds
int rewriteTimeout; ///< Write request timeout, in milliseconds int rewriteTimeout; ///< Write request timeout, in milliseconds
int retransmissionBurstRequestSize; ///< Number of packets requested for retransmission per burst int retransmissionBurstRequestSize; ///< Number of packets requested for retransmission per burst
......
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