diff --git a/src/qgcunittest/MockMavlinkFileServer.cc b/src/qgcunittest/MockMavlinkFileServer.cc index 8264edb4aecc10d4ef3a9c54a057ac6400cf078a..ef56b6ac88bf11f749139f0e5e75a1c103e5476b 100644 --- a/src/qgcunittest/MockMavlinkFileServer.cc +++ b/src/qgcunittest/MockMavlinkFileServer.cc @@ -23,20 +23,31 @@ #include "MockMavlinkFileServer.h" -const char* MockMavlinkFileServer::smallFilename = "small"; -const char* MockMavlinkFileServer::largeFilename = "large"; - -// FIXME: -2 to avoid eof on full packet -const uint8_t MockMavlinkFileServer::smallFileLength = sizeof(((QGCUASFileManager::Request*)0)->data) - 2; -const uint8_t MockMavlinkFileServer::largeFileLength = sizeof(((QGCUASFileManager::Request*)0)->data) + 1; +const MockMavlinkFileServer::FileTestCase MockMavlinkFileServer::rgFileTestCases[MockMavlinkFileServer::cFileTestCases] = { + // File fits one Read Ack packet, partially filling data + { "partial.qgc", sizeof(((QGCUASFileManager::Request*)0)->data) - 1 }, + // File fits one Read Ack packet, exactly filling all data + { "exact.qgc", sizeof(((QGCUASFileManager::Request*)0)->data) }, + // File is larger than a single Read Ack packets, requires multiple Reads + { "multi.qgc", sizeof(((QGCUASFileManager::Request*)0)->data) + 1 }, +}; +// We only support a single fixed session const uint8_t MockMavlinkFileServer::_sessionId = 1; +MockMavlinkFileServer::MockMavlinkFileServer(void) +{ + +} + + /// @brief Handles List command requests. Only supports root folder paths. /// File list returned is set using the setFileList method. void MockMavlinkFileServer::_listCommand(QGCUASFileManager::Request* request) { + // FIXME: Does not support directories that span multiple packets + QGCUASFileManager::Request ackResponse; QString path; @@ -56,7 +67,9 @@ void MockMavlinkFileServer::_listCommand(QGCUASFileManager::Request* request) ackResponse.hdr.magic = 'f'; ackResponse.hdr.opcode = QGCUASFileManager::kRspAck; ackResponse.hdr.session = 0; + ackResponse.hdr.offset = request->hdr.offset; ackResponse.hdr.size = 0; + ackResponse.hdr.errCode = QGCUASFileManager::kErrNone; if (request->hdr.offset == 0) { // Requesting first batch of file names @@ -69,42 +82,35 @@ void MockMavlinkFileServer::_listCommand(QGCUASFileManager::Request* request) ackResponse.hdr.size += cchFilename + 1; bufPtr += cchFilename + 1; } - - // Final double termination - *bufPtr = 0; - ackResponse.hdr.size++; - } else { - // All filenames fit in first ack, send final null terminated ack - ackResponse.data[0] = 0; - ackResponse.hdr.size = 1; + // FIXME: Does not support directories that span multiple packets + _sendNak(QGCUASFileManager::kErrEOF); } _emitResponse(&ackResponse); } -/// @brief Handles Open command requests. Two filenames are supported: -/// '/small' - file fits in a single packet -/// '/large' - file requires multiple packets to be sent -/// In all cases file contents are one byte data length, followed by a single -/// byte repeating increasing sequence (0x00, 0x01, .. 0xFF) for specified -/// number of bytes. +/// @brief Handles Open command requests. void MockMavlinkFileServer::_openCommand(QGCUASFileManager::Request* request) { QGCUASFileManager::Request response; QString path; - // Make sure one byte of length is enough to overflow into two packets. - Q_ASSERT((sizeof(request->data) & 0xFF) == sizeof(request->data)); + size_t cchPath = strnlen((char *)request->data, sizeof(request->data)); + Q_ASSERT(cchPath != sizeof(request->data)); + path = (char *)request->data; + + // Check path against one of our known test cases - path = (char *)&request->data[0]; - if (path == smallFilename) { - _readFileLength = smallFileLength; - qDebug() << "Reading file length" << smallFileLength; - } else if (path == largeFilename) { - _readFileLength = largeFileLength; - qDebug() << "Reading file length" << largeFileLength; - } else { + bool found = false; + for (size_t i=0; ihdr.offset; - QGCUASFileManager::Request response; if (request->hdr.session != _sessionId) { @@ -129,53 +134,70 @@ void MockMavlinkFileServer::_readCommand(QGCUASFileManager::Request* request) return; } - if (request->hdr.size > sizeof(response.data)) { - _sendNak(QGCUASFileManager::kErrPerm); - return; - } - - uint8_t size = 0; - uint32_t offset = request->hdr.offset; + uint32_t readOffset = request->hdr.offset; // offset into file for reading + uint8_t cDataBytes = 0; // current number of data bytes used - // Offset check is > instead of >= to take into accoutn extra length byte at beginning of file - if (offset > _readFileLength) { - _sendNak(QGCUASFileManager::kErrIO); + if (readOffset > _readFileLength) { + _sendNak(QGCUASFileManager::kErrEOF); return; } // Write length byte if needed - if (offset == 0) { + if (readOffset == 0) { response.data[0] = _readFileLength; - offset++; - size++; + readOffset++; + cDataBytes++; } // Write file bytes. Data is a repeating sequence of 0x00, 0x01, .. 0xFF. - for (; size < sizeof(response.data) && offset <= _readFileLength; offset++, size++) { - response.data[size] = (offset - 1) & 0xFF; + for (; cDataBytes < sizeof(response.data) && readOffset < _readFileLength; readOffset++, cDataBytes++) { + // Subtract one from readOffset to take into account length byte and start file data a 0x00 + response.data[cDataBytes] = (readOffset - 1) & 0xFF; } - qDebug() << "_readCommand bytes written" << size; - - // If we didn't write any bytes it was a bad request - if (size == 0) { - _sendNak(QGCUASFileManager::kErrEOF); - return; - } + // We should always have written something, otherwise there is something wrong with the code above + Q_ASSERT(cDataBytes); response.hdr.magic = 'f'; response.hdr.opcode = QGCUASFileManager::kRspAck; response.hdr.session = _sessionId; - response.hdr.size = size; + response.hdr.size = cDataBytes; response.hdr.offset = request->hdr.offset; + if (readOffset >= _readFileLength) { + // Something wrong with the reading code, should not have gone past last byte + Q_ASSERT(readOffset == _readFileLength); + + // We have read all the bytes in the file + response.hdr.errCode = QGCUASFileManager::kErrNone; + + } else { + // There are still more bytes left to read in the file + response.hdr.errCode = QGCUASFileManager::kErrMore; + } + _emitResponse(&response); } +/// @brief Handles Terminate commands +void MockMavlinkFileServer::_terminateCommand(QGCUASFileManager::Request* request) +{ + if (request->hdr.session != _sessionId) { + _sendNak(QGCUASFileManager::kErrNoSession); + return; + } + + _sendAck(); + + // Let our test harness know that we got a terminate command. This is used to validate the a Terminate is correctly + // sent after an Open. + emit terminateCommandReceived(); +} + /// @brief Handles messages sent to the FTP server. void MockMavlinkFileServer::sendMessage(mavlink_message_t message) { - QGCUASFileManager::Request ackResponse; + QGCUASFileManager::Request ackResponse; Q_ASSERT(message.msgid == MAVLINK_MSG_ID_ENCAPSULATED_DATA); @@ -204,6 +226,7 @@ void MockMavlinkFileServer::sendMessage(mavlink_message_t message) ackResponse.hdr.session = 0; ackResponse.hdr.crc32 = 0; ackResponse.hdr.size = 0; + ackResponse.hdr.errCode = QGCUASFileManager::kErrNone; _emitResponse(&ackResponse); break; @@ -219,10 +242,12 @@ void MockMavlinkFileServer::sendMessage(mavlink_message_t message) _readCommand(request); break; + case QGCUASFileManager::kCmdTerminate: + _terminateCommand(request); + break; + // Remainder of commands are NYI - case QGCUASFileManager::kCmdTerminate: - // releases sessionID, closes file case QGCUASFileManager::kCmdCreate: // creates for writing, returns case QGCUASFileManager::kCmdWrite: @@ -236,6 +261,20 @@ void MockMavlinkFileServer::sendMessage(mavlink_message_t message) } } +/// @brief Sends an Ack +void MockMavlinkFileServer::_sendAck(void) +{ + QGCUASFileManager::Request ackResponse; + + ackResponse.hdr.magic = 'f'; + ackResponse.hdr.opcode = QGCUASFileManager::kRspAck; + ackResponse.hdr.session = 0; + ackResponse.hdr.size = 0; + ackResponse.hdr.errCode = QGCUASFileManager::kErrNone; + + _emitResponse(&ackResponse); +} + /// @brief Sends a Nak with the specified error code. void MockMavlinkFileServer::_sendNak(QGCUASFileManager::ErrorCode error) { @@ -244,8 +283,8 @@ void MockMavlinkFileServer::_sendNak(QGCUASFileManager::ErrorCode error) nakResponse.hdr.magic = 'f'; nakResponse.hdr.opcode = QGCUASFileManager::kRspNak; nakResponse.hdr.session = 0; - nakResponse.hdr.size = sizeof(nakResponse.data[0]); - nakResponse.data[0] = error; + nakResponse.hdr.size = 0; + nakResponse.hdr.errCode = error; _emitResponse(&nakResponse); } diff --git a/src/qgcunittest/MockMavlinkFileServer.h b/src/qgcunittest/MockMavlinkFileServer.h index 6abe12fc8d0206db01b1e4ead1906d21b761c335..7c581c788b26dce8b36aa3a77f75ccc4f6a3267d 100644 --- a/src/qgcunittest/MockMavlinkFileServer.h +++ b/src/qgcunittest/MockMavlinkFileServer.h @@ -40,7 +40,7 @@ class MockMavlinkFileServer : public MockMavlinkInterface Q_OBJECT public: - MockMavlinkFileServer(void) { }; + MockMavlinkFileServer(void); /// @brief Sets the list of files returned by the List command. Prepend names with F or D /// to indicate (F)ile or (D)irectory. @@ -49,17 +49,25 @@ public: // From MockMavlinkInterface virtual void sendMessage(mavlink_message_t message); - static const char* smallFilename; - static const char* largeFilename; - static const uint8_t smallFileLength; - static const uint8_t largeFileLength; + struct FileTestCase { + const char* filename; + uint8_t length; + }; + + static const size_t cFileTestCases = 3; + static const FileTestCase rgFileTestCases[cFileTestCases]; + +signals: + void terminateCommandReceived(void); private: + void _sendAck(void); void _sendNak(QGCUASFileManager::ErrorCode error); void _emitResponse(QGCUASFileManager::Request* request); void _listCommand(QGCUASFileManager::Request* request); void _openCommand(QGCUASFileManager::Request* request); void _readCommand(QGCUASFileManager::Request* request); + void _terminateCommand(QGCUASFileManager::Request* request); QStringList _fileList; ///< List of files returned by List command diff --git a/src/qgcunittest/QGCUASFileManagerTest.cc b/src/qgcunittest/QGCUASFileManagerTest.cc index c18b1162c5898b2c549b0da03331683a893d6e32..7da1dbdab6e78af49fa93ffccaa6795dbcd7246a 100644 --- a/src/qgcunittest/QGCUASFileManagerTest.cc +++ b/src/qgcunittest/QGCUASFileManagerTest.cc @@ -132,7 +132,7 @@ void QGCUASFileManagerUnitTest::_listTest(void) // Send a bogus path // We should get a single resetStatusMessages signal // We should get a single errorMessage signal - _fileManager->listRecursively("/bogus"); + _fileManager->listDirectory("/bogus"); QCOMPARE(_multiSpy->checkOnlySignalByMask(errorMessageSignalMask | resetStatusMessagesSignalMask), true); _multiSpy->clearAllSignals(); @@ -151,7 +151,7 @@ void QGCUASFileManagerUnitTest::_listTest(void) _fileListReceived.clear(); - _fileManager->listRecursively("/"); + _fileManager->listDirectory("/"); QCOMPARE(_multiSpy->checkSignalByMask(resetStatusMessagesSignalMask), true); // We should be told to reset status messages QCOMPARE(_multiSpy->checkNoSignalByMask(errorMessageSignalMask), true); // We should not get an error signals QVERIFY(_fileListReceived == fileListExpected); @@ -160,16 +160,20 @@ void QGCUASFileManagerUnitTest::_listTest(void) void QGCUASFileManagerUnitTest::_validateFileContents(const QString& filePath, uint8_t length) { QFile file(filePath); + + // Make sure file size is correct + QCOMPARE(file.size(), (qint64)length); + + // Read data QVERIFY(file.open(QIODevice::ReadOnly)); QByteArray bytes = file.readAll(); file.close(); - QCOMPARE(bytes.length(), length + 1); // +1 for length byte - // Validate length byte QCOMPARE((uint8_t)bytes[0], length); - // Validate file contents + // Validate file contents: + // Repeating 0x00, 0x01 .. 0xFF until file is full for (uint8_t i=1; iclearAllSignals(); // Clean previous downloads - - QString smallFilePath; - smallFilePath = QDir::temp().absoluteFilePath(MockMavlinkFileServer::smallFilename); - if (QFile::exists(smallFilePath)) { - Q_ASSERT(QFile::remove(smallFilePath)); - } - - QString largeFilePath; - largeFilePath = QDir::temp().absoluteFilePath(MockMavlinkFileServer::largeFilename); - if (QFile::exists(largeFilePath)) { - Q_ASSERT(QFile::remove(largeFilePath)); + for (size_t i=0; idownloadPath(MockMavlinkFileServer::smallFilename, QDir::temp()); - QCOMPARE(_multiSpy->checkOnlySignalByMask(statusMessageSignalMask | resetStatusMessagesSignalMask), true); - _multiSpy->clearAllSignals(); - _validateFileContents(smallFilePath, MockMavlinkFileServer::smallFileLength); - _fileManager->downloadPath(MockMavlinkFileServer::largeFilename, QDir::temp()); - QCOMPARE(_multiSpy->checkOnlySignalByMask(statusMessageSignalMask | resetStatusMessagesSignalMask), true); - _multiSpy->clearAllSignals(); - _validateFileContents(largeFilePath, MockMavlinkFileServer::largeFileLength); + // Run through the set of file test cases + + // We setup a spy on the terminate command signal so that we can determine that a Terminate command was + // correctly sent after the Open/Read commands complete. + QSignalSpy terminateSpy(&_mockFileServer, SIGNAL(terminateCommandReceived())); + + for (size_t i=0; idownloadPath(MockMavlinkFileServer::rgFileTestCases[i].filename, QDir::temp()); + + // We should get a single resetStatusMessages signal + // We should get a single statusMessage signal, which indicated download completion + QCOMPARE(_multiSpy->checkOnlySignalByMask(statusMessageSignalMask | resetStatusMessagesSignalMask), true); + _multiSpy->clearAllSignals(); + + // We should get a single Terminate command + QCOMPARE(terminateSpy.count(), 1); + terminateSpy.clear(); + + QString filePath = QDir::temp().absoluteFilePath(MockMavlinkFileServer::rgFileTestCases[i].filename); + _validateFileContents(filePath, MockMavlinkFileServer::rgFileTestCases[i].length); + } } diff --git a/src/uas/QGCUASFileManager.cc b/src/uas/QGCUASFileManager.cc index 1efe9b2ffc15967612204309929995a18890d236..41412c03377471a833ad589f749ce8f5cd6db28b 100644 --- a/src/uas/QGCUASFileManager.cc +++ b/src/uas/QGCUASFileManager.cc @@ -104,13 +104,14 @@ void QGCUASFileManager::nothingMessage() // FIXME: Connect ui correctly } -/// @brief Respond to the Ack associated with the Open command. -void QGCUASFileManager::_openResponse(Request* openAck) +/// @brief Respond to the Ack associated with the Open command with the next Read command. +void QGCUASFileManager::_openAckResponse(Request* openAck) { _currentOperation = kCORead; _activeSession = openAck->hdr.session; - _readOffset = 0; - _readFileAccumulator.clear(); + + _readOffset = 0; // Start reading at beginning of file + _readFileAccumulator.clear(); // Start with an empty file Request request; request.hdr.magic = 'f'; @@ -123,7 +124,7 @@ void QGCUASFileManager::_openResponse(Request* openAck) } /// @brief Respond to the Ack associated with the Read command. -void QGCUASFileManager::_readResponse(Request* readAck) +void QGCUASFileManager::_readAckResponse(Request* readAck) { if (readAck->hdr.session != _activeSession) { _currentOperation = kCOIdle; @@ -139,24 +140,27 @@ void QGCUASFileManager::_readResponse(Request* readAck) return; } - qDebug() << "Accumulator size" << readAck->hdr.size; _readFileAccumulator.append((const char*)readAck->data, readAck->hdr.size); - if (readAck->hdr.size == sizeof(readAck->data)) { - // Still more data to read + if (readAck->hdr.errCode == kErrMore) { + // Still more data to read, send next read request + _currentOperation = kCORead; - _readOffset += sizeof(readAck->data); + _readOffset += readAck->hdr.size; Request request; request.hdr.magic = 'f'; request.hdr.session = _activeSession; request.hdr.opcode = kCmdRead; request.hdr.offset = _readOffset; - request.hdr.size = sizeof(request.data); _sendRequest(&request); } else { + // We're at the end of the file, we can write it out now + + Q_ASSERT(readAck->hdr.errCode == kErrNone); + _currentOperation = kCOIdle; QString downloadFilePath = _readFileDownloadDir.absoluteFilePath(_readFileDownloadFilename); @@ -176,6 +180,70 @@ void QGCUASFileManager::_readResponse(Request* readAck) file.close(); _emitStatusMessage(tr("Download complete '%1'").arg(downloadFilePath)); + + // Close the open session + _sendTerminateCommand(); + } +} + +/// @brief Respond to the Ack associated with the List command. +void QGCUASFileManager::_listAckResponse(Request* listAck) +{ + if (listAck->hdr.offset != _listOffset) { + _currentOperation = kCOIdle; + _emitErrorMessage(tr("List: Offset returned (%1) differs from offset requested (%2)").arg(listAck->hdr.offset).arg(_listOffset)); + return; + } + + uint8_t offset = 0; + uint8_t cListEntries = 0; + uint8_t cBytes = listAck->hdr.size; + + // parse filenames out of the buffer + while (offset < cBytes) { + const char * ptr = ((const char *)listAck->data) + offset; + + // get the length of the name + uint8_t cBytesLeft = cBytes - offset; + size_t nlen = strnlen(ptr, cBytesLeft); + if (nlen < 2) { + _currentOperation = kCOIdle; + _emitErrorMessage(tr("Incorrectly formed list entry: '%1'").arg(ptr)); + return; + } else if (nlen == cBytesLeft) { + _currentOperation = kCOIdle; + _emitErrorMessage(tr("Missing NULL termination in list entry")); + return; + } + + // Returned names are prepended with D for directory or F for file + QString s(ptr + 1); + if (*ptr == 'D') { + s.append('/'); + } else if (*ptr != 'F') { + _currentOperation = kCOIdle; + _emitErrorMessage(tr("Unknown prefix list entry: '%1'").arg(ptr)); + return; + } + + // put it in the view + _emitStatusMessage(s); + + // account for the name + NUL + offset += nlen + 1; + + cListEntries++; + } + + if (listAck->hdr.errCode == kErrMore) { + // Still more data to read, send next list request + _currentOperation = kCOList; + _listOffset += cListEntries; + _sendListCommand(); + } else { + // We've gotten the last list entries we can go back to idle + Q_ASSERT(listAck->hdr.errCode == kErrNone); + _currentOperation = kCOIdle; } } @@ -200,7 +268,6 @@ void QGCUASFileManager::receiveMessage(LinkInterface* link, mavlink_message_t me switch (_currentOperation) { case kCOIdle: // we should not be seeing anything here.. shut the other guy up - qDebug() << "FTP resetting file transfer session"; _sendCmdReset(); break; @@ -210,15 +277,15 @@ void QGCUASFileManager::receiveMessage(LinkInterface* link, mavlink_message_t me break; case kCOList: - listDecode(&request->data[0], request->hdr.size); + _listAckResponse(request); break; case kCOOpen: - _openResponse(request); + _openAckResponse(request); break; case kCORead: - _readResponse(request); + _readAckResponse(request); break; default: @@ -227,7 +294,7 @@ void QGCUASFileManager::receiveMessage(LinkInterface* link, mavlink_message_t me } } else if (request->hdr.opcode == kRspNak) { _clearAckTimeout(); - _emitErrorMessage(QString("Nak received, error: ").append(errorString(request->data[0]))); + _emitErrorMessage(tr("Nak received, error: %1").arg(request->hdr.errCode)); _currentOperation = kCOIdle; } else { // Note that we don't change our operation state. If something goes wrong beyond this, the operation @@ -236,7 +303,7 @@ void QGCUASFileManager::receiveMessage(LinkInterface* link, mavlink_message_t me } } -void QGCUASFileManager::listRecursively(const QString &from) +void QGCUASFileManager::listDirectory(const QString& dirPath) { if (_currentOperation != kCOIdle) { _emitErrorMessage(tr("Command not sent. Waiting for previous command to complete.")); @@ -247,55 +314,12 @@ void QGCUASFileManager::listRecursively(const QString &from) emit resetStatusMessages(); // initialise the lister - _listPath = from; + _listPath = dirPath; _listOffset = 0; _currentOperation = kCOList; // and send the initial request - sendList(); -} - -void QGCUASFileManager::listDecode(const uint8_t *data, unsigned len) -{ - unsigned offset = 0; - unsigned files = 0; - - // parse filenames out of the buffer - while (offset < len) { - const char * ptr = (const char *)data + offset; - - // get the length of the name - unsigned nlen = strnlen(ptr, len - offset); - if (nlen < 2) { - break; - } - - // Returned names are prepended with D for directory or F for file - QString s(ptr + 1); - if (*ptr == 'D') { - s.append('/'); - } - - // put it in the view - _emitStatusMessage(s); - - // account for the name + NUL - offset += nlen + 1; - - // account for the file - files++; - } - - // we have run out of files to list - if (files == 0) { - _currentOperation = kCOIdle; - } else { - // update our state - _listOffset += files; - - // and send another request - sendList(); - } + _sendListCommand(); } void QGCUASFileManager::_fillRequestWithString(Request* request, const QString& str) @@ -304,7 +328,7 @@ void QGCUASFileManager::_fillRequestWithString(Request* request, const QString& request->hdr.size = strnlen((const char *)&request->data[0], sizeof(request->data)); } -void QGCUASFileManager::sendList() +void QGCUASFileManager::_sendListCommand(void) { Request request; @@ -432,8 +456,26 @@ void QGCUASFileManager::_clearAckTimeout(void) /// @brief Called when ack timeout timer fires void QGCUASFileManager::_ackTimeout(void) { - _currentOperation = kCOIdle; _emitErrorMessage(tr("Timeout waiting for ack")); + + switch (_currentOperation) { + case kCORead: + _currentOperation = kCOAck; + _sendTerminateCommand(); + break; + default: + _currentOperation = kCOIdle; + break; + } +} + +void QGCUASFileManager::_sendTerminateCommand(void) +{ + Request request; + request.hdr.magic = 'f'; + request.hdr.session = _activeSession; + request.hdr.opcode = kCmdTerminate; + _sendRequest(&request); } void QGCUASFileManager::_emitErrorMessage(const QString& msg) diff --git a/src/uas/QGCUASFileManager.h b/src/uas/QGCUASFileManager.h index 408c74c35ba31a82e039931bd1281b0e12d9c29b..48fb5be1793d23df9963806741a90bf8b0c46bab 100644 --- a/src/uas/QGCUASFileManager.h +++ b/src/uas/QGCUASFileManager.h @@ -48,18 +48,19 @@ signals: public slots: void receiveMessage(LinkInterface* link, mavlink_message_t message); void nothingMessage(); - void listRecursively(const QString &from); + void listDirectory(const QString& dirPath); void downloadPath(const QString& from, const QDir& downloadDir); protected: struct RequestHeader { - uint8_t magic; - uint8_t session; - uint8_t opcode; - uint8_t size; - uint32_t crc32; - uint32_t offset; + uint8_t magic; ///> Magic byte 'f' to idenitfy FTP protocol + uint8_t session; ///> Session id for read and write commands + uint8_t opcode; ///> Command opcode + uint8_t size; ///> Size of data + uint32_t crc32; ///> CRC for entire Request structure, with crc32 set to 0 + uint32_t offset; ///> Offsets for List and Read commands + uint8_t errCode; ///> Error code from Ack and Naks (ignored for commands) }; struct Request @@ -72,25 +73,29 @@ protected: enum Opcode { - kCmdNone, // ignored, always acked - kCmdTerminate, // releases sessionID, closes file - kCmdReset, // terminates all sessions - kCmdList, // list files in from - kCmdOpen, // opens for reading, returns - kCmdRead, // reads bytes from in - kCmdCreate, // creates for writing, returns - kCmdWrite, // appends bytes at in - kCmdRemove, // remove file (only if created by server?) - - kRspAck, - kRspNak, + // Commands + kCmdNone, ///> ignored, always acked + kCmdTerminate, ///> releases sessionID, closes file + kCmdReset, ///> terminates all sessions + kCmdList, ///> list files in from + kCmdOpen, ///> opens for reading, returns + kCmdRead, ///> reads bytes from in + kCmdCreate, ///> creates for writing, returns + kCmdWrite, ///> appends bytes at in + kCmdRemove, ///> remove file (only if created by server?) + + // Responses + kRspAck, ///> positive acknowledgement of previous command + kRspNak, ///> negative acknowledgement of previous command - kCmdTestNoAck, // ignored, ack not sent back, for testing only, should timeout waiting for ack + // Used for testing only, not part of protocol + kCmdTestNoAck, // ignored, ack not sent back, should timeout waiting for ack }; enum ErrorCode { kErrNone, + kErrMore, kErrNoRequest, kErrNoSession, kErrSequence, @@ -127,12 +132,12 @@ protected: void _emitStatusMessage(const QString& msg); void _sendRequest(Request* request); void _fillRequestWithString(Request* request, const QString& str); - void _openResponse(Request* openAck); - void _readResponse(Request* readAck); - - void sendList(); - void listDecode(const uint8_t *data, unsigned len); - + void _openAckResponse(Request* openAck); + void _readAckResponse(Request* readAck); + void _listAckResponse(Request* listAck); + void _sendListCommand(void); + void _sendTerminateCommand(void); + static quint32 crc32(Request* request, unsigned state = 0); static QString errorString(uint8_t errorCode); diff --git a/src/ui/QGCUASFileView.cc b/src/ui/QGCUASFileView.cc index f9323489490d348c18926d54f450d347a64a6be6..55412e18f815ba17135efee732b3de831b6c125f 100644 --- a/src/ui/QGCUASFileView.cc +++ b/src/ui/QGCUASFileView.cc @@ -28,7 +28,7 @@ QGCUASFileView::~QGCUASFileView() void QGCUASFileView::listFiles() { - _manager->listRecursively(ui->pathLineEdit->text()); + _manager->listDirectory(ui->pathLineEdit->text()); } void QGCUASFileView::downloadFiles()