Browse Source

Merge pull request #8865 from DonLakeFlyer/FTPPacketLoss

Harden FTPManager::download against packet loss
QGC4.4
Don Gagne 5 years ago committed by GitHub
parent
commit
6afe69b854
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23
  1. 437
      src/Vehicle/FTPManager.cc
  2. 85
      src/Vehicle/FTPManager.h
  3. 84
      src/Vehicle/FTPManagerTest.cc
  4. 8
      src/Vehicle/FTPManagerTest.h
  5. 4
      src/comm/LinkManager.cc
  6. 4
      src/comm/LinkManager.h
  7. 7
      src/comm/MockLink.cc
  8. 6
      src/comm/MockLink.h
  9. 220
      src/comm/MockLinkFTP.cc
  10. 20
      src/comm/MockLinkFTP.h
  11. 19
      src/qgcunittest/UnitTest.cc

437
src/Vehicle/FTPManager.cc

@ -24,6 +24,13 @@ FTPManager::FTPManager(Vehicle* vehicle) @@ -24,6 +24,13 @@ FTPManager::FTPManager(Vehicle* vehicle)
: QObject (vehicle)
, _vehicle (vehicle)
{
_ackTimer.setSingleShot(true);
if (qgcApp()->runningUnitTests()) {
// Mock link responds immediately if at all
_ackTimer.setInterval(10);
} else {
_ackTimer.setInterval(_ackTimerTimeoutMsecs);
}
connect(&_ackTimer, &QTimer::timeout, this, &FTPManager::_ackTimeout);
_lastOutgoingRequest.hdr.seqNumber = 0;
@ -34,63 +41,76 @@ FTPManager::FTPManager(Vehicle* vehicle) @@ -34,63 +41,76 @@ FTPManager::FTPManager(Vehicle* vehicle)
void FTPManager::_handlOpenFileROAck(MavlinkFTP::Request* ack)
{
qCDebug(FTPManagerLog) << QString("_openAckResponse: _waitState(%1) _openFileType(%2) _readFileLength(%3)").arg(MavlinkFTP::opCodeToString(_waitState)).arg(MavlinkFTP::opCodeToString(_openFileType)).arg(ack->openFileLength);
qCDebug(FTPManagerLog) << QString("_handlOpenFileROAck: _waitState(%1) _readFileLength(%3)").arg(MavlinkFTP::opCodeToString(_waitState)).arg(ack->openFileLength);
if (_waitState != MavlinkFTP::kCmdOpenFileRO && _waitState != MavlinkFTP::kCmdBurstReadFile) {
qCDebug(FTPManagerLog) << "Received OpenFileRO Ack while not waiting for it. _waitState" << MavlinkFTP::opCodeToString(_waitState);
if (_waitState != MavlinkFTP::kCmdOpenFileRO) {
qCDebug(FTPManagerLog) << "Received OpenFileRO Ack while not waiting for it";
return;
}
if (ack->hdr.size != sizeof(uint32_t)) {
_downloadComplete(tr("Download failed: Invalid response to OpenFileRO command."));
qCDebug(FTPManagerLog) << "_handlOpenFileROAck: ack->hdr.size != sizeof(uint32_t)" << ack->hdr.size << sizeof(uint32_t);
_downloadComplete(tr("Download failed"));
return;
}
_waitState = _openFileType;
_activeSession = ack->hdr.session;
_downloadFileSize = ack->openFileLength;
_requestedDownloadOffset = 0;
_readFileAccumulator.clear();
_downloadState.reset();
_waitState = MavlinkFTP::kCmdBurstReadFile;
_activeSession = ack->hdr.session;
_downloadState.fileSize = ack->openFileLength;
_downloadState.expectedBurstOffset = 0;
_downloadState.file.setFileName(_downloadState.toDir.filePath(_downloadState.fileName));
if (!_downloadState.file.open(QFile::WriteOnly | QFile::Truncate)) {
qCDebug(FTPManagerLog) << "_handlOpenFileROAck: _downloadState.file open failed" << _downloadState.file.errorString();
_downloadComplete(tr("Download failed"));
return;
}
MavlinkFTP::Request request;
request.hdr.session = _activeSession;
request.hdr.opcode = _waitState;
request.hdr.offset = _requestedDownloadOffset;
request.hdr.opcode = MavlinkFTP::kCmdBurstReadFile;
request.hdr.offset = _downloadState.expectedBurstOffset;
request.hdr.size = sizeof(request.data);
_sendRequestExpectAck(&request);
}
/// request the next missing part of a (partially) downloaded file
void FTPManager::_requestMissingData()
void FTPManager::_requestMissingBurstData()
{
#if 0
if (_missingData.empty()) {
_downloadingMissingParts = false;
_missingDownloadedBytes = 0;
// there might be more data missing at the end
if ((uint32_t)_readFileAccumulator.length() != _downloadFileSize) {
_downloadOffset = _readFileAccumulator.length();
qCDebug(FTPManagerLog) << QString("_requestMissingData: missing parts done, downloadOffset(%1) downloadFileSize(%2)")
.arg(_downloadOffset).arg(_downloadFileSize);
MavlinkFTP::Request request;
if (_downloadState.missingData.count()) {
MissingData_t& missingData = _downloadState.missingData.first();
uint32_t cBytesToRead = qMin((uint32_t)sizeof(request.data), missingData.cBytes);
qCDebug(FTPManagerLog) << "_requestMissingBurstData: offset:cBytesToRead" << missingData.offset << cBytesToRead;
request.hdr.session = _activeSession;
request.hdr.opcode = MavlinkFTP::kCmdReadFile;
request.hdr.offset = missingData.offset;
request.hdr.size = cBytesToRead;
_waitState = MavlinkFTP::kCmdReadFile;
_downloadState.retryCount = 0;
_downloadState.expectedReadOffset = request.hdr.offset;
if (cBytesToRead < missingData.cBytes) {
missingData.offset += cBytesToRead;
missingData.cBytes -= cBytesToRead;
} else {
_closeDownloadSession(true);
return;
_downloadState.missingData.takeFirst();
}
} else {
qCDebug(FTPManagerLog) << QString("_requestMissingData: offset(%1) size(%2)").arg(_missingData.head().offset).arg(_missingData.head().size);
_downloadOffset = _missingData.head().offset;
qCDebug(FTPManagerLog) << "_requestMissingBurstData: starting next burst" << _downloadState.expectedBurstOffset;
request.hdr.session = _activeSession;
request.hdr.opcode = MavlinkFTP::kCmdBurstReadFile;
request.hdr.offset = _downloadState.expectedBurstOffset;
request.hdr.size = sizeof(request.data);
_waitState = MavlinkFTP::kCmdBurstReadFile;
}
MavlinkFTP::Request request;
_currentOperation = kCORead;
request.hdr.session = _activeSession;
request.hdr.opcode = MavlinkFTP::kCmdReadFile;
request.hdr.offset = _downloadOffset;
request.hdr.size = sizeof(request.data);
_sendRequestExpectAck(&request);
#endif
}
/// Closes out a download session by writing the file and doing cleanup.
@ -99,26 +119,17 @@ void FTPManager::_downloadComplete(const QString& errorMsg) @@ -99,26 +119,17 @@ void FTPManager::_downloadComplete(const QString& errorMsg)
{
qCDebug(FTPManagerLog) << QString("_downloadComplete: errorMsg(%1)").arg(errorMsg);
QString downloadFilePath = _readFileDownloadDir.absoluteFilePath(_readFileDownloadFilename);
QString downloadFilePath = _downloadState.toDir.absoluteFilePath(_downloadState.fileName);
QString error = errorMsg;
_ackTimer.stop();
_waitState = MavlinkFTP::kCmdNone;
if (error.isEmpty()) {
QFile file(downloadFilePath);
if (file.open(QIODevice::WriteOnly | QIODevice::Truncate)) {
qint64 bytesWritten = file.write((const char *)_readFileAccumulator, _readFileAccumulator.length());
if (bytesWritten != _readFileAccumulator.length()) {
error = tr("Download failed: Unable to write data to local file '%1'.").arg(downloadFilePath);
}
} else {
error = tr("Download failed: Unable to open local file '%1' for writing. Error: '%2'.").arg(downloadFilePath).arg(file.errorString());
}
file.close();
_downloadState.file.close();
}
_readFileAccumulator.clear();
_downloadState.reset();
_sendResetCommand(); // Close the open session
emit downloadComplete(downloadFilePath, error);
}
@ -136,43 +147,93 @@ void FTPManager::_uploadComplete(const QString& errorMsg) @@ -136,43 +147,93 @@ void FTPManager::_uploadComplete(const QString& errorMsg)
emit uploadComplete(errorMsg);
}
void FTPManager::_handleReadFileAck(MavlinkFTP::Request* ack, bool burstReadFile)
// We only do read files to fill in holes from a burst read
void FTPManager::_handleReadFileAck(MavlinkFTP::Request* ack)
{
if (ack->hdr.session != _activeSession) {
return;
}
qCDebug(FTPManagerLog) << QString("_handleReadFileAck: burstReadFile(%1) offset(%2) size(%3) burstComplete(%4)").arg(burstReadFile).arg(ack->hdr.offset).arg(ack->hdr.size).arg(ack->hdr.burstComplete);
qCDebug(FTPManagerLog) << "_handleReadFileAck: offset:size" << ack->hdr.offset << ack->hdr.size;
if (ack->hdr.offset != _requestedDownloadOffset) {
// FIXME: NYI deal with missing packets
_downloadComplete(tr("Download failed: Received incorrect offset: received:expected %1/%2").arg(ack->hdr.offset).arg(_requestedDownloadOffset));
return;
}
_readFileAccumulator.append((const char*)ack->data, ack->hdr.size);
_requestedDownloadOffset += ack->hdr.size;
if (_downloadFileSize != 0) {
emit commandProgress(100 * ((float)(_readFileAccumulator.length()) / (float)_downloadFileSize));
}
if (ack->hdr.offset != _downloadState.expectedReadOffset) {
if (++_downloadState.retryCount > _maxRetry) {
qCDebug(FTPManagerLog) << QString("_handleReadFileAck: retries exceeded");
_downloadComplete(tr("Download failed: Unable to retrieve specified file contents"));
return;
}
if (!burstReadFile || ack->hdr.burstComplete) {
// Ask for current offset again
qCDebug(FTPManagerLog) << QString("_handleReadFileAck: retry retryCount(%1) offset(%2)").arg(_downloadState.retryCount).arg(_downloadState.expectedReadOffset);
MavlinkFTP::Request request;
request.hdr.session = _activeSession;
request.hdr.opcode = _waitState;
request.hdr.offset = _requestedDownloadOffset;
request.hdr.offset = _downloadState.expectedReadOffset;
request.hdr.size = 0;
_sendRequestExpectAck(&request);
} else if (burstReadFile) {
// Burst read, next ack should come without having to request it
_setupAckTimeout();
return;
}
_downloadState.file.seek(ack->hdr.offset);
int bytesWritten = _downloadState.file.write((const char*)ack->data, ack->hdr.size);
if (bytesWritten != ack->hdr.size) {
_downloadComplete(tr("Download failed: Error saving file"));
return;
}
_downloadState.bytesWritten += ack->hdr.size;
if (_downloadState.fileSize != 0) {
emit commandProgress(100 * ((float)(_downloadState.bytesWritten) / (float)_downloadState.fileSize));
}
// Move on to fill in possible next hole
_requestMissingBurstData();
}
/// @brief Respond to the Ack associated with the List command.
void FTPManager::_listAckResponse(MavlinkFTP::Request* listAck)
void FTPManager::_handleBurstReadFileAck(MavlinkFTP::Request* ack)
{
if (ack->hdr.session != _activeSession) {
return;
}
qCDebug(FTPManagerLog) << QString("_handleBurstReadFileAck: offset(%1) size(%2) burstComplete(%3)").arg(ack->hdr.offset).arg(ack->hdr.size).arg(ack->hdr.burstComplete);
if (ack->hdr.offset != _downloadState.expectedBurstOffset) {
if (ack->hdr.offset > _downloadState.expectedBurstOffset) {
MissingData_t missingData;
missingData.offset = _downloadState.expectedBurstOffset;
missingData.cBytes = ack->hdr.offset - _downloadState.expectedBurstOffset;
_downloadState.missingData.append(missingData);
qCDebug(FTPManagerLog) << "_handleBurstReadFileAck: adding missing data offset:cBytes" << missingData.offset << missingData.cBytes;
} else {
qCDebug(FTPManagerLog) << "_handleBurstReadFileAck: received offset less than expected offset received:expected" << ack->hdr.offset << _downloadState.expectedBurstOffset;
_ackTimer.start();
return;
}
}
_downloadState.file.seek(ack->hdr.offset);
int bytesWritten = _downloadState.file.write((const char*)ack->data, ack->hdr.size);
if (bytesWritten != ack->hdr.size) {
_downloadComplete(tr("Download failed: Error saving file"));
return;
}
_downloadState.bytesWritten += ack->hdr.size;
_downloadState.expectedBurstOffset = ack->hdr.offset + ack->hdr.size;
if (_downloadState.fileSize != 0) {
emit commandProgress(100 * ((float)(_downloadState.bytesWritten) / (float)_downloadState.fileSize));
}
if (ack->hdr.burstComplete) {
_requestMissingBurstData();
} else {
// Still within a burst, next ack should come automatically
_ackTimer.start();
}
}
void FTPManager::_listAckResponse(MavlinkFTP::Request* /*listAck*/)
{
#if 0
if (listAck->hdr.offset != _listOffset) {
@ -234,7 +295,7 @@ void FTPManager::_listAckResponse(MavlinkFTP::Request* listAck) @@ -234,7 +295,7 @@ void FTPManager::_listAckResponse(MavlinkFTP::Request* listAck)
}
/// @brief Respond to the Ack associated with the create command.
void FTPManager::_createAckResponse(MavlinkFTP::Request* createAck)
void FTPManager::_createAckResponse(MavlinkFTP::Request* /*createAck*/)
{
#if 0
qCDebug(FTPManagerLog) << "_createAckResponse";
@ -252,7 +313,7 @@ void FTPManager::_createAckResponse(MavlinkFTP::Request* createAck) @@ -252,7 +313,7 @@ void FTPManager::_createAckResponse(MavlinkFTP::Request* createAck)
}
/// @brief Respond to the Ack associated with the write command.
void FTPManager::_writeAckResponse(MavlinkFTP::Request* writeAck)
void FTPManager::_writeAckResponse(MavlinkFTP::Request* /*writeAck*/)
{
#if 0
if(_writeOffset + _writeSize >= _writeFileSize){
@ -318,6 +379,95 @@ void FTPManager::_writeFileDatablock(void) @@ -318,6 +379,95 @@ void FTPManager::_writeFileDatablock(void)
#endif
}
void FTPManager::_handleAck(MavlinkFTP::Request* ack)
{
switch (ack->hdr.req_opcode) {
case MavlinkFTP::kCmdOpenFileRO:
_handlOpenFileROAck(ack);
break;
case MavlinkFTP::kCmdReadFile:
_handleReadFileAck(ack);
break;
case MavlinkFTP::kCmdBurstReadFile:
_handleBurstReadFileAck(ack);
break;
#if 0
case MavlinkFTP::kCmdListDirectory:
_listAckResponse(request);
break;
case MavlinkFTP::kCmdOpenFileRO:
case MavlinkFTP::kCmdOpenFileWO:
_handlOpenFileROAck(request);
break;
case MavlinkFTP::kCmdCreateFile:
_createAckResponse(request);
break;
case MavlinkFTP::kCmdWriteFile:
_writeAckResponse(request);
break;
#endif
default:
// Ack back from operation which does not require additional work
_waitState = MavlinkFTP::kCmdNone;
break;
}
}
void FTPManager::_handleNak(MavlinkFTP::Request* nak)
{
QString errorMsg;
MavlinkFTP::OpCode_t requestOpCode = static_cast<MavlinkFTP::OpCode_t>(nak->hdr.req_opcode);
MavlinkFTP::ErrorCode_t errorCode = static_cast<MavlinkFTP::ErrorCode_t>(nak->data[0]);
if (errorCode == MavlinkFTP::kErrEOF) {
qCDebug(FTPManagerLog) << "_handleNak EOF";
if (requestOpCode == MavlinkFTP::kCmdReadFile && _downloadState.bytesWritten == _downloadState.fileSize) {
// This could be an EOF on a normal read sequence, or an EOF for a read to fill in holes from a burst read.
// Either way it means we should be done.
_downloadComplete(QString());
return;
} else if (requestOpCode == MavlinkFTP::kCmdBurstReadFile) {
// This is an EOF during a burst read, we still have to check for filling in missing data
if (_downloadState.missingData.count()) {
// We only call _requestMissingBurstData if there are no missing blocks since _requestMissingBurstData will start a new
// burst sequence if you call it with no missing blocks which would put us into an infinite loop on EOFs.
_requestMissingBurstData();
return;
} else if (_downloadState.bytesWritten == _downloadState.fileSize) {
_downloadComplete(QString());
return;
}
}
}
// Nak's normally have 1 byte of data for error code, except for MavlinkFTP::kErrFailErrno which has additional byte for errno
if ((errorCode == MavlinkFTP::kErrFailErrno && nak->hdr.size != 2) || ((errorCode != MavlinkFTP::kErrFailErrno) && nak->hdr.size != 1)) {
errorMsg = tr("Invalid Nak format");
} else if (errorCode == MavlinkFTP::kErrFailErrno) {
errorMsg = tr("errno %1").arg(nak->data[1]);
} else {
errorMsg = MavlinkFTP::errorCodeToString(errorCode);
}
_waitState = MavlinkFTP::kCmdNone;
switch (nak->hdr.req_opcode) {
case MavlinkFTP::kCmdOpenFileRO:
case MavlinkFTP::kCmdReadFile:
case MavlinkFTP::kCmdBurstReadFile:
_downloadComplete(tr("Download failed: %1").arg(errorMsg));
break;
default:
// FIXME: Rest is NYI
break;
}
}
void FTPManager::mavlinkMessageReceived(mavlink_message_t message)
{
if (message.msgid != MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL) {
@ -340,21 +490,23 @@ void FTPManager::mavlinkMessageReceived(mavlink_message_t message) @@ -340,21 +490,23 @@ void FTPManager::mavlinkMessageReceived(mavlink_message_t message)
// ignore old/reordered packets (handle wrap-around properly)
if ((uint16_t)((expectedSeqNumber - 1) - incomingSeqNumber) < (std::numeric_limits<uint16_t>::max()/2)) {
qDebug() << "Received old packet: expected seq:" << expectedSeqNumber << "got:" << incomingSeqNumber;
qCDebug(FTPManagerLog) << "Received old packet: expected seq:" << expectedSeqNumber << "got:" << incomingSeqNumber;
return;
}
_clearAckTimeout();
_ackTimer.stop();
qCDebug(FTPManagerLog) << "mavlinkMessageReceived" << MavlinkFTP::opCodeToString(static_cast<MavlinkFTP::OpCode_t>(request->hdr.opcode)) << MavlinkFTP::opCodeToString(static_cast<MavlinkFTP::OpCode_t>(request->hdr.req_opcode));
if (incomingSeqNumber != expectedSeqNumber) {
switch (_waitState) {
case MavlinkFTP::kCmdOpenFileRO:
_downloadComplete(tr("Download failed: Unable to handle packet loss"));
break;
case MavlinkFTP::kCmdReadFile:
case MavlinkFTP::kCmdBurstReadFile:
_downloadComplete(tr("Download failed: Unable to handle packet loss"));
return;
// These can handle packet loss
break;
#if 0
case kCOWrite:
_closeUploadSession(false /* failure */);
@ -379,70 +531,9 @@ void FTPManager::mavlinkMessageReceived(mavlink_message_t message) @@ -379,70 +531,9 @@ void FTPManager::mavlinkMessageReceived(mavlink_message_t message)
_lastOutgoingRequest.hdr.seqNumber = incomingSeqNumber;
if (request->hdr.opcode == MavlinkFTP::kRspAck) {
switch (request->hdr.req_opcode) {
case MavlinkFTP::kCmdOpenFileRO:
_handlOpenFileROAck(request);
break;
case MavlinkFTP::kCmdReadFile:
_handleReadFileAck(request, false /* burstReadFile */);
break;
case MavlinkFTP::kCmdBurstReadFile:
_handleReadFileAck(request, true /*burstReadFile */);
break;
#if 0
case MavlinkFTP::kCmdListDirectory:
_listAckResponse(request);
break;
case MavlinkFTP::kCmdOpenFileRO:
case MavlinkFTP::kCmdOpenFileWO:
_handlOpenFileROAck(request);
break;
case MavlinkFTP::kCmdCreateFile:
_createAckResponse(request);
break;
case MavlinkFTP::kCmdWriteFile:
_writeAckResponse(request);
break;
#endif
default:
// Ack back from operation which does not require additional work
_waitState = MavlinkFTP::kCmdNone;
break;
}
_handleAck(request);
} else if (request->hdr.opcode == MavlinkFTP::kRspNak) {
QString errorMsg;
MavlinkFTP::OpCode_t requestOpCode = static_cast<MavlinkFTP::OpCode_t>(request->hdr.req_opcode);
MavlinkFTP::ErrorCode_t errorCode = static_cast<MavlinkFTP::ErrorCode_t>(request->data[0]);
if (requestOpCode == MavlinkFTP::kCmdReadFile && errorCode == MavlinkFTP::kErrEOF && _readFileAccumulator.size() == _downloadFileSize) {
_downloadComplete(QString());
} else {
// Nak's normally have 1 byte of data for error code, except for MavlinkFTP::kErrFailErrno which has additional byte for errno
if ((errorCode == MavlinkFTP::kErrFailErrno && request->hdr.size != 2) || ((errorCode != MavlinkFTP::kErrFailErrno) && request->hdr.size != 1)) {
errorMsg = tr("Invalid Nak format");
} else if (errorCode == MavlinkFTP::kErrFailErrno) {
errorMsg = tr("errno %1").arg(request->data[1]);
} else {
errorMsg = MavlinkFTP::errorCodeToString(errorCode);
}
_waitState = MavlinkFTP::kCmdNone;
switch (request->hdr.req_opcode) {
case MavlinkFTP::kCmdOpenFileRO:
case MavlinkFTP::kCmdReadFile:
case MavlinkFTP::kCmdBurstReadFile:
_downloadComplete(tr("Download failed: %1").arg(errorMsg));
break;
default:
// FIXME: Rest is NYI
break;
}
}
_handleNak(request);
}
}
@ -493,16 +584,10 @@ void FTPManager::_sendListCommand(void) @@ -493,16 +584,10 @@ void FTPManager::_sendListCommand(void)
bool FTPManager::download(const QString& from, const QString& toDir)
{
qCDebug(FTPManagerLog) << "download from:" << from << "to:" << toDir;
return _downloadWorker(from, toDir, false /* burstReadFile */);
return _downloadWorker(from, toDir);
}
bool FTPManager::burstDownload(const QString& from, const QString& toDir)
{
qCDebug(FTPManagerLog) << "burstDownload from:" << from << "to:" << toDir;
return _downloadWorker(from, toDir, true /* burstReadFile */);
}
bool FTPManager::_downloadWorker(const QString& from, const QString& toDir, bool burstReadFile)
bool FTPManager::_downloadWorker(const QString& from, const QString& toDir)
{
if (_waitState != MavlinkFTP::kCmdNone) {
qCDebug(FTPManagerLog) << "Cannot download. Already in another operation";
@ -515,7 +600,8 @@ bool FTPManager::_downloadWorker(const QString& from, const QString& toDir, bool @@ -515,7 +600,8 @@ bool FTPManager::_downloadWorker(const QString& from, const QString& toDir, bool
return false;
}
_readFileDownloadDir.setPath(toDir);
_downloadState.reset();
_downloadState.toDir.setPath(toDir);
QString strippedFrom;
QString ftpPrefix("mavlinkftp://");
@ -534,10 +620,9 @@ bool FTPManager::_downloadWorker(const QString& from, const QString& toDir, bool @@ -534,10 +620,9 @@ bool FTPManager::_downloadWorker(const QString& from, const QString& toDir, bool
}
}
lastDirSlashIndex++; // move past slash
_readFileDownloadFilename = strippedFrom.right(strippedFrom.size() - lastDirSlashIndex);
_waitState = MavlinkFTP::kCmdOpenFileRO;
_openFileType = burstReadFile ? MavlinkFTP::kCmdBurstReadFile : MavlinkFTP::kCmdReadFile;
_downloadState.fileName = strippedFrom.right(strippedFrom.size() - lastDirSlashIndex);
_waitState = MavlinkFTP::kCmdOpenFileRO;
MavlinkFTP::Request request;
request.hdr.session = 0;
@ -553,7 +638,7 @@ bool FTPManager::_downloadWorker(const QString& from, const QString& toDir, bool @@ -553,7 +638,7 @@ bool FTPManager::_downloadWorker(const QString& from, const QString& toDir, bool
/// @brief Uploads the specified file.
/// @param toPath File in UAS to upload to, fully qualified path
/// @param uploadFile Local file to upload from
void FTPManager::upload(const QString& toPath, const QFileInfo& uploadFile)
void FTPManager::upload(const QString& /*toPath*/, const QFileInfo& /*uploadFile*/)
{
#if 0
if(_currentOperation != kCOIdle){
@ -604,7 +689,7 @@ void FTPManager::upload(const QString& toPath, const QFileInfo& uploadFile) @@ -604,7 +689,7 @@ void FTPManager::upload(const QString& toPath, const QFileInfo& uploadFile)
#endif
}
void FTPManager::createDirectory(const QString& directory)
void FTPManager::createDirectory(const QString& /*directory*/)
{
#if 0
if(_currentOperation != kCOIdle){
@ -647,31 +732,22 @@ bool FTPManager::_sendOpcodeOnlyCmd(MavlinkFTP::OpCode_t opcode, MavlinkFTP::OpC @@ -647,31 +732,22 @@ bool FTPManager::_sendOpcodeOnlyCmd(MavlinkFTP::OpCode_t opcode, MavlinkFTP::OpC
return true;
}
/// @brief Starts the ack timeout timer
void FTPManager::_setupAckTimeout(void)
void FTPManager::_ackTimeout(void)
{
qCDebug(FTPManagerLog) << "_setupAckTimeout";
qCDebug(FTPManagerLog) << "_ackTimeout" << MavlinkFTP::opCodeToString(static_cast<MavlinkFTP::OpCode_t>(_waitState));
Q_ASSERT(!_ackTimer.isActive());
_ackNumTries = 0;
_ackTimer.setSingleShot(false);
_ackTimer.start(_ackTimerTimeoutMsecs);
}
/// @brief Clears the ack timeout timer
void FTPManager::_clearAckTimeout(void)
{
qCDebug(FTPManagerLog) << "_clearAckTimeout";
_ackTimer.stop();
}
switch (_waitState) {
case MavlinkFTP::kCmdReadFile:
// FIXME: retry count?
// Resend last request
_lastOutgoingRequest.hdr.seqNumber--;
_sendRequestExpectAck(&_lastOutgoingRequest);
return;
default:
break;
}
void FTPManager::_ackTimeout(void)
{
qCDebug(FTPManagerLog) << "_ackTimeout";
#if 0
// FIXME: retry NYI
if (++_ackNumTries <= _ackTimerMaxRetries) {
qCDebug(FTPManagerLog) << "ack timeout - retrying";
if (_currentOperation == kCOBurst) {
@ -691,17 +767,15 @@ void FTPManager::_ackTimeout(void) @@ -691,17 +767,15 @@ void FTPManager::_ackTimeout(void)
}
#endif
_clearAckTimeout();
// Make sure to set _currentOperation state before emitting error message. Code may respond
// to error message signal by sending another command, which will fail if state is not back
// to idle. FileView UI works this way with the List command.
switch (_waitState) {
case MavlinkFTP::kCmdOpenFileRO:
case MavlinkFTP::kCmdReadFile:
case MavlinkFTP::kCmdBurstReadFile:
_downloadComplete(tr("Download failed: Vehicle did not response to %1").arg(MavlinkFTP::opCodeToString(_waitState)));
case MavlinkFTP::kCmdReadFile:
_downloadComplete(tr("Download failed: Vehicle did not respond to %1").arg(MavlinkFTP::opCodeToString(_waitState)));
break;
#if 0
// FIXME: NYI
@ -736,8 +810,9 @@ void FTPManager::_ackTimeout(void) @@ -736,8 +810,9 @@ void FTPManager::_ackTimeout(void)
void FTPManager::_sendResetCommand(void)
{
MavlinkFTP::Request request;
request.hdr.opcode = MavlinkFTP::kCmdResetSessions;
request.hdr.size = 0;
request.hdr.opcode = MavlinkFTP::kCmdResetSessions;
request.hdr.size = 0;
_waitState = MavlinkFTP::kCmdResetSessions;
_sendRequestExpectAck(&request);
}
@ -755,7 +830,7 @@ void FTPManager::_emitListEntry(const QString& entry) @@ -755,7 +830,7 @@ void FTPManager::_emitListEntry(const QString& entry)
void FTPManager::_sendRequestExpectAck(MavlinkFTP::Request* request)
{
_setupAckTimeout();
_ackTimer.start();
request->hdr.seqNumber = ++_lastOutgoingRequest.hdr.seqNumber;
qCDebug(FTPManagerLog) << "_sendRequestExpectAck opcode:" << MavlinkFTP::opCodeToString(static_cast<MavlinkFTP::OpCode_t>(request->hdr.opcode)) << "seqNumber:" << request->hdr.seqNumber;

85
src/Vehicle/FTPManager.h

@ -78,30 +78,30 @@ private slots: @@ -78,30 +78,30 @@ private slots:
void _ackTimeout(void);
private:
bool _sendOpcodeOnlyCmd (MavlinkFTP::OpCode_t opcode, MavlinkFTP::OpCode_t newWaitState);
void _setupAckTimeout (void);
void _clearAckTimeout (void);
void _emitErrorMessage (const QString& msg);
void _emitListEntry (const QString& entry);
void _sendRequestExpectAck (MavlinkFTP::Request* request);
void _sendRequestNoAck (MavlinkFTP::Request* request);
void _sendMessageOnLink (LinkInterface* link, mavlink_message_t message);
void _fillRequestWithString (MavlinkFTP::Request* request, const QString& str);
void _handlOpenFileROAck (MavlinkFTP::Request* ack);
void _handleReadFileAck (MavlinkFTP::Request* ack, bool burstReadFile);
void _listAckResponse (MavlinkFTP::Request* listAck);
void _createAckResponse (MavlinkFTP::Request* createAck);
void _writeAckResponse (MavlinkFTP::Request* writeAck);
void _writeFileDatablock (void);
void _sendListCommand (void);
void _sendResetCommand (void);
void _downloadComplete (const QString& errorMsg);
void _uploadComplete (const QString& errorMsg);
bool _downloadWorker (const QString& from, const QString& toDir, bool burstReadFile);
void _requestMissingData (void);
bool _sendOpcodeOnlyCmd (MavlinkFTP::OpCode_t opcode, MavlinkFTP::OpCode_t newWaitState);
void _emitErrorMessage (const QString& msg);
void _emitListEntry (const QString& entry);
void _sendRequestExpectAck (MavlinkFTP::Request* request);
void _sendRequestNoAck (MavlinkFTP::Request* request);
void _sendMessageOnLink (LinkInterface* link, mavlink_message_t message);
void _fillRequestWithString (MavlinkFTP::Request* request, const QString& str);
void _handlOpenFileROAck (MavlinkFTP::Request* ack);
void _handleReadFileAck (MavlinkFTP::Request* ack);
void _handleBurstReadFileAck (MavlinkFTP::Request* ack);
void _listAckResponse (MavlinkFTP::Request* listAck);
void _createAckResponse (MavlinkFTP::Request* createAck);
void _writeAckResponse (MavlinkFTP::Request* writeAck);
void _writeFileDatablock (void);
void _sendListCommand (void);
void _sendResetCommand (void);
void _downloadComplete (const QString& errorMsg);
void _uploadComplete (const QString& errorMsg);
bool _downloadWorker (const QString& from, const QString& toDir);
void _requestMissingBurstData(void);
void _handleAck (MavlinkFTP::Request* ack);
void _handleNak (MavlinkFTP::Request* nak);
MavlinkFTP::OpCode_t _waitState = MavlinkFTP::kCmdNone; ///< Current operation of state machine
MavlinkFTP::OpCode_t _openFileType = MavlinkFTP::kCmdReadFile; ///< Type of read to use after open file succeeds
QTimer _ackTimer; ///< Used to signal a timeout waiting for an ack
int _ackNumTries; ///< current number of tries
Vehicle* _vehicle;
@ -117,17 +117,34 @@ private: @@ -117,17 +117,34 @@ private:
uint32_t _writeFileSize; ///< Size of file being uploaded
QByteArray _writeFileAccumulator; ///< Holds file being uploaded
struct MissingData {
typedef struct {
uint32_t offset;
uint32_t size;
};
uint32_t _requestedDownloadOffset; ///< current download offset
QByteArray _readFileAccumulator; ///< Holds file being downloaded
QDir _readFileDownloadDir; ///< Directory to download file to
QString _readFileDownloadFilename; ///< Filename (no path) for download file
int _downloadFileSize; ///< Size of file being downloaded
static const int _ackTimerTimeoutMsecs = 5000;
static const int _ackTimerMaxRetries = 6;
uint32_t cBytes;
} MissingData_t;
struct {
uint32_t expectedBurstOffset; ///< offset which should be coming next in a burst sequence
uint32_t expectedReadOffset; ///< offset which should be coming from a hole filling read request
uint32_t bytesWritten;
QList<MissingData_t> missingData;
QDir toDir; ///< Directory to download file to
QString fileName; ///< Filename (no path) for download file
uint32_t fileSize; ///< Size of file being downloaded
QFile file;
int retryCount;
void reset() {
expectedBurstOffset = 0;
expectedReadOffset = 0;
bytesWritten = 0;
retryCount = 0;
missingData.clear();
file.close();
}
} _downloadState;
static const int _ackTimerTimeoutMsecs = 1000;
static const int _ackTimerMaxRetries = 6;
static const int _maxRetry = 5;
};

84
src/Vehicle/FTPManagerTest.cc

@ -39,6 +39,48 @@ void FTPManagerTest::_testCaseWorker(const TestCase_t& testCase) @@ -39,6 +39,48 @@ void FTPManagerTest::_testCaseWorker(const TestCase_t& testCase)
_disconnectMockLink();
}
void FTPManagerTest::_sizeTestCaseWorker(int fileSize)
{
_connectMockLinkNoInitialConnectSequence();
FTPManager* ftpManager = _vehicle->ftpManager();
QString filename = QStringLiteral("%1%2").arg(MockLinkFTP::sizeFilenamePrefix).arg(fileSize);
QSignalSpy spyDownloadComplete(ftpManager, &FTPManager::downloadComplete);
ftpManager->download(filename, QStandardPaths::writableLocation(QStandardPaths::TempLocation));
QCOMPARE(spyDownloadComplete.wait(10000), true);
QCOMPARE(spyDownloadComplete.count(), 1);
// void downloadComplete (const QString& file, const QString& errorMsg);
QList<QVariant> arguments = spyDownloadComplete.takeFirst();
QVERIFY(arguments[1].toString().isEmpty());
_verifyFileSizeAndDelete(arguments[0].toString(), fileSize);
_disconnectMockLink();
}
void FTPManagerTest::_performSizeBasedTestCases(void)
{
// We test various boundary conditions on file sizes with respect to buffer sizes
const QList<int> rgSizeTestCases = {
// File fits one Read Ack packet, partially filling data
sizeof(((MavlinkFTP::Request*)0)->data) - 1,
// File fits one Read Ack packet, exactly filling all data
sizeof(((MavlinkFTP::Request*)0)->data),
// File is larger than a single Read Ack packets, requires multiple Reads
sizeof(((MavlinkFTP::Request*)0)->data) + 1,
// File is large enough to require multiple bursts
3 * 1024,
};
for (int fileSize: rgSizeTestCases) {
_sizeTestCaseWorker(fileSize);
}
}
void FTPManagerTest::_performTestCases(void)
{
int index = 0;
@ -47,3 +89,45 @@ void FTPManagerTest::_performTestCases(void) @@ -47,3 +89,45 @@ void FTPManagerTest::_performTestCases(void)
_testCaseWorker(testCase);
}
}
void FTPManagerTest::_testLostPackets(void)
{
_connectMockLinkNoInitialConnectSequence();
FTPManager* ftpManager = _vehicle->ftpManager();
int fileSize = 4 * 1024;
QString filename = QStringLiteral("%1%2").arg(MockLinkFTP::sizeFilenamePrefix).arg(fileSize);
QSignalSpy spyDownloadComplete(ftpManager, &FTPManager::downloadComplete);
_mockLink->mockLinkFTP()->enableRandromDrops(true);
ftpManager->download(filename, QStandardPaths::writableLocation(QStandardPaths::TempLocation));
QCOMPARE(spyDownloadComplete.wait(10000), true);
QCOMPARE(spyDownloadComplete.count(), 1);
// void downloadComplete (const QString& file, const QString& errorMsg);
QList<QVariant> arguments = spyDownloadComplete.takeFirst();
QVERIFY(arguments[1].toString().isEmpty());
_verifyFileSizeAndDelete(arguments[0].toString(), fileSize);
_disconnectMockLink();
}
void FTPManagerTest::_verifyFileSizeAndDelete(const QString& filename, int expectedSize)
{
QFileInfo fileInfo(filename);
QVERIFY(fileInfo.exists());
QCOMPARE(fileInfo.size(), expectedSize);
QFile file(filename);
QVERIFY(file.open(QFile::ReadOnly));
for (int i=0; i<expectedSize; i++) {
QByteArray bytes = file.read(1);
QCOMPARE(bytes[0], (char)(i % 255));
}
file.close();
file.remove();
}

8
src/Vehicle/FTPManagerTest.h

@ -16,14 +16,18 @@ class FTPManagerTest : public UnitTest @@ -16,14 +16,18 @@ class FTPManagerTest : public UnitTest
Q_OBJECT
private slots:
void _performTestCases(void);
void _performSizeBasedTestCases (void);
void _performTestCases (void);
void _testLostPackets (void);
private:
typedef struct {
const char* file;
} TestCase_t;
void _testCaseWorker(const TestCase_t& testCase);
void _testCaseWorker (const TestCase_t& testCase);
void _sizeTestCaseWorker (int fileSize);
void _verifyFileSizeAndDelete (const QString& filename, int expectedSize);
static const TestCase_t _rgTestCases[];
};

4
src/comm/LinkManager.cc

@ -31,6 +31,10 @@ @@ -31,6 +31,10 @@
#include "PositionManager.h"
#endif
#ifdef QT_DEBUG
#include "MockLink.h"
#endif
QGC_LOGGING_CATEGORY(LinkManagerLog, "LinkManagerLog")
QGC_LOGGING_CATEGORY(LinkManagerVerboseLog, "LinkManagerVerboseLog")

4
src/comm/LinkManager.h

@ -32,10 +32,6 @@ @@ -32,10 +32,6 @@
#include "SerialLink.h"
#endif
#ifdef QT_DEBUG
#include "MockLink.h"
#endif
Q_DECLARE_LOGGING_CATEGORY(LinkManagerLog)
Q_DECLARE_LOGGING_CATEGORY(LinkManagerVerboseLog)

7
src/comm/MockLink.cc

@ -70,7 +70,6 @@ MockLink::MockLink(SharedLinkConfigurationPointer& config) @@ -70,7 +70,6 @@ MockLink::MockLink(SharedLinkConfigurationPointer& config)
, _vehicleLatitude (_defaultVehicleLatitude + ((_vehicleSystemId - 128) * 0.0001)) // Slight offset for each vehicle
, _vehicleLongitude (_defaultVehicleLongitude + ((_vehicleSystemId - 128) * 0.0001))
, _vehicleAltitude (_defaultVehicleAltitude)
, _fileServer (nullptr)
, _sendStatusText (false)
, _apmSendHomePositionOnEmptyList (false)
, _failureMode (MockConfiguration::FailNone)
@ -96,8 +95,7 @@ MockLink::MockLink(SharedLinkConfigurationPointer& config) @@ -96,8 +95,7 @@ MockLink::MockLink(SharedLinkConfigurationPointer& config)
px4_cm.main_mode = PX4_CUSTOM_MAIN_MODE_MANUAL;
_mavCustomMode = px4_cm.data;
_fileServer = new MockLinkFTP(_vehicleSystemId, _vehicleComponentId, this);
Q_CHECK_PTR(_fileServer);
_mockLinkFTP = new MockLinkFTP(_vehicleSystemId, _vehicleComponentId, this);
moveToThread(this);
@ -899,8 +897,7 @@ void MockLink::emitRemoteControlChannelRawChanged(int channel, uint16_t raw) @@ -899,8 +897,7 @@ void MockLink::emitRemoteControlChannelRawChanged(int channel, uint16_t raw)
void MockLink::_handleFTP(const mavlink_message_t& msg)
{
Q_ASSERT(_fileServer);
_fileServer->handleFTPMessage(msg);
_mockLinkFTP->mavlinkMessageReceived(msg);
}
void MockLink::_handleCommandLong(const mavlink_message_t& msg)

6
src/comm/MockLink.h

@ -119,7 +119,7 @@ public: @@ -119,7 +119,7 @@ public:
/// Sends the specified mavlink message to QGC
void respondWithMavlinkMessage(const mavlink_message_t& msg);
MockLinkFTP* getFileServer(void) { return _fileServer; }
MockLinkFTP* mockLinkFTP(void) { return _mockLinkFTP; }
// Overrides from LinkInterface
QString getName (void) const override { return _name; }
@ -132,7 +132,7 @@ public: @@ -132,7 +132,7 @@ public:
bool connect(void);
bool disconnect(void);
/// Sets a failure mode for unit testing
/// Sets a failure mode for unit testingqgcm
/// @param failureMode Type of failure to simulate
/// @param failureAckResult Error to send if one the ack error modes
void setMissionItemFailureMode(MockLinkMissionItemHandler::FailureMode_t failureMode, MAV_MISSION_RESULT failureAckResult);
@ -266,7 +266,7 @@ private: @@ -266,7 +266,7 @@ private:
double _vehicleLongitude;
double _vehicleAltitude;
MockLinkFTP* _fileServer;
MockLinkFTP* _mockLinkFTP = nullptr;
bool _sendStatusText;
bool _apmSendHomePositionOnEmptyList;

220
src/comm/MockLinkFTP.cc

@ -20,14 +20,7 @@ const MockLinkFTP::ErrorMode_t MockLinkFTP::rgFailureModes[] = { @@ -20,14 +20,7 @@ const MockLinkFTP::ErrorMode_t MockLinkFTP::rgFailureModes[] = {
};
const size_t MockLinkFTP::cFailureModes = sizeof(MockLinkFTP::rgFailureModes) / sizeof(MockLinkFTP::rgFailureModes[0]);
const MockLinkFTP::FileTestCase MockLinkFTP::rgFileTestCases[MockLinkFTP::cFileTestCases] = {
// File fits one Read Ack packet, partially filling data
{ "partial.qgc", sizeof(((MavlinkFTP::Request*)0)->data) - 1, 1, false},
// File fits one Read Ack packet, exactly filling all data
{ "exact.qgc", sizeof(((MavlinkFTP::Request*)0)->data), 1, true },
// File is larger than a single Read Ack packets, requires multiple Reads
{ "multi.qgc", sizeof(((MavlinkFTP::Request*)0)->data) + 1, 2, false },
};
const char* MockLinkFTP::sizeFilenamePrefix = "mocklink-size-";
MockLinkFTP::MockLinkFTP(uint8_t systemIdServer, uint8_t componentIdServer, MockLink* mockLink)
: _systemIdServer (systemIdServer)
@ -119,19 +112,13 @@ void MockLinkFTP::_openCommand(uint8_t senderSystemId, uint8_t senderComponentId @@ -119,19 +112,13 @@ void MockLinkFTP::_openCommand(uint8_t senderSystemId, uint8_t senderComponentId
path = (char *)request->data;
_currentFile.close();
// Check path against one of our known test cases
for (const FileTestCase& testCase: rgFileTestCases) {
if (path == testCase.filename) {
tmpFilename = _createTestCaseTempFile(testCase);
break;
}
}
if (tmpFilename.isEmpty()) {
if (path == "/version.json") {
tmpFilename = ":MockLink/Version.MetaData.json";
}
QString sizePrefix = sizeFilenamePrefix;
if (path.startsWith(sizePrefix)) {
QString sizeString = path.right(path.length() - sizePrefix.length());
tmpFilename = _createTestTempFile(sizeString.toInt());
} else if (path == "/version.json") {
tmpFilename = ":MockLink/Version.MetaData.json";
}
if (!tmpFilename.isEmpty()) {
@ -204,53 +191,42 @@ void MockLinkFTP::_readCommand(uint8_t senderSystemId, uint8_t senderComponentId @@ -204,53 +191,42 @@ void MockLinkFTP::_readCommand(uint8_t senderSystemId, uint8_t senderComponentId
void MockLinkFTP::_burstReadCommand(uint8_t senderSystemId, uint8_t senderComponentId, MavlinkFTP::Request* request, uint16_t seqNumber)
{
uint16_t outgoingSeqNumber = _nextSeqNumber(seqNumber);
MavlinkFTP::Request response;
uint16_t outgoingSeqNumber = _nextSeqNumber(seqNumber);
MavlinkFTP::Request response;
if (request->hdr.session != _sessionId) {
_sendNak(senderSystemId, senderComponentId, MavlinkFTP::kErrFail, outgoingSeqNumber, MavlinkFTP::kCmdBurstReadFile);
return;
}
uint32_t readOffset = 0; // offset into file for reading
uint32_t ackOffset = 0; // offset for ack
uint8_t cDataAck; // number of bytes in ack
int burstMax = 10;
int burstCount = 1;
uint32_t burstOffset = request->hdr.offset;
while (readOffset < _currentFile.size()) {
cDataAck = 0;
if (readOffset != 0) {
// If we get here it means the client is requesting additional data past the first request
if (_errMode == errModeNakSecondResponse) {
// Nak error all subsequent requests
_sendNak(senderSystemId, senderComponentId, MavlinkFTP::kErrFail, outgoingSeqNumber, MavlinkFTP::kCmdBurstReadFile);
return;
} else if (_errMode == errModeNoSecondResponse) {
// No response for all subsequent requests
return;
}
}
uint8_t cBytesToRead = (uint8_t)qMin((qint64)sizeof(response.data), _currentFile.size());
_currentFile.seek(readOffset);
QByteArray bytes = _currentFile.read(cBytesToRead);
memcpy(response.data, bytes.constData(), cBytesToRead);
while (burstOffset < _currentFile.size() && burstCount++ < burstMax) {
_currentFile.seek(burstOffset);
uint8_t cBytes = (uint8_t)qMin((qint64)sizeof(response.data), _currentFile.size() - burstOffset);
QByteArray bytes = _currentFile.read(cBytes);
// We should always have written something, otherwise there is something wrong with the code above
Q_ASSERT(cBytesToRead);
response.hdr.session = _sessionId;
response.hdr.size = cDataAck;
response.hdr.offset = cBytesToRead;
response.hdr.opcode = MavlinkFTP::kRspAck;
response.hdr.req_opcode = MavlinkFTP::kCmdBurstReadFile;
Q_ASSERT(cBytes);
memcpy(response.data, bytes.constData(), cBytes);
response.hdr.session = _sessionId;
response.hdr.size = cBytes;
response.hdr.offset = burstOffset;
response.hdr.opcode = MavlinkFTP::kRspAck;
response.hdr.req_opcode = MavlinkFTP::kCmdBurstReadFile;
response.hdr.burstComplete = burstCount == burstMax ? 1 : 0;
_sendResponse(senderSystemId, senderComponentId, &response, outgoingSeqNumber);
outgoingSeqNumber = _nextSeqNumber(outgoingSeqNumber);
ackOffset += cDataAck;
burstOffset += cBytes;
}
_sendNak(senderSystemId, senderComponentId, MavlinkFTP::kErrEOF, outgoingSeqNumber, MavlinkFTP::kCmdBurstReadFile);
}
@ -264,7 +240,7 @@ void MockLinkFTP::_terminateCommand(uint8_t senderSystemId, uint8_t senderCompon @@ -264,7 +240,7 @@ void MockLinkFTP::_terminateCommand(uint8_t senderSystemId, uint8_t senderCompon
}
_sendAck(senderSystemId, senderComponentId, outgoingSeqNumber, MavlinkFTP::kCmdTerminateSession);
emit terminateCommandReceived();
}
@ -272,12 +248,14 @@ void MockLinkFTP::_resetCommand(uint8_t senderSystemId, uint8_t senderComponentI @@ -272,12 +248,14 @@ void MockLinkFTP::_resetCommand(uint8_t senderSystemId, uint8_t senderComponentI
{
uint16_t outgoingSeqNumber = _nextSeqNumber(seqNumber);
_currentFile.close();
_currentFile.remove();
_sendAck(senderSystemId, senderComponentId, outgoingSeqNumber, MavlinkFTP::kCmdResetSessions);
emit resetCommandReceived();
}
void MockLinkFTP::handleFTPMessage(const mavlink_message_t& message)
void MockLinkFTP::mavlinkMessageReceived(const mavlink_message_t& message)
{
if (message.msgid != MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL) {
return;
@ -294,20 +272,20 @@ void MockLinkFTP::handleFTPMessage(const mavlink_message_t& message) @@ -294,20 +272,20 @@ void MockLinkFTP::handleFTPMessage(const mavlink_message_t& message)
MavlinkFTP::Request* request = (MavlinkFTP::Request*)&requestFTP.payload[0];
if (_randomDropsEnabled) {
if (rand() % 3 == 0) {
qDebug() << "FileServer: Random drop of incoming packet";
return;
}
}
if (_lastReplyValid && request->hdr.seqNumber + 1 == _lastReplySequence) {
// this is the same request as the one we replied to last. It means the (n)ack got lost, and the GCS
// resent the request
qDebug() << "FileServer: resending response";
_mockLink->respondWithMavlinkMessage(_lastReply);
return;
}
if (_randomDropsEnabled) {
if ((rand() % 5) == 0) {
qDebug() << "MockLinkFTP: Random drop of incoming packet";
return;
}
}
if (_lastReplyValid && request->hdr.seqNumber == _lastReplySequence - 1) {
// This is the same request as the one we replied to last. It means the (n)ack got lost, and the GCS
// resent the request
qDebug() << "MockLinkFTP: resending response";
_mockLink->respondWithMavlinkMessage(_lastReply);
return;
}
uint16_t incomingSeqNumber = request->hdr.seqNumber;
uint16_t outgoingSeqNumber = _nextSeqNumber(incomingSeqNumber);
@ -324,42 +302,42 @@ void MockLinkFTP::handleFTPMessage(const mavlink_message_t& message) @@ -324,42 +302,42 @@ void MockLinkFTP::handleFTPMessage(const mavlink_message_t& message)
}
switch (request->hdr.opcode) {
case MavlinkFTP::kCmdNone:
// ignored, always acked
ackResponse.hdr.opcode = MavlinkFTP::kRspAck;
ackResponse.hdr.session = 0;
ackResponse.hdr.size = 0;
_sendResponse(message.sysid, message.compid, &ackResponse, outgoingSeqNumber);
break;
case MavlinkFTP::kCmdListDirectory:
_listCommand(message.sysid, message.compid, request, incomingSeqNumber);
break;
case MavlinkFTP::kCmdOpenFileRO:
_openCommand(message.sysid, message.compid, request, incomingSeqNumber);
break;
case MavlinkFTP::kCmdReadFile:
_readCommand(message.sysid, message.compid, request, incomingSeqNumber);
break;
case MavlinkFTP::kCmdBurstReadFile:
_burstReadCommand(message.sysid, message.compid, request, incomingSeqNumber);
break;
case MavlinkFTP::kCmdTerminateSession:
_terminateCommand(message.sysid, message.compid, request, incomingSeqNumber);
break;
case MavlinkFTP::kCmdResetSessions:
_resetCommand(message.sysid, message.compid, incomingSeqNumber);
break;
default:
// nack for all NYI opcodes
_sendNak(message.sysid, message.compid, MavlinkFTP::kErrUnknownCommand, outgoingSeqNumber, (MavlinkFTP::OpCode_t)request->hdr.opcode);
break;
case MavlinkFTP::kCmdNone:
// ignored, always acked
ackResponse.hdr.opcode = MavlinkFTP::kRspAck;
ackResponse.hdr.session = 0;
ackResponse.hdr.size = 0;
_sendResponse(message.sysid, message.compid, &ackResponse, outgoingSeqNumber);
break;
case MavlinkFTP::kCmdListDirectory:
_listCommand(message.sysid, message.compid, request, incomingSeqNumber);
break;
case MavlinkFTP::kCmdOpenFileRO:
_openCommand(message.sysid, message.compid, request, incomingSeqNumber);
break;
case MavlinkFTP::kCmdReadFile:
_readCommand(message.sysid, message.compid, request, incomingSeqNumber);
break;
case MavlinkFTP::kCmdBurstReadFile:
_burstReadCommand(message.sysid, message.compid, request, incomingSeqNumber);
break;
case MavlinkFTP::kCmdTerminateSession:
_terminateCommand(message.sysid, message.compid, request, incomingSeqNumber);
break;
case MavlinkFTP::kCmdResetSessions:
_resetCommand(message.sysid, message.compid, incomingSeqNumber);
break;
default:
// nack for all NYI opcodes
_sendNak(message.sysid, message.compid, MavlinkFTP::kErrUnknownCommand, outgoingSeqNumber, (MavlinkFTP::OpCode_t)request->hdr.opcode);
break;
}
}
@ -368,10 +346,10 @@ void MockLinkFTP::_sendAck(uint8_t targetSystemId, uint8_t targetComponentId, ui @@ -368,10 +346,10 @@ void MockLinkFTP::_sendAck(uint8_t targetSystemId, uint8_t targetComponentId, ui
{
MavlinkFTP::Request ackResponse;
ackResponse.hdr.opcode = MavlinkFTP::kRspAck;
ackResponse.hdr.req_opcode = reqOpcode;
ackResponse.hdr.session = 0;
ackResponse.hdr.size = 0;
ackResponse.hdr.opcode = MavlinkFTP::kRspAck;
ackResponse.hdr.req_opcode = reqOpcode;
ackResponse.hdr.session = 0;
ackResponse.hdr.size = 0;
_sendResponse(targetSystemId, targetComponentId, &ackResponse, seqNumber);
}
@ -406,9 +384,9 @@ void MockLinkFTP::_sendNakErrno(uint8_t targetSystemId, uint8_t targetComponentI @@ -406,9 +384,9 @@ void MockLinkFTP::_sendNakErrno(uint8_t targetSystemId, uint8_t targetComponentI
/// @brief Emits a Request through the messageReceived signal.
void MockLinkFTP::_sendResponse(uint8_t targetSystemId, uint8_t targetComponentId, MavlinkFTP::Request* request, uint16_t seqNumber)
{
request->hdr.seqNumber = seqNumber;
_lastReplySequence = seqNumber;
_lastReplyValid = true;
request->hdr.seqNumber = seqNumber;
_lastReplySequence = seqNumber;
_lastReplyValid = true;
mavlink_msg_file_transfer_protocol_pack_chan(_systemIdServer, // System ID
_componentIdServer, // Component ID
@ -419,12 +397,12 @@ void MockLinkFTP::_sendResponse(uint8_t targetSystemId, uint8_t targetComponentI @@ -419,12 +397,12 @@ void MockLinkFTP::_sendResponse(uint8_t targetSystemId, uint8_t targetComponentI
targetComponentId,
(uint8_t*)request); // Payload
if (_randomDropsEnabled) {
if (rand() % 3 == 0) {
qDebug() << "FileServer: Random drop of outgoing packet";
return;
}
}
if (_randomDropsEnabled) {
if ((rand() % 5) == 0) {
qDebug() << "MockLinkFTP: Random drop of outgoing packet";
return;
}
}
_mockLink->respondWithMavlinkMessage(_lastReply);
}
@ -441,11 +419,11 @@ uint16_t MockLinkFTP::_nextSeqNumber(uint16_t seqNumber) @@ -441,11 +419,11 @@ uint16_t MockLinkFTP::_nextSeqNumber(uint16_t seqNumber)
return outgoingSeqNumber;
}
QString MockLinkFTP::_createTestCaseTempFile(const FileTestCase& testCase)
QString MockLinkFTP::_createTestTempFile(int size)
{
QGCTemporaryFile tmpFile("MockLinkFTPTestCase");
tmpFile.open(QIODevice::WriteOnly | QIODevice::Truncate);
for (int i=0; i<testCase.length; i++) {
for (int i=0; i<size; i++) {
tmpFile.write(QByteArray(1, i % 255));
}
tmpFile.close();

20
src/comm/MockLinkFTP.h

@ -51,24 +51,12 @@ public: @@ -51,24 +51,12 @@ public:
static const size_t cFailureModes;
/// Called to handle an FTP message
void handleFTPMessage(const mavlink_message_t& message);
void mavlinkMessageReceived(const mavlink_message_t& message);
/// @brief Used to represent a single test case for download testing.
struct FileTestCase {
const char* filename; ///< Filename to download
uint8_t length; ///< Length of file in bytes
int packetCount; ///< Number of packets required for data
bool exactFit; ///< true: last packet is exact fit, false: last packet is partially filled
};
/// @brief The numbers of test cases in the rgFileTestCases array.
static const size_t cFileTestCases = 3;
/// @brief The set of files supported by the mock server for testing purposes. Each one represents a different edge case for testing.
static const FileTestCase rgFileTestCases[cFileTestCases];
void enableRandromDrops(bool enable) { _randomDropsEnabled = enable; }
static const char* sizeFilenamePrefix;
signals:
/// You can connect to this signal to be notified when the server receives a Terminate command.
void terminateCommandReceived(void);
@ -88,7 +76,7 @@ private: @@ -88,7 +76,7 @@ private:
void _terminateCommand (uint8_t senderSystemId, uint8_t senderComponentId, MavlinkFTP::Request* request, uint16_t seqNumber);
void _resetCommand (uint8_t senderSystemId, uint8_t senderComponentId, uint16_t seqNumber);
uint16_t _nextSeqNumber (uint16_t seqNumber);
QString _createTestCaseTempFile (const FileTestCase& testCase);
QString _createTestTempFile (int size);
/// if request is a string, this ensures it's null-terminated
static void ensureNullTemination(MavlinkFTP::Request* request);

19
src/qgcunittest/UnitTest.cc

@ -19,6 +19,7 @@ @@ -19,6 +19,7 @@
#include "Vehicle.h"
#include "AppSettings.h"
#include "SettingsManager.h"
#include "MockLink.h"
#include <QRandomGenerator>
#include <QTemporaryFile>
@ -36,15 +37,15 @@ enum UnitTest::FileDialogType UnitTest::_fileDialogExpectedType = getOpenFileNam @@ -36,15 +37,15 @@ enum UnitTest::FileDialogType UnitTest::_fileDialogExpectedType = getOpenFileNam
int UnitTest::_missedFileDialogCount = 0;
UnitTest::UnitTest(void)
: _linkManager(nullptr)
, _mockLink(nullptr)
, _mainWindow(nullptr)
, _vehicle(nullptr)
, _expectMissedFileDialog(false)
, _expectMissedMessageBox(false)
, _unitTestRun(false)
, _initCalled(false)
, _cleanupCalled(false)
: _linkManager (nullptr)
, _mockLink (nullptr)
, _mainWindow (nullptr)
, _vehicle (nullptr)
, _expectMissedFileDialog (false)
, _expectMissedMessageBox (false)
, _unitTestRun (false)
, _initCalled (false)
, _cleanupCalled (false)
{
}

Loading…
Cancel
Save