diff --git a/src/comm/MockLinkFileServer.cc b/src/comm/MockLinkFileServer.cc index 238e6c9667d4949ec515956d6c266fb7ad7cb2d5..cb02d81adada2a29bbe79df80f4cba5271ec878b 100644 --- a/src/comm/MockLinkFileServer.cc +++ b/src/comm/MockLinkFileServer.cc @@ -36,9 +36,22 @@ MockLinkFileServer::MockLinkFileServer(uint8_t systemIdServer, uint8_t component _errMode(errModeNone), _systemIdServer(systemIdServer), _componentIdServer(componentIdServer), - _mockLink(mockLink) + _mockLink(mockLink), + _lastReplyValid(false), + _lastReplySequence(0), + _randomDropsEnabled(false) { + srand(0); // make sure unit tests are deterministic +} + +void MockLinkFileServer::ensureNullTemination(FileManager::Request* request) +{ + if (request->hdr.size < sizeof(request->data)) { + request->data[request->hdr.size] = '\0'; + } else { + request->data[sizeof(request->data)-1] = '\0'; + } } /// @brief Handles List command requests. Only supports root folder paths. @@ -51,6 +64,8 @@ void MockLinkFileServer::_listCommand(uint8_t senderSystemId, uint8_t senderComp QString path; uint16_t outgoingSeqNumber = _nextSeqNumber(seqNumber); + ensureNullTemination(request); + // We only support root path path = (char *)&request->data[0]; if (!path.isEmpty() && path != "/") { @@ -103,6 +118,8 @@ void MockLinkFileServer::_openCommand(uint8_t senderSystemId, uint8_t senderComp QString path; uint16_t outgoingSeqNumber = _nextSeqNumber(seqNumber); + ensureNullTemination(request); + size_t cchPath = strnlen((char *)request->data, sizeof(request->data)); Q_ASSERT(cchPath != sizeof(request->data)); Q_UNUSED(cchPath); // Fix initialized-but-not-referenced warning on release builds @@ -270,9 +287,24 @@ void MockLinkFileServer::handleFTPMessage(const mavlink_message_t& message) if (requestFTP.target_system != _systemIdServer) { return; } - + FileManager::Request* request = (FileManager::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; + } + uint16_t incomingSeqNumber = request->hdr.seqNumber; uint16_t outgoingSeqNumber = _nextSeqNumber(incomingSeqNumber); @@ -361,20 +393,27 @@ void MockLinkFileServer::_sendNak(uint8_t targetSystemId, uint8_t targetComponen /// @brief Emits a Request through the messageReceived signal. void MockLinkFileServer::_sendResponse(uint8_t targetSystemId, uint8_t targetComponentId, FileManager::Request* request, uint16_t seqNumber) { - mavlink_message_t mavlinkMessage; - request->hdr.seqNumber = seqNumber; + _lastReplySequence = seqNumber; + _lastReplyValid = true; mavlink_msg_file_transfer_protocol_pack_chan(_systemIdServer, // System ID 0, // Component ID _mockLink->mavlinkChannel(), - &mavlinkMessage, // Mavlink Message to pack into + &_lastReply, // Mavlink Message to pack into 0, // Target network targetSystemId, targetComponentId, (uint8_t*)request); // Payload + + if (_randomDropsEnabled) { + if (rand() % 3 == 0) { + qDebug() << "FileServer: Random drop of outgoing packet"; + return; + } + } - _mockLink->respondWithMavlinkMessage(mavlinkMessage); + _mockLink->respondWithMavlinkMessage(_lastReply); } /// @brief Generates the next sequence number given an incoming sequence number. Handles generating diff --git a/src/comm/MockLinkFileServer.h b/src/comm/MockLinkFileServer.h index 26fdb7bd5a6d35569762f53ce8879e3878e1c3de..81e77e6618dc50084dc47528393c333e28f7d277 100644 --- a/src/comm/MockLinkFileServer.h +++ b/src/comm/MockLinkFileServer.h @@ -70,6 +70,8 @@ public: /// @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; } + signals: /// You can connect to this signal to be notified when the server receives a Terminate command. void terminateCommandReceived(void); @@ -89,6 +91,9 @@ private: void _resetCommand(uint8_t senderSystemId, uint8_t senderComponentId, uint16_t seqNumber); uint16_t _nextSeqNumber(uint16_t seqNumber); + /// if request is a string, this ensures it's null-terminated + static void ensureNullTemination(FileManager::Request* request); + QStringList _fileList; ///< List of files returned by List command static const uint8_t _sessionId; @@ -97,6 +102,12 @@ private: const uint8_t _systemIdServer; ///< System ID for server const uint8_t _componentIdServer; ///< Component ID for server MockLink* _mockLink; ///< MockLink to communicate through + + bool _lastReplyValid; + uint16_t _lastReplySequence; + mavlink_message_t _lastReply; + + bool _randomDropsEnabled; }; #endif diff --git a/src/qgcunittest/FileManagerTest.cc b/src/qgcunittest/FileManagerTest.cc index 0a8cc1f9158d4ab1db5be735268e59e97a1a0b5b..9fc3425d31e75617f365ba1c7377e38cdba36574 100644 --- a/src/qgcunittest/FileManagerTest.cc +++ b/src/qgcunittest/FileManagerTest.cc @@ -127,6 +127,9 @@ void FileManagerTest::_listTest(void) Q_ASSERT(_fileManager); Q_ASSERT(_multiSpy); Q_ASSERT(_multiSpy->checkNoSignals() == true); + + // test the automatic retry behavior by enabling random drops + _fileServer->enableRandromDrops(true); // FileManager::listDirectory signalling as follows: // Emits a listEntry signal for each list entry @@ -192,6 +195,8 @@ void FileManagerTest::_listTest(void) _multiSpy->clearAllSignals(); _fileServer->setErrorMode(MockLinkFileServer::errModeNone); } + + _fileServer->enableRandromDrops(false); } #if 0 diff --git a/src/qgcunittest/FileManagerTest.h b/src/qgcunittest/FileManagerTest.h index 1f1dd1ab65eba20b1ee636df0f077b29a3591c28..50ab8af903f90c9da4d3bcb3ab8b4926604d754b 100644 --- a/src/qgcunittest/FileManagerTest.h +++ b/src/qgcunittest/FileManagerTest.h @@ -72,7 +72,7 @@ private: /// @brief This is the amount of time to wait to allow the FileManager enough time to timeout waiting for an Ack. /// As such it must be larger than the Ack Timeout used by the FileManager. - static const int _ackTimerTimeoutMsecs = FileManager::ackTimerTimeoutMsecs * 2; + static const int _ackTimerTimeoutMsecs = FileManager::ackTimerMaxRetries * FileManager::ackTimerTimeoutMsecs * 2; QStringList _fileListReceived; }; diff --git a/src/uas/FileManager.cc b/src/uas/FileManager.cc index 15f6ea623245c1cf1174a89debc36b7b906d88aa..db7fee8217203deb23b0edb2fcaa26d791155b0c 100644 --- a/src/uas/FileManager.cc +++ b/src/uas/FileManager.cc @@ -26,12 +26,15 @@ FileManager::FileManager(QObject* parent, Vehicle* vehicle) , _currentOperation(kCOIdle) , _vehicle(vehicle) , _dedicatedLink(NULL) - , _lastOutgoingSeqNumber(0) , _activeSession(0) + , _missingDownloadedBytes(0) + , _downloadingMissingParts(false) , _systemIdQGC(0) { connect(&_ackTimer, &QTimer::timeout, this, &FileManager::_ackTimeout); + _lastOutgoingRequest.hdr.seqNumber = 0; + _systemIdServer = _vehicle->id(); // Make sure we don't have bad structure packing @@ -55,6 +58,9 @@ void FileManager::_openAckResponse(Request* openAck) _downloadOffset = 0; // Start reading at beginning of file _readFileAccumulator.clear(); // Start with an empty file + _missingDownloadedBytes = 0; + _downloadingMissingParts = false; + _missingData.clear(); Request request; request.hdr.session = _activeSession; @@ -66,15 +72,54 @@ void FileManager::_openAckResponse(Request* openAck) _sendRequest(&request); } +/// request the next missing part of a (partially) downloaded file +void FileManager::_requestMissingData() +{ + 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(FileManagerLog) << QString("_requestMissingData: missing parts done, downloadOffset(%1) downloadFileSize(%2)") + .arg(_downloadOffset).arg(_downloadFileSize); + } else { + _closeDownloadSession(true); + return; + } + } else { + qCDebug(FileManagerLog) << QString("_requestMissingData: offset(%1) size(%2)").arg(_missingData.head().offset).arg(_missingData.head().size); + + _downloadOffset = _missingData.head().offset; + } + + Request request; + _currentOperation = kCORead; + request.hdr.session = _activeSession; + request.hdr.opcode = kCmdReadFile; + request.hdr.offset = _downloadOffset; + request.hdr.size = sizeof(request.data); + + _sendRequest(&request); +} + /// Closes out a download session by writing the file and doing cleanup. /// @param success true: successful download completion, false: error during download void FileManager::_closeDownloadSession(bool success) { - qCDebug(FileManagerLog) << QString("_closeDownloadSession: success(%1)").arg(success); + qCDebug(FileManagerLog) << QString("_closeDownloadSession: success(%1) missingBytes(%2)").arg(success).arg(_missingDownloadedBytes); _currentOperation = kCOIdle; if (success) { + if (_missingDownloadedBytes > 0 || (uint32_t)_readFileAccumulator.length() < _downloadFileSize) { + // we're not done yet: request the missing parts individually (either we had missing parts or + // the last (few) packets right before the EOF got dropped) + _downloadingMissingParts = true; + _requestMissingData(); + return; + } + QString downloadFilePath = _readFileDownloadDir.absoluteFilePath(_readFileDownloadFilename); QFile file(downloadFilePath); @@ -129,21 +174,51 @@ void FileManager::_downloadAckResponse(Request* readAck, bool readFile) } if (readAck->hdr.offset != _downloadOffset) { - _closeDownloadSession(false /* failure */); - _emitErrorMessage(tr("Download: Offset returned (%1) differs from offset requested/expected (%2)").arg(readAck->hdr.offset).arg(_downloadOffset)); - return; + if (readFile) { + _closeDownloadSession(false /* failure */); + _emitErrorMessage(tr("Download: Offset returned (%1) differs from offset requested/expected (%2)").arg(readAck->hdr.offset).arg(_downloadOffset)); + return; + } else { // burst + if (readAck->hdr.offset < _downloadOffset) { // old data: ignore it + _setupAckTimeout(); + return; + } + // keep track of missing data chunks + MissingData missingData; + missingData.offset = _downloadOffset; + missingData.size = readAck->hdr.offset - _downloadOffset; + _missingData.push_back(missingData); + _missingDownloadedBytes += readAck->hdr.offset - _downloadOffset; + qCDebug(FileManagerLog) << QString("_downloadAckResponse: missing data: offset(%1) size(%2)").arg(missingData.offset).arg(missingData.size); + _downloadOffset = readAck->hdr.offset; + _readFileAccumulator.resize(_downloadOffset); // placeholder for the missing data + } } qCDebug(FileManagerLog) << QString("_downloadAckResponse: offset(%1) size(%2) burstComplete(%3)").arg(readAck->hdr.offset).arg(readAck->hdr.size).arg(readAck->hdr.burstComplete); - _downloadOffset += readAck->hdr.size; - _readFileAccumulator.append((const char*)readAck->data, readAck->hdr.size); + if (_downloadingMissingParts) { + Q_ASSERT(_missingData.head().offset == _downloadOffset); + _missingDownloadedBytes -= readAck->hdr.size; + _readFileAccumulator.replace(_downloadOffset, readAck->hdr.size, (const char*)readAck->data, readAck->hdr.size); + if (_missingData.head().size <= readAck->hdr.size) { + _missingData.pop_front(); + } else { + _missingData.head().size -= readAck->hdr.size; + _missingData.head().offset += readAck->hdr.size; + } + } else { + _downloadOffset += readAck->hdr.size; + _readFileAccumulator.append((const char*)readAck->data, readAck->hdr.size); + } if (_downloadFileSize != 0) { - emit commandProgress(100 * ((float)_readFileAccumulator.length() / (float)_downloadFileSize)); + emit commandProgress(100 * ((float)(_readFileAccumulator.length() - _missingDownloadedBytes) / (float)_downloadFileSize)); } - if (readFile || readAck->hdr.burstComplete) { + if (_downloadingMissingParts) { + _requestMissingData(); + } else if (readFile || readAck->hdr.burstComplete) { // Possibly still more data to read, send next read request Request request; @@ -163,6 +238,7 @@ void FileManager::_downloadAckResponse(Request* readAck, bool readFile) void FileManager::_listAckResponse(Request* listAck) { if (listAck->hdr.offset != _listOffset) { + // this is a real error (directory listing is synchronous), no need to retransmit _currentOperation = kCOIdle; _emitErrorMessage(tr("List: Offset returned (%1) differs from offset requested (%2)").arg(listAck->hdr.offset).arg(_listOffset)); return; @@ -303,7 +379,7 @@ void FileManager::receiveMessage(mavlink_message_t message) if (message.msgid != MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL) { return; } - + mavlink_file_transfer_protocol_t data; mavlink_msg_file_transfer_protocol_decode(&message, &data); @@ -314,18 +390,28 @@ void FileManager::receiveMessage(mavlink_message_t message) } Request* request = (Request*)&data.payload[0]; + + uint16_t incomingSeqNumber = request->hdr.seqNumber; + // Make sure we have a good sequence number + uint16_t expectedSeqNumber = _lastOutgoingRequest.hdr.seqNumber + 1; + + // ignore old/reordered packets (handle wrap-around properly) + if ((uint16_t)((expectedSeqNumber - 1) - incomingSeqNumber) < (std::numeric_limits::max()/2)) { + qDebug() << "Received old packet: expected seq:" << expectedSeqNumber << "got:" << incomingSeqNumber; + return; + } + _clearAckTimeout(); qCDebug(FileManagerLog) << "receiveMessage" << request->hdr.opcode; - uint16_t incomingSeqNumber = request->hdr.seqNumber; - - // Make sure we have a good sequence number - uint16_t expectedSeqNumber = _lastOutgoingSeqNumber + 1; if (incomingSeqNumber != expectedSeqNumber) { + bool doAbort = true; switch (_currentOperation) { - case kCOBurst: + case kCOBurst: // burst download drops are handled in _downloadAckResponse() + doAbort = false; + break; case kCORead: _closeDownloadSession(false /* failure */); break; @@ -348,12 +434,14 @@ void FileManager::receiveMessage(mavlink_message_t message) break; } - _emitErrorMessage(tr("Bad sequence number on received message: expected(%1) received(%2)").arg(expectedSeqNumber).arg(incomingSeqNumber)); - return; + if (doAbort) { + _emitErrorMessage(tr("Bad sequence number on received message: expected(%1) received(%2)").arg(expectedSeqNumber).arg(incomingSeqNumber)); + return; + } } // Move past the incoming sequence number for next request - _lastOutgoingSeqNumber = incomingSeqNumber; + _lastOutgoingRequest.hdr.seqNumber = incomingSeqNumber; if (request->hdr.opcode == kRspAck) { switch (request->hdr.req_opcode) { @@ -406,6 +494,9 @@ void FileManager::receiveMessage(mavlink_message_t message) } else if (request->hdr.req_opcode == kCmdCreateFile) { _emitErrorMessage(tr("Nak received creating file, error: %1").arg(errorString(request->data[0]))); return; + } else if (request->hdr.req_opcode == kCmdCreateDirectory) { + _emitErrorMessage(tr("Nak received creating directory, error: %1").arg(errorString(request->data[0]))); + return; } else { // Generic Nak handling if (request->hdr.req_opcode == kCmdReadFile || request->hdr.req_opcode == kCmdBurstReadFile) { @@ -538,7 +629,7 @@ void FileManager::_downloadWorker(const QString& from, const QDir& downloadDir, void FileManager::uploadPath(const QString& toPath, const QFileInfo& uploadFile) { if(_currentOperation != kCOIdle){ - _emitErrorMessage(tr("UAS File manager busy. Try again later")); + _emitErrorMessage(tr("UAS File manager busy. Try again later")); return; } @@ -584,6 +675,24 @@ void FileManager::uploadPath(const QString& toPath, const QFileInfo& uploadFile) _sendRequest(&request); } +void FileManager::createDirectory(const QString& directory) +{ + if(_currentOperation != kCOIdle){ + _emitErrorMessage(tr("UAS File manager busy. Try again later")); + return; + } + + _currentOperation = kCOCreateDir; + + Request request; + request.hdr.session = 0; + request.hdr.opcode = kCmdCreateDirectory; + request.hdr.offset = 0; + request.hdr.size = 0; + _fillRequestWithString(&request, directory); + _sendRequest(&request); +} + QString FileManager::errorString(uint8_t errorCode) { switch(errorCode) { @@ -643,7 +752,8 @@ void FileManager::_setupAckTimeout(void) Q_ASSERT(!_ackTimer.isActive()); - _ackTimer.setSingleShot(true); + _ackNumTries = 0; + _ackTimer.setSingleShot(false); _ackTimer.start(ackTimerTimeoutMsecs); } @@ -659,6 +769,26 @@ void FileManager::_ackTimeout(void) { qCDebug(FileManagerLog) << "_ackTimeout"; + if (++_ackNumTries <= ackTimerMaxRetries) { + qCDebug(FileManagerLog) << "ack timeout - retrying"; + if (_currentOperation == kCOBurst) { + // for burst downloads try to initiate a new burst + Request request; + request.hdr.session = _activeSession; + request.hdr.opcode = kCmdBurstReadFile; + request.hdr.offset = _downloadOffset; + request.hdr.size = 0; + request.hdr.seqNumber = ++_lastOutgoingRequest.hdr.seqNumber; + + _sendRequestNoAck(&request); + } else { + _sendRequestNoAck(&_lastOutgoingRequest); + } + return; + } + + _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. @@ -689,8 +819,11 @@ void FileManager::_ackTimeout(void) break; default: + { + OperationState currentOperation = _currentOperation; _currentOperation = kCOIdle; - _emitErrorMessage(QString("Timeout waiting for ack: Command failed (%1)").arg(_currentOperation)); + _emitErrorMessage(QString("Timeout waiting for ack: Command failed (%1)").arg(currentOperation)); + } break; } } @@ -719,19 +852,28 @@ void FileManager::_emitListEntry(const QString& entry) void FileManager::_sendRequest(Request* request) { - mavlink_message_t message; - _setupAckTimeout(); - _lastOutgoingSeqNumber++; - - request->hdr.seqNumber = _lastOutgoingSeqNumber; + request->hdr.seqNumber = ++_lastOutgoingRequest.hdr.seqNumber; + // store the current request + if (request->hdr.size <= sizeof(request->data)) { + memcpy(&_lastOutgoingRequest, request, sizeof(RequestHeader) + request->hdr.size); + } else { + qCCritical(FileManagerLog) << "request length too long:" << request->hdr.size; + } qCDebug(FileManagerLog) << "_sendRequest opcode:" << request->hdr.opcode << "seqNumber:" << request->hdr.seqNumber; if (_systemIdQGC == 0) { _systemIdQGC = qgcApp()->toolbox()->mavlinkProtocol()->getSystemId(); } + _sendRequestNoAck(request); +} + +/// @brief Sends the specified Request out to the UAS, without ack timeout handling +void FileManager::_sendRequestNoAck(Request* request) +{ + mavlink_message_t message; // Unit testing code can end up here without _dedicateLink set since it tests inidividual commands. LinkInterface* link; diff --git a/src/uas/FileManager.h b/src/uas/FileManager.h index c74d6aca620805763ec4dcc6b4bbd395aae04420..5c95a98080e556c5147e159351df330b0b5fb480 100644 --- a/src/uas/FileManager.h +++ b/src/uas/FileManager.h @@ -14,10 +14,18 @@ #include #include #include +#include #include "UASInterface.h" #include "QGCLoggingCategory.h" +#ifdef __GNUC__ + #define PACKED_STRUCT( __Declaration__ ) __Declaration__ __attribute__((packed)) +#else + #define PACKED_STRUCT( __Declaration__ ) __pragma( pack(push, 1) ) __Declaration__ __pragma( pack(pop) ) +#endif + + Q_DECLARE_LOGGING_CATEGORY(FileManagerLog) class Vehicle; @@ -35,7 +43,9 @@ public: /// Timeout in msecs to wait for an Ack time come back. This is public so we can write unit tests which wait long enough /// for the FileManager to timeout. - static const int ackTimerTimeoutMsecs = 10000; + static const int ackTimerTimeoutMsecs = 50; + + static const int ackTimerMaxRetries = 6; /// Downloads the specified file. /// @param from File to download from UAS, fully qualified path @@ -54,6 +64,9 @@ public: /// Upload the specified file to the specified location void uploadPath(const QString& toPath, const QFileInfo& uploadFile); + /// Create a remote directory + void createDirectory(const QString& directory); + signals: // Signals associated with the listDirectory method @@ -80,9 +93,11 @@ private slots: void _ackTimeout(void); private: - /// @brief This is the fixed length portion of the protocol data. Trying to pack structures across differing compilers is - /// questionable, so we pad the structure ourselves to 32 bit alignment which should get us what we want. - struct RequestHeader + /// @brief This is the fixed length portion of the protocol data. + /// This needs to be packed, because it's typecasted from mavlink_file_transfer_protocol_t.payload, which starts + /// at a 3 byte offset, causing an unaligned access to seq_number and offset + PACKED_STRUCT( + typedef struct _RequestHeader { uint16_t seqNumber; ///< sequence number for message uint8_t session; ///< Session id for read and write commands @@ -92,11 +107,12 @@ private: uint8_t burstComplete; ///< Only used if req_opcode=kCmdBurstReadFile - 1: set of burst packets complete, 0: More burst packets coming. uint8_t padding; ///< 32 bit aligment padding uint32_t offset; ///< Offsets for List and Read commands - }; + }) RequestHeader; - struct Request + PACKED_STRUCT( + typedef struct _Request { - struct RequestHeader hdr; + RequestHeader hdr; // We use a union here instead of just casting (uint32_t)&payload[0] to not break strict aliasing rules union { @@ -110,7 +126,7 @@ private: // Length of file chunk written by write command uint32_t writeFileLength; }; - }; + }) Request; enum Opcode { @@ -164,6 +180,7 @@ private: kCOBurst, // waiting for Burst response kCOWrite, // waiting for Write response kCOCreate, // waiting for Create response + kCOCreateDir, // waiting for Create Directory response }; bool _sendOpcodeOnlyCmd(uint8_t opcode, OperationState newOpState); @@ -172,6 +189,7 @@ private: void _emitErrorMessage(const QString& msg); void _emitListEntry(const QString& entry); void _sendRequest(Request* request); + void _sendRequestNoAck(Request* request); void _fillRequestWithString(Request* request, const QString& str); void _openAckResponse(Request* openAck); void _downloadAckResponse(Request* readAck, bool readFile); @@ -183,17 +201,19 @@ private: void _sendResetCommand(void); void _closeDownloadSession(bool success); void _closeUploadSession(bool success); - void _downloadWorker(const QString& from, const QDir& downloadDir, bool readFile); + void _downloadWorker(const QString& from, const QDir& downloadDir, bool readFile); + void _requestMissingData(); static QString errorString(uint8_t errorCode); OperationState _currentOperation; ///< Current operation of state machine QTimer _ackTimer; ///< Used to signal a timeout waiting for an ack + int _ackNumTries; ///< current number of tries Vehicle* _vehicle; LinkInterface* _dedicatedLink; ///< Link to use for communication - uint16_t _lastOutgoingSeqNumber; ///< Sequence number sent in last outgoing packet + Request _lastOutgoingRequest; ///< contains the last outgoing packet unsigned _listOffset; ///< offset for the current List operation QString _listPath; ///< path for the current List operation @@ -207,7 +227,14 @@ private: uint32_t _writeFileSize; ///< Size of file being uploaded QByteArray _writeFileAccumulator; ///< Holds file being uploaded + struct MissingData { + uint32_t offset; + uint32_t size; + }; uint32_t _downloadOffset; ///< current download offset + uint32_t _missingDownloadedBytes; ///< number of missing bytes for burst download + QQueue _missingData; ///< missing chunks of downloaded file (for burst downloads) + bool _downloadingMissingParts; ///< true if we are currently downloading missing parts QByteArray _readFileAccumulator; ///< Holds file being downloaded QDir _readFileDownloadDir; ///< Directory to download file to QString _readFileDownloadFilename; ///< Filename (no path) for download file