@ -423,11 +424,11 @@ void UASParameterCommsMgr::receivedParameterUpdate(int uas, int compId, int para
@@ -423,11 +424,11 @@ void UASParameterCommsMgr::receivedParameterUpdate(int uas, int compId, int para
// List mode is different from single parameter transfers
if(transmissionListMode){
@ -439,8 +440,8 @@ void UASParameterCommsMgr::receivedParameterUpdate(int uas, int compId, int para
@@ -439,8 +440,8 @@ void UASParameterCommsMgr::receivedParameterUpdate(int uas, int compId, int para
qDebug()<<"Mark all parameters as missing: "<<paramCount;
for(inti=1;i<paramCount;++i){//TODO check: param Id 0 is "all parameters" and not valid ?
if(!compXmitMissing->contains(i)){
compXmitMissing->append(i);
if(!compMissReadPackets->contains(i)){
compMissReadPackets->append(i);
}
}
@ -456,28 +457,27 @@ void UASParameterCommsMgr::receivedParameterUpdate(int uas, int compId, int para
@@ -456,28 +457,27 @@ void UASParameterCommsMgr::receivedParameterUpdate(int uas, int compId, int para
}
// Mark this parameter as received in read list
intindex=compXmitMissing->indexOf(paramId);
// If the MAV sent the parameter without request, it wont be in missing list
intindex=compMissReadPackets->indexOf(paramId);
if(index!=-1){
compXmitMissing->removeAt(index);
compMissReadPackets->removeAt(index);
}
booljustWritten=false;
boolwriteMismatch=false;
// Mark this parameter as received in write ACK list
@ -488,15 +488,14 @@ void UASParameterCommsMgr::receivedParameterUpdate(int uas, int compId, int para
@@ -488,15 +488,14 @@ void UASParameterCommsMgr::receivedParameterUpdate(int uas, int compId, int para
//TODO simplify this if-else tree
if(justWritten){
if(!writeMismatch){
setParameterStatusMsg(tr("SUCCESS: Wrote %2 (#%1/%4): %3").arg(paramId+1).arg(paramName).arg(value.toDouble()).arg(paramCount));
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"));
paramDataModel->commitAllPendingParams();
}
}
else{
// Mismatch, tell user
setParameterStatusMsg(tr("FAILURE: Wrote %1: sent %2 != onboard %3").arg(paramName).arg(map->value(paramName).toDouble()).arg(value.toDouble()),
setParameterStatusMsg(tr("FAILURE: Wrote %1: sent %2 != onboard %3").arg(paramName).arg(compMissWritePackets->value(paramName).toDouble()).arg(value.toDouble()),
ParamCommsStatusLevel_Warning);
}
}
@ -512,6 +511,7 @@ void UASParameterCommsMgr::receivedParameterUpdate(int uas, int compId, int para
@@ -512,6 +511,7 @@ void UASParameterCommsMgr::receivedParameterUpdate(int uas, int compId, int para