From 3090fcf2596a04125fe57f19dce2db6e9f6e0fc5 Mon Sep 17 00:00:00 2001 From: tstellanova Date: Thu, 8 Aug 2013 10:20:52 -0700 Subject: [PATCH] Retransmit param list request; fix null data model --- libs/eigen/Eigen/src/Core/BandMatrix.h | 1 + src/uas/UAS.cc | 12 ++++++++---- src/uas/UASParameterCommsMgr.cc | 27 ++++++++++++++++++++++---- src/uas/UASParameterCommsMgr.h | 1 + 4 files changed, 33 insertions(+), 8 deletions(-) diff --git a/libs/eigen/Eigen/src/Core/BandMatrix.h b/libs/eigen/Eigen/src/Core/BandMatrix.h index dda8efba3..e6922b50f 100644 --- a/libs/eigen/Eigen/src/Core/BandMatrix.h +++ b/libs/eigen/Eigen/src/Core/BandMatrix.h @@ -285,6 +285,7 @@ class BandMatrixWrapper : public BandMatrixBaseat(i)) { - qDebug()<<"Antenna tracking: Forwarding Over link: "<getName()<<" "<isConnected()) { + qDebug()<<"Antenna tracking: Forwarding Over link: "<getName()<<" "<getParamDataModel(); loadParamCommsSettings(); @@ -57,6 +58,8 @@ void UASParameterCommsMgr::loadParamCommsSettings() settings.endGroup(); } + + /** * Send a request to deliver the list of onboard parameters * from the MAV. @@ -82,7 +85,9 @@ void UASParameterCommsMgr::requestParameterList() transmissionActive = true; setParameterStatusMsg(tr("Requested param list.. waiting")); + listRecvTimeout = QGC::groundTimeMilliseconds() + 10000; mav->requestParameters(); + setRetransmissionGuardEnabled(true); } else { qDebug() << __FILE__ << __LINE__ << "Ignoring requestParameterList because we're receiving params list"; @@ -94,6 +99,17 @@ void UASParameterCommsMgr::requestParameterList() void UASParameterCommsMgr::retransmissionGuardTick() { if (transmissionActive) { + if (transmissionListMode && transmissionListSizeKnown.isEmpty() ) { + //we are still waitin for the first parameter list response + if (QGC::groundTimeMilliseconds() > this->listRecvTimeout) { + //re-request parameters + setParameterStatusMsg(tr("TIMEOUT: Re-requesting param list"),ParamCommsStatusLevel_Warning); + listRecvTimeout = QGC::groundTimeMilliseconds() + 10000; + mav->requestParameters(); + } + return; + } + qDebug() << __FILE__ << __LINE__ << "RETRANSMISSION GUARD ACTIVE, CHECKING FOR DROPS.."; // Check for timeout @@ -466,11 +482,9 @@ void UASParameterCommsMgr::receivedParameterUpdate(int uas, int compId, int para transmissionMissingPackets.value(key)->clear(); } + setRetransmissionGuardEnabled(false); //all parameters have been received, broadcast to UI emit parameterListUpToDate(); - //TODO in UI - // Expand visual tree - //tree->expandItem(tree->topLevelItem(0)); } } @@ -527,5 +541,10 @@ void UASParameterCommsMgr::sendPendingParameters() UASParameterCommsMgr::~UASParameterCommsMgr() { setRetransmissionGuardEnabled(false); + + QString ptrStr; + ptrStr.sprintf("%8p", this); + qDebug() << "UASParameterCommsMgr destructor: " << ptrStr ; + } diff --git a/src/uas/UASParameterCommsMgr.h b/src/uas/UASParameterCommsMgr.h index 3ac5f53d6..03286c1e1 100644 --- a/src/uas/UASParameterCommsMgr.h +++ b/src/uas/UASParameterCommsMgr.h @@ -98,6 +98,7 @@ protected: int retransmissionTimeout; ///< Retransmission request timeout, in milliseconds int rewriteTimeout; ///< Write request timeout, in milliseconds int retransmissionBurstRequestSize; ///< Number of packets requested for retransmission per burst + quint64 listRecvTimeout; ///< How long to wait for first parameter list response before re-requesting // Status QString parameterStatusMsg; -- 2.22.0