Browse Source

ComponentInformationManager: add fallback & abort slow mavlink ftp downloads

QGC4.4
Beat Küng 4 years ago committed by Don Gagne
parent
commit
4d551281ed
  1. 3
      src/Vehicle/CompInfo.h
  2. 48
      src/Vehicle/ComponentInformationManager.cc
  3. 6
      src/Vehicle/ComponentInformationManager.h

3
src/Vehicle/CompInfo.h

@ -29,10 +29,13 @@ public: @@ -29,10 +29,13 @@ public:
CompInfo(COMP_METADATA_TYPE type, uint8_t compId, Vehicle* vehicle, QObject* parent = nullptr);
const QString& uriMetaData() const { return _uris.uriMetaData; }
const QString& uriMetaDataFallback() const { return _uris.uriMetaDataFallback; }
const QString& uriTranslation() const { return _uris.uriTranslation; }
uint32_t crcMetaData() const { return _uris.crcMetaData; }
uint32_t crcMetaDataFallback() const { return _uris.crcMetaDataFallback; }
bool crcMetaDataValid() const { return _uris.crcMetaDataValid; }
bool crcMetaDataFallbackValid() const { return _uris.crcMetaDataFallbackValid; }
uint32_t crcTranslation() const { return _uris.crcTranslation; }
bool crcTranslationValid() const { return _uris.crcTranslationValid; }

48
src/Vehicle/ComponentInformationManager.cc

@ -37,6 +37,7 @@ int ComponentInformationManager::_cStates = sizeof(ComponentInformationManager:: @@ -37,6 +37,7 @@ int ComponentInformationManager::_cStates = sizeof(ComponentInformationManager::
RequestMetaDataTypeStateMachine::StateFn RequestMetaDataTypeStateMachine::_rgStates[]= {
RequestMetaDataTypeStateMachine::_stateRequestCompInfo,
RequestMetaDataTypeStateMachine::_stateRequestMetaDataJson,
RequestMetaDataTypeStateMachine::_stateRequestMetaDataJsonFallback,
RequestMetaDataTypeStateMachine::_stateRequestTranslationJson,
RequestMetaDataTypeStateMachine::_stateRequestComplete,
};
@ -264,6 +265,7 @@ void RequestMetaDataTypeStateMachine::_ftpDownloadComplete(const QString& fileNa @@ -264,6 +265,7 @@ void RequestMetaDataTypeStateMachine::_ftpDownloadComplete(const QString& fileNa
qCDebug(ComponentInformationManagerLog) << "RequestMetaDataTypeStateMachine::_ftpDownloadComplete fileName:errorMsg" << fileName << errorMsg;
disconnect(_compInfo->vehicle->ftpManager(), &FTPManager::downloadComplete, this, &RequestMetaDataTypeStateMachine::_ftpDownloadComplete);
disconnect(_compInfo->vehicle->ftpManager(), &FTPManager::commandProgress, this, &RequestMetaDataTypeStateMachine::_ftpDownloadProgress);
if (errorMsg.isEmpty()) {
if (_currentFileName) {
*_currentFileName = _downloadCompleteJsonWorker(fileName);
@ -271,11 +273,24 @@ void RequestMetaDataTypeStateMachine::_ftpDownloadComplete(const QString& fileNa @@ -271,11 +273,24 @@ void RequestMetaDataTypeStateMachine::_ftpDownloadComplete(const QString& fileNa
} else if (qgcApp()->runningUnitTests()) {
// Unit test should always succeed
qCWarning(ComponentInformationManagerLog) << "RequestMetaDataTypeStateMachine::_ftpDownloadComplete failed filename:errorMsg" << fileName << errorMsg;
} // TODO: else: try fallback uri
}
advance();
}
void RequestMetaDataTypeStateMachine::_ftpDownloadProgress(float progress)
{
int elapsedSec = _downloadStartTime.elapsed() / 1000;
float totalDownloadTime = elapsedSec / progress;
// abort download if it's too slow (e.g. over telemetry link) and use the fallback.
// (we could also check if there's a http fallback)
const int maxDownloadTimeSec = 40;
if (elapsedSec > 10 && progress < 0.5 && totalDownloadTime > maxDownloadTimeSec) {
qCDebug(ComponentInformationManagerLog) << "Slow download, aborting. Total time (s):" << totalDownloadTime;
_compInfo->vehicle->ftpManager()->cancel();
}
}
void RequestMetaDataTypeStateMachine::_httpDownloadComplete(QString remoteFile, QString localFile, QString errorMsg)
{
qCDebug(ComponentInformationManagerLog) << "RequestMetaDataTypeStateMachine::_httpDownloadComplete remoteFile:localFile:errorMsg" << remoteFile << localFile << errorMsg;
@ -288,7 +303,7 @@ void RequestMetaDataTypeStateMachine::_httpDownloadComplete(QString remoteFile, @@ -288,7 +303,7 @@ void RequestMetaDataTypeStateMachine::_httpDownloadComplete(QString remoteFile,
} else if (qgcApp()->runningUnitTests()) {
// Unit test should always succeed
qCWarning(ComponentInformationManagerLog) << "RequestMetaDataTypeStateMachine::_httpDownloadCompleteMetaDataJson failed remoteFile:localFile:errorMsg" << remoteFile << localFile << errorMsg;
} // TODO: else: try fallback uri
}
advance();
}
@ -299,6 +314,7 @@ void RequestMetaDataTypeStateMachine::_requestFile(const QString& cacheFileTag, @@ -299,6 +314,7 @@ void RequestMetaDataTypeStateMachine::_requestFile(const QString& cacheFileTag,
_currentCacheFileTag = cacheFileTag;
_currentFileName = &outputFileName;
_currentFileValidCrc = crcValid;
outputFileName.clear();
if (_compInfo->available() && !uri.isEmpty()) {
const QString cachedFile = crcValid ? _compMgr->fileCache().access(cacheFileTag) : "";
@ -307,19 +323,22 @@ void RequestMetaDataTypeStateMachine::_requestFile(const QString& cacheFileTag, @@ -307,19 +323,22 @@ void RequestMetaDataTypeStateMachine::_requestFile(const QString& cacheFileTag,
qCDebug(ComponentInformationManagerLog) << "Downloading json" << uri;
if (_uriIsMAVLinkFTP(uri)) {
connect(ftpManager, &FTPManager::downloadComplete, this, &RequestMetaDataTypeStateMachine::_ftpDownloadComplete);
if (!ftpManager->download(uri, QStandardPaths::writableLocation(QStandardPaths::TempLocation))) {
if (ftpManager->download(uri, QStandardPaths::writableLocation(QStandardPaths::TempLocation))) {
_downloadStartTime.start();
connect(ftpManager, &FTPManager::commandProgress, this, &RequestMetaDataTypeStateMachine::_ftpDownloadProgress);
} else {
qCWarning(ComponentInformationManagerLog) << "RequestMetaDataTypeStateMachine::_requestFile FTPManager::download returned failure";
disconnect(ftpManager, &FTPManager::downloadComplete, this, &RequestMetaDataTypeStateMachine::_ftpDownloadComplete);
// TODO: try fallback uri
advance();
}
} else {
QGCFileDownload* download = new QGCFileDownload(this);
connect(download, &QGCFileDownload::downloadComplete, this, &RequestMetaDataTypeStateMachine::_httpDownloadComplete);
if (!download->download(uri)) {
if (download->download(uri)) {
_downloadStartTime.start();
} else {
qCWarning(ComponentInformationManagerLog) << "RequestMetaDataTypeStateMachine::_requestFile QGCFileDownload::download returned failure";
disconnect(download, &QGCFileDownload::downloadComplete, this, &RequestMetaDataTypeStateMachine::_httpDownloadComplete);
// TODO: try fallback uri
advance();
}
}
@ -346,6 +365,23 @@ void RequestMetaDataTypeStateMachine::_stateRequestMetaDataJson(StateMachine* st @@ -346,6 +365,23 @@ void RequestMetaDataTypeStateMachine::_stateRequestMetaDataJson(StateMachine* st
requestMachine->_requestFile(fileTag, compInfo->crcMetaDataValid(), uri, requestMachine->_jsonMetadataFileName);
}
void RequestMetaDataTypeStateMachine::_stateRequestMetaDataJsonFallback(StateMachine* stateMachine)
{
RequestMetaDataTypeStateMachine* requestMachine = static_cast<RequestMetaDataTypeStateMachine*>(stateMachine);
if (!requestMachine->_jsonMetadataFileName.isEmpty()) {
requestMachine->advance();
return;
}
qCDebug(ComponentInformationManagerLog) << "RequestMetaDataTypeStateMachine::_stateRequestMetaDataJsonFallback: trying fallback download";
CompInfo* compInfo = requestMachine->compInfo();
const QString fileTag = ComponentInformationManager::_getFileCacheTag(
compInfo->type, compInfo->crcMetaDataFallback(), false);
const QString uri = compInfo->uriMetaDataFallback();
requestMachine->_jsonMetadataCrcValid = compInfo->crcMetaDataFallbackValid();
requestMachine->_requestFile(fileTag, compInfo->crcMetaDataFallbackValid(), uri, requestMachine->_jsonMetadataFileName);
}
void RequestMetaDataTypeStateMachine::_stateRequestTranslationJson(StateMachine* stateMachine)
{
RequestMetaDataTypeStateMachine* requestMachine = static_cast<RequestMetaDataTypeStateMachine*>(stateMachine);

6
src/Vehicle/ComponentInformationManager.h

@ -14,6 +14,8 @@ @@ -14,6 +14,8 @@
#include "StateMachine.h"
#include "ComponentInformationCache.h"
#include <QTime>
Q_DECLARE_LOGGING_CATEGORY(ComponentInformationManagerLog)
class Vehicle;
@ -40,12 +42,14 @@ public: @@ -40,12 +42,14 @@ public:
private slots:
void _ftpDownloadComplete (const QString& file, const QString& errorMsg);
void _ftpDownloadProgress (float progress);
void _httpDownloadComplete (QString remoteFile, QString localFile, QString errorMsg);
QString _downloadCompleteJsonWorker (const QString& jsonFileName);
private:
static void _stateRequestCompInfo (StateMachine* stateMachine);
static void _stateRequestMetaDataJson (StateMachine* stateMachine);
static void _stateRequestMetaDataJsonFallback(StateMachine* stateMachine);
static void _stateRequestTranslationJson (StateMachine* stateMachine);
static void _stateRequestComplete (StateMachine* stateMachine);
static bool _uriIsMAVLinkFTP (const QString& uri);
@ -63,6 +67,8 @@ private: @@ -63,6 +67,8 @@ private:
QString _currentCacheFileTag;
bool _currentFileValidCrc = false;
QTime _downloadStartTime;
static StateFn _rgStates[];
static int _cStates;
};

Loading…
Cancel
Save