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();
}
......
This diff is collapsed.
......@@ -7,7 +7,6 @@
*
****************************************************************************/
#pragma once
#include <QObject>
......@@ -26,6 +25,8 @@ class Vehicle;
class FTPManager : public QObject
{
Q_OBJECT
friend class Vehicle;
public:
FTPManager(Vehicle* vehicle);
......@@ -36,32 +37,9 @@ public:
/// @return true: download has started, false: error, no download
/// 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;
bytesWritten = 0;
retryCount = 0;
missingData.clear();
sessionId = 0;
expectedOffset = 0;
bytesWritten = 0;
retryCount = 0;
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 diff is collapsed.
......@@ -206,7 +206,7 @@ void MockLinkFTP::_burstReadCommand(uint8_t senderSystemId, uint8_t senderCompon
int burstMax = 10;
int burstCount = 1;
uint32_t burstOffset = request->hdr.offset;
while (burstOffset < _currentFile.size() && burstCount++ < burstMax) {
_currentFile.seek(burstOffset);
......@@ -231,7 +231,10 @@ void MockLinkFTP::_burstReadCommand(uint8_t senderSystemId, uint8_t senderCompon
burstOffset += cBytes;
}
_sendNak(senderSystemId, senderComponentId, MavlinkFTP::kErrEOF, outgoingSeqNumber, MavlinkFTP::kCmdBurstReadFile);
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