Commit f534aa7e authored by Don Gagne's avatar Don Gagne

Bug fixes in download

parent 956d25e3
......@@ -32,13 +32,13 @@
QGC_LOGGING_CATEGORY(FileManagerLog, "FileManagerLog")
FileManager::FileManager(QObject* parent, UASInterface* uas, uint8_t unitTestSystemIdQGC) :
FileManager::FileManager(QObject* parent, UASInterface* uas) :
QObject(parent),
_currentOperation(kCOIdle),
_mav(uas),
_lastOutgoingSeqNumber(0),
_activeSession(0),
_systemIdQGC(unitTestSystemIdQGC)
_systemIdQGC(0)
{
connect(&_ackTimer, &QTimer::timeout, this, &FileManager::_ackTimeout);
......@@ -104,8 +104,8 @@ void FileManager::_closeDownloadSession(bool success)
emit commandComplete();
}
// If !success error is emitted elsewhere
_readFileAccumulator.clear();
// Close the open session
_sendResetCommand();
}
......@@ -153,24 +153,19 @@ void FileManager::_downloadAckResponse(Request* readAck, bool readFile)
emit commandProgress(100 * ((float)_readFileAccumulator.length() / (float)_downloadFileSize));
}
if (readAck->hdr.size == sizeof(readAck->data)) {
if (readFile || readAck->hdr.burstComplete) {
// Possibly still more data to read, send next read request
if (readFile || readAck->hdr.burstComplete) {
// Possibly still more data to read, send next read request
Request request;
request.hdr.session = _activeSession;
request.hdr.opcode = readFile ? kCmdReadFile : kCmdBurstReadFile;
request.hdr.offset = _downloadOffset;
request.hdr.size = 0;
Request request;
request.hdr.session = _activeSession;
request.hdr.opcode = readFile ? kCmdReadFile : kCmdBurstReadFile;
request.hdr.offset = _downloadOffset;
request.hdr.size = 0;
_sendRequest(&request);
} else {
// Streaming, so next ack should come automatically
_setupAckTimeout();
}
} else if (readFile) {
// We only receieved a partial buffer back. These means we are at EOF
_closeDownloadSession(true /* success */);
_sendRequest(&request);
} else if (!readFile) {
// Streaming, so next ack should come automatically
_setupAckTimeout();
}
}
......@@ -340,7 +335,30 @@ void FileManager::receiveMessage(LinkInterface* link, mavlink_message_t message)
// Make sure we have a good sequence number
uint16_t expectedSeqNumber = _lastOutgoingSeqNumber + 1;
if (incomingSeqNumber != expectedSeqNumber) {
_currentOperation = kCOIdle;
switch (_currentOperation) {
case kCOBurst:
case kCORead:
_closeDownloadSession(false /* failure */);
break;
case kCOWrite:
_closeUploadSession(false /* failure */);
break;
case kCOOpenRead:
case kCOOpenBurst:
case kCOCreate:
// We could have an open session hanging around
_currentOperation = kCOIdle;
_sendResetCommand();
break;
default:
// Don't need to do anything special
_currentOperation = kCOIdle;
break;
}
_emitErrorMessage(tr("Bad sequence number on received message: expected(%1) received(%2)").arg(expectedSeqNumber).arg(incomingSeqNumber));
return;
}
......@@ -457,12 +475,22 @@ void FileManager::_sendListCommand(void)
void FileManager::downloadPath(const QString& from, const QDir& downloadDir)
{
if (_currentOperation != kCOIdle) {
_emitErrorMessage(tr("Command not sent. Waiting for previous command to complete."));
return;
}
qCDebug(FileManagerLog) << "downloadPath from:" << from << "to:" << downloadDir;
_downloadWorker(from, downloadDir, true /* read file */);
}
void FileManager::streamPath(const QString& from, const QDir& downloadDir)
{
if (_currentOperation != kCOIdle) {
_emitErrorMessage(tr("Command not sent. Waiting for previous command to complete."));
return;
}
qCDebug(FileManagerLog) << "streamPath from:" << from << "to:" << downloadDir;
_downloadWorker(from, downloadDir, false /* stream file */);
}
......@@ -677,7 +705,6 @@ void FileManager::_emitListEntry(const QString& entry)
/// @brief Sends the specified Request out to the UAS.
void FileManager::_sendRequest(Request* request)
{
qCDebug(FileManagerLog) << "_sendRequest opcode:" << request->hdr.opcode;
mavlink_message_t message;
......@@ -687,6 +714,8 @@ void FileManager::_sendRequest(Request* request)
request->hdr.seqNumber = _lastOutgoingSeqNumber;
qCDebug(FileManagerLog) << "_sendRequest opcode:" << request->hdr.opcode << "seqNumber:" << request->hdr.seqNumber;
if (_systemIdQGC == 0) {
_systemIdQGC = MAVLinkProtocol::instance()->getSystemId();
}
......
......@@ -37,12 +37,11 @@ class FileManager : public QObject
Q_OBJECT
public:
FileManager(QObject* parent, UASInterface* uas, uint8_t unitTestSystemIdQGC = 0);
FileManager(QObject* parent, UASInterface* uas);
/// These methods are only used for testing purposes.
bool _sendCmdTestAck(void) { return _sendOpcodeOnlyCmd(kCmdNone, kCOAck); };
bool _sendCmdTestNoAck(void) { return _sendOpcodeOnlyCmd(kCmdTestNoAck, kCOAck); };
bool _sendCmdReset(void) { return _sendOpcodeOnlyCmd(kCmdResetSessions, kCOAck); };
/// 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.
......@@ -226,9 +225,9 @@ private:
uint8_t _systemIdQGC; ///< System ID for QGC
uint8_t _systemIdServer; ///< System ID for server
// We give MockMavlinkFileServer friend access so that it can use the data structures and opcodes
// We give MockLinkFileServer friend access so that it can use the data structures and opcodes
// to build a mock mavlink file server for testing.
friend class MockMavlinkFileServer;
friend class MockLinkFileServer;
};
#endif // FileManager_H
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment