Unverified Commit ec4bb916 authored by Don Gagne's avatar Don Gagne Committed by GitHub

FTP Manager rewrite, COMPONENT_INFORMATION fixes (#9139)

* Use correct key names

* Rewrite FTPManager

* Fix Reset Session at end of download

* Fixes for metadata download
parent d33b2f0b
......@@ -31,8 +31,10 @@ CompInfoParam::CompInfoParam(uint8_t compId, Vehicle* vehicle, QObject* parent)
}
void CompInfoParam::setJson(const QString& metadataJsonFileName, const QString& /*translationJsonFileName*/)
void CompInfoParam::setJson(const QString& metadataJsonFileName, const QString& translationJsonFileName)
{
qCDebug(CompInfoParamLog) << "setJson: metadataJsonFileName:translationJsonFileName" << metadataJsonFileName << translationJsonFileName;
if (metadataJsonFileName.isEmpty()) {
// This will fall back to using the old FirmwarePlugin mechanism for parameter meta data.
// In this case paramter metadata is loaded through the _parameterMajorVersionKnown call which happens after parameter are downloaded
......
......@@ -215,8 +215,9 @@ QString RequestMetaDataTypeStateMachine::_downloadCompleteJsonWorker(const QStri
void RequestMetaDataTypeStateMachine::_ftpDownloadCompleteMetaDataJson(const QString& fileName, const QString& errorMsg)
{
qCDebug(ComponentInformationManagerLog) << "RequestMetaDataTypeStateMachine::_downloadCompleteMetaDataJson fileName:errorMsg" << fileName << errorMsg;
qCDebug(ComponentInformationManagerLog) << "RequestMetaDataTypeStateMachine::_ftpDownloadCompleteMetaDataJson fileName:errorMsg" << fileName << errorMsg;
disconnect(_compInfo->vehicle->ftpManager(), &FTPManager::downloadComplete, this, &RequestMetaDataTypeStateMachine::_ftpDownloadCompleteMetaDataJson);
if (errorMsg.isEmpty()) {
_jsonMetadataFileName = _downloadCompleteJsonWorker(fileName, "metadata.json");
}
......@@ -226,15 +227,15 @@ void RequestMetaDataTypeStateMachine::_ftpDownloadCompleteMetaDataJson(const QSt
void RequestMetaDataTypeStateMachine::_ftpDownloadCompleteTranslationJson(const QString& fileName, const QString& errorMsg)
{
qCDebug(ComponentInformationManagerLog) << "RequestMetaDataTypeStateMachine::_downloadCompleteTranslationJson fileName:errorMsg" << fileName << errorMsg;
QString jsonTranslationFileName;
qCDebug(ComponentInformationManagerLog) << "RequestMetaDataTypeStateMachine::_ftpDownloadCompleteTranslationJson fileName:errorMsg" << fileName << errorMsg;
disconnect(_compInfo->vehicle->ftpManager(), &FTPManager::downloadComplete, this, &RequestMetaDataTypeStateMachine::_ftpDownloadCompleteTranslationJson);
if (errorMsg.isEmpty()) {
jsonTranslationFileName = _downloadCompleteJsonWorker(fileName, "translation.json");
_jsonTranslationFileName = _downloadCompleteJsonWorker(fileName, "translation.json");
}
_compInfo->setJson(_jsonMetadataFileName, jsonTranslationFileName);
advance();
}
......@@ -242,6 +243,7 @@ void RequestMetaDataTypeStateMachine::_httpDownloadCompleteMetaDataJson(QString
{
qCDebug(ComponentInformationManagerLog) << "RequestMetaDataTypeStateMachine::_httpDownloadCompleteMetaDataJson remoteFile:localFile:errorMsg" << remoteFile << localFile << errorMsg;
disconnect(qobject_cast<QGCFileDownload*>(sender()), &QGCFileDownload::downloadComplete, this, &RequestMetaDataTypeStateMachine::_httpDownloadCompleteMetaDataJson);
if (errorMsg.isEmpty()) {
_jsonMetadataFileName = _downloadCompleteJsonWorker(localFile, "metadata.json");
}
......@@ -251,15 +253,15 @@ void RequestMetaDataTypeStateMachine::_httpDownloadCompleteMetaDataJson(QString
void RequestMetaDataTypeStateMachine::_httpDownloadCompleteTranslationJson(QString remoteFile, QString localFile, QString errorMsg)
{
QString jsonTranslationFileName;
qCDebug(ComponentInformationManagerLog) << "RequestMetaDataTypeStateMachine::_httpDownloadCompleteTranslationJson remoteFile:localFile:errorMsg" << remoteFile << localFile << errorMsg;
QString jsonTranslationFileName;
disconnect(qobject_cast<QGCFileDownload*>(sender()), &QGCFileDownload::downloadComplete, this, &RequestMetaDataTypeStateMachine::_httpDownloadCompleteTranslationJson);
if (errorMsg.isEmpty()) {
jsonTranslationFileName = _downloadCompleteJsonWorker(localFile, "translation.json");
_jsonTranslationFileName = _downloadCompleteJsonWorker(localFile, "translation.json");
}
_compInfo->setJson(_jsonMetadataFileName, jsonTranslationFileName);
advance();
}
......@@ -318,6 +320,14 @@ void RequestMetaDataTypeStateMachine::_stateRequestComplete(StateMachine* stateM
CompInfo* compInfo = requestMachine->compInfo();
compInfo->setJson(requestMachine->_jsonMetadataFileName, requestMachine->_jsonTranslationFileName);
if (!requestMachine->_jsonMetadataFileName.isEmpty()) {
QFile(requestMachine->_jsonMetadataFileName).remove();
}
if (!requestMachine->_jsonTranslationFileName.isEmpty()) {
QFile(requestMachine->_jsonTranslationFileName).remove();
}
requestMachine->advance();
}
......
......@@ -7,7 +7,6 @@
*
****************************************************************************/
#include "FTPManager.h"
#include "QGC.h"
#include "MAVLinkProtocol.h"
......@@ -24,97 +23,66 @@ 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;
_ackOrNakTimeoutTimer.setSingleShot(true);
// Mock link responds immediately if at all, speed up unit tests with faster timoue
_ackOrNakTimeoutTimer.setInterval(qgcApp()->runningUnitTests() ? 10 : _ackOrNakTimeoutMsecs);
connect(&_ackOrNakTimeoutTimer, &QTimer::timeout, this, &FTPManager::_ackOrNakTimeout);
// Make sure we don't have bad structure packing
Q_ASSERT(sizeof(MavlinkFTP::RequestHeader) == 12);
}
void FTPManager::_handlOpenFileROAck(MavlinkFTP::Request* ack)
bool FTPManager::download(const QString& from, const QString& toDir)
{
qCDebug(FTPManagerLog) << QString("_handlOpenFileROAck: _waitState(%1) _readFileLength(%3)").arg(MavlinkFTP::opCodeToString(_waitState)).arg(ack->openFileLength);
qCDebug(FTPManagerLog) << "download from:" << from << "to:" << toDir;
if (_waitState != MavlinkFTP::kCmdOpenFileRO) {
qCDebug(FTPManagerLog) << "Received OpenFileRO Ack while not waiting for it";
return;
if (!_rgStateMachine.isEmpty()) {
qCDebug(FTPManagerLog) << "Cannot download. Already in another operation";
return false;
}
if (ack->hdr.size != sizeof(uint32_t)) {
qCDebug(FTPManagerLog) << "_handlOpenFileROAck: ack->hdr.size != sizeof(uint32_t)" << ack->hdr.size << sizeof(uint32_t);
_downloadComplete(tr("Download failed"));
return;
static const StateFunctions_t rgDownloadStateMachine[] = {
{ &FTPManager::_openFileROBegin, &FTPManager::_openFileROAckOrNak, &FTPManager::_openFileROTimeout },
{ &FTPManager::_burstReadFileBegin, &FTPManager::_burstReadFileAckOrNak, &FTPManager::_burstReadFileTimeout },
{ &FTPManager::_fillMissingBlocksBegin, &FTPManager::_fillMissingBlocksAckOrNak, &FTPManager::_fillMissingBlocksTimeout },
{ &FTPManager::_resetSessionsBegin, &FTPManager::_resetSessionsAckOrNak, &FTPManager::_resetSessionsTimeout },
{ &FTPManager::_downloadCompleteNoError, nullptr, nullptr },
};
for (size_t i=0; i<sizeof(rgDownloadStateMachine)/sizeof(rgDownloadStateMachine[0]); i++) {
_rgStateMachine.append(rgDownloadStateMachine[i]);
}
_downloadState.reset();
_downloadState.toDir.setPath(toDir);
_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;
QString ftpPrefix("mavlinkftp://");
if (from.startsWith(ftpPrefix, Qt::CaseInsensitive)) {
_downloadState.fullPathOnVehicle = from.right(from.length() - ftpPrefix.length() + 1);
} else {
_downloadState.fullPathOnVehicle = from;
}
MavlinkFTP::Request request;
request.hdr.session = _activeSession;
request.hdr.opcode = MavlinkFTP::kCmdBurstReadFile;
request.hdr.offset = _downloadState.expectedBurstOffset;
request.hdr.size = sizeof(request.data);
_sendRequestExpectAck(&request);
}
void FTPManager::_requestMissingBurstData()
{
MavlinkFTP::Request request;
if (_downloadState.missingData.count()) {
MissingData_t& missingData = _downloadState.missingData.first();
uint32_t cBytesToRead = qMin((uint32_t)sizeof(request.data), missingData.cBytes);
// We need to strip off the file name from the fully qualified path. We can't use the usual QDir
// routines because this path does not exist locally.
int lastDirSlashIndex;
for (lastDirSlashIndex=_downloadState.fullPathOnVehicle.size()-1; lastDirSlashIndex>=0; lastDirSlashIndex--) {
if (_downloadState.fullPathOnVehicle[lastDirSlashIndex] == '/') {
break;
}
}
lastDirSlashIndex++; // move past slash
qCDebug(FTPManagerLog) << "_requestMissingBurstData: offset:cBytesToRead" << missingData.offset << cBytesToRead;
_downloadState.fileName = _downloadState.fullPathOnVehicle.right(_downloadState.fullPathOnVehicle.size() - lastDirSlashIndex);
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;
qDebug() << _downloadState.fullPathOnVehicle << _downloadState.fileName;
if (cBytesToRead < missingData.cBytes) {
missingData.offset += cBytesToRead;
missingData.cBytes -= cBytesToRead;
} else {
_downloadState.missingData.takeFirst();
}
} else {
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;
}
_startStateMachine();
_sendRequestExpectAck(&request);
return true;
}
/// Closes out a download session by writing the file and doing cleanup.
/// @param success true: successful download completion, false: error during download
/// @param errorMsg Error message, empty if no error
void FTPManager::_downloadComplete(const QString& errorMsg)
{
qCDebug(FTPManagerLog) << QString("_downloadComplete: errorMsg(%1)").arg(errorMsg);
......@@ -122,698 +90,433 @@ void FTPManager::_downloadComplete(const QString& errorMsg)
QString downloadFilePath = _downloadState.toDir.absoluteFilePath(_downloadState.fileName);
QString error = errorMsg;
_ackTimer.stop();
_waitState = MavlinkFTP::kCmdNone;
if (error.isEmpty()) {
_ackOrNakTimeoutTimer.stop();
_rgStateMachine.clear();
_currentStateMachineIndex = -1;
if (_downloadState.file.isOpen()) {
_downloadState.file.close();
if (!errorMsg.isEmpty()) {
_downloadState.file.remove();
}
}
_downloadState.reset();
_sendResetCommand(); // Close the open session
emit downloadComplete(downloadFilePath, error);
}
/// Closes out an upload session doing cleanup.
/// @param success true: successful upload completion, false: error during download
void FTPManager::_uploadComplete(const QString& errorMsg)
{
qCDebug(FTPManagerLog) << QString("_uploadComplete: errorMsg(%1)").arg(errorMsg);
_waitState = MavlinkFTP::kCmdNone;
_writeFileSize = 0;
_writeFileAccumulator.clear();
_sendResetCommand();
emit uploadComplete(errorMsg);
emit downloadComplete(downloadFilePath, errorMsg);
}
// We only do read files to fill in holes from a burst read
void FTPManager::_handleReadFileAck(MavlinkFTP::Request* ack)
void FTPManager::_mavlinkMessageReceived(const mavlink_message_t& message)
{
if (ack->hdr.session != _activeSession) {
if (message.msgid != MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL) {
return;
}
qCDebug(FTPManagerLog) << "_handleReadFileAck: offset:size" << ack->hdr.offset << ack->hdr.size;
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"));
if (_currentStateMachineIndex == -1) {
return;
}
// 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 = _downloadState.expectedReadOffset;
request.hdr.size = 0;
_sendRequestExpectAck(&request);
return;
}
mavlink_file_transfer_protocol_t data;
mavlink_msg_file_transfer_protocol_decode(&message, &data);
_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"));
// Make sure we are the target system
int qgcId = qgcApp()->toolbox()->mavlinkProtocol()->getSystemId();
if (data.target_system != qgcId) {
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();
}
void FTPManager::_handleBurstReadFileAck(MavlinkFTP::Request* ack)
{
if (ack->hdr.session != _activeSession) {
return;
}
MavlinkFTP::Request* request = (MavlinkFTP::Request*)&data.payload[0];
qCDebug(FTPManagerLog) << QString("_handleBurstReadFileAck: offset(%1) size(%2) burstComplete(%3)").arg(ack->hdr.offset).arg(ack->hdr.size).arg(ack->hdr.burstComplete);
// Ignore old/reordered packets (handle wrap-around properly)
uint16_t actualIncomingSeqNumber = request->hdr.seqNumber;
if ((uint16_t)((_expectedIncomingSeqNumber - 1) - actualIncomingSeqNumber) < (std::numeric_limits<uint16_t>::max()/2)) {
qCDebug(FTPManagerLog) << "_mavlinkMessageReceived: Received old packet seqNum expected:actual" << _expectedIncomingSeqNumber << actualIncomingSeqNumber
<< "hdr.opcode:hdr.req_opcode" << MavlinkFTP::opCodeToString(static_cast<MavlinkFTP::OpCode_t>(request->hdr.opcode)) << MavlinkFTP::opCodeToString(static_cast<MavlinkFTP::OpCode_t>(request->hdr.req_opcode));
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;
qCDebug(FTPManagerLog) << "_mavlinkMessageReceived: hdr.opcode:hdr.req_opcode:seqNumber"
<< MavlinkFTP::opCodeToString(static_cast<MavlinkFTP::OpCode_t>(request->hdr.opcode)) << MavlinkFTP::opCodeToString(static_cast<MavlinkFTP::OpCode_t>(request->hdr.req_opcode))
<< request->hdr.seqNumber;
if (_downloadState.fileSize != 0) {
emit commandProgress(100 * ((float)(_downloadState.bytesWritten) / (float)_downloadState.fileSize));
}
(this->*_rgStateMachine[_currentStateMachineIndex].ackNakFn)(request);
}
if (ack->hdr.burstComplete) {
_requestMissingBurstData();
} else {
// Still within a burst, next ack should come automatically
_ackTimer.start();
}
void FTPManager::_startStateMachine(void)
{
_currentStateMachineIndex = -1;
_advanceStateMachine();
}
void FTPManager::_listAckResponse(MavlinkFTP::Request* /*listAck*/)
void FTPManager::_advanceStateMachine(void)
{
#if 0
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;
}
_currentStateMachineIndex++;
(this->*_rgStateMachine[_currentStateMachineIndex].beginFn)();
}
uint8_t offset = 0;
uint8_t cListEntries = 0;
uint8_t cBytes = listAck->hdr.size;
void FTPManager::_ackOrNakTimeout(void)
{
(this->*_rgStateMachine[_currentStateMachineIndex].timeoutFn)();
}
// parse filenames out of the buffer
while (offset < cBytes) {
const char * ptr = ((const char *)listAck->data) + offset;
void FTPManager::_fillRequestDataWithString(MavlinkFTP::Request* request, const QString& str)
{
strncpy((char *)&request->data[0], str.toStdString().c_str(), sizeof(request->data));
request->hdr.size = static_cast<uint8_t>(strnlen((const char *)&request->data[0], sizeof(request->data)));
}
// get the length of the name
uint8_t cBytesLeft = cBytes - offset;
uint8_t nlen = static_cast<uint8_t>(strnlen(ptr, cBytesLeft));
if ((*ptr == 'S' && nlen > 1) || (*ptr != 'S' && 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;
}
QString FTPManager::_errorMsgFromNak(const MavlinkFTP::Request* nak)
{
QString errorMsg;
MavlinkFTP::ErrorCode_t errorCode = static_cast<MavlinkFTP::ErrorCode_t>(nak->data[0]);
// Returned names are prepended with D for directory, F for file, S for skip
if (*ptr == 'F' || *ptr == 'D') {
// put it in the view
_emitListEntry(ptr);
} else if (*ptr == 'S') {
// do nothing
// 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 {
qDebug() << "unknown entry" << ptr;
}
// account for the name + NUL
offset += nlen + 1;
cListEntries++;
errorMsg = MavlinkFTP::errorCodeToString(errorCode);
}
if (listAck->hdr.size == 0 || cListEntries == 0) {
// Directory is empty, we're done
Q_ASSERT(listAck->hdr.opcode == MavlinkFTP::kRspAck);
_currentOperation = kCOIdle;
emit commandComplete();
} else {
// Possibly more entries to come, need to keep trying till we get EOF
_currentOperation = kCOList;
_listOffset += cListEntries;
_sendListCommand();
}
#endif
return errorMsg;
}
/// @brief Respond to the Ack associated with the create command.
void FTPManager::_createAckResponse(MavlinkFTP::Request* /*createAck*/)
void FTPManager::_openFileROBegin(void)
{
#if 0
qCDebug(FTPManagerLog) << "_createAckResponse";
_currentOperation = kCOWrite;
_activeSession = createAck->hdr.session;
// Start the sequence of write commands from the beginning of the file
_writeOffset = 0;
_writeSize = 0;
MavlinkFTP::Request request;
request.hdr.session = 0;
request.hdr.opcode = MavlinkFTP::kCmdOpenFileRO;
request.hdr.offset = 0;
request.hdr.size = 0;
_fillRequestDataWithString(&request, _downloadState.fullPathOnVehicle);
_sendRequestExpectAck(&request);
}
_writeFileDatablock();
#endif
void FTPManager::_openFileROTimeout(void)
{
qCDebug(FTPManagerLog) << "_openFileROTimeout";
_downloadComplete(tr("Download failed"));
}
/// @brief Respond to the Ack associated with the write command.
void FTPManager::_writeAckResponse(MavlinkFTP::Request* /*writeAck*/)
void FTPManager::_openFileROAckOrNak(const MavlinkFTP::Request* ackOrNak)
{
#if 0
if(_writeOffset + _writeSize >= _writeFileSize){
_closeUploadSession(true /* success */);
MavlinkFTP::OpCode_t requestOpCode = static_cast<MavlinkFTP::OpCode_t>(ackOrNak->hdr.req_opcode);
if (requestOpCode != MavlinkFTP::kCmdOpenFileRO) {
qCDebug(FTPManagerLog) << "_openFileROAckOrNak: Ack disregarding ack for incorrect requestOpCode" << MavlinkFTP::opCodeToString(requestOpCode);
return;
}
if (writeAck->hdr.session != _activeSession) {
_closeUploadSession(false /* failure */);
_emitErrorMessage(tr("Write: Incorrect session returned"));
if (ackOrNak->hdr.seqNumber != _expectedIncomingSeqNumber) {
qCDebug(FTPManagerLog) << "_openFileROAckOrNak: Ack disregarding ack for incorrect sequence actual:expected" << ackOrNak->hdr.seqNumber << _expectedIncomingSeqNumber;
return;
}
if (writeAck->hdr.offset != _writeOffset) {
_closeUploadSession(false /* failure */);
_emitErrorMessage(tr("Write: Offset returned (%1) differs from offset requested (%2)").arg(writeAck->hdr.offset).arg(_writeOffset));
return;
}
_ackOrNakTimeoutTimer.stop();
if (ackOrNak->hdr.opcode == MavlinkFTP::kRspAck) {
qCDebug(FTPManagerLog) << "_openFileROAckOrNak: Ack - sessionId:openFileLength" << ackOrNak->hdr.session << ackOrNak->openFileLength;
if (writeAck->hdr.size != sizeof(uint32_t)) {
_closeUploadSession(false /* failure */);
_emitErrorMessage(tr("Write: Returned invalid size of write size data"));
if (ackOrNak->hdr.size != sizeof(uint32_t)) {
qCDebug(FTPManagerLog) << "_openFileROAckOrNak: Ack ack->hdr.size != sizeof(uint32_t)" << ackOrNak->hdr.size << sizeof(uint32_t);
_downloadComplete(tr("Download failed"));
return;
}
_downloadState.sessionId = ackOrNak->hdr.session;
_downloadState.fileSize = ackOrNak->openFileLength;
_downloadState.expectedOffset = 0;
if( writeAck->writeFileLength !=_writeSize) {
_closeUploadSession(false /* failure */);
_emitErrorMessage(tr("Write: Size returned (%1) differs from size requested (%2)").arg(writeAck->writeFileLength).arg(_writeSize));
return;
_downloadState.file.setFileName(_downloadState.toDir.filePath(_downloadState.fileName));
if (_downloadState.file.open(QFile::WriteOnly | QFile::Truncate)) {
_advanceStateMachine();
} else {
qCDebug(FTPManagerLog) << "_openFileROAckOrNak: Ack _downloadState.file open failed" << _downloadState.file.errorString();
_downloadComplete(tr("Download failed"));
}
} else if (ackOrNak->hdr.opcode == MavlinkFTP::kRspNak) {
qCDebug(FTPManagerLog) << "_handlOpenFileROAck: Nak -" << _errorMsgFromNak(ackOrNak);
_downloadComplete(tr("Download failed"));
}
_writeFileDatablock();
#endif
}
/// @brief Send next write file data block.
void FTPManager::_writeFileDatablock(void)
void FTPManager::_burstReadFileWorker(bool firstRequest)
{
#if 0
if (_writeOffset + _writeSize >= _writeFileSize){
_closeUploadSession(true /* success */);
return;
}
_writeOffset += _writeSize;
qCDebug(FTPManagerLog) << "_burstReadFileWorker: starting burst at offset:firstRequest:retryCount" << _downloadState.expectedOffset << firstRequest << _downloadState.retryCount;
MavlinkFTP::Request request;
request.hdr.session = _activeSession;
request.hdr.opcode = MavlinkFTP::kCmdWriteFile;
request.hdr.offset = _writeOffset;
if(_writeFileSize -_writeOffset > sizeof(request.data) )
_writeSize = sizeof(request.data);
else
_writeSize = _writeFileSize - _writeOffset;
request.hdr.size = _writeSize;
request.hdr.session = _downloadState.sessionId;
request.hdr.opcode = MavlinkFTP::kCmdBurstReadFile;
request.hdr.offset = _downloadState.expectedOffset;
request.hdr.size = sizeof(request.data);
memcpy(request.data, &_writeFileAccumulator.data()[_writeOffset], _writeSize);
if (firstRequest) {
_downloadState.retryCount = 0;
} else {
// Must used same sequence number as previous request
_expectedIncomingSeqNumber -= 2;
}
_sendRequestExpectAck(&request);
#endif
}
void FTPManager::_handleAck(MavlinkFTP::Request* ack)
void FTPManager::_burstReadFileBegin(void)
{
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;
}
_burstReadFileWorker(true /* firstRequestr */);
}
void FTPManager::_handleNak(MavlinkFTP::Request* nak)
void FTPManager::_burstReadFileAckOrNak(const MavlinkFTP::Request* ackOrNak)
{
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]);
MavlinkFTP::OpCode_t requestOpCode = static_cast<MavlinkFTP::OpCode_t>(ackOrNak->hdr.req_opcode);
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();
if (requestOpCode != MavlinkFTP::kCmdBurstReadFile) {
qCDebug(FTPManagerLog) << "_burstReadFileAckOrNak: Disregarding due to incorrect requestOpCode" << MavlinkFTP::opCodeToString(requestOpCode);
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) {
if (ackOrNak->hdr.session != _downloadState.sessionId) {
qCDebug(FTPManagerLog) << "_burstReadFileAckOrNak: Disregarding due to incorrect session id actual:expected" << ackOrNak->hdr.session << _downloadState.sessionId;
return;
}
mavlink_file_transfer_protocol_t data;
mavlink_msg_file_transfer_protocol_decode(&message, &data);
_ackOrNakTimeoutTimer.stop();
// Make sure we are the target system
int qgcId = qgcApp()->toolbox()->mavlinkProtocol()->getSystemId();
if (data.target_system != qgcId) {
if (ackOrNak->hdr.opcode == MavlinkFTP::kRspAck) {
if (ackOrNak->hdr.seqNumber < _expectedIncomingSeqNumber) {
qCDebug(FTPManagerLog) << "_burstReadFileAckOrNak: Disregarding Ack due to incorrect sequence actual:expected" << ackOrNak->hdr.seqNumber << _expectedIncomingSeqNumber;
return;
}
MavlinkFTP::Request* request = (MavlinkFTP::Request*)&data.payload[0];
uint16_t incomingSeqNumber = request->hdr.seqNumber;
uint16_t expectedSeqNumber = _lastOutgoingRequest.hdr.seqNumber + 1;
qCDebug(FTPManagerLog) << QString("_burstReadFileAckOrNak: Ack offset(%1) size(%2) burstComplete(%3)").arg(ackOrNak->hdr.offset).arg(ackOrNak->hdr.size).arg(ackOrNak->hdr.burstComplete);
// ignore old/reordered packets (handle wrap-around properly)
if ((uint16_t)((expectedSeqNumber - 1) - incomingSeqNumber) < (std::numeric_limits<uint16_t>::max()/2)) {
qCDebug(FTPManagerLog) << "Received old packet: expected seq:" << expectedSeqNumber << "got:" << incomingSeqNumber;
if (ackOrNak->hdr.offset != _downloadState.expectedOffset) {
if (ackOrNak->hdr.offset > _downloadState.expectedOffset) {
// There is a hole in our data, record it as missing and continue on
MissingData_t missingData;
missingData.offset = _downloadState.expectedOffset;
missingData.cBytesMissing = ackOrNak->hdr.offset - _downloadState.expectedOffset;
_downloadState.rgMissingData.append(missingData);
qCDebug(FTPManagerLog) << "_handleBurstReadFileAck: adding missing data offset:cBytesMissing" << missingData.offset << missingData.cBytesMissing;
} else {
// Offset is past what we have already seen, disregard and wait for something usefule
_ackOrNakTimeoutTimer.start();
qCDebug(FTPManagerLog) << "_handleBurstReadFileAck: received offset less than expected offset received:expected" << ackOrNak->hdr.offset << _downloadState.expectedOffset;
return;
}
_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:
// These can handle packet loss
break;
#if 0
case kCOWrite:
_closeUploadSession(false /* failure */);
break;
case kCOOpenRead:
case kCOOpenBurst:
case kCOCreate:
// We could have an open session hanging around
_currentOperation = kCOIdle;
_sendResetCommand();
break;
#endif
default:
// Don't need to do anything special
_waitState = MavlinkFTP::kCmdNone;
break;
}
}
// Move past the incoming sequence number for next request
_lastOutgoingRequest.hdr.seqNumber = incomingSeqNumber;
if (request->hdr.opcode == MavlinkFTP::kRspAck) {
_handleAck(request);
} else if (request->hdr.opcode == MavlinkFTP::kRspNak) {
_handleNak(request);
_downloadState.file.seek(ackOrNak->hdr.offset);
int bytesWritten = _downloadState.file.write((const char*)ackOrNak->data, ackOrNak->hdr.size);
if (bytesWritten != ackOrNak->hdr.size) {
_downloadComplete(tr("Download failed: Error saving file"));
return;
}
}
_downloadState.bytesWritten += ackOrNak->hdr.size;
_downloadState.expectedOffset = ackOrNak->hdr.offset + ackOrNak->hdr.size;
void FTPManager::listDirectory(const QString& dirPath)
{
if (_waitState != MavlinkFTP::kCmdNone) {
_emitErrorMessage(tr("Command not sent. Waiting for previous command to complete."));
return;
if (_downloadState.fileSize != 0) {
emit commandProgress(100 * ((float)(_downloadState.bytesWritten) / (float)_downloadState.fileSize));
}
_dedicatedLink = _vehicle->vehicleLinkManager()->primaryLink();
if (!_dedicatedLink) {
_emitErrorMessage(tr("Command not sent. No Vehicle links."));
if (ackOrNak->hdr.burstComplete) {
// The current burst is done, request next one in offset sequence
_expectedIncomingSeqNumber = ackOrNak->hdr.seqNumber;
_burstReadFileWorker(true /* firstRequest */);
} else {
// Still within a burst, next ack should come automatically
_expectedIncomingSeqNumber = ackOrNak->hdr.seqNumber + 1;
_ackOrNakTimeoutTimer.start();
}
} else if (ackOrNak->hdr.opcode == MavlinkFTP::kRspNak) {
if (ackOrNak->hdr.seqNumber != _expectedIncomingSeqNumber) {
qCDebug(FTPManagerLog) << "_burstReadFileAckOrNak: Disregarding Nak due to incorrect sequence actual:expected" << ackOrNak->hdr.seqNumber << _expectedIncomingSeqNumber;
return;
}
// initialise the lister
_listPath = dirPath;
_listOffset = 0;
_waitState = MavlinkFTP::kCmdListDirectory;
MavlinkFTP::ErrorCode_t errorCode = static_cast<MavlinkFTP::ErrorCode_t>(ackOrNak->data[0]);
// and send the initial request
_sendListCommand();
if (errorCode == MavlinkFTP::kErrEOF) {
// Burst sequence has gone through the whole file
qCDebug(FTPManagerLog) << "_burstReadFileAckOrNak EOF";
_advanceStateMachine();
} else {
qCDebug(FTPManagerLog) << "_burstReadFileAckOrNak: Nak -" << _errorMsgFromNak(ackOrNak);
_downloadComplete(tr("Download failed"));
}
}
}
void FTPManager::_fillRequestWithString(MavlinkFTP::Request* request, const QString& str)
void FTPManager::_burstReadFileTimeout(void)
{
strncpy((char *)&request->data[0], str.toStdString().c_str(), sizeof(request->data));
request->hdr.size = static_cast<uint8_t>(strnlen((const char *)&request->data[0], sizeof(request->data)));
if (++_downloadState.retryCount > _maxRetry) {
qCDebug(FTPManagerLog) << QString("_burstReadFileTimeout retries exceeded");
_downloadComplete(tr("Download failed"));
} else {
// Try again
qCDebug(FTPManagerLog) << QString("_burstReadFileTimeout: retrying - retryCount(%1) offset(%2)").arg(_downloadState.retryCount).arg(_downloadState.expectedOffset);
_burstReadFileWorker(false /* firstReqeust */);
}
}
void FTPManager::_sendListCommand(void)
void FTPManager::_fillMissingBlocksWorker(bool firstRequest)
{
if (_downloadState.rgMissingData.count()) {
MavlinkFTP::Request request;
MissingData_t& missingData = _downloadState.rgMissingData.first();
request.hdr.session = 0;
request.hdr.opcode = MavlinkFTP::kCmdListDirectory;
request.hdr.offset = _listOffset;
request.hdr.size = 0;
uint32_t cBytesToRead = qMin((uint32_t)sizeof(request.data), missingData.cBytesMissing);
_fillRequestWithString(&request, _listPath);
qCDebug(FTPManagerLog) << "_fillMissingBlocksBegin: offset:cBytesToRead" << missingData.offset << cBytesToRead;
qCDebug(FTPManagerLog) << "listDirectory: path:" << _listPath << "offset:" << _listOffset;
request.hdr.session = _downloadState.sessionId;
request.hdr.opcode = MavlinkFTP::kCmdReadFile;
request.hdr.offset = missingData.offset;
request.hdr.size = cBytesToRead;
if (firstRequest) {
_downloadState.retryCount = 0;
} else {
// Must used same sequence number as previous request
_expectedIncomingSeqNumber -= 2;
}
_downloadState.expectedOffset = request.hdr.offset;
_sendRequestExpectAck(&request);
} else {
// We should have the full file now
if (_downloadState.bytesWritten == _downloadState.fileSize) {
_advanceStateMachine();
} else {
qCDebug(FTPManagerLog) << "_fillMissingBlocksWorker: no missing blocks but file still incomplete - bytesWritten:fileSize" << _downloadState.bytesWritten << _downloadState.fileSize;
_downloadComplete(tr("Download failed"));
}
}
}
bool FTPManager::download(const QString& from, const QString& toDir)
void FTPManager::_fillMissingBlocksBegin(void)
{
qCDebug(FTPManagerLog) << "download from:" << from << "to:" << toDir;
return _downloadWorker(from, toDir);
_fillMissingBlocksWorker(true /* firstRequest */);
}
bool FTPManager::_downloadWorker(const QString& from, const QString& toDir)
void FTPManager::_fillMissingBlocksAckOrNak(const MavlinkFTP::Request* ackOrNak)
{
if (_waitState != MavlinkFTP::kCmdNone) {
qCDebug(FTPManagerLog) << "Cannot download. Already in another operation";
return false;
}
_dedicatedLink = _vehicle->vehicleLinkManager()->primaryLink();
if (!_dedicatedLink) {
qCDebug(FTPManagerLog) << "Cannot download. Vehicle has no priority link";
return false;
}
MavlinkFTP::OpCode_t requestOpCode = static_cast<MavlinkFTP::OpCode_t>(ackOrNak->hdr.req_opcode);
_downloadState.reset();
_downloadState.toDir.setPath(toDir);
QString strippedFrom;
QString ftpPrefix("mavlinkftp://");
if (from.startsWith(ftpPrefix, Qt::CaseInsensitive)) {
strippedFrom = from.right(from.length() - ftpPrefix.length() + 1);
} else {
strippedFrom = from;
if (requestOpCode != MavlinkFTP::kCmdReadFile) {
qCDebug(FTPManagerLog) << "_fillMissingBlocksAckOrNak: Disregarding due to incorrect requestOpCode" << MavlinkFTP::opCodeToString(requestOpCode);
return;
}
// We need to strip off the file name from the fully qualified path. We can't use the usual QDir
// routines because this path does not exist locally.
int lastDirSlashIndex;
for (lastDirSlashIndex=strippedFrom.size()-1; lastDirSlashIndex>=0; lastDirSlashIndex--) {
if (strippedFrom[lastDirSlashIndex] == '/') {
break;
if (ackOrNak->hdr.seqNumber != _expectedIncomingSeqNumber) {
qCDebug(FTPManagerLog) << "_fillMissingBlocksAckOrNak: Disregarding due to incorrect sequence actual:expected" << ackOrNak->hdr.seqNumber << _expectedIncomingSeqNumber;
return;
}
if (ackOrNak->hdr.session != _downloadState.sessionId) {
qCDebug(FTPManagerLog) << "_fillMissingBlocksAckOrNak: Disregarding due to incorrect session id actual:expected" << ackOrNak->hdr.session << _downloadState.sessionId;
return;
}
lastDirSlashIndex++; // move past slash
_downloadState.fileName = strippedFrom.right(strippedFrom.size() - lastDirSlashIndex);
_waitState = MavlinkFTP::kCmdOpenFileRO;
_ackOrNakTimeoutTimer.stop();
MavlinkFTP::Request request;
request.hdr.session = 0;
request.hdr.opcode = MavlinkFTP::kCmdOpenFileRO;
request.hdr.offset = 0;
request.hdr.size = 0;
_fillRequestWithString(&request, strippedFrom);
_sendRequestExpectAck(&request);
if (ackOrNak->hdr.opcode == MavlinkFTP::kRspAck) {
qCDebug(FTPManagerLog) << "_fillMissingBlocksAckOrNak: Ack offset:size" << ackOrNak->hdr.offset << ackOrNak->hdr.size;
return true;
}
/// @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*/)
{
#if 0
if(_currentOperation != kCOIdle){
_emitErrorMessage(tr("UAS File manager busy. Try again later"));
if (ackOrNak->hdr.offset != _downloadState.expectedOffset) {
if (++_downloadState.retryCount > _maxRetry) {
qCDebug(FTPManagerLog) << QString("_fillMissingBlocksAckOrNak: offset mismatch, retries exceeded");
_downloadComplete(tr("Download failed"));
return;
}
_dedicatedLink = _vehicle->vehicleLinkManager()->primaryLink();
if (!_dedicatedLink) {
_emitErrorMessage(tr("Command not sent. No Vehicle links."));
// Ask for current offset again
qCDebug(FTPManagerLog) << QString("_fillMissingBlocksAckOrNak: Ack offset mismatch retry, retryCount(%1) offset(%2)").arg(_downloadState.retryCount).arg(_downloadState.expectedOffset);
_fillMissingBlocksWorker(false /* firstReqeust */);
return;
}
if (toPath.isEmpty()) {
_downloadState.file.seek(ackOrNak->hdr.offset);
int bytesWritten = _downloadState.file.write((const char*)ackOrNak->data, ackOrNak->hdr.size);
if (bytesWritten != ackOrNak->hdr.size) {
_downloadComplete(tr("Download failed: Error saving file"));
return;
}
_downloadState.bytesWritten += ackOrNak->hdr.size;
if (!uploadFile.isReadable()){
_emitErrorMessage(tr("File (%1) is not readable for upload").arg(uploadFile.path()));
return;
MissingData_t& missingData = _downloadState.rgMissingData.first();
missingData.offset += ackOrNak->hdr.size;
missingData.cBytesMissing -= ackOrNak->hdr.size;
if (missingData.cBytesMissing == 0) {
// This block is finished, remove it
_downloadState.rgMissingData.takeFirst();
}
QFile file(uploadFile.absoluteFilePath());
if (!file.open(QIODevice::ReadOnly)) {
_emitErrorMessage(tr("Unable to open local file for upload (%1)").arg(uploadFile.absoluteFilePath()));
return;
if (_downloadState.fileSize != 0) {
emit commandProgress(100 * ((float)(_downloadState.bytesWritten) / (float)_downloadState.fileSize));
}
_writeFileAccumulator = file.readAll();
_writeFileSize = _writeFileAccumulator.size();
file.close();
// Move on to fill in possible next hole
_fillMissingBlocksWorker(true /* firstReqeust */);
} else if (ackOrNak->hdr.opcode == MavlinkFTP::kRspNak) {
MavlinkFTP::ErrorCode_t errorCode = static_cast<MavlinkFTP::ErrorCode_t>(ackOrNak->data[0]);
if (_writeFileAccumulator.size() == 0) {
_emitErrorMessage(tr("Unable to read data from local file (%1)").arg(uploadFile.absoluteFilePath()));
if (errorCode == MavlinkFTP::kErrEOF) {
qCDebug(FTPManagerLog) << "_fillMissingBlocksAckOrNak EOF";
if (_downloadState.bytesWritten == _downloadState.fileSize) {
// We've successfully complete filling in all missing blocks
_advanceStateMachine();
return;
}
}
_currentOperation = kCOCreate;
qCDebug(FTPManagerLog) << "_fillMissingBlocksAckOrNak: Nak -" << _errorMsgFromNak(ackOrNak);
_downloadComplete(tr("Download failed"));
}
MavlinkFTP::Request request;
request.hdr.session = 0;
request.hdr.opcode = MavlinkFTP::kCmdCreateFile;
request.hdr.offset = 0;
request.hdr.size = 0;
_fillRequestWithString(&request, toPath + "/" + uploadFile.fileName());
_sendRequestExpectAck(&request);
#endif
}
void FTPManager::createDirectory(const QString& /*directory*/)
void FTPManager::_fillMissingBlocksTimeout(void)
{
#if 0
if(_currentOperation != kCOIdle){
_emitErrorMessage(tr("UAS File manager busy. Try again later"));
return;
if (++_downloadState.retryCount > _maxRetry) {
qCDebug(FTPManagerLog) << QString("_fillMissingBlocksTimeout retries exceeded");
_downloadComplete(tr("Download failed"));
} else {
// Ask for current offset again
qCDebug(FTPManagerLog) << QString("_fillMissingBlocksTimeout: retrying - retryCount(%1) offset(%2)").arg(_downloadState.retryCount).arg(_downloadState.expectedOffset);
_fillMissingBlocksWorker(false /* firstReqeust */);
}
_currentOperation = kCOCreateDir;
MavlinkFTP::Request request;
request.hdr.session = 0;
request.hdr.opcode = MavlinkFTP::kCmdCreateDirectory;
request.hdr.offset = 0;
request.hdr.size = 0;
_fillRequestWithString(&request, directory);
_sendRequestExpectAck(&request);
#endif
}
/// @brief Sends a command which only requires an opcode and no additional data
/// @param opcode Opcode to send
/// @param newOpState State to put state machine into
/// @return TRUE: command sent, FALSE: command not sent, waiting for previous command to finish
bool FTPManager::_sendOpcodeOnlyCmd(MavlinkFTP::OpCode_t opcode, MavlinkFTP::OpCode_t newWaitState)
void FTPManager::_resetSessionsBegin(void)
{
if (_waitState != MavlinkFTP::kCmdNone) {
// Can't have multiple commands in play at the same time
return false;
}
_waitState = newWaitState;
MavlinkFTP::Request request;
request.hdr.session = 0;
request.hdr.opcode = opcode;
request.hdr.offset = 0;
request.hdr.opcode = MavlinkFTP::kCmdResetSessions;
request.hdr.size = 0;
_sendRequestExpectAck(&request);
return true;
}
void FTPManager::_ackTimeout(void)
void FTPManager::_resetSessionsAckOrNak(const MavlinkFTP::Request* ackOrNak)
{
qCDebug(FTPManagerLog) << "_ackTimeout" << MavlinkFTP::opCodeToString(static_cast<MavlinkFTP::OpCode_t>(_waitState));
switch (_waitState) {
case MavlinkFTP::kCmdReadFile:
// FIXME: retry count?
// Resend last request
_lastOutgoingRequest.hdr.seqNumber--;
_sendRequestExpectAck(&_lastOutgoingRequest);
return;
default:
break;
}
#if 0
if (++_ackNumTries <= _ackTimerMaxRetries) {
qCDebug(FTPManagerLog) << "ack timeout - retrying";
if (_currentOperation == kCOBurst) {
// for burst downloads try to initiate a new burst
MavlinkFTP::Request request;
request.hdr.session = _activeSession;
request.hdr.opcode = MavlinkFTP::kCmdBurstReadFile;
request.hdr.offset = _downloadOffset;
request.hdr.size = 0;
request.hdr.seqNumber = ++_lastOutgoingRequest.hdr.seqNumber;
MavlinkFTP::OpCode_t requestOpCode = static_cast<MavlinkFTP::OpCode_t>(ackOrNak->hdr.req_opcode);
_sendRequestNoAck(&request);
} else {
_sendRequestNoAck(&_lastOutgoingRequest);
if (requestOpCode != MavlinkFTP::kCmdResetSessions) {
qCDebug(FTPManagerLog) << "_fillMissingBlocksAckOrNak: Disregarding due to incorrect requestOpCode" << MavlinkFTP::opCodeToString(requestOpCode);
return;
}
if (ackOrNak->hdr.seqNumber != _expectedIncomingSeqNumber) {
qCDebug(FTPManagerLog) << "_resetSessionsAckOrNak: Disregarding due to incorrect sequence actual:expected" << ackOrNak->hdr.seqNumber << _expectedIncomingSeqNumber;
return;
}
#endif
// 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::kCmdBurstReadFile:
case MavlinkFTP::kCmdReadFile:
_downloadComplete(tr("Download failed: Vehicle did not respond to %1").arg(MavlinkFTP::opCodeToString(_waitState)));
break;
#if 0
// FIXME: NYI
case kCOOpenRead:
case kCOOpenBurst:
_currentOperation = kCOIdle;
_emitErrorMessage(tr("Timeout waiting for ack: Download failed"));
_sendResetCommand();
break;
case kCOCreate:
_currentOperation = kCOIdle;
_emitErrorMessage(tr("Timeout waiting for ack: Upload failed"));
_sendResetCommand();
break;
_ackOrNakTimeoutTimer.stop();
case kCOWrite:
_closeUploadSession(false /* failure */);
_emitErrorMessage(tr("Timeout waiting for ack: Upload failed"));
break;
#endif
default:
{
MavlinkFTP::OpCode_t _lastCommand = _waitState;
_waitState = MavlinkFTP::kCmdNone;
_emitErrorMessage(QString("Timeout waiting for ack: Command failed (%1)").arg(MavlinkFTP::opCodeToString(_lastCommand)));
}
break;
if (ackOrNak->hdr.opcode == MavlinkFTP::kRspAck) {
qCDebug(FTPManagerLog) << "_resetSessionsAckOrNak: Ack";
_advanceStateMachine();
} else if (ackOrNak->hdr.opcode == MavlinkFTP::kRspNak) {
qCDebug(FTPManagerLog) << "_resetSessionsAckOrNak: Nak -" << _errorMsgFromNak(ackOrNak);
_downloadComplete(QString());
}
}
void FTPManager::_sendResetCommand(void)
void FTPManager::_resetSessionsTimeout(void)
{
MavlinkFTP::Request request;
request.hdr.opcode = MavlinkFTP::kCmdResetSessions;
request.hdr.size = 0;
_waitState = MavlinkFTP::kCmdResetSessions;
_sendRequestExpectAck(&request);
qCDebug(FTPManagerLog) << "_resetSessionsTimeout";
_downloadComplete(QString());
}
void FTPManager::_emitErrorMessage(const QString& msg)
......@@ -822,41 +525,29 @@ void FTPManager::_emitErrorMessage(const QString& msg)
emit commandError(msg);
}
void FTPManager::_emitListEntry(const QString& entry)
{
qCDebug(FTPManagerLog) << "_emitListEntry" << entry;
emit listEntry(entry);
}
void FTPManager::_sendRequestExpectAck(MavlinkFTP::Request* request)
{
_ackTimer.start();
LinkInterface* primaryLink = _vehicle->vehicleLinkManager()->primaryLink();
request->hdr.seqNumber = ++_lastOutgoingRequest.hdr.seqNumber;
qCDebug(FTPManagerLog) << "_sendRequestExpectAck opcode:" << MavlinkFTP::opCodeToString(static_cast<MavlinkFTP::OpCode_t>(request->hdr.opcode)) << "seqNumber:" << request->hdr.seqNumber;
_ackOrNakTimeoutTimer.start();
if (request->hdr.size <= sizeof(request->data)) {
memcpy(&_lastOutgoingRequest, request, sizeof(MavlinkFTP::RequestHeader) + request->hdr.size);
} else {
// FIXME: Shouldn't this fail something?
qCCritical(FTPManagerLog) << "request length too long:" << request->hdr.size;
}
if (primaryLink) {
request->hdr.seqNumber = _expectedIncomingSeqNumber + 1; // Outgoing is 1 past last incoming
_expectedIncomingSeqNumber += 2;
_sendRequestNoAck(request);
}
void FTPManager::_sendRequestNoAck(MavlinkFTP::Request* request)
{
qCDebug(FTPManagerLog) << "_sendRequestNoAck opcode:" << MavlinkFTP::opCodeToString(static_cast<MavlinkFTP::OpCode_t>(request->hdr.opcode));
qCDebug(FTPManagerLog) << "_sendRequestExpectAck opcode:" << MavlinkFTP::opCodeToString(static_cast<MavlinkFTP::OpCode_t>(request->hdr.opcode)) << "seqNumber:" << request->hdr.seqNumber;
mavlink_message_t message;
mavlink_msg_file_transfer_protocol_pack_chan(qgcApp()->toolbox()->mavlinkProtocol()->getSystemId(),
qgcApp()->toolbox()->mavlinkProtocol()->getComponentId(),
_dedicatedLink->mavlinkChannel(),
primaryLink->mavlinkChannel(),
&message,
0, // Target network, 0=broadcast?
_vehicle->id(),
MAV_COMP_ID_AUTOPILOT1,
(uint8_t*)request); // Payload
_vehicle->sendMessageOnLinkThreadSafe(_dedicatedLink, message);
_vehicle->sendMessageOnLinkThreadSafe(primaryLink, message);
} else {
qCDebug(FTPManagerLog) << "_sendRequestExpectAck No primary link. Allowing timeout to fail sequence.";
}
}
......@@ -7,7 +7,6 @@
*
****************************************************************************/
#pragma once
#include <QObject>
......@@ -27,6 +26,8 @@ class FTPManager : public QObject
{
Q_OBJECT
friend class Vehicle;
public:
FTPManager(Vehicle* vehicle);
......@@ -37,31 +38,8 @@ public:
/// Signals downloadComplete, commandError, commandProgress
bool download(const QString& from, const QString& toDir);
/// Stream downloads the specified file.
/// @param from File to download from UAS, fully qualified path. May be in the format mavlinkftp://...
/// @param toDir Local directory to download file to
/// @return true: download has started, false: error, no download
/// Signals downloadComplete, commandError, commandProgress
bool burstDownload(const QString& from, const QString& toDir);
/// Lists the specified directory. Emits listEntry signal for each entry, followed by listComplete signal.
/// @param dirPath Fully qualified path to list
void listDirectory(const QString& dirPath);
/// Upload the specified file to the specified location
void upload(const QString& toPath, const QFileInfo& uploadFile);
/// Create a remote directory
void createDirectory(const QString& directory);
void mavlinkMessageReceived(mavlink_message_t message);
signals:
void downloadComplete (const QString& file, const QString& errorMsg);
void uploadComplete (const QString& errorMsg);
/// Signalled to indicate a new directory entry was received.
void listEntry(const QString& entry);
void downloadComplete(const QString& file, const QString& errorMsg);
// Signals associated with all commands
......@@ -75,58 +53,30 @@ signals:
void commandProgress(int value);
private slots:
void _ackTimeout(void);
void _ackOrNakTimeout(void);
private:
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
QTimer _ackTimer; ///< Used to signal a timeout waiting for an ack
int _ackNumTries; ///< current number of tries
Vehicle* _vehicle;
LinkInterface* _dedicatedLink = nullptr; ///< Link to use for communication
MavlinkFTP::Request _lastOutgoingRequest; ///< contains the last outgoing packet
unsigned _listOffset; ///< offset for the current List operation
QString _listPath; ///< path for the current List operation
uint8_t _activeSession = 0; ///< currently active session, 0 for none
uint32_t _readOffset; ///< current read offset
uint32_t _writeOffset; ///< current write offset
uint32_t _writeSize; ///< current write data size
uint32_t _writeFileSize; ///< Size of file being uploaded
QByteArray _writeFileAccumulator; ///< Holds file being uploaded
typedef void (FTPManager::*StateBeginFn) (void);
typedef void (FTPManager::*StateAckNakFn) (const MavlinkFTP::Request* ackOrNak);
typedef void (FTPManager::*StateTimeoutFn) (void);
typedef struct {
StateBeginFn beginFn;
StateAckNakFn ackNakFn;
StateTimeoutFn timeoutFn;
} StateFunctions_t;
typedef struct {
uint32_t offset;
uint32_t cBytes;
uint32_t cBytesMissing;
} 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
typedef struct {
uint8_t sessionId;
uint32_t expectedOffset; ///< offset which should be coming next
uint32_t bytesWritten;
QList<MissingData_t> missingData;
QList<MissingData_t> rgMissingData;
QString fullPathOnVehicle; ///< Fully qualified path to file on vehicle
QDir toDir; ///< Directory to download file to
QString fileName; ///< Filename (no path) for download file
uint32_t fileSize; ///< Size of file being downloaded
......@@ -134,17 +84,51 @@ private:
int retryCount;
void reset() {
expectedBurstOffset = 0;
expectedReadOffset = 0;
sessionId = 0;
expectedOffset = 0;
bytesWritten = 0;
retryCount = 0;
missingData.clear();
fileSize = 0;
fullPathOnVehicle.clear();
fileName.clear();
rgMissingData.clear();
file.close();
}
} _downloadState;
} DownloadState_t;
void _mavlinkMessageReceived (const mavlink_message_t& message);
void _startStateMachine (void);
void _advanceStateMachine (void);
void _openFileROBegin (void);
void _openFileROAckOrNak (const MavlinkFTP::Request* ackOrNak);
void _openFileROTimeout (void);
void _burstReadFileBegin (void);
void _burstReadFileAckOrNak (const MavlinkFTP::Request* ackOrNak);
void _burstReadFileTimeout (void);
void _fillMissingBlocksBegin (void);
void _fillMissingBlocksAckOrNak (const MavlinkFTP::Request* ackOrNak);
void _fillMissingBlocksTimeout (void);
void _resetSessionsBegin (void);
void _resetSessionsAckOrNak (const MavlinkFTP::Request* ackOrNak);
void _resetSessionsTimeout (void);
QString _errorMsgFromNak (const MavlinkFTP::Request* nak);
void _sendRequestExpectAck (MavlinkFTP::Request* request);
void _downloadCompleteNoError (void) { _downloadComplete(QString()); }
void _downloadComplete (const QString& errorMsg);
void _emitErrorMessage (const QString& msg);
void _fillRequestDataWithString(MavlinkFTP::Request* request, const QString& str);
void _fillMissingBlocksWorker (bool firstRequest);
void _burstReadFileWorker (bool firstRequest);
static const int _ackTimerTimeoutMsecs = 1000;
static const int _ackTimerMaxRetries = 6;
static const int _maxRetry = 5;
Vehicle* _vehicle;
QList<StateFunctions_t> _rgStateMachine;
DownloadState_t _downloadState;
QTimer _ackOrNakTimeoutTimer;
int _currentStateMachineIndex = -1;
uint16_t _expectedIncomingSeqNumber = 0;
static const int _ackOrNakTimeoutMsecs = 1000;
static const int _maxRetry = 3;
};
......@@ -17,6 +17,11 @@ const FTPManagerTest::TestCase_t FTPManagerTest::_rgTestCases[] = {
{ "/version.json" },
};
void FTPManagerTest::cleanup(void)
{
_disconnectMockLink();
}
void FTPManagerTest::_testCaseWorker(const TestCase_t& testCase)
{
_connectMockLinkNoInitialConnectSequence();
......
......@@ -20,6 +20,9 @@ private slots:
void _performTestCases (void);
void _testLostPackets (void);
// Overrides from UnitTest
void cleanup(void) override;
private:
typedef struct {
const char* file;
......
......@@ -600,7 +600,7 @@ void Vehicle::_mavlinkMessageReceived(LinkInterface* link, mavlink_message_t mes
if (!_terrainProtocolHandler->mavlinkMessageReceived(message)) {
return;
}
_ftpManager->mavlinkMessageReceived(message);
_ftpManager->_mavlinkMessageReceived(message);
_parameterManager->mavlinkMessageReceived(message);
_waitForMavlinkMessageMessageReceived(message);
......
This source diff could not be displayed because it is too large. You can view the blob instead.
......@@ -231,7 +231,10 @@ void MockLinkFTP::_burstReadCommand(uint8_t senderSystemId, uint8_t senderCompon
burstOffset += cBytes;
}
if (burstOffset >= _currentFile.size()) {
// Burst is fully complete
_sendNak(senderSystemId, senderComponentId, MavlinkFTP::kErrEOF, outgoingSeqNumber, MavlinkFTP::kCmdBurstReadFile);
}
}
void MockLinkFTP::_terminateCommand(uint8_t senderSystemId, uint8_t senderComponentId, MavlinkFTP::Request* request, uint16_t seqNumber)
......@@ -352,7 +355,7 @@ void MockLinkFTP::_sendAck(uint8_t targetSystemId, uint8_t targetComponentId, ui
ackResponse.hdr.opcode = MavlinkFTP::kRspAck;
ackResponse.hdr.req_opcode = reqOpcode;
ackResponse.hdr.session = 0;
ackResponse.hdr.session = _sessionId;
ackResponse.hdr.size = 0;
_sendResponse(targetSystemId, targetComponentId, &ackResponse, seqNumber);
......@@ -364,7 +367,7 @@ void MockLinkFTP::_sendNak(uint8_t targetSystemId, uint8_t targetComponentId, Ma
nakResponse.hdr.opcode = MavlinkFTP::kRspNak;
nakResponse.hdr.req_opcode = reqOpcode;
nakResponse.hdr.session = 0;
nakResponse.hdr.session = _sessionId;
nakResponse.hdr.size = 1;
nakResponse.data[0] = error;
......@@ -377,7 +380,7 @@ void MockLinkFTP::_sendNakErrno(uint8_t targetSystemId, uint8_t targetComponentI
nakResponse.hdr.opcode = MavlinkFTP::kRspNak;
nakResponse.hdr.req_opcode = reqOpcode;
nakResponse.hdr.session = 0;
nakResponse.hdr.session = _sessionId;
nakResponse.hdr.size = 2;
nakResponse.data[0] = MavlinkFTP::kErrFailErrno;
nakResponse.data[1] = nakErrno;
......
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