@ -5,18 +5,18 @@
@@ -5,18 +5,18 @@
# include "QGCUASParamManager.h"
# include "UASInterface.h"
# define RC_CAL_CHAN_MAX 8
UASParameterCommsMgr : : UASParameterCommsMgr ( QObject * parent ) :
QObject ( parent ) ,
mav ( NULL ) ,
maxSilenceTimeout ( 30000 ) ,
paramDataModel ( NULL ) ,
transmissionListMode ( false ) ,
transmissionActive ( false ) ,
transmissionTimeout ( 0 ) ,
retransmissionTimeout ( 1000 ) ,
rewriteTimeout ( 1000 ) ,
retransmissionBurstRequestSize ( 5 )
retransmitBurstLimit ( 5 ) ,
silenceTimeout ( 1000 ) ,
transmissionListMode ( false )
{
@ -40,29 +40,27 @@ UASParameterCommsMgr* UASParameterCommsMgr::initWithUAS(UASInterface* uas)
@@ -40,29 +40,27 @@ UASParameterCommsMgr* UASParameterCommsMgr::initWithUAS(UASInterface* uas)
connect ( mav , SIGNAL ( parameterChanged ( int , int , int , int , QString , QVariant ) ) ,
this , SLOT ( receivedParameterUpdate ( int , int , int , int , QString , QVariant ) ) ) ;
//connect to retransmissionTimer
connect ( & retransmissionTimer , SIGNAL ( timeout ( ) ) ,
this , SLOT ( retransmissionGuardTick ( ) ) ) ;
connect ( & silenceTimer , SIGNAL ( timeout ( ) ) ,
this , SLOT ( silenceTimerExpired ( ) ) ) ;
return this ;
}
void UASParameterCommsMgr : : loadParamCommsSettings ( )
{
QSettings settings ;
//TODO these are duplicates of MAVLinkProtocol settings...seems wrong to use them in two places
settings . beginGroup ( " QGC_MAVLINK_PROTOCOL " ) ;
bool ok ;
int val = settings . value ( " PARAMETER_RETRANSMISSION_TIMEOUT " , retransmissionTimeout ) . toInt ( & ok ) ;
if ( ok ) {
retransmissionTimeout = val ;
qDebug ( ) < < " retransmissionTimeout " < < retransmissionTimeout ;
}
val = settings . value ( " PARAMETER_REWRITE_TIMEOUT " , rewriteTimeout ) . toInt ( & ok ) ;
int val = settings . value ( " PARAMETER_RETRANSMISSION_TIMEOUT " , 1000 ) . toInt ( & ok ) ;
if ( ok ) {
rewriteTimeout = val ;
silenceTimeout = val ;
qDebug ( ) < < " silenceTimeout " < < silenceTimeout ;
}
settings . endGroup ( ) ;
}
@ -79,20 +77,11 @@ void UASParameterCommsMgr::requestParameterList()
@@ -79,20 +77,11 @@ void UASParameterCommsMgr::requestParameterList()
}
if ( ! transmissionListMode ) {
// Clear transmission state
receivedParamsList . clear ( ) ;
transmissionListSizeKnown . clear ( ) ;
transmissionListMode = true ;
foreach ( int key , missingReadPackets . keys ( ) ) {
missingReadPackets . value ( key ) - > clear ( ) ;
}
transmissionActive = true ;
setParameterStatusMsg ( tr ( " Requested param list.. waiting " ) ) ;
listRecvTimeout = QGC : : groundTimeMilliseconds ( ) + 10000 ;
transmissionListMode = true ; //TODO eliminate?
//we use (compId 0, paramId 0) as indicating all params for the system
markReadParamWaiting ( 0 , 0 ) ;
mav - > requestParameters ( ) ;
setRetransmissionGuardEnabled ( true ) ;
updateSilenceTimer ( ) ;
}
else {
qDebug ( ) < < __FILE__ < < __LINE__ < < " Ignoring requestParameterList because we're receiving params list " ;
@ -101,6 +90,26 @@ void UASParameterCommsMgr::requestParameterList()
@@ -101,6 +90,26 @@ void UASParameterCommsMgr::requestParameterList()
}
void UASParameterCommsMgr : : markReadParamWaiting ( int compId , int paramId )
{
if ( ! readsWaiting . contains ( compId ) ) {
readsWaiting . insert ( compId , new QSet < int > ( ) ) ;
}
readsWaiting . value ( compId ) - > insert ( paramId ) ;
}
void UASParameterCommsMgr : : markWriteParamWaiting ( int compId , QString paramName , QVariant value )
{
//ensure we have a map for this compId
if ( ! writesWaiting . contains ( compId ) ) {
writesWaiting . insert ( compId , new QMap < QString , QVariant > ( ) ) ;
}
// Insert it in missing write ACK list
writesWaiting . value ( compId ) - > insert ( paramName , value ) ;
}
/*
Empty read retransmission list
Empty write retransmission list
@ -110,17 +119,17 @@ void UASParameterCommsMgr::clearRetransmissionLists(int& missingReadCount, int&
@@ -110,17 +119,17 @@ void UASParameterCommsMgr::clearRetransmissionLists(int& missingReadCount, int&
qDebug ( ) < < __FILE__ < < __LINE__ < < " clearRetransmissionLists " ;
missingReadCount = 0 ;
QList < int > readKeys = missingReadPackets . keys ( ) ;
foreach ( int compId , readKey s) {
missingReadCount + = missingReadPackets . value ( compId ) - > count ( ) ;
missingReadPackets . value ( compId ) - > clear ( ) ;
QList < int > compIds = readsWaiting . keys ( ) ;
foreach ( int compId , compId s) {
missingReadCount + = readsWaiting . value ( compId ) - > count ( ) ;
readsWaiting . value ( compId ) - > clear ( ) ;
}
missingWriteCount = 0 ;
QList < int > writeKeys = missingWriteAckPackets . keys ( ) ;
foreach ( int compId , writeKey s) {
missingWriteCount + = missingWriteAckPackets . value ( compId ) - > count ( ) ;
missingWriteAckPackets . value ( compId ) - > clear ( ) ;
compIds = writesWaiting . keys ( ) ;
foreach ( int compId , compId s) {
missingWriteCount + = writesWaiting . value ( compId ) - > count ( ) ;
writesWaiting . value ( compId ) - > clear ( ) ;
}
}
@ -170,16 +179,21 @@ void UASParameterCommsMgr::resendReadWriteRequests()
@@ -170,16 +179,21 @@ void UASParameterCommsMgr::resendReadWriteRequests()
int compId ;
QList < int > compIds ;
// Re-request at maximum retransmissionBurstRequestSize parameters at once
// Re-request at maximum retransmitBurstLimit parameters at once
// to prevent link flooding'
int requestedReadCount = 0 ;
compIds = missingReadPackets . keys ( ) ;
compIds = readsWaiting . keys ( ) ;
foreach ( compId , compIds ) {
// Request n parameters from this component (at maximum)
QLis t < int > * missingReadParams = missingReadPackets . value ( compId , NULL ) ;
qDebug ( ) < < " missingReadParams :" < < missingReadParams - > count ( ) ;
QSe t < int > * missingReadParams = readsWaiting . value ( compId , NULL ) ;
qDebug ( ) < < " compId " < < compId < < " readsWaiting :" < < missingReadParams - > count ( ) ;
foreach ( int paramId , * missingReadParams ) {
if ( requestedReadCount < retransmissionBurstRequestSize ) {
if ( 0 = = paramId & & 0 = = compId ) {
mav - > requestParameters ( ) ;
//don't request any other params individually for this component
break ;
}
if ( requestedReadCount < retransmitBurstLimit ) {
//qDebug() << __FILE__ << __LINE__ << "RETRANSMISSION GUARD REQUESTS RETRANSMISSION OF PARAM #" << paramId << "FROM COMPONENT #" << compId;
emit parameterUpdateRequestedById ( compId , paramId ) ;
setParameterStatusMsg ( tr ( " Requested retransmission of #%1 " ) . arg ( paramId + 1 ) ) ;
@ -192,16 +206,16 @@ void UASParameterCommsMgr::resendReadWriteRequests()
@@ -192,16 +206,16 @@ void UASParameterCommsMgr::resendReadWriteRequests()
}
}
// Re-request at maximum retransmissionBurstRequestSize parameters at once
// Re-request at maximum retransmitBurstLimit parameters at once
// to prevent write-request link flooding
int requestedWriteCount = 0 ;
compIds = missingWriteAckPackets . keys ( ) ;
compIds = writesWaiting . keys ( ) ;
foreach ( compId , compIds ) {
QMap < QString , QVariant > * missingParams = missingWriteAckPackets . value ( compId ) ;
foreach ( QString key , missingParams - > keys ( ) ) {
if ( requestedWriteCount < retransmissionBurstRequestSize ) {
QMap < QString , QVariant > * missingWrite Params = writesWaiting . value ( compId ) ;
foreach ( QString key , missingWrite Params - > keys ( ) ) {
if ( requestedWriteCount < retransmitBurstLimit ) {
// Re-request write operation
QVariant value = missingParams - > value ( key ) ;
QVariant value = missingWrite Params - > value ( key ) ;
emitPendingParameterCommit ( compId , key , value ) ;
requestedWriteCount + + ;
}
@ -212,106 +226,47 @@ void UASParameterCommsMgr::resendReadWriteRequests()
@@ -212,106 +226,47 @@ void UASParameterCommsMgr::resendReadWriteRequests()
}
}
if ( ( 0 = = requestedWriteCount ) & & ( 0 = = requestedReadCount ) ) {
qDebug ( ) < < __FILE__ < < __LINE__ < < " No pending re-read or rewrite requests " ;
if ( ! transmissionListMode ) {
setRetransmissionGuardEnabled ( false ) ;
transmissionActive = false ;
}
}
else {
//restart the timer now that we've sent
setRetransmissionGuardEnabled ( true ) ;
}
updateSilenceTimer ( ) ;
}
void UASParameterCommsMgr : : resetAfterListReceive ( )
{
transmissionListMode = false ;
transmissionListSizeKnown . clear ( ) ;
//We shouldn't clear missingPackets because other transactions might be using them?
knownParamListSize . clear ( ) ;
}
void UASParameterCommsMgr : : retransmissionGuardTick ( )
void UASParameterCommsMgr : : silenceTimerExpired ( )
{
quint64 curTime = QGC : : groundTimeMilliseconds ( ) ;
int elapsed = ( int ) ( curTime - lastSilenceTimerReset ) ;
qDebug ( ) < < " silenceTimerExpired elapsed: " < < elapsed ;
//Workaround for an apparent Qt bug that causes retransmission guard timer to fire prematurely (350ms)
int elapsed = ( int ) ( curTime - lastTimerReset ) ;
if ( elapsed < retransmissionTimeout ) {
qDebug ( ) < < " retransmissionGuardTick elapsed: " < < ( curTime - lastTimerReset ) ;
if ( elapsed < silenceTimeout ) {
//reset the guard timer: it fired prematurely
setRetransmissionGuardEnabled ( true ) ;
updateSilenceTimer ( ) ;
return ;
}
qDebug ( ) < < __FILE__ < < __LINE__ < < " RETRANSMISSION GUARD ACTIVE after " < < elapsed ;
if ( transmissionActive ) {
if ( transmissionListMode & & transmissionListSizeKnown . isEmpty ( ) ) {
//we are still waitin for the first parameter list response
if ( curTime > this - > listRecvTimeout ) {
//re-request parameters
setParameterStatusMsg ( tr ( " TIMEOUT: Re-requesting param list " ) , ParamCommsStatusLevel_Warning ) ;
listRecvTimeout = curTime + 10000 ;
mav - > requestParameters ( ) ;
//reset the timer
setRetransmissionGuardEnabled ( true ) ;
}
return ;
}
// Check for timeout
// stop retransmission attempts on timeout
if ( curTime > transmissionTimeout ) {
setRetransmissionGuardEnabled ( false ) ;
resetAfterListReceive ( ) ;
int missingReadCount , missingWriteCount ;
clearRetransmissionLists ( missingReadCount , missingWriteCount ) ;
if ( ( missingReadCount > 0 ) | | ( missingWriteCount > 0 ) ) {
setParameterStatusMsg ( tr ( " TIMEOUT! MISSING: %1 read, %2 write. " ) . arg ( missingReadCount ) . arg ( missingWriteCount ) ,
ParamCommsStatusLevel_Warning ) ;
}
return ;
}
resendReadWriteRequests ( ) ;
int totalElapsed = ( int ) ( curTime - lastReceiveTime ) ;
if ( totalElapsed > maxSilenceTimeout ) {
qDebug ( ) < < " Max silence time exceeded: " + totalElapsed ;
int missingReads , missingWrites ;
clearRetransmissionLists ( missingReads , missingWrites ) ;
//TODO notify user!
}
else {
qDebug ( ) < < __FILE__ < < __LINE__ < < " STOPPING RETRANSMISSION GUARD GRACEFULLY " ;
setRetransmissionGuardEnabled ( false ) ;
resendReadWriteRequests ( ) ;
}
}
/**
* Enabling the retransmission guard enables the parameter widget to track
* dropped parameters and to re - request them . This works for both individual
* parameter reads as well for whole list requests .
*
* @ param enabled True if retransmission checking should be enabled , false else
*/
void UASParameterCommsMgr : : setRetransmissionGuardEnabled ( bool enabled )
{
if ( enabled ) {
retransmissionTimer . start ( retransmissionTimeout ) ;
lastTimerReset = QGC : : groundTimeMilliseconds ( ) ;
} else {
retransmissionTimer . stop ( ) ;
}
}
void UASParameterCommsMgr : : requestParameterUpdate ( int component , const QString & parameter )
void UASParameterCommsMgr : : requestParameterUpdate ( int compId , const QString & paramName )
{
if ( mav ) {
mav - > requestParameter ( component , parameter ) ;
mav - > requestParameter ( compId , paramName ) ;
//TODO track these read requests with a paramName but no param ID : use index in getOnboardParamsForComponent?
//ensure we keep track of every single read request
}
}
@ -326,15 +281,14 @@ void UASParameterCommsMgr::requestRcCalibrationParamsUpdate()
@@ -326,15 +281,14 @@ void UASParameterCommsMgr::requestRcCalibrationParamsUpdate()
// Do not request the RC type, as these values depend on this
// active onboard parameter
int defCompId = paramDataModel - > getDefaultComponentId ( ) ;
for ( unsigned int i = 1 ; i < ( RC_CAL_CHAN_MAX + 1 ) ; + + i ) {
qDebug ( ) < < " Request RC " < < i ;
mav - > requestParameter ( 0 , minTpl . arg ( i ) ) ;
QGC : : SLEEP : : usleep ( 5000 ) ;
mav - > requestParameter ( 0 , trimTpl . arg ( i ) ) ;
QGC : : SLEEP : : usleep ( 5000 ) ;
mav - > requestParameter ( 0 , maxTpl . arg ( i ) ) ;
QGC : : SLEEP : : usleep ( 5000 ) ;
mav - > requestParameter ( 0 , revTpl . arg ( i ) ) ;
requestParameterUpdate ( defCompId , minTpl . arg ( i ) ) ;
requestParameterUpdate ( defCompId , trimTpl . arg ( i ) ) ;
requestParameterUpdate ( defCompId , maxTpl . arg ( i ) ) ;
requestParameterUpdate ( defCompId , revTpl . arg ( i ) ) ;
QGC : : SLEEP : : usleep ( 5000 ) ;
}
}
@ -349,158 +303,152 @@ void UASParameterCommsMgr::requestRcCalibrationParamsUpdate()
@@ -349,158 +303,152 @@ void UASParameterCommsMgr::requestRcCalibrationParamsUpdate()
* @ param parameterName name of the parameter , as delivered by the system
* @ param value value of the parameter
*/
void UASParameterCommsMgr : : setParameter ( int component , QString parameter Name , QVariant value )
void UASParameterCommsMgr : : setParameter ( int compId , QString paramName , QVariant value )
{
if ( parameter Name . isEmpty ( ) ) {
if ( paramName . isEmpty ( ) ) {
return ;
}
double dblValue = value . toDouble ( ) ;
if ( paramDataModel - > isValueLessThanParamMin ( parameter Name , dblValue ) ) {
setParameterStatusMsg ( tr ( " REJ. %1, %2 < min " ) . arg ( parameter Name ) . arg ( dblValue ) ,
if ( paramDataModel - > isValueLessThanParamMin ( paramName , dblValue ) ) {
setParameterStatusMsg ( tr ( " REJ. %1, %2 < min " ) . arg ( paramName ) . arg ( dblValue ) ,
ParamCommsStatusLevel_Error
) ;
return ;
}
if ( paramDataModel - > isValueGreaterThanParamMax ( parameter Name , dblValue ) ) {
setParameterStatusMsg ( tr ( " REJ. %1, %2 > max " ) . arg ( parameter Name ) . arg ( dblValue ) ,
if ( paramDataModel - > isValueGreaterThanParamMax ( paramName , dblValue ) ) {
setParameterStatusMsg ( tr ( " REJ. %1, %2 > max " ) . arg ( paramName ) . arg ( dblValue ) ,
ParamCommsStatusLevel_Error
) ;
return ;
}
QVariant onboardVal ;
paramDataModel - > getOnboardParamValue ( component , parameter Name , onboardVal ) ;
paramDataModel - > getOnboardParamValue ( compId , paramName , onboardVal ) ;
if ( onboardVal = = value ) {
setParameterStatusMsg ( tr ( " REJ. %1 already %2 " ) . arg ( parameter Name ) . arg ( dblValue ) ,
setParameterStatusMsg ( tr ( " REJ. %1 already %2 " ) . arg ( paramName ) . arg ( dblValue ) ,
ParamCommsStatusLevel_Warning
) ;
return ;
}
emitPendingParameterCommit ( component , parameterName , value ) ;
emitPendingParameterCommit ( compId , paramName , value ) ;
//Add this request to list of writes not yet ack'd
// Wait for parameter to be written back
// mark it therefore as missing
if ( ! missingWriteAckPackets . contains ( component ) ) {
missingWriteAckPackets . insert ( component , new QMap < QString , QVariant > ( ) ) ;
markWriteParamWaiting ( compId , paramName , value ) ;
updateSilenceTimer ( ) ;
}
void UASParameterCommsMgr : : updateSilenceTimer ( )
{
//if there are pending reads or writes, ensure we timeout in a little while
//if we hear nothing but silence from our partner
int missReadCount = 0 ;
foreach ( int key , readsWaiting . keys ( ) ) {
missReadCount + = readsWaiting . value ( key ) - > count ( ) ;
}
int missWriteCount = 0 ;
foreach ( int key , writesWaiting . keys ( ) ) {
missWriteCount + = writesWaiting . value ( key ) - > count ( ) ;
}
// Insert it in missing write ACK list
missingWriteAckPackets . value ( component ) - > insert ( parameterName , value ) ;
// Set timeouts
if ( transmissionActive ) {
transmissionTimeout + = rewriteTimeout ;
if ( missReadCount > 0 | | missWriteCount > 0 ) {
silenceTimer . start ( silenceTimeout ) ; //TODO configurable silence timeout
lastSilenceTimerReset = QGC : : groundTimeMilliseconds ( ) ;
}
else {
quint64 newTransmissionTimeout = QGC : : groundTimeMilliseconds ( ) + rewriteTimeout ;
if ( newTransmissionTimeout > transmissionTimeout ) {
transmissionTimeout = newTransmissionTimeout ;
}
transmissionActive = true ;
//all parameters have been received, broadcast to UI
emit parameterListUpToDate ( ) ;
resetAfterListReceive ( ) ;
silenceTimer . stop ( ) ;
}
// Enable guard / reset timeouts
setRetransmissionGuardEnabled ( true ) ;
}
void UASParameterCommsMgr : : setParameterStatusMsg ( const QString & msg , ParamCommsStatusLevel_t level )
{
qDebug ( ) < < " parameterStatusMsg: " < < msg ;
parameterStatusMsg = msg ;
emit parameterStatusMsgUpdated ( msg , level ) ;
}
/**
* @ param uas System which has the component
* @ param component id of the component
* @ param parameterName human friendly name of the parameter
*/
void UASParameterCommsMgr : : receivedParameterUpdate ( int uas , int compId , int paramCount , int paramId , QString paramName , QVariant value )
{
Q_UNUSED ( uas ) ; //this object is assigned to one UAS only
lastReceiveTime = QGC : : groundTimeMilliseconds ( ) ;
qDebug ( ) < < " compId " < < compId < < " receivedParameterUpdate: " < < paramName ;
//notify the data model that we have an updated param
paramDataModel - > handleParamUpdate ( compId , paramName , value ) ;
// Missing packets list has to be instantiated for all components
if ( ! missingReadPackets . contains ( compId ) ) {
missingReadPackets . insert ( compId , new QList < int > ( ) ) ;
}
QList < int > * compMissReadPackets = missingReadPackets . value ( compId ) ;
// Ensure we have missing read/write lists for this compId
if ( ! readsWaiting . contains ( compId ) ) {
readsWaiting . insert ( compId , new QSet < int > ( ) ) ;
}
if ( ! writesWaiting . contains ( compId ) ) {
writesWaiting . insert ( compId , new QMap < QString , QVariant > ( ) ) ;
}
QSet < int > * compMissingReads = readsWaiting . value ( compId ) ;
// List mode is different from single parameter transfers
if ( transmissionListMode ) {
// Only accept the list size once on the first packet from
// each component
if ( ! transmissionListSizeKnown . contains ( compId ) ) {
// Only accept the list size once on the first packet from each component
if ( ! knownParamListSize . contains ( compId ) ) {
// Mark list size as known
transmissionListSizeKnown . insert ( compId , true ) ;
knownParamListSize . insert ( compId , paramCount ) ;
qDebug ( ) < < " Mark all parameters as missing: " < < paramCount ;
for ( int i = 1 ; i < paramCount ; + + i ) { //TODO check: param Id 0 is "all parameters" and not valid ?
if ( ! compMissReadPackets - > contains ( i ) ) {
compMissReadPackets - > append ( i ) ;
}
}
//remove our placeholder read request for all params
readsWaiting . value ( 0 ) - > remove ( 0 ) ;
// There is only one transmission timeout for all components
// since components do not manage their transmission,
// the longest timeout is safe for all components.
quint64 thisTransmissionTimeout = QGC : : groundTimeMilliseconds ( ) + ( paramCount * retransmissionTimeout ) ;
if ( thisTransmissionTimeout > transmissionTimeout ) {
transmissionTimeout = thisTransmissionTimeout ;
qDebug ( ) < < " Mark all parameters as missing: " < < paramCount ;
for ( int i = 1 ; i < paramCount ; + + i ) { //param Id 0 is "all parameters" and not valid
compMissingReads - > insert ( i ) ;
}
}
}
// Mark this parameter as received in read list
int index = compMissReadPackets - > indexOf ( paramId ) ;
if ( index ! = - 1 ) {
compMissReadPackets - > removeAt ( index ) ;
}
compMissingReads - > remove ( paramId ) ;
bool justWritten = false ;
bool writeMismatch = false ;
// Mark this parameter as received in write ACK list
QMap < QString , QVariant > * compMissWritePacket s = missingWriteAckPackets . value ( compId ) ;
if ( ! compMissWritePacket s ) {
QMap < QString , QVariant > * compMissing Writes = writesWaiting . value ( compId ) ;
if ( ! compMissing Writes ) {
//we sometimes send a write request on compId 0 and get a response on a nonzero compId eg 50
compMissWritePacket s = missingWriteAckPackets . value ( 0 ) ;
compMissing Writes = writesWaiting . value ( 0 ) ;
}
if ( compMissWritePacket s & & compMissWritePacket s - > contains ( paramName ) ) {
if ( compMissing Writes & & compMissing Writes - > contains ( paramName ) ) {
justWritten = true ;
if ( compMissWritePacket s - > value ( paramName ) ! = value ) {
if ( compMissing Writes - > value ( paramName ) ! = value ) {
writeMismatch = true ;
}
compMissWritePacket s - > remove ( paramName ) ;
compMissing Writes - > remove ( paramName ) ;
}
int missReadCount = 0 ;
foreach ( int key , missingReadPackets . keys ( ) ) {
missReadCount + = missingReadPackets . value ( key ) - > count ( ) ;
}
int missWriteCount = 0 ;
foreach ( int key , missingWriteAckPackets . keys ( ) ) {
missWriteCount + = missingWriteAckPackets . value ( key ) - > count ( ) ;
}
//TODO simplify this if-else tree
if ( justWritten ) {
int waitingWritesCount = compMissingWrites - > count ( ) ;
if ( ! writeMismatch ) {
setParameterStatusMsg ( tr ( " SUCCESS: Wrote %2 (#%1/%4): %3 [%5] " ) . arg ( paramId + 1 ) . arg ( paramName ) . arg ( value . toDouble ( ) ) . arg ( paramCount ) . arg ( missWriteCount ) ) ;
if ( 0 = = missWriteCount ) {
setParameterStatusMsg ( tr ( " SUCCESS: WROTE ALL PARAMETERS " ) ) ;
setParameterStatusMsg ( tr ( " SUCCESS: Wrote %2 (#%1): %3 " ) . arg ( paramId + 1 ) . arg ( paramName ) . arg ( value . toDouble ( ) ) ) ;
}
if ( ! writeMismatch ) {
if ( 0 = = waitingWritesCount ) {
setParameterStatusMsg ( tr ( " SUCCESS: Wrote all params for component %1 " ) . arg ( compId ) ) ;
if ( persistParamsAfterSend ) {
writeParamsToPersistentStorage ( ) ;
persistParamsAfterSend = false ;
@ -509,60 +457,30 @@ void UASParameterCommsMgr::receivedParameterUpdate(int uas, int compId, int para
@@ -509,60 +457,30 @@ void UASParameterCommsMgr::receivedParameterUpdate(int uas, int compId, int para
}
else {
// Mismatch, tell user
setParameterStatusMsg ( tr ( " FAILURE: Wrote %1: sent %2 != onboard %3 " ) . arg ( paramName ) . arg ( compMissWritePacket s - > value ( paramName ) . toDouble ( ) ) . arg ( value . toDouble ( ) ) ,
setParameterStatusMsg ( tr ( " FAILURE: Wrote %1: sent %2 != onboard %3 " ) . arg ( paramName ) . arg ( compMissing Writes - > value ( paramName ) . toDouble ( ) ) . arg ( value . toDouble ( ) ) ,
ParamCommsStatusLevel_Warning ) ;
}
}
else {
if ( missReadCount = = 0 ) {
int waitingReadsCount = compMissingReads - > count ( ) ;
if ( 0 = = waitingReadsCount ) {
// Transmission done
QTime time = QTime : : currentTime ( ) ;
QString timeString = time . toString ( ) ;
setParameterStatusMsg ( tr ( " All received. (updated at %1) " ) . arg ( timeString ) ) ;
}
else {
// Transmission in progress
// Waiting to receive more
QString val = QString ( " %1 " ) . arg ( value . toFloat ( ) , 5 , ' f ' , 1 , QChar ( ' ' ) ) ;
setParameterStatusMsg ( tr ( " OK: %1 %2 (%3/%4) " ) . arg ( paramName ) . arg ( val ) . arg ( paramCount - missReadCount ) . arg ( paramCount ) ,
ParamCommsStatusLevel_Warning ) ;
//transmissionMissingPackets
setParameterStatusMsg ( tr ( " OK: %1 %2 (%3/%4) " ) . arg ( paramName ) . arg ( val ) . arg ( paramCount - waitingReadsCount ) . arg ( paramCount ) ,
ParamCommsStatusLevel_OK ) ;
}
}
// Check if last parameter was received
if ( missReadCount = = 0 & & missWriteCount = = 0 ) {
resetAfterListReceive ( ) ;
setRetransmissionGuardEnabled ( false ) ;
//all parameters have been received, broadcast to UI
emit parameterListUpToDate ( ) ;
}
else {
//reset the timeout timer since we received one
setRetransmissionGuardEnabled ( true ) ;
//qDebug() << "missCount:" << missCount << "missWriteCount:" << missWriteCount;
//if (missCount < 4) {
// foreach (int key, transmissionMissingPackets.keys()) {
// QList<int>* list = transmissionMissingPackets.value(key);
// if (list && list->count()) {
// QString yazza = QString().sprintf("Component %d missing %d: ",key,list->count());
// for (int i = 0; i < list->count(); i++) {
// int val = list->at(i);
// yazza.append( QString().sprintf("%d,",val) );
// }
// qDebug() << yazza;
// }
// else {
// //very suspicious...no actual missing items??
// transmissionMissingPackets.remove(key);
// break;
// }
// }
//}
}
updateSilenceTimer ( ) ;
}
@ -591,42 +509,27 @@ void UASParameterCommsMgr::sendPendingParameters(bool copyToPersistent)
@@ -591,42 +509,27 @@ void UASParameterCommsMgr::sendPendingParameters(bool copyToPersistent)
setParameterStatusMsg ( tr ( " %1 pending params for component %2 " ) . arg ( paramList - > count ( ) ) . arg ( compId ) ) ;
for ( j = paramList - > begin ( ) ; j ! = paramList - > end ( ) ; + + j ) {
//TODO mavlink command for "set parameter list" ?
setParameter ( compId , j . key ( ) , j . value ( ) ) ;
parametersSent + + ;
}
}
// Change transmission status if necessary
if ( parametersSent = = 0 ) {
if ( 0 = = parametersSent ) {
setParameterStatusMsg ( tr ( " No transmission: No changed values. " ) , ParamCommsStatusLevel_Warning ) ;
if ( persistParamsAfterSend ) {
writeParamsToPersistentStorage ( ) ;
}
}
else {
setParameterStatusMsg ( tr ( " Transmitting %1 parameters. " ) . arg ( parametersSent ) ) ;
// Set timeouts
if ( transmissionActive ) {
transmissionTimeout + = parametersSent * rewriteTimeout ;
}
else {
transmissionActive = true ;
quint64 newTransmissionTimeout = QGC : : groundTimeMilliseconds ( ) + parametersSent * rewriteTimeout ;
if ( newTransmissionTimeout > transmissionTimeout ) {
transmissionTimeout = newTransmissionTimeout ;
}
}
// Enable guard
setRetransmissionGuardEnabled ( true ) ;
qDebug ( ) < < " Pending parameters now: " < < paramDataModel - > countPendingParams ( ) ;
}
updateSilenceTimer ( ) ;
}
UASParameterCommsMgr : : ~ UASParameterCommsMgr ( )
{
setRetransmissionGuardEnabled ( false ) ;
silenceTimer . stop ( ) ;
QString ptrStr ;
ptrStr . sprintf ( " %8p " , this ) ;