diff --git a/src/API/QGCCorePlugin.cc b/src/API/QGCCorePlugin.cc index 62aa405a364..eff380070ab 100644 --- a/src/API/QGCCorePlugin.cc +++ b/src/API/QGCCorePlugin.cc @@ -75,11 +75,6 @@ const QVariantList &QGCCorePlugin::analyzePages() QUrl::fromUserInput(QStringLiteral("qrc:/qml/QGroundControl/AnalyzeView/OnboardLogs/OnboardLogPage.qml")), QUrl::fromUserInput(QStringLiteral("qrc:/qmlimages/OnboardLogIcon.svg")), nullptr, true /* requiresVehicle */)), - QVariant::fromValue(new QmlComponentInfo( - tr("Onboard Logs (FTP)"), - QUrl::fromUserInput(QStringLiteral("qrc:/qml/QGroundControl/AnalyzeView/OnboardLogsFtp/OnboardLogFtpPage.qml")), - QUrl::fromUserInput(QStringLiteral("qrc:/qmlimages/OnboardLogIcon.svg")), - nullptr, true /* requiresVehicle */)), QVariant::fromValue(new QmlComponentInfo( tr("GeoTag Images"), QUrl::fromUserInput(QStringLiteral("qrc:/qml/QGroundControl/AnalyzeView/GeoTag/GeoTagPage.qml")), diff --git a/src/AnalyzeView/CMakeLists.txt b/src/AnalyzeView/CMakeLists.txt index a6cd0a4837a..ac9de469a9d 100644 --- a/src/AnalyzeView/CMakeLists.txt +++ b/src/AnalyzeView/CMakeLists.txt @@ -7,11 +7,6 @@ add_subdirectory(GeoTag) add_subdirectory(MAVLinkConsole) add_subdirectory(MAVLinkInspector) add_subdirectory(OnboardLogs) -add_subdirectory(OnboardLogsFtp) - -target_sources(${CMAKE_PROJECT_NAME} - PRIVATE -) target_include_directories(${CMAKE_PROJECT_NAME} PRIVATE ${CMAKE_CURRENT_SOURCE_DIR}) @@ -32,7 +27,7 @@ qt_add_qml_module(AnalyzeViewModule MAVLinkInspector/MAVLinkMessageButton.qml MAVLinkInspector/MAVLinkInspectorPage.qml OnboardLogs/OnboardLogPage.qml - OnboardLogsFtp/OnboardLogFtpPage.qml + OnboardLogs/OnboardLogTable.qml Vibration/VibrationPage.qml NO_PLUGIN ) diff --git a/src/AnalyzeView/OnboardLogs/CMakeLists.txt b/src/AnalyzeView/OnboardLogs/CMakeLists.txt index f47679afa27..f54c4ef6be3 100644 --- a/src/AnalyzeView/OnboardLogs/CMakeLists.txt +++ b/src/AnalyzeView/OnboardLogs/CMakeLists.txt @@ -1,14 +1,22 @@ # ============================================================================ # Onboard Logs Module -# Onboard log list and download functionality +# Onboard log list and download (LOG protocol + MAVLink FTP) # ============================================================================ target_sources(${CMAKE_PROJECT_NAME} PRIVATE + FtpTransport.cc + FtpTransport.h + LogProtocolTransport.cc + LogProtocolTransport.h OnboardLogController.cc OnboardLogController.h + OnboardLogDownloadData.cc + OnboardLogDownloadData.h OnboardLogEntry.cc OnboardLogEntry.h + OnboardLogTransport.cc + OnboardLogTransport.h ) target_include_directories(${CMAKE_PROJECT_NAME} PRIVATE ${CMAKE_CURRENT_SOURCE_DIR}) diff --git a/src/AnalyzeView/OnboardLogsFtp/OnboardLogFtpController.cc b/src/AnalyzeView/OnboardLogs/FtpTransport.cc similarity index 53% rename from src/AnalyzeView/OnboardLogsFtp/OnboardLogFtpController.cc rename to src/AnalyzeView/OnboardLogs/FtpTransport.cc index 048af7f3324..677b6698e14 100644 --- a/src/AnalyzeView/OnboardLogsFtp/OnboardLogFtpController.cc +++ b/src/AnalyzeView/OnboardLogs/FtpTransport.cc @@ -1,8 +1,14 @@ -#include "OnboardLogFtpController.h" +#include "FtpTransport.h" + +#include +#include +#include +#include + #include "AppSettings.h" #include "FTPManager.h" #include "MultiVehicleManager.h" -#include "OnboardLogFtpEntry.h" +#include "OnboardLogEntry.h" #include "QGCFormat.h" #include "QGCLoggingCategory.h" #include "QmlObjectListModel.h" @@ -10,36 +16,30 @@ #include "Vehicle.h" #include "VehicleLinkManager.h" -#include -#include -#include -#include - -QGC_LOGGING_CATEGORY(OnboardLogFtpControllerLog, "AnalyzeView.OnboardLogFtpController") +QGC_LOGGING_CATEGORY(FtpTransportLog, "AnalyzeView.FtpTransport") // MAVLink FTP defines "@MAV_LOG" as the virtual log directory. // Older firmware that doesn't implement the alias requires the physical path // instead — which is firmware-specific. -static constexpr const char *kMavlinkLogRoot = "@MAV_LOG"; -static constexpr const char *kPx4LogRootFallback = "/fs/microsd/log"; -static constexpr const char *kApmLogRootFallback = "/APM/LOGS"; +static constexpr const char* kMavlinkLogRoot = "@MAV_LOG"; +static constexpr const char* kPx4LogRootFallback = "/fs/microsd/log"; +static constexpr const char* kApmLogRootFallback = "/APM/LOGS"; -OnboardLogFtpController::OnboardLogFtpController(QObject *parent) - : QObject(parent) - , _logEntriesModel(new QmlObjectListModel(this)) +FtpTransport::FtpTransport(QObject* parent) : OnboardLogTransport(parent) { - qCDebug(OnboardLogFtpControllerLog) << this; + qCDebug(FtpTransportLog) << this; - (void) connect(MultiVehicleManager::instance(), &MultiVehicleManager::activeVehicleChanged, this, &OnboardLogFtpController::_setActiveVehicle); + (void)connect(MultiVehicleManager::instance(), &MultiVehicleManager::activeVehicleChanged, this, + &FtpTransport::_setActiveVehicle); _setActiveVehicle(MultiVehicleManager::instance()->activeVehicle()); } -OnboardLogFtpController::~OnboardLogFtpController() +FtpTransport::~FtpTransport() { - qCDebug(OnboardLogFtpControllerLog) << this; + qCDebug(FtpTransportLog) << this; } -void OnboardLogFtpController::_setActiveVehicle(Vehicle *vehicle) +void FtpTransport::_setActiveVehicle(Vehicle* vehicle) { if (vehicle == _vehicle) { return; @@ -47,10 +47,10 @@ void OnboardLogFtpController::_setActiveVehicle(Vehicle *vehicle) if (_vehicle) { _logEntriesModel->clearAndDeleteContents(); - FTPManager *const ftp = _vehicle->ftpManager(); - (void) disconnect(ftp, &FTPManager::listDirectoryComplete, this, &OnboardLogFtpController::_listDirComplete); - (void) disconnect(ftp, &FTPManager::downloadComplete, this, &OnboardLogFtpController::_downloadComplete); - (void) disconnect(ftp, &FTPManager::commandProgress, this, &OnboardLogFtpController::_downloadProgress); + FTPManager* const ftp = _vehicle->ftpManager(); + (void)disconnect(ftp, &FTPManager::listDirectoryComplete, this, &FtpTransport::_listDirComplete); + (void)disconnect(ftp, &FTPManager::downloadComplete, this, &FtpTransport::_downloadComplete); + (void)disconnect(ftp, &FTPManager::commandProgress, this, &FtpTransport::_downloadProgress); _listState = Idle; _dirsToList.clear(); @@ -62,56 +62,56 @@ void OnboardLogFtpController::_setActiveVehicle(Vehicle *vehicle) _vehicle = vehicle; } -void OnboardLogFtpController::refresh() +void FtpTransport::refresh() { _logEntriesModel->clearAndDeleteContents(); if (!_vehicle) { - qCWarning(OnboardLogFtpControllerLog) << "refresh: no active vehicle"; + qCWarning(FtpTransportLog) << "refresh: no active vehicle"; return; } if (!_vehicle->capabilitiesKnown() || !(_vehicle->capabilityBits() & MAV_PROTOCOL_CAPABILITY_FTP)) { - qCWarning(OnboardLogFtpControllerLog) << "refresh: vehicle does not advertise MAV_PROTOCOL_CAPABILITY_FTP" - << "(capsKnown:" << _vehicle->capabilitiesKnown() << ")"; + qCWarning(FtpTransportLog) << "refresh: vehicle does not advertise MAV_PROTOCOL_CAPABILITY_FTP" + << "(capsKnown:" << _vehicle->capabilitiesKnown() << ")"; return; } _startListing(); } -void OnboardLogFtpController::_startListing() +void FtpTransport::_startListing() { _dirsToList.clear(); _logIdCounter = 0; _logRoot = QString::fromLatin1(kMavlinkLogRoot); _triedFallbackRoot = false; - FTPManager *const ftp = _vehicle->ftpManager(); - (void) disconnect(ftp, &FTPManager::listDirectoryComplete, this, &OnboardLogFtpController::_listDirComplete); - (void) connect(ftp, &FTPManager::listDirectoryComplete, this, &OnboardLogFtpController::_listDirComplete); + FTPManager* const ftp = _vehicle->ftpManager(); + (void)disconnect(ftp, &FTPManager::listDirectoryComplete, this, &FtpTransport::_listDirComplete); + (void)connect(ftp, &FTPManager::listDirectoryComplete, this, &FtpTransport::_listDirComplete); _setListing(true); _listRoot(); } -void OnboardLogFtpController::_listRoot() +void FtpTransport::_listRoot() { _listState = ListingRoot; - qCDebug(OnboardLogFtpControllerLog) << "listing root" << _logRoot; + qCDebug(FtpTransportLog) << "listing root" << _logRoot; if (!_vehicle->ftpManager()->listDirectory(MAV_COMP_ID_AUTOPILOT1, _logRoot)) { - qCWarning(OnboardLogFtpControllerLog) << "failed to start root listing for" << _logRoot; + qCWarning(FtpTransportLog) << "failed to start root listing for" << _logRoot; _finishListing(); } } -void OnboardLogFtpController::_listDirComplete(const QStringList &dirList, const QString &errorMsg) +void FtpTransport::_listDirComplete(const QStringList& dirList, const QString& errorMsg) { if (!errorMsg.isEmpty()) { if (_listState == ListingRoot && !_triedFallbackRoot && _vehicle) { - const char *fallback = nullptr; + const char* fallback = nullptr; if (_vehicle->px4Firmware()) { fallback = kPx4LogRootFallback; } else if (_vehicle->apmFirmware()) { @@ -119,8 +119,8 @@ void OnboardLogFtpController::_listDirComplete(const QStringList &dirList, const } if (fallback) { - qCDebug(OnboardLogFtpControllerLog) << "root listing of" << _logRoot << "failed (" << errorMsg - << "), falling back to" << fallback; + qCDebug(FtpTransportLog) << "root listing of" << _logRoot << "failed (" << errorMsg + << "), falling back to" << fallback; _triedFallbackRoot = true; _logRoot = QString::fromLatin1(fallback); _listRoot(); @@ -128,7 +128,7 @@ void OnboardLogFtpController::_listDirComplete(const QStringList &dirList, const } } - qCWarning(OnboardLogFtpControllerLog) << "listing error:" << errorMsg; + qCWarning(FtpTransportLog) << "listing error:" << errorMsg; _finishListing(); return; } @@ -138,7 +138,7 @@ void OnboardLogFtpController::_listDirComplete(const QStringList &dirList, const // and/or date subdirectories to descend into (PX4 fallback /fs/microsd/log). const uint flatLogs = _processFileEntries(dirList, QString()); - for (const QString &entry : dirList) { + for (const QString& entry : dirList) { if (entry.startsWith(QLatin1Char('D'))) { const QString dirName = entry.mid(1); if (!dirName.isEmpty()) { @@ -148,8 +148,8 @@ void OnboardLogFtpController::_listDirComplete(const QStringList &dirList, const } _dirsToList.sort(); - qCDebug(OnboardLogFtpControllerLog) << "root listing of" << _logRoot - << "found" << flatLogs << "flat logs and" << _dirsToList.size() << "subdirectories"; + qCDebug(FtpTransportLog) << "root listing of" << _logRoot << "found" << flatLogs << "flat logs and" + << _dirsToList.size() << "subdirectories"; _listState = ListingSubdir; _listNextSubdir(); @@ -159,7 +159,7 @@ void OnboardLogFtpController::_listDirComplete(const QStringList &dirList, const const QString currentDir = _dirsToList.isEmpty() ? QString() : _dirsToList.first(); const uint logsFoundInDir = _processFileEntries(dirList, currentDir); - qCDebug(OnboardLogFtpControllerLog) << currentDir << "->" << logsFoundInDir << "logs"; + qCDebug(FtpTransportLog) << currentDir << "->" << logsFoundInDir << "logs"; if (!_dirsToList.isEmpty()) { _dirsToList.removeFirst(); @@ -168,12 +168,12 @@ void OnboardLogFtpController::_listDirComplete(const QStringList &dirList, const _listNextSubdir(); } -uint OnboardLogFtpController::_processFileEntries(const QStringList &dirList, const QString &subdir) +uint FtpTransport::_processFileEntries(const QStringList& dirList, const QString& subdir) { const QDate dirDate = subdir.isEmpty() ? QDate() : QDate::fromString(subdir, QStringLiteral("yyyy-MM-dd")); uint logsFound = 0; - for (const QString &entry : dirList) { + for (const QString& entry : dirList) { if (!entry.startsWith(QLatin1Char('F'))) { continue; } @@ -210,10 +210,10 @@ uint OnboardLogFtpController::_processFileEntries(const QStringList &dirList, co } const QString ftpPath = subdir.isEmpty() - ? (_logRoot + QStringLiteral("/") + fileName) - : (_logRoot + QStringLiteral("/") + subdir + QStringLiteral("/") + fileName); + ? (_logRoot + QStringLiteral("/") + fileName) + : (_logRoot + QStringLiteral("/") + subdir + QStringLiteral("/") + fileName); - QGCOnboardLogFtpEntry *const logEntry = new QGCOnboardLogFtpEntry(_logIdCounter++, dateTime, fileSize, true, this); + OnboardLogEntry* const logEntry = new OnboardLogEntry(_logIdCounter++, dateTime, fileSize, true, this); logEntry->setFtpPath(ftpPath); logEntry->setStatus(tr("Available")); _logEntriesModel->append(logEntry); @@ -223,10 +223,10 @@ uint OnboardLogFtpController::_processFileEntries(const QStringList &dirList, co return logsFound; } -void OnboardLogFtpController::_listNextSubdir() +void FtpTransport::_listNextSubdir() { if (_dirsToList.isEmpty()) { - qCDebug(OnboardLogFtpControllerLog) << "listing complete, found" << _logEntriesModel->count() << "logs"; + qCDebug(FtpTransportLog) << "listing complete, found" << _logEntriesModel->count() << "logs"; _finishListing(); return; } @@ -234,28 +234,28 @@ void OnboardLogFtpController::_listNextSubdir() const QString subdir = _dirsToList.first(); const QString path = _logRoot + QStringLiteral("/") + subdir; - qCDebug(OnboardLogFtpControllerLog) << "listing subdir" << path; + qCDebug(FtpTransportLog) << "listing subdir" << path; if (!_vehicle->ftpManager()->listDirectory(MAV_COMP_ID_AUTOPILOT1, path)) { - qCWarning(OnboardLogFtpControllerLog) << "failed to list subdir" << path; + qCWarning(FtpTransportLog) << "failed to list subdir" << path; _dirsToList.removeFirst(); _listNextSubdir(); } } -void OnboardLogFtpController::_finishListing() +void FtpTransport::_finishListing() { _listState = Idle; _setListing(false); } -void OnboardLogFtpController::download(const QString &path) +void FtpTransport::download(const QString& path) { const QString dir = path.isEmpty() ? SettingsManager::instance()->appSettings()->logSavePath() : path; _downloadToDirectory(dir); } -void OnboardLogFtpController::_downloadToDirectory(const QString &dir) +void FtpTransport::_downloadToDirectory(const QString& dir) { _downloadPath = dir; if (_downloadPath.isEmpty()) { @@ -269,7 +269,7 @@ void OnboardLogFtpController::_downloadToDirectory(const QString &dir) _downloadQueue.clear(); const int numLogs = _logEntriesModel->count(); for (int i = 0; i < numLogs; i++) { - QGCOnboardLogFtpEntry *const entry = _logEntriesModel->value(i); + OnboardLogEntry* const entry = _logEntriesModel->value(i); if (entry && entry->selected() && !entry->ftpPath().isEmpty()) { entry->setStatus(tr("Waiting")); _downloadQueue.enqueue(entry); @@ -277,17 +277,17 @@ void OnboardLogFtpController::_downloadToDirectory(const QString &dir) } if (_downloadQueue.isEmpty()) { - qCWarning(OnboardLogFtpControllerLog) << "no selected logs have FTP paths for download"; + qCWarning(FtpTransportLog) << "no selected logs have FTP paths for download"; return; } - qCDebug(OnboardLogFtpControllerLog) << "queued" << _downloadQueue.size() << "logs for download to" << _downloadPath; + qCDebug(FtpTransportLog) << "queued" << _downloadQueue.size() << "logs for download to" << _downloadPath; _setDownloading(true); _downloadEntry(_downloadQueue.dequeue()); } -void OnboardLogFtpController::_downloadEntry(QGCOnboardLogFtpEntry *entry) +void FtpTransport::_downloadEntry(OnboardLogEntry* entry) { if (!entry || !_vehicle) { return; @@ -319,16 +319,16 @@ void OnboardLogFtpController::_downloadEntry(QGCOnboardLogFtpEntry *entry) } while (QFile::exists(_downloadPath + localFilename)); } - FTPManager *const ftp = _vehicle->ftpManager(); - (void) disconnect(ftp, &FTPManager::downloadComplete, this, &OnboardLogFtpController::_downloadComplete); - (void) disconnect(ftp, &FTPManager::commandProgress, this, &OnboardLogFtpController::_downloadProgress); - (void) connect(ftp, &FTPManager::downloadComplete, this, &OnboardLogFtpController::_downloadComplete); - (void) connect(ftp, &FTPManager::commandProgress, this, &OnboardLogFtpController::_downloadProgress); + FTPManager* const ftp = _vehicle->ftpManager(); + (void)disconnect(ftp, &FTPManager::downloadComplete, this, &FtpTransport::_downloadComplete); + (void)disconnect(ftp, &FTPManager::commandProgress, this, &FtpTransport::_downloadProgress); + (void)connect(ftp, &FTPManager::downloadComplete, this, &FtpTransport::_downloadComplete); + (void)connect(ftp, &FTPManager::commandProgress, this, &FtpTransport::_downloadProgress); - qCDebug(OnboardLogFtpControllerLog) << "downloading" << entry->ftpPath() << "to" << _downloadPath + localFilename; + qCDebug(FtpTransportLog) << "downloading" << entry->ftpPath() << "to" << _downloadPath + localFilename; if (!ftp->download(MAV_COMP_ID_AUTOPILOT1, entry->ftpPath(), _downloadPath, localFilename, true)) { - qCWarning(OnboardLogFtpControllerLog) << "failed to start download for" << entry->ftpPath(); + qCWarning(FtpTransportLog) << "failed to start download for" << entry->ftpPath(); entry->setStatus(tr("Error")); _currentDownloadEntry = nullptr; @@ -340,7 +340,7 @@ void OnboardLogFtpController::_downloadEntry(QGCOnboardLogFtpEntry *entry) } } -void OnboardLogFtpController::_downloadComplete(const QString &file, const QString &errorMsg) +void FtpTransport::_downloadComplete(const QString& file, const QString& errorMsg) { if (!_currentDownloadEntry) { return; @@ -348,10 +348,10 @@ void OnboardLogFtpController::_downloadComplete(const QString &file, const QStri if (errorMsg.isEmpty()) { _currentDownloadEntry->setStatus(tr("Downloaded")); - qCDebug(OnboardLogFtpControllerLog) << "download complete" << file; + qCDebug(FtpTransportLog) << "download complete" << file; } else { _currentDownloadEntry->setStatus(tr("Error")); - qCWarning(OnboardLogFtpControllerLog) << "download error:" << errorMsg; + qCWarning(FtpTransportLog) << "download error:" << errorMsg; } _currentDownloadEntry = nullptr; @@ -363,7 +363,7 @@ void OnboardLogFtpController::_downloadComplete(const QString &file, const QStri } } -void OnboardLogFtpController::_downloadProgress(float value) +void FtpTransport::_downloadProgress(float value) { if (!_currentDownloadEntry) { return; @@ -373,7 +373,8 @@ void OnboardLogFtpController::_downloadProgress(float value) return; } - const size_t totalBytes = static_cast(static_cast(_currentDownloadEntry->size()) * static_cast(value)); + const size_t totalBytes = + static_cast(static_cast(_currentDownloadEntry->size()) * static_cast(value)); const size_t bytesSinceLastUpdate = totalBytes - _downloadBytesAtLastUpdate; const qreal elapsedSec = _downloadElapsed.elapsed() / 1000.0; const qreal rate = (elapsedSec > 0) ? (bytesSinceLastUpdate / elapsedSec) : 0; @@ -381,14 +382,13 @@ void OnboardLogFtpController::_downloadProgress(float value) _downloadBytesAtLastUpdate = totalBytes; _downloadElapsed.start(); - const QString status = QStringLiteral("%1 (%2/s)").arg( - QGC::bigSizeToString(totalBytes), - QGC::bigSizeToString(_downloadRateAvg)); + const QString status = + QStringLiteral("%1 (%2/s)").arg(QGC::bigSizeToString(totalBytes), QGC::bigSizeToString(_downloadRateAvg)); _currentDownloadEntry->setStatus(status); } -void OnboardLogFtpController::cancel() +void FtpTransport::cancel() { if (!_vehicle) { return; @@ -409,15 +409,117 @@ void OnboardLogFtpController::cancel() _downloadQueue.clear(); } + if (_erasing) { + _vehicle->ftpManager()->cancelDelete(); + if (_currentEraseEntry) { + _currentEraseEntry->setStatus(tr("Canceled")); + _currentEraseEntry = nullptr; + } + _eraseQueue.clear(); + _finishErase(); + } + _resetSelection(true); _setDownloading(false); } -void OnboardLogFtpController::_resetSelection(bool canceled) +void FtpTransport::eraseAll() +{ + if (!_vehicle) { + qCWarning(FtpTransportLog) << "eraseAll: no active vehicle"; + return; + } + if (_erasing) { + return; + } + + const int numLogs = _logEntriesModel->count(); + _eraseQueue.clear(); + _eraseFailureCount = 0; + for (int i = 0; i < numLogs; i++) { + OnboardLogEntry* const entry = _logEntriesModel->value(i); + if (entry && !entry->ftpPath().isEmpty()) { + entry->setStatus(tr("Waiting")); + _eraseQueue.enqueue(entry); + } + } + + if (_eraseQueue.isEmpty()) { + qCWarning(FtpTransportLog) << "eraseAll: nothing to delete"; + return; + } + + qCDebug(FtpTransportLog) << "queued" << _eraseQueue.size() << "files for delete"; + + FTPManager* const ftp = _vehicle->ftpManager(); + (void)disconnect(ftp, &FTPManager::deleteComplete, this, &FtpTransport::_deleteComplete); + (void)connect(ftp, &FTPManager::deleteComplete, this, &FtpTransport::_deleteComplete); + + _erasing = true; + // _setListing surfaces "busy" to QML so Refresh/Download stay disabled during erase. + _setListing(true); + + _eraseNext(); +} + +void FtpTransport::_eraseNext() +{ + if (_eraseQueue.isEmpty()) { + _finishErase(); + return; + } + + _currentEraseEntry = _eraseQueue.dequeue(); + _currentEraseEntry->setStatus(tr("Deleting")); + + FTPManager* const ftp = _vehicle->ftpManager(); + if (!ftp->deleteFile(MAV_COMP_ID_AUTOPILOT1, _currentEraseEntry->ftpPath())) { + qCWarning(FtpTransportLog) << "deleteFile failed to start for" << _currentEraseEntry->ftpPath(); + _currentEraseEntry->setStatus(tr("Error")); + _currentEraseEntry = nullptr; + ++_eraseFailureCount; + _eraseNext(); + } +} + +void FtpTransport::_deleteComplete(const QString& file, const QString& errorMsg) +{ + if (!_currentEraseEntry) { + return; + } + + if (errorMsg.isEmpty()) { + qCDebug(FtpTransportLog) << "deleted" << file; + // Remove the row from the model so the UI reflects the erase immediately. + _logEntriesModel->removeOne(_currentEraseEntry); + _currentEraseEntry->deleteLater(); + } else { + qCWarning(FtpTransportLog) << "delete failed for" << file << ":" << errorMsg; + _currentEraseEntry->setStatus(tr("Error")); + ++_eraseFailureCount; + } + + _currentEraseEntry = nullptr; + _eraseNext(); +} + +void FtpTransport::_finishErase() +{ + _erasing = false; + _setListing(false); + + if (_eraseFailureCount > 0) { + qCWarning(FtpTransportLog) << "erase finished with" << _eraseFailureCount << "failure(s)"; + } else { + qCDebug(FtpTransportLog) << "erase finished"; + } +} + +void FtpTransport::_resetSelection(bool canceled) { const int numLogs = _logEntriesModel->count(); for (int i = 0; i < numLogs; i++) { - QGCOnboardLogFtpEntry *const entry = _logEntriesModel->value(i); + OnboardLogEntry* const entry = _logEntriesModel->value(i); if (!entry) { continue; } @@ -433,7 +535,7 @@ void OnboardLogFtpController::_resetSelection(bool canceled) emit selectionChanged(); } -void OnboardLogFtpController::_setDownloading(bool active) +void FtpTransport::_setDownloading(bool active) { if (_downloadingLogs != active) { _downloadingLogs = active; @@ -444,7 +546,7 @@ void OnboardLogFtpController::_setDownloading(bool active) } } -void OnboardLogFtpController::_setListing(bool active) +void FtpTransport::_setListing(bool active) { if (_requestingLogEntries != active) { _requestingLogEntries = active; diff --git a/src/AnalyzeView/OnboardLogs/FtpTransport.h b/src/AnalyzeView/OnboardLogs/FtpTransport.h new file mode 100644 index 00000000000..850696b4a13 --- /dev/null +++ b/src/AnalyzeView/OnboardLogs/FtpTransport.h @@ -0,0 +1,78 @@ +#pragma once + +#include +#include + +#include "OnboardLogTransport.h" + +class OnboardLogEntry; +class Vehicle; + +class FtpTransport : public OnboardLogTransport +{ + Q_OBJECT + Q_MOC_INCLUDE("Vehicle.h") + +public: + explicit FtpTransport(QObject* parent = nullptr); + ~FtpTransport(); + + bool canErase() const override { return true; } + + QString transportName() const override { return QStringLiteral("ftp"); } + + Q_INVOKABLE void refresh() override; + Q_INVOKABLE void download(const QString& path = QString()) override; + Q_INVOKABLE void eraseAll() override; + Q_INVOKABLE void cancel() override; + +private slots: + void _setActiveVehicle(Vehicle* vehicle); + void _listDirComplete(const QStringList& dirList, const QString& errorMsg); + void _downloadComplete(const QString& file, const QString& errorMsg); + void _downloadProgress(float value); + void _deleteComplete(const QString& file, const QString& errorMsg); + +private: + enum ListState + { + Idle, + ListingRoot, + ListingSubdir + }; + + void _startListing(); + void _listRoot(); + void _listNextSubdir(); + uint _processFileEntries(const QStringList& dirList, const QString& subdir); + void _downloadEntry(OnboardLogEntry* entry); + void _downloadToDirectory(const QString& dir); + void _resetSelection(bool canceled = false); + void _setDownloading(bool active); + void _setListing(bool active); + void _finishListing(); + void _eraseNext(); + void _finishErase(); + + Vehicle* _vehicle = nullptr; + + ListState _listState = Idle; + QString _logRoot; + bool _triedFallbackRoot = false; + QStringList _dirsToList; + uint _logIdCounter = 0; + + QQueue _downloadQueue; + OnboardLogEntry* _currentDownloadEntry = nullptr; + QString _downloadPath; + QElapsedTimer _downloadElapsed; + size_t _downloadBytesAtLastUpdate = 0; + qreal _downloadRateAvg = 0.; + + bool _erasing = false; + QQueue _eraseQueue; + OnboardLogEntry* _currentEraseEntry = nullptr; + uint _eraseFailureCount = 0; + + static constexpr uint32_t kGUIRateMs = 17; +}; diff --git a/src/AnalyzeView/OnboardLogs/LogProtocolTransport.cc b/src/AnalyzeView/OnboardLogs/LogProtocolTransport.cc new file mode 100644 index 00000000000..10d4227f317 --- /dev/null +++ b/src/AnalyzeView/OnboardLogs/LogProtocolTransport.cc @@ -0,0 +1,662 @@ +#include "LogProtocolTransport.h" + +#include +#include + +#include "AppSettings.h" +#include "MAVLinkLib.h" +#include "MAVLinkProtocol.h" +#include "MultiVehicleManager.h" +#include "OnboardLogDownloadData.h" +#include "OnboardLogEntry.h" +#include "ParameterManager.h" +#include "QGCFormat.h" +#include "QGCLoggingCategory.h" +#include "QmlObjectListModel.h" +#include "SettingsManager.h" +#include "Vehicle.h" +#include "VehicleLinkManager.h" + +QGC_LOGGING_CATEGORY(LogProtocolTransportLog, "AnalyzeView.LogProtocolTransport") + +LogProtocolTransport::LogProtocolTransport(QObject* parent) : OnboardLogTransport(parent), _timer(new QTimer(this)) +{ + qCDebug(LogProtocolTransportLog) << this; + + (void)connect(MultiVehicleManager::instance(), &MultiVehicleManager::activeVehicleChanged, this, + &LogProtocolTransport::_setActiveVehicle); + (void)connect(_timer, &QTimer::timeout, this, &LogProtocolTransport::_processDownload); + + _timer->setSingleShot(false); + + _setActiveVehicle(MultiVehicleManager::instance()->activeVehicle()); +} + +LogProtocolTransport::~LogProtocolTransport() +{ + qCDebug(LogProtocolTransportLog) << this; +} + +void LogProtocolTransport::download(const QString& path) +{ + const QString dir = path.isEmpty() ? SettingsManager::instance()->appSettings()->logSavePath() : path; + _downloadToDirectory(dir); +} + +void LogProtocolTransport::_downloadToDirectory(const QString& dir) +{ + _receivedAllEntries(); + + _downloadData.reset(); + + _downloadPath = dir; + if (_downloadPath.isEmpty()) { + return; + } + + if (!_downloadPath.endsWith(QDir::separator())) { + _downloadPath += QDir::separator(); + } + + OnboardLogEntry* const log = _getNextSelected(); + if (log) { + log->setStatus(tr("Waiting")); + } + + _setDownloading(true); + _receivedAllData(); +} + +void LogProtocolTransport::_processDownload() +{ + if (_requestingLogEntries) { + _findMissingEntries(); + } else if (_downloadingLogs) { + _findMissingData(); + } +} + +void LogProtocolTransport::_findMissingEntries() +{ + const int num_logs = _logEntriesModel->count(); + int start = -1; + int end = -1; + for (int i = 0; i < num_logs; i++) { + const OnboardLogEntry* const entry = _logEntriesModel->value(i); + if (!entry) { + continue; + } + + if (!entry->received()) { + if (start < 0) { + start = i; + } else { + end = i; + } + } else if (start >= 0) { + break; + } + } + + if (start < 0) { + _receivedAllEntries(); + return; + } + + if (_retries++ > 2) { + for (int i = 0; i < num_logs; i++) { + OnboardLogEntry* const entry = _logEntriesModel->value(i); + if (entry && !entry->received()) { + entry->setStatus(tr("Error")); + } + } + + _receivedAllEntries(); + qCWarning(LogProtocolTransportLog) << "Too many errors retreiving log list. Giving up."; + return; + } + + if (end < 0) { + end = start; + } + + start += _apmOffset; + end += _apmOffset; + + _requestLogList(static_cast(start), static_cast(end)); +} + +void LogProtocolTransport::_setActiveVehicle(Vehicle* vehicle) +{ + if (vehicle == _vehicle) { + return; + } + + if (_vehicle) { + _logEntriesModel->clearAndDeleteContents(); + (void)disconnect(_vehicle, &Vehicle::logEntry, this, &LogProtocolTransport::_logEntry); + (void)disconnect(_vehicle, &Vehicle::logData, this, &LogProtocolTransport::_logData); + } + + _vehicle = vehicle; + + if (_vehicle) { + (void)connect(_vehicle, &Vehicle::logEntry, this, &LogProtocolTransport::_logEntry); + (void)connect(_vehicle, &Vehicle::logData, this, &LogProtocolTransport::_logData); + } +} + +void LogProtocolTransport::_logEntry(uint32_t time_utc, uint32_t size, uint16_t id, uint16_t num_logs, + uint16_t last_log_num) +{ + Q_UNUSED(last_log_num); + + if (!_requestingLogEntries) { + return; + } + + if ((_logEntriesModel->count() == 0) && (num_logs > 0)) { + if (_vehicle->firmwareType() == MAV_AUTOPILOT_ARDUPILOTMEGA) { + // APM ID starts at 1 + _apmOffset = 1; + } + + for (int i = 0; i < num_logs; i++) { + OnboardLogEntry* const entry = new OnboardLogEntry(i); + _logEntriesModel->append(entry); + } + } + + if (num_logs > 0) { + if ((size > 0) || (_vehicle->firmwareType() != MAV_AUTOPILOT_ARDUPILOTMEGA)) { + id -= _apmOffset; + if (id < _logEntriesModel->count()) { + OnboardLogEntry* const entry = _logEntriesModel->value(id); + entry->setSize(size); + entry->setTime(QDateTime::fromSecsSinceEpoch(time_utc)); + entry->setReceived(true); + entry->setStatus(tr("Available")); + } else { + qCWarning(LogProtocolTransportLog) << "Received onboard log entry for out-of-bound index:" << id; + } + } + } else { + _receivedAllEntries(); + } + + _retries = 0; + + if (_entriesComplete()) { + _receivedAllEntries(); + } else { + _timer->start(kTimeOutMs); + } +} + +void LogProtocolTransport::_receivedAllEntries() +{ + _timer->stop(); + _setListing(false); +} + +bool LogProtocolTransport::_entriesComplete() const +{ + const int num_logs = _logEntriesModel->count(); + for (int i = 0; i < num_logs; i++) { + const OnboardLogEntry* const entry = _logEntriesModel->value(i); + if (!entry) { + continue; + } + + if (!entry->received()) { + return false; + } + } + + return true; +} + +void LogProtocolTransport::_logData(uint32_t ofs, uint16_t id, uint8_t count, const uint8_t* data) +{ + if (!_downloadingLogs || !_downloadData) { + return; + } + + id -= _apmOffset; + if (_downloadData->ID != id) { + qCWarning(LogProtocolTransportLog) << "Received log data for wrong log"; + return; + } + + if ((ofs % MAVLINK_MSG_LOG_DATA_FIELD_DATA_LEN) != 0) { + qCWarning(LogProtocolTransportLog) << "Ignored misaligned incoming packet @" << ofs; + return; + } + + bool result = false; + if (ofs <= _downloadData->entry->size()) { + const uint32_t chunk = ofs / OnboardLogDownloadData::kChunkSize; + // qCDebug(LogProtocolTransportLog) << "Received data - Offset:" << ofs << "Chunk:" << chunk; + if (chunk != _downloadData->current_chunk) { + qCWarning(LogProtocolTransportLog) + << "Ignored packet for out of order chunk actual:expected" << chunk << _downloadData->current_chunk; + return; + } + + const uint16_t bin = (ofs - (chunk * OnboardLogDownloadData::kChunkSize)) / MAVLINK_MSG_LOG_DATA_FIELD_DATA_LEN; + if (bin >= _downloadData->chunk_table.size()) { + qCWarning(LogProtocolTransportLog) << "Out of range bin received"; + } else { + _downloadData->chunk_table.setBit(bin); + } + + if (_downloadData->file.pos() != ofs) { + if (!_downloadData->file.seek(ofs)) { + qCWarning(LogProtocolTransportLog) << "Error while seeking log file offset"; + return; + } + } + + if (_downloadData->file.write(reinterpret_cast(data), count)) { + _downloadData->written += count; + _downloadData->rate_bytes += count; + _updateDataRate(); + + result = true; + _retries = 0; + + _timer->start(kTimeOutMs); + if (_logComplete()) { + _downloadData->entry->setStatus(tr("Downloaded")); + _receivedAllData(); + } else if (_chunkComplete()) { + _downloadData->advanceChunk(); + _requestLogData(_downloadData->ID, _downloadData->current_chunk * OnboardLogDownloadData::kChunkSize, + _downloadData->chunk_table.size() * MAVLINK_MSG_LOG_DATA_FIELD_DATA_LEN); + } else if ((bin < (_downloadData->chunk_table.size() - 1)) && _downloadData->chunk_table.at(bin + 1)) { + // Likely to be grabbing fragments and got to the end of a gap + _findMissingData(); + } + } else { + qCWarning(LogProtocolTransportLog) << "Error while writing log file chunk"; + } + } else { + qCWarning(LogProtocolTransportLog) << "Received log offset greater than expected"; + } + + if (!result) { + _downloadData->entry->setStatus(tr("Error")); + } +} + +void LogProtocolTransport::_findMissingData() +{ + if (_logComplete()) { + _receivedAllData(); + return; + } + + if (_chunkComplete()) { + _downloadData->advanceChunk(); + } + + _retries++; + + _updateDataRate(); + + uint16_t start = 0, end = 0; + const int size = _downloadData->chunk_table.size(); + for (; start < size; start++) { + if (!_downloadData->chunk_table.testBit(start)) { + break; + } + } + + for (end = start; end < size; end++) { + if (_downloadData->chunk_table.testBit(end)) { + break; + } + } + + const uint32_t pos = (_downloadData->current_chunk * OnboardLogDownloadData::kChunkSize) + + (start * MAVLINK_MSG_LOG_DATA_FIELD_DATA_LEN); + const uint32_t len = (end - start) * MAVLINK_MSG_LOG_DATA_FIELD_DATA_LEN; + _requestLogData(_downloadData->ID, pos, len, _retries); +} + +void LogProtocolTransport::_updateDataRate() +{ + constexpr uint kSizeUpdateThreshold = 102400; // 0.1 MB + const bool timeThresholdMet = _downloadData->elapsed.elapsed() >= kGUIRateMs; + const bool sizeThresholdMet = (_downloadData->written - _downloadData->last_status_written) >= kSizeUpdateThreshold; + + if (!timeThresholdMet && !sizeThresholdMet) { + return; + } + + QString status; + if (timeThresholdMet) { + // Update both rate and size + const qreal rate = _downloadData->rate_bytes / (_downloadData->elapsed.elapsed() / 1000.0); + _downloadData->rate_avg = (_downloadData->rate_avg * 0.95) + (rate * 0.05); + _downloadData->rate_bytes = 0; + + status = QStringLiteral("%1 (%2/s)") + .arg(QGC::bigSizeToString(_downloadData->written), QGC::bigSizeToString(_downloadData->rate_avg)); + _downloadData->elapsed.start(); + } else { + // Update size only, keep previous rate + status = QStringLiteral("%1 (%2/s)") + .arg(QGC::bigSizeToString(_downloadData->written), QGC::bigSizeToString(_downloadData->rate_avg)); + } + + _downloadData->entry->setStatus(status); + _downloadData->last_status_written = _downloadData->written; +} + +bool LogProtocolTransport::_chunkComplete() const +{ + return _downloadData->chunkEquals(true); +} + +bool LogProtocolTransport::_logComplete() const +{ + return (_chunkComplete() && ((_downloadData->current_chunk + 1) == _downloadData->numChunks())); +} + +void LogProtocolTransport::_receivedAllData() +{ + _timer->stop(); + if (_prepareLogDownload()) { + _requestLogData(_downloadData->ID, 0, _downloadData->chunk_table.size() * MAVLINK_MSG_LOG_DATA_FIELD_DATA_LEN); + _timer->start(kTimeOutMs); + } else { + _resetSelection(); + _setDownloading(false); + } +} + +bool LogProtocolTransport::_prepareLogDownload() +{ + _downloadData.reset(); + + OnboardLogEntry* const entry = _getNextSelected(); + if (!entry) { + return false; + } + + entry->setSelected(false); + emit selectionChanged(); + + const QString ftime = (entry->time().date().year() >= 2010) + ? entry->time().toString(QStringLiteral("yyyy-M-d-hh-mm-ss")) + : QStringLiteral("UnknownDate"); + + _downloadData = std::make_unique(entry); + _downloadData->filename = QStringLiteral("log_") + QString::number(entry->id()) + "_" + ftime; + + if (_vehicle->firmwareType() == MAV_AUTOPILOT_PX4) { + const QString loggerParam = QStringLiteral("SYS_LOGGER"); + ParameterManager* const parameterManager = _vehicle->parameterManager(); + Fact* const loggerFact = parameterManager->parameterExists(ParameterManager::defaultComponentId, loggerParam) + ? parameterManager->getParameter(ParameterManager::defaultComponentId, loggerParam) + : nullptr; + if (loggerFact && loggerFact->rawValue().toInt() == 0) { + _downloadData->filename += ".px4log"; + } else { + _downloadData->filename += ".ulg"; + } + } else { + _downloadData->filename += ".bin"; + } + + _downloadData->file.setFileName(_downloadPath + _downloadData->filename); + + if (_downloadData->file.exists()) { + uint32_t numDups = 0; + const QStringList filename_spl = _downloadData->filename.split('.'); + do { + numDups += 1; + const QString filename = filename_spl[0] + '_' + QString::number(numDups) + '.' + filename_spl[1]; + _downloadData->file.setFileName(_downloadPath + filename); + } while (_downloadData->file.exists()); + } + + bool result = false; + if (!_downloadData->file.open(QIODevice::WriteOnly)) { + qCWarning(LogProtocolTransportLog) << "Failed to create log file:" << _downloadData->filename; + } else if (!_downloadData->file.resize(entry->size())) { + qCWarning(LogProtocolTransportLog) << "Failed to allocate space for log file:" << _downloadData->filename; + } else { + _downloadData->current_chunk = 0; + _downloadData->chunk_table = QBitArray(_downloadData->chunkBins(), false); + _downloadData->elapsed.start(); + result = true; + } + + if (!result) { + if (_downloadData->file.exists()) { + (void)_downloadData->file.remove(); + } + + _downloadData->entry->setStatus(QStringLiteral("Error")); + _downloadData.reset(); + } + + return result; +} + +void LogProtocolTransport::refresh() +{ + _logEntriesModel->clearAndDeleteContents(); + _requestLogList(0, 0xffff); +} + +OnboardLogEntry* LogProtocolTransport::_getNextSelected() const +{ + const int numLogs = _logEntriesModel->count(); + for (int i = 0; i < numLogs; i++) { + OnboardLogEntry* const entry = _logEntriesModel->value(i); + if (!entry) { + continue; + } + + if (entry->selected()) { + return entry; + } + } + + return nullptr; +} + +void LogProtocolTransport::cancel() +{ + _requestLogEnd(); + _receivedAllEntries(); + + if (_downloadData) { + _downloadData->entry->setStatus(QStringLiteral("Canceled")); + if (_downloadData->file.exists()) { + (void)_downloadData->file.remove(); + } + + _downloadData.reset(); + } + + _resetSelection(true); + _setDownloading(false); +} + +void LogProtocolTransport::_resetSelection(bool canceled) +{ + const int num_logs = _logEntriesModel->count(); + for (int i = 0; i < num_logs; i++) { + OnboardLogEntry* const entry = _logEntriesModel->value(i); + if (!entry) { + continue; + } + + if (entry->selected()) { + if (canceled) { + entry->setStatus(tr("Canceled")); + } + entry->setSelected(false); + } + } + + emit selectionChanged(); +} + +void LogProtocolTransport::eraseAll() +{ + if (!_vehicle) { + qCWarning(LogProtocolTransportLog) << "Vehicle Unavailable"; + return; + } + + SharedLinkInterfacePtr sharedLink = _vehicle->vehicleLinkManager()->primaryLink().lock(); + if (!sharedLink) { + qCWarning(LogProtocolTransportLog) << "Link Unavailable"; + return; + } + + mavlink_message_t msg{}; + (void)mavlink_msg_log_erase_pack_chan(MAVLinkProtocol::instance()->getSystemId(), MAVLinkProtocol::getComponentId(), + sharedLink->mavlinkChannel(), &msg, _vehicle->id(), + _vehicle->defaultComponentId()); + + if (!_vehicle->sendMessageOnLinkThreadSafe(sharedLink.get(), msg)) { + qCWarning(LogProtocolTransportLog) << "Failed to send"; + return; + } + + refresh(); +} + +void LogProtocolTransport::_requestLogList(uint32_t start, uint32_t end) +{ + if (!_vehicle) { + qCWarning(LogProtocolTransportLog) << "Vehicle Unavailable"; + return; + } + + SharedLinkInterfacePtr sharedLink = _vehicle->vehicleLinkManager()->primaryLink().lock(); + if (!sharedLink) { + qCWarning(LogProtocolTransportLog) << "Link Unavailable"; + return; + } + + mavlink_message_t msg{}; + (void)mavlink_msg_log_request_list_pack_chan(MAVLinkProtocol::instance()->getSystemId(), + MAVLinkProtocol::getComponentId(), sharedLink->mavlinkChannel(), &msg, + _vehicle->id(), _vehicle->defaultComponentId(), start, end); + + if (!_vehicle->sendMessageOnLinkThreadSafe(sharedLink.get(), msg)) { + qCWarning(LogProtocolTransportLog) << "Failed to send"; + return; + } + + qCDebug(LogProtocolTransportLog) << "Request onboard log entry list (" << start << "through" << end << ")"; + _setListing(true); + _timer->start(kRequestLogListTimeoutMs); +} + +void LogProtocolTransport::_requestLogData(uint16_t id, uint32_t offset, uint32_t count, int retryCount) +{ + if (!_vehicle) { + qCWarning(LogProtocolTransportLog) << "Vehicle Unavailable"; + return; + } + + SharedLinkInterfacePtr sharedLink = _vehicle->vehicleLinkManager()->primaryLink().lock(); + if (!sharedLink) { + qCWarning(LogProtocolTransportLog) << "Link Unavailable"; + return; + } + + id += _apmOffset; + qCDebug(LogProtocolTransportLog) << "Request log data (id:" << id << "offset:" << offset << "size:" << count + << "retryCount" << retryCount << ")"; + + mavlink_message_t msg{}; + (void)mavlink_msg_log_request_data_pack_chan(MAVLinkProtocol::instance()->getSystemId(), + MAVLinkProtocol::getComponentId(), sharedLink->mavlinkChannel(), &msg, + _vehicle->id(), _vehicle->defaultComponentId(), id, offset, count); + + if (!_vehicle->sendMessageOnLinkThreadSafe(sharedLink.get(), msg)) { + qCWarning(LogProtocolTransportLog) << "Failed to send"; + } +} + +void LogProtocolTransport::_requestLogEnd() +{ + if (!_vehicle) { + qCWarning(LogProtocolTransportLog) << "Vehicle Unavailable"; + return; + } + + SharedLinkInterfacePtr sharedLink = _vehicle->vehicleLinkManager()->primaryLink().lock(); + if (!sharedLink) { + qCWarning(LogProtocolTransportLog) << "Link Unavailable"; + return; + } + + mavlink_message_t msg{}; + (void)mavlink_msg_log_request_end_pack_chan(MAVLinkProtocol::instance()->getSystemId(), + MAVLinkProtocol::getComponentId(), sharedLink->mavlinkChannel(), &msg, + _vehicle->id(), _vehicle->defaultComponentId()); + + if (!_vehicle->sendMessageOnLinkThreadSafe(sharedLink.get(), msg)) { + qCWarning(LogProtocolTransportLog) << "Failed to send"; + } +} + +void LogProtocolTransport::_setDownloading(bool active) +{ + if (_downloadingLogs != active) { + _downloadingLogs = active; + _vehicle->vehicleLinkManager()->setCommunicationLostEnabled(!active); + emit downloadingLogsChanged(); + } +} + +void LogProtocolTransport::_setListing(bool active) +{ + if (_requestingLogEntries != active) { + _requestingLogEntries = active; + _vehicle->vehicleLinkManager()->setCommunicationLostEnabled(!active); + emit requestingListChanged(); + } +} + +void LogProtocolTransport::setCompressLogs(bool compress) +{ + if (_compressLogs != compress) { + _compressLogs = compress; + emit compressLogsChanged(); + } +} + +bool LogProtocolTransport::compressLogFile(const QString& logPath) +{ + Q_UNUSED(logPath) + qCWarning(LogProtocolTransportLog) << "Log compression not yet implemented (decompression-only API)"; + return false; +} + +void LogProtocolTransport::cancelCompression() +{ + // Not implemented - compression API is decompression-only +} + +void LogProtocolTransport::_handleCompressionProgress(qreal progress) +{ + Q_UNUSED(progress) + // Not implemented - compression API is decompression-only +} + +void LogProtocolTransport::_handleCompressionFinished(bool success) +{ + Q_UNUSED(success) + // Not implemented - compression API is decompression-only +} diff --git a/src/AnalyzeView/OnboardLogs/LogProtocolTransport.h b/src/AnalyzeView/OnboardLogs/LogProtocolTransport.h new file mode 100644 index 00000000000..1fd8aeecd71 --- /dev/null +++ b/src/AnalyzeView/OnboardLogs/LogProtocolTransport.h @@ -0,0 +1,93 @@ +#pragma once + +#include "OnboardLogTransport.h" + +struct OnboardLogDownloadData; +class OnboardLogEntry; +class QTimer; +class Vehicle; + +class LogProtocolTransport : public OnboardLogTransport +{ + Q_OBJECT + Q_MOC_INCLUDE("Vehicle.h") + Q_PROPERTY(bool compressLogs READ compressLogs WRITE setCompressLogs NOTIFY compressLogsChanged) + Q_PROPERTY(bool compressing READ compressing NOTIFY compressingChanged) + Q_PROPERTY(float compressionProgress READ compressionProgress NOTIFY compressionProgressChanged) + +public: + explicit LogProtocolTransport(QObject* parent = nullptr); + ~LogProtocolTransport(); + + bool canErase() const override { return true; } + + QString transportName() const override { return QStringLiteral("log"); } + + Q_INVOKABLE void refresh() override; + Q_INVOKABLE void download(const QString& path = QString()) override; + Q_INVOKABLE void eraseAll() override; + Q_INVOKABLE void cancel() override; + + bool compressLogs() const { return _compressLogs; } + + void setCompressLogs(bool compress); + + bool compressing() const { return _compressing; } + + float compressionProgress() const { return _compressionProgress; } + + /// Compress a single log file + Q_INVOKABLE bool compressLogFile(const QString& logPath); + + /// Cancel compression + Q_INVOKABLE void cancelCompression(); + +signals: + void compressLogsChanged(); + void compressingChanged(); + void compressionProgressChanged(); + void compressionComplete(const QString& outputPath, const QString& error); + +private slots: + void _setActiveVehicle(Vehicle* vehicle); + void _logEntry(uint32_t time_utc, uint32_t size, uint16_t id, uint16_t num_logs, uint16_t last_log_num); + void _logData(uint32_t ofs, uint16_t id, uint8_t count, const uint8_t* data); + void _processDownload(); + void _handleCompressionProgress(qreal progress); + void _handleCompressionFinished(bool success); + +private: + bool _chunkComplete() const; + bool _entriesComplete() const; + bool _logComplete() const; + bool _prepareLogDownload(); + void _downloadToDirectory(const QString& dir); + void _findMissingData(); + void _findMissingEntries(); + void _receivedAllData(); + void _receivedAllEntries(); + void _requestLogData(uint16_t id, uint32_t offset, uint32_t count, int retryCount = 0); + void _requestLogList(uint32_t start, uint32_t end); + void _requestLogEnd(); + void _resetSelection(bool canceled = false); + void _setDownloading(bool active); + void _setListing(bool active); + void _updateDataRate(); + + OnboardLogEntry* _getNextSelected() const; + + QTimer* _timer = nullptr; + + int _apmOffset = 0; + int _retries = 0; + std::unique_ptr _downloadData; + QString _downloadPath; + Vehicle* _vehicle = nullptr; + bool _compressLogs = false; + bool _compressing = false; + float _compressionProgress = 0.0F; + + static constexpr uint32_t kTimeOutMs = 500; + static constexpr uint32_t kGUIRateMs = 500; ///< Update download rate twice per second + static constexpr uint32_t kRequestLogListTimeoutMs = 5000; +}; diff --git a/src/AnalyzeView/OnboardLogs/OnboardLogController.cc b/src/AnalyzeView/OnboardLogs/OnboardLogController.cc index 623a4a3b5cc..4f986a4f80c 100644 --- a/src/AnalyzeView/OnboardLogs/OnboardLogController.cc +++ b/src/AnalyzeView/OnboardLogs/OnboardLogController.cc @@ -1,679 +1,162 @@ #include "OnboardLogController.h" -#include "AppSettings.h" -#include "OnboardLogEntry.h" + +#include "Fact.h" +#include "FtpTransport.h" +#include "LogProtocolTransport.h" #include "MAVLinkLib.h" -#include "MAVLinkProtocol.h" +#include "MavlinkSettings.h" #include "MultiVehicleManager.h" -#include "ParameterManager.h" -#include "QGCFormat.h" #include "QGCLoggingCategory.h" -#include "QmlObjectListModel.h" #include "SettingsManager.h" #include "Vehicle.h" -#include "VehicleLinkManager.h" - -#include -#include QGC_LOGGING_CATEGORY(OnboardLogControllerLog, "AnalyzeView.OnboardLogController") -OnboardLogController::OnboardLogController(QObject *parent) - : QObject(parent) - , _timer(new QTimer(this)) - , _logEntriesModel(new QmlObjectListModel(this)) -{ - qCDebug(OnboardLogControllerLog) << this; - - (void) connect(MultiVehicleManager::instance(), &MultiVehicleManager::activeVehicleChanged, this, &OnboardLogController::_setActiveVehicle); - (void) connect(_timer, &QTimer::timeout, this, &OnboardLogController::_processDownload); - - _timer->setSingleShot(false); - - _setActiveVehicle(MultiVehicleManager::instance()->activeVehicle()); -} - -OnboardLogController::~OnboardLogController() +OnboardLogController::OnboardLogController(QObject* parent) + : OnboardLogTransport(parent), _logTransport(new LogProtocolTransport(this)), _ftpTransport(new FtpTransport(this)) { qCDebug(OnboardLogControllerLog) << this; -} - -void OnboardLogController::download(const QString &path) -{ - const QString dir = path.isEmpty() ? SettingsManager::instance()->appSettings()->logSavePath() : path; - _downloadToDirectory(dir); -} - -void OnboardLogController::_downloadToDirectory(const QString &dir) -{ - _receivedAllEntries(); - - _downloadData.reset(); - - _downloadPath = dir; - if (_downloadPath.isEmpty()) { - return; - } - - if (!_downloadPath.endsWith(QDir::separator())) { - _downloadPath += QDir::separator(); - } - - QGCOnboardLogEntry *const log = _getNextSelected(); - if (log) { - log->setStatus(tr("Waiting")); - } - - _setDownloading(true); - _receivedAllData(); -} - -void OnboardLogController::_processDownload() -{ - if (_requestingLogEntries) { - _findMissingEntries(); - } else if (_downloadingLogs) { - _findMissingData(); - } -} - -void OnboardLogController::_findMissingEntries() -{ - const int num_logs = _logEntriesModel->count(); - int start = -1; - int end = -1; - for (int i = 0; i < num_logs; i++) { - const QGCOnboardLogEntry *const entry = _logEntriesModel->value(i); - if (!entry) { - continue; - } - - if (!entry->received()) { - if (start < 0) { - start = i; - } else { - end = i; - } - } else if (start >= 0) { - break; - } - } - - if (start < 0) { - _receivedAllEntries(); - return; - } - - if (_retries++ > 2) { - for (int i = 0; i < num_logs; i++) { - QGCOnboardLogEntry *const entry = _logEntriesModel->value(i); - if (entry && !entry->received()) { - entry->setStatus(tr("Error")); - } - } - - _receivedAllEntries(); - qCWarning(OnboardLogControllerLog) << "Too many errors retreiving log list. Giving up."; - return; - } - - if (end < 0) { - end = start; - } - - start += _apmOffset; - end += _apmOffset; - - _requestLogList(static_cast(start), static_cast(end)); -} - -void OnboardLogController::_setActiveVehicle(Vehicle *vehicle) -{ - if (vehicle == _vehicle) { - return; - } - - if (_vehicle) { - _logEntriesModel->clearAndDeleteContents(); - (void) disconnect(_vehicle, &Vehicle::logEntry, this, &OnboardLogController::_logEntry); - (void) disconnect(_vehicle, &Vehicle::logData, this, &OnboardLogController::_logData); - } - - _vehicle = vehicle; - - if (_vehicle) { - (void) connect(_vehicle, &Vehicle::logEntry, this, &OnboardLogController::_logEntry); - (void) connect(_vehicle, &Vehicle::logData, this, &OnboardLogController::_logData); - } -} - -void OnboardLogController::_logEntry(uint32_t time_utc, uint32_t size, uint16_t id, uint16_t num_logs, uint16_t last_log_num) -{ - Q_UNUSED(last_log_num); - - if (!_requestingLogEntries) { - return; - } - - if ((_logEntriesModel->count() == 0) && (num_logs > 0)) { - if (_vehicle->firmwareType() == MAV_AUTOPILOT_ARDUPILOTMEGA) { - // APM ID starts at 1 - _apmOffset = 1; - } - - for (int i = 0; i < num_logs; i++) { - QGCOnboardLogEntry *const entry = new QGCOnboardLogEntry(i); - _logEntriesModel->append(entry); - } - } - - if (num_logs > 0) { - if ((size > 0) || (_vehicle->firmwareType() != MAV_AUTOPILOT_ARDUPILOTMEGA)) { - id -= _apmOffset; - if (id < _logEntriesModel->count()) { - QGCOnboardLogEntry *const entry = _logEntriesModel->value(id); - entry->setSize(size); - entry->setTime(QDateTime::fromSecsSinceEpoch(time_utc)); - entry->setReceived(true); - entry->setStatus(tr("Available")); - } else { - qCWarning(OnboardLogControllerLog) << "Received onboard log entry for out-of-bound index:" << id; - } - } - } else { - _receivedAllEntries(); - } - _retries = 0; + _setActiveTransport(_logTransport); - if (_entriesComplete()) { - _receivedAllEntries(); - } else { - _timer->start(kTimeOutMs); - } -} + (void)connect(MultiVehicleManager::instance(), &MultiVehicleManager::activeVehicleChanged, this, + &OnboardLogController::_setActiveVehicle); -void OnboardLogController::_receivedAllEntries() -{ - _timer->stop(); - _setListing(false); -} - -bool OnboardLogController::_entriesComplete() const -{ - const int num_logs = _logEntriesModel->count(); - for (int i = 0; i < num_logs; i++) { - const QGCOnboardLogEntry *const entry = _logEntriesModel->value(i); - if (!entry) { - continue; - } + // Re-pick transport when the user toggles the override Fact at runtime. + Fact* const transportFact = SettingsManager::instance()->mavlinkSettings()->onboardLogTransport(); + (void)connect(transportFact, &Fact::rawValueChanged, this, &OnboardLogController::_reevaluateTransport); - if (!entry->received()) { - return false; - } - } - - return true; -} - -void OnboardLogController::_logData(uint32_t ofs, uint16_t id, uint8_t count, const uint8_t *data) -{ - if (!_downloadingLogs || !_downloadData) { - return; - } - - id -= _apmOffset; - if (_downloadData->ID != id) { - qCWarning(OnboardLogControllerLog) << "Received log data for wrong log"; - return; - } - - if ((ofs % MAVLINK_MSG_LOG_DATA_FIELD_DATA_LEN) != 0) { - qCWarning(OnboardLogControllerLog) << "Ignored misaligned incoming packet @" << ofs; - return; - } - - bool result = false; - if (ofs <= _downloadData->entry->size()) { - const uint32_t chunk = ofs / OnboardLogDownloadData::kChunkSize; - // qCDebug(OnboardLogControllerLog) << "Received data - Offset:" << ofs << "Chunk:" << chunk; - if (chunk != _downloadData->current_chunk) { - qCWarning(OnboardLogControllerLog) << "Ignored packet for out of order chunk actual:expected" << chunk << _downloadData->current_chunk; - return; - } - - const uint16_t bin = (ofs - (chunk * OnboardLogDownloadData::kChunkSize)) / MAVLINK_MSG_LOG_DATA_FIELD_DATA_LEN; - if (bin >= _downloadData->chunk_table.size()) { - qCWarning(OnboardLogControllerLog) << "Out of range bin received"; - } else { - _downloadData->chunk_table.setBit(bin); - } - - if (_downloadData->file.pos() != ofs) { - if (!_downloadData->file.seek(ofs)) { - qCWarning(OnboardLogControllerLog) << "Error while seeking log file offset"; - return; - } - } - - if (_downloadData->file.write(reinterpret_cast(data), count)) { - _downloadData->written += count; - _downloadData->rate_bytes += count; - _updateDataRate(); - - result = true; - _retries = 0; - - _timer->start(kTimeOutMs); - if (_logComplete()) { - _downloadData->entry->setStatus(tr("Downloaded")); - _receivedAllData(); - } else if (_chunkComplete()) { - _downloadData->advanceChunk(); - _requestLogData(_downloadData->ID, - _downloadData->current_chunk * OnboardLogDownloadData::kChunkSize, - _downloadData->chunk_table.size() * MAVLINK_MSG_LOG_DATA_FIELD_DATA_LEN); - } else if ((bin < (_downloadData->chunk_table.size() - 1)) && _downloadData->chunk_table.at(bin + 1)) { - // Likely to be grabbing fragments and got to the end of a gap - _findMissingData(); - } - } else { - qCWarning(OnboardLogControllerLog) << "Error while writing log file chunk"; - } - } else { - qCWarning(OnboardLogControllerLog) << "Received log offset greater than expected"; - } - - if (!result) { - _downloadData->entry->setStatus(tr("Error")); - } + _setActiveVehicle(MultiVehicleManager::instance()->activeVehicle()); } -void OnboardLogController::_findMissingData() -{ - if (_logComplete()) { - _receivedAllData(); - return; - } - - if (_chunkComplete()) { - _downloadData->advanceChunk(); - } - - _retries++; - - _updateDataRate(); - - uint16_t start = 0, end = 0; - const int size = _downloadData->chunk_table.size(); - for (; start < size; start++) { - if (!_downloadData->chunk_table.testBit(start)) { - break; - } - } - - for (end = start; end < size; end++) { - if (_downloadData->chunk_table.testBit(end)) { - break; - } - } - - const uint32_t pos = (_downloadData->current_chunk * OnboardLogDownloadData::kChunkSize) + (start * MAVLINK_MSG_LOG_DATA_FIELD_DATA_LEN); - const uint32_t len = (end - start) * MAVLINK_MSG_LOG_DATA_FIELD_DATA_LEN; - _requestLogData(_downloadData->ID, pos, len, _retries); -} +OnboardLogController::~OnboardLogController() = default; -void OnboardLogController::_updateDataRate() +QmlObjectListModel* OnboardLogController::model() const { - constexpr uint kSizeUpdateThreshold = 102400; // 0.1 MB - const bool timeThresholdMet = _downloadData->elapsed.elapsed() >= kGUIRateMs; - const bool sizeThresholdMet = (_downloadData->written - _downloadData->last_status_written) >= kSizeUpdateThreshold; - - if (!timeThresholdMet && !sizeThresholdMet) { - return; - } - - QString status; - if (timeThresholdMet) { - // Update both rate and size - const qreal rate = _downloadData->rate_bytes / (_downloadData->elapsed.elapsed() / 1000.0); - _downloadData->rate_avg = (_downloadData->rate_avg * 0.95) + (rate * 0.05); - _downloadData->rate_bytes = 0; - - status = QStringLiteral("%1 (%2/s)").arg(QGC::bigSizeToString(_downloadData->written), - QGC::bigSizeToString(_downloadData->rate_avg)); - _downloadData->elapsed.start(); - } else { - // Update size only, keep previous rate - status = QStringLiteral("%1 (%2/s)").arg(QGC::bigSizeToString(_downloadData->written), - QGC::bigSizeToString(_downloadData->rate_avg)); - } - - _downloadData->entry->setStatus(status); - _downloadData->last_status_written = _downloadData->written; + return _active ? _active->model() : nullptr; } -bool OnboardLogController::_chunkComplete() const +bool OnboardLogController::requestingList() const { - return _downloadData->chunkEquals(true); + return _active && _active->requestingList(); } -bool OnboardLogController::_logComplete() const +bool OnboardLogController::downloadingLogs() const { - return (_chunkComplete() && ((_downloadData->current_chunk + 1) == _downloadData->numChunks())); + return _active && _active->downloadingLogs(); } -void OnboardLogController::_receivedAllData() +bool OnboardLogController::canErase() const { - _timer->stop(); - if (_prepareLogDownload()) { - _requestLogData(_downloadData->ID, 0, _downloadData->chunk_table.size() * MAVLINK_MSG_LOG_DATA_FIELD_DATA_LEN); - _timer->start(kTimeOutMs); - } else { - _resetSelection(); - _setDownloading(false); - } + return _active && _active->canErase(); } -bool OnboardLogController::_prepareLogDownload() +QString OnboardLogController::transportName() const { - _downloadData.reset(); - - QGCOnboardLogEntry *const entry = _getNextSelected(); - if (!entry) { - return false; - } - - entry->setSelected(false); - emit selectionChanged(); - - const QString ftime = (entry->time().date().year() >= 2010) ? entry->time().toString(QStringLiteral("yyyy-M-d-hh-mm-ss")) : QStringLiteral("UnknownDate"); - - _downloadData = std::make_unique(entry); - _downloadData->filename = QStringLiteral("log_") + QString::number(entry->id()) + "_" + ftime; - - if (_vehicle->firmwareType() == MAV_AUTOPILOT_PX4) { - const QString loggerParam = QStringLiteral("SYS_LOGGER"); - ParameterManager *const parameterManager = _vehicle->parameterManager(); - if (parameterManager->parameterExists(ParameterManager::defaultComponentId, loggerParam) && parameterManager->getParameter(ParameterManager::defaultComponentId, loggerParam)->rawValue().toInt() == 0) { - _downloadData->filename += ".px4log"; - } else { - _downloadData->filename += ".ulg"; - } - } else { - _downloadData->filename += ".bin"; - } - - _downloadData->file.setFileName(_downloadPath + _downloadData->filename); - - if (_downloadData->file.exists()) { - uint32_t numDups = 0; - const QStringList filename_spl = _downloadData->filename.split('.'); - do { - numDups += 1; - const QString filename = filename_spl[0] + '_' + QString::number(numDups) + '.' + filename_spl[1]; - _downloadData->file.setFileName(_downloadPath + filename); - } while ( _downloadData->file.exists()); - } - - bool result = false; - if (!_downloadData->file.open(QIODevice::WriteOnly)) { - qCWarning(OnboardLogControllerLog) << "Failed to create log file:" << _downloadData->filename; - } else if (!_downloadData->file.resize(entry->size())) { - qCWarning(OnboardLogControllerLog) << "Failed to allocate space for log file:" << _downloadData->filename; - } else { - _downloadData->current_chunk = 0; - _downloadData->chunk_table = QBitArray(_downloadData->chunkBins(), false); - _downloadData->elapsed.start(); - result = true; - } - - if (!result) { - if (_downloadData->file.exists()) { - (void) _downloadData->file.remove(); - } - - _downloadData->entry->setStatus(QStringLiteral("Error")); - _downloadData.reset(); - } - - return result; + return _active ? _active->transportName() : QString(); } void OnboardLogController::refresh() { - _logEntriesModel->clearAndDeleteContents(); - _requestLogList(0, 0xffff); + if (_active) + _active->refresh(); } -QGCOnboardLogEntry *OnboardLogController::_getNextSelected() const +void OnboardLogController::download(const QString& path) { - const int numLogs = _logEntriesModel->count(); - for (int i = 0; i < numLogs; i++) { - QGCOnboardLogEntry *const entry = _logEntriesModel->value(i); - if (!entry) { - continue; - } - - if (entry->selected()) { - return entry; - } - } - - return nullptr; -} - -void OnboardLogController::cancel() -{ - _requestLogEnd(); - _receivedAllEntries(); - - if (_downloadData) { - _downloadData->entry->setStatus(QStringLiteral("Canceled")); - if (_downloadData->file.exists()) { - (void) _downloadData->file.remove(); - } - - _downloadData.reset(); - } - - _resetSelection(true); - _setDownloading(false); + if (_active) + _active->download(path); } -void OnboardLogController::_resetSelection(bool canceled) +void OnboardLogController::eraseAll() { - const int num_logs = _logEntriesModel->count(); - for (int i = 0; i < num_logs; i++) { - QGCOnboardLogEntry *const entry = _logEntriesModel->value(i); - if (!entry) { - continue; - } - - if (entry->selected()) { - if (canceled) { - entry->setStatus(tr("Canceled")); - } - entry->setSelected(false); - } - } - - emit selectionChanged(); + if (_active) + _active->eraseAll(); } -void OnboardLogController::eraseAll() +void OnboardLogController::cancel() { - if (!_vehicle) { - qCWarning(OnboardLogControllerLog) << "Vehicle Unavailable"; - return; - } - - SharedLinkInterfacePtr sharedLink = _vehicle->vehicleLinkManager()->primaryLink().lock(); - if (!sharedLink) { - qCWarning(OnboardLogControllerLog) << "Link Unavailable"; - return; - } - - mavlink_message_t msg{}; - (void) mavlink_msg_log_erase_pack_chan( - MAVLinkProtocol::instance()->getSystemId(), - MAVLinkProtocol::getComponentId(), - sharedLink->mavlinkChannel(), - &msg, - _vehicle->id(), - _vehicle->defaultComponentId() - ); - - if (!_vehicle->sendMessageOnLinkThreadSafe(sharedLink.get(), msg)) { - qCWarning(OnboardLogControllerLog) << "Failed to send"; - return; - } - - refresh(); + if (_active) + _active->cancel(); } -void OnboardLogController::_requestLogList(uint32_t start, uint32_t end) +void OnboardLogController::_setActiveVehicle(Vehicle* vehicle) { - if (!_vehicle) { - qCWarning(OnboardLogControllerLog) << "Vehicle Unavailable"; + if (vehicle == _vehicle) { + _reevaluateTransport(); return; } - SharedLinkInterfacePtr sharedLink = _vehicle->vehicleLinkManager()->primaryLink().lock(); - if (!sharedLink) { - qCWarning(OnboardLogControllerLog) << "Link Unavailable"; - return; + if (_vehicle) { + disconnect(_vehicle, &Vehicle::capabilityBitsChanged, this, &OnboardLogController::_reevaluateTransport); } - mavlink_message_t msg{}; - (void) mavlink_msg_log_request_list_pack_chan( - MAVLinkProtocol::instance()->getSystemId(), - MAVLinkProtocol::getComponentId(), - sharedLink->mavlinkChannel(), - &msg, - _vehicle->id(), - _vehicle->defaultComponentId(), - start, - end - ); + _vehicle = vehicle; - if (!_vehicle->sendMessageOnLinkThreadSafe(sharedLink.get(), msg)) { - qCWarning(OnboardLogControllerLog) << "Failed to send"; - return; + if (_vehicle) { + // Capability bits may arrive after the vehicle is active; re-pick when they do. + (void)connect(_vehicle, &Vehicle::capabilityBitsChanged, this, &OnboardLogController::_reevaluateTransport); } - qCDebug(OnboardLogControllerLog) << "Request onboard log entry list (" << start << "through" << end << ")"; - _setListing(true); - _timer->start(kRequestLogListTimeoutMs); + _reevaluateTransport(); } -void OnboardLogController::_requestLogData(uint16_t id, uint32_t offset, uint32_t count, int retryCount) +void OnboardLogController::_reevaluateTransport() { - if (!_vehicle) { - qCWarning(OnboardLogControllerLog) << "Vehicle Unavailable"; - return; - } + enum TransportOverride { Auto = 0, LogProtocol = 1, MavlinkFtp = 2 }; + const TransportOverride override_ = static_cast( + SettingsManager::instance()->mavlinkSettings()->onboardLogTransport()->rawValue().toUInt()); - SharedLinkInterfacePtr sharedLink = _vehicle->vehicleLinkManager()->primaryLink().lock(); - if (!sharedLink) { - qCWarning(OnboardLogControllerLog) << "Link Unavailable"; - return; + OnboardLogTransport* target = _logTransport; + switch (override_) { + case LogProtocol: + target = _logTransport; + break; + case MavlinkFtp: + target = _ftpTransport; + break; + case Auto: + default: + if (_vehicle && _vehicle->capabilitiesKnown() && (_vehicle->capabilityBits() & MAV_PROTOCOL_CAPABILITY_FTP)) { + target = _ftpTransport; + } + break; } - id += _apmOffset; - qCDebug(OnboardLogControllerLog) << "Request log data (id:" << id << "offset:" << offset << "size:" << count << "retryCount" << retryCount << ")"; - - mavlink_message_t msg{}; - (void) mavlink_msg_log_request_data_pack_chan( - MAVLinkProtocol::instance()->getSystemId(), - MAVLinkProtocol::getComponentId(), - sharedLink->mavlinkChannel(), - &msg, - _vehicle->id(), - _vehicle->defaultComponentId(), - id, - offset, - count - ); + qCDebug(OnboardLogControllerLog) << "vehicle" << _vehicle << "override" << override_ << "→ transport" + << (target ? target->transportName() : QStringLiteral("none")); - if (!_vehicle->sendMessageOnLinkThreadSafe(sharedLink.get(), msg)) { - qCWarning(OnboardLogControllerLog) << "Failed to send"; - } + _setActiveTransport(target); } -void OnboardLogController::_requestLogEnd() +void OnboardLogController::_setActiveTransport(OnboardLogTransport* transport) { - if (!_vehicle) { - qCWarning(OnboardLogControllerLog) << "Vehicle Unavailable"; + if (transport == _active) { return; } - SharedLinkInterfacePtr sharedLink = _vehicle->vehicleLinkManager()->primaryLink().lock(); - if (!sharedLink) { - qCWarning(OnboardLogControllerLog) << "Link Unavailable"; - return; - } - - mavlink_message_t msg{}; - (void) mavlink_msg_log_request_end_pack_chan( - MAVLinkProtocol::instance()->getSystemId(), - MAVLinkProtocol::getComponentId(), - sharedLink->mavlinkChannel(), - &msg, - _vehicle->id(), - _vehicle->defaultComponentId() - ); - - if (!_vehicle->sendMessageOnLinkThreadSafe(sharedLink.get(), msg)) { - qCWarning(OnboardLogControllerLog) << "Failed to send"; + if (_active) { + disconnect(_active, nullptr, this, nullptr); + _active->cancel(); // stop any in-flight work on the deselected transport } -} -void OnboardLogController::_setDownloading(bool active) -{ - if (_downloadingLogs != active) { - _downloadingLogs = active; - _vehicle->vehicleLinkManager()->setCommunicationLostEnabled(!active); - emit downloadingLogsChanged(); - } -} + _active = transport; -void OnboardLogController::_setListing(bool active) -{ - if (_requestingLogEntries != active) { - _requestingLogEntries = active; - _vehicle->vehicleLinkManager()->setCommunicationLostEnabled(!active); - emit requestingListChanged(); + if (_active) { + (void)connect(_active, &OnboardLogTransport::modelChanged, this, &OnboardLogController::modelChanged); + (void)connect(_active, &OnboardLogTransport::requestingListChanged, this, + &OnboardLogController::requestingListChanged); + (void)connect(_active, &OnboardLogTransport::downloadingLogsChanged, this, + &OnboardLogController::downloadingLogsChanged); + (void)connect(_active, &OnboardLogTransport::canEraseChanged, this, &OnboardLogController::canEraseChanged); + (void)connect(_active, &OnboardLogTransport::transportNameChanged, this, + &OnboardLogController::transportNameChanged); + (void)connect(_active, &OnboardLogTransport::selectionChanged, this, &OnboardLogController::selectionChanged); } -} -void OnboardLogController::setCompressLogs(bool compress) -{ - if (_compressLogs != compress) { - _compressLogs = compress; - emit compressLogsChanged(); - } -} - -bool OnboardLogController::compressLogFile(const QString &logPath) -{ - Q_UNUSED(logPath) - qCWarning(OnboardLogControllerLog) << "Log compression not yet implemented (decompression-only API)"; - return false; -} - -void OnboardLogController::cancelCompression() -{ - // Not implemented - compression API is decompression-only -} - -void OnboardLogController::_handleCompressionProgress(qreal progress) -{ - Q_UNUSED(progress) - // Not implemented - compression API is decompression-only -} - -void OnboardLogController::_handleCompressionFinished(bool success) -{ - Q_UNUSED(success) - // Not implemented - compression API is decompression-only + emit modelChanged(); + emit requestingListChanged(); + emit downloadingLogsChanged(); + emit canEraseChanged(); + emit transportNameChanged(); } diff --git a/src/AnalyzeView/OnboardLogs/OnboardLogController.h b/src/AnalyzeView/OnboardLogs/OnboardLogController.h index e5e896abec9..38c1ecbdb5e 100644 --- a/src/AnalyzeView/OnboardLogs/OnboardLogController.h +++ b/src/AnalyzeView/OnboardLogs/OnboardLogController.h @@ -1,108 +1,46 @@ #pragma once -#include #include -struct OnboardLogDownloadData; -class QGCOnboardLogEntry; +#include "OnboardLogTransport.h" + +class FtpTransport; +class LogProtocolTransport; class QmlObjectListModel; -class QTimer; -class QThread; class Vehicle; -class OnboardLogDownloadTest; -class OnboardLogController : public QObject +/// QML facade picking LOG-protocol vs MAVLink-FTP transport per active vehicle. +class OnboardLogController : public OnboardLogTransport { Q_OBJECT QML_ELEMENT QML_SINGLETON Q_MOC_INCLUDE("Vehicle.h") - Q_MOC_INCLUDE("QmlObjectListModel.h") - Q_PROPERTY(QmlObjectListModel *model READ _getModel CONSTANT) - Q_PROPERTY(bool requestingList READ _getRequestingList NOTIFY requestingListChanged) - Q_PROPERTY(bool downloadingLogs READ _getDownloadingLogs NOTIFY downloadingLogsChanged) - Q_PROPERTY(bool compressLogs READ compressLogs WRITE setCompressLogs NOTIFY compressLogsChanged) - Q_PROPERTY(bool compressing READ compressing NOTIFY compressingChanged) - Q_PROPERTY(float compressionProgress READ compressionProgress NOTIFY compressionProgressChanged) - - friend class OnboardLogDownloadTest; public: - explicit OnboardLogController(QObject *parent = nullptr); - ~OnboardLogController(); - - Q_INVOKABLE void refresh(); - Q_INVOKABLE void download(const QString &path = QString()); - Q_INVOKABLE void eraseAll(); - Q_INVOKABLE void cancel(); - - bool compressLogs() const { return _compressLogs; } - void setCompressLogs(bool compress); - bool compressing() const { return _compressing; } - float compressionProgress() const { return _compressionProgress; } - - /// Compress a single log file - Q_INVOKABLE bool compressLogFile(const QString &logPath); + explicit OnboardLogController(QObject* parent = nullptr); + ~OnboardLogController() override; - /// Cancel compression - Q_INVOKABLE void cancelCompression(); + QmlObjectListModel* model() const override; + bool requestingList() const override; + bool downloadingLogs() const override; + bool canErase() const override; + QString transportName() const override; -signals: - void requestingListChanged(); - void downloadingLogsChanged(); - void selectionChanged(); - void compressLogsChanged(); - void compressingChanged(); - void compressionProgressChanged(); - void compressionComplete(const QString &outputPath, const QString &error); + Q_INVOKABLE void refresh() override; + Q_INVOKABLE void download(const QString& path = QString()) override; + Q_INVOKABLE void eraseAll() override; + Q_INVOKABLE void cancel() override; private slots: - void _setActiveVehicle(Vehicle *vehicle); - void _logEntry(uint32_t time_utc, uint32_t size, uint16_t id, uint16_t num_logs, uint16_t last_log_num); - void _logData(uint32_t ofs, uint16_t id, uint8_t count, const uint8_t *data); - void _processDownload(); - void _handleCompressionProgress(qreal progress); - void _handleCompressionFinished(bool success); + void _setActiveVehicle(Vehicle* vehicle); + void _reevaluateTransport(); private: - QmlObjectListModel *_getModel() const { return _logEntriesModel; } - bool _getRequestingList() const { return _requestingLogEntries; } - bool _getDownloadingLogs() const { return _downloadingLogs; } - - bool _chunkComplete() const; - bool _entriesComplete() const; - bool _logComplete() const; - bool _prepareLogDownload(); - void _downloadToDirectory(const QString &dir); - void _findMissingData(); - void _findMissingEntries(); - void _receivedAllData(); - void _receivedAllEntries(); - void _requestLogData(uint16_t id, uint32_t offset, uint32_t count, int retryCount = 0); - void _requestLogList(uint32_t start, uint32_t end); - void _requestLogEnd(); - void _resetSelection(bool canceled = false); - void _setDownloading(bool active); - void _setListing(bool active); - void _updateDataRate(); - - QGCOnboardLogEntry *_getNextSelected() const; - - QTimer *_timer = nullptr; - QmlObjectListModel *_logEntriesModel = nullptr; - - bool _downloadingLogs = false; - bool _requestingLogEntries = false; - int _apmOffset = 0; - int _retries = 0; - std::unique_ptr _downloadData; - QString _downloadPath; - Vehicle *_vehicle = nullptr; - bool _compressLogs = false; - bool _compressing = false; - float _compressionProgress = 0.0F; + void _setActiveTransport(OnboardLogTransport* transport); - static constexpr uint32_t kTimeOutMs = 500; - static constexpr uint32_t kGUIRateMs = 500; ///< Update download rate twice per second - static constexpr uint32_t kRequestLogListTimeoutMs = 5000; + LogProtocolTransport* _logTransport = nullptr; + FtpTransport* _ftpTransport = nullptr; + OnboardLogTransport* _active = nullptr; + Vehicle* _vehicle = nullptr; }; diff --git a/src/AnalyzeView/OnboardLogs/OnboardLogDownloadData.cc b/src/AnalyzeView/OnboardLogs/OnboardLogDownloadData.cc new file mode 100644 index 00000000000..d7bb41b1285 --- /dev/null +++ b/src/AnalyzeView/OnboardLogs/OnboardLogDownloadData.cc @@ -0,0 +1,46 @@ +#include "OnboardLogDownloadData.h" + +#include + +#include "MAVLinkLib.h" +#include "OnboardLogEntry.h" +#include "QGCLoggingCategory.h" + +QGC_LOGGING_CATEGORY(OnboardLogDownloadDataLog, "AnalyzeView.OnboardLogDownloadData") + +const uint32_t OnboardLogDownloadData::kChunkSize = + OnboardLogDownloadData::kTableBins * MAVLINK_MSG_LOG_DATA_FIELD_DATA_LEN; + +OnboardLogDownloadData::OnboardLogDownloadData(OnboardLogEntry* const logEntry) : ID(logEntry->id()), entry(logEntry) +{ + qCDebug(OnboardLogDownloadDataLog) << Q_FUNC_INFO << "id" << ID; +} + +OnboardLogDownloadData::~OnboardLogDownloadData() +{ + qCDebug(OnboardLogDownloadDataLog) << Q_FUNC_INFO << "id" << ID; +} + +void OnboardLogDownloadData::advanceChunk() +{ + ++current_chunk; + chunk_table = QBitArray(chunkBins(), false); +} + +uint32_t OnboardLogDownloadData::chunkBins() const +{ + const qreal num = static_cast((entry->size() - (current_chunk * kChunkSize))) / + static_cast(MAVLINK_MSG_LOG_DATA_FIELD_DATA_LEN); + return qMin(static_cast(qCeil(num)), kTableBins); +} + +uint32_t OnboardLogDownloadData::numChunks() const +{ + const qreal num = static_cast(entry->size()) / static_cast(kChunkSize); + return qCeil(num); +} + +bool OnboardLogDownloadData::chunkEquals(const bool val) const +{ + return (chunk_table == QBitArray(chunk_table.size(), val)); +} diff --git a/src/AnalyzeView/OnboardLogs/OnboardLogDownloadData.h b/src/AnalyzeView/OnboardLogs/OnboardLogDownloadData.h new file mode 100644 index 00000000000..df3d7f1686a --- /dev/null +++ b/src/AnalyzeView/OnboardLogs/OnboardLogDownloadData.h @@ -0,0 +1,41 @@ +#pragma once + +#include +#include +#include +#include + +class OnboardLogEntry; + +struct OnboardLogDownloadData +{ + explicit OnboardLogDownloadData(OnboardLogEntry* const logEntry); + ~OnboardLogDownloadData(); + + void advanceChunk(); + + /// The number of MAVLINK_MSG_LOG_DATA_FIELD_DATA_LEN bins in the current chunk + uint32_t chunkBins() const; + + /// The number of kChunkSize chunks in the file + uint32_t numChunks() const; + + /// True if all bins in the chunk have been set to val + bool chunkEquals(const bool val) const; + + uint ID = 0; + OnboardLogEntry* const entry = nullptr; + + QBitArray chunk_table; + uint32_t current_chunk = 0; + QFile file; + QString filename; + uint written = 0; + uint last_status_written = 0; + size_t rate_bytes = 0; + qreal rate_avg = 0.; + QElapsedTimer elapsed; + + static constexpr uint32_t kTableBins = 2048; // 2048 packets = ~180 KB chunks (4x larger for better throughput) + static const uint32_t kChunkSize; // kTableBins * MAVLINK_MSG_LOG_DATA_FIELD_DATA_LEN (defined in .cc) +}; diff --git a/src/AnalyzeView/OnboardLogs/OnboardLogEntry.cc b/src/AnalyzeView/OnboardLogs/OnboardLogEntry.cc index 33d7f5bf347..d88ce6d5f74 100644 --- a/src/AnalyzeView/OnboardLogs/OnboardLogEntry.cc +++ b/src/AnalyzeView/OnboardLogs/OnboardLogEntry.cc @@ -1,67 +1,23 @@ #include "OnboardLogEntry.h" -#include "MAVLinkLib.h" + #include "QGCFormat.h" #include "QGCLoggingCategory.h" -#include - -QGC_LOGGING_CATEGORY(OnboardLogEntryLog, "AnalyzeView.QGCOnboardLogEntry") - -const uint32_t OnboardLogDownloadData::kChunkSize = OnboardLogDownloadData::kTableBins * MAVLINK_MSG_LOG_DATA_FIELD_DATA_LEN; - -OnboardLogDownloadData::OnboardLogDownloadData(QGCOnboardLogEntry * const logEntry) - : ID(logEntry->id()) - , entry(logEntry) -{ - qCDebug(OnboardLogEntryLog) << Q_FUNC_INFO << "id" << ID; -} - -OnboardLogDownloadData::~OnboardLogDownloadData() -{ - qCDebug(OnboardLogEntryLog) << Q_FUNC_INFO << "id" << ID; -} - -void OnboardLogDownloadData::advanceChunk() -{ - ++current_chunk; - chunk_table = QBitArray(chunkBins(), false); -} - -uint32_t OnboardLogDownloadData::chunkBins() const -{ - const qreal num = static_cast((entry->size() - (current_chunk * kChunkSize))) / static_cast(MAVLINK_MSG_LOG_DATA_FIELD_DATA_LEN); - return qMin(static_cast(qCeil(num)), kTableBins); -} - -uint32_t OnboardLogDownloadData::numChunks() const -{ - const qreal num = static_cast(entry->size()) / static_cast(kChunkSize); - return qCeil(num); -} - -bool OnboardLogDownloadData::chunkEquals(const bool val) const -{ - return (chunk_table == QBitArray(chunk_table.size(), val)); -} - -/*===========================================================================*/ +QGC_LOGGING_CATEGORY(OnboardLogEntryLog, "AnalyzeView.OnboardLogEntry") -QGCOnboardLogEntry::QGCOnboardLogEntry(uint logId, const QDateTime &dateTime, uint logSize, bool received, QObject *parent) - : QObject(parent) - , _logID(logId) - , _logSize(logSize) - , _logTimeUTC(dateTime) - , _received(received) +OnboardLogEntry::OnboardLogEntry(uint logId, const QDateTime& dateTime, uint logSize, bool received, + QObject* parent) + : QObject(parent), _logID(logId), _logSize(logSize), _logTimeUTC(dateTime), _received(received) { qCDebug(OnboardLogEntryLog) << Q_FUNC_INFO << "id" << _logID; } -QGCOnboardLogEntry::~QGCOnboardLogEntry() +OnboardLogEntry::~OnboardLogEntry() { qCDebug(OnboardLogEntryLog) << Q_FUNC_INFO << "id" << _logID; } -QString QGCOnboardLogEntry::sizeStr() const +QString OnboardLogEntry::sizeStr() const { return QGC::bigSizeToString(_logSize); } diff --git a/src/AnalyzeView/OnboardLogs/OnboardLogEntry.h b/src/AnalyzeView/OnboardLogs/OnboardLogEntry.h index 1aa5b4e5e5a..e5adecea596 100644 --- a/src/AnalyzeView/OnboardLogs/OnboardLogEntry.h +++ b/src/AnalyzeView/OnboardLogs/OnboardLogEntry.h @@ -1,81 +1,92 @@ #pragma once -#include #include -#include -#include #include #include #include -class QGCOnboardLogEntry; - -struct OnboardLogDownloadData -{ - explicit OnboardLogDownloadData(QGCOnboardLogEntry * const logEntry); - ~OnboardLogDownloadData(); - - void advanceChunk(); - - /// The number of MAVLINK_MSG_LOG_DATA_FIELD_DATA_LEN bins in the current chunk - uint32_t chunkBins() const; - - /// The number of kChunkSize chunks in the file - uint32_t numChunks() const; - - /// True if all bins in the chunk have been set to val - bool chunkEquals(const bool val) const; - - uint ID = 0; - QGCOnboardLogEntry *const entry = nullptr; - - QBitArray chunk_table; - uint32_t current_chunk = 0; - QFile file; - QString filename; - uint written = 0; - uint last_status_written = 0; - size_t rate_bytes = 0; - qreal rate_avg = 0.; - QElapsedTimer elapsed; - - static constexpr uint32_t kTableBins = 2048; // 2048 packets = ~180 KB chunks (4x larger for better throughput) - static const uint32_t kChunkSize; // kTableBins * MAVLINK_MSG_LOG_DATA_FIELD_DATA_LEN (defined in .cc) -}; - -/*===========================================================================*/ - -class QGCOnboardLogEntry : public QObject +class OnboardLogEntry : public QObject { Q_OBJECT - // QML_ELEMENT - Q_PROPERTY(uint id READ id NOTIFY idChanged) - Q_PROPERTY(QDateTime time READ time NOTIFY timeChanged) - Q_PROPERTY(uint size READ size NOTIFY sizeChanged) - Q_PROPERTY(QString sizeStr READ sizeStr NOTIFY sizeChanged) - Q_PROPERTY(bool received READ received NOTIFY receivedChanged) - Q_PROPERTY(bool selected READ selected WRITE setSelected NOTIFY selectedChanged) - Q_PROPERTY(QString status READ status NOTIFY statusChanged) + Q_PROPERTY(uint id READ id NOTIFY idChanged) + Q_PROPERTY(QDateTime time READ time NOTIFY timeChanged) + Q_PROPERTY(uint size READ size NOTIFY sizeChanged) + Q_PROPERTY(QString sizeStr READ sizeStr NOTIFY sizeChanged) + Q_PROPERTY(bool received READ received NOTIFY receivedChanged) + Q_PROPERTY(bool selected READ selected WRITE setSelected NOTIFY selectedChanged) + Q_PROPERTY(QString status READ status NOTIFY statusChanged) public: - explicit QGCOnboardLogEntry(uint logId, const QDateTime &dateTime = QDateTime(), uint logSize = 0, bool received = false, QObject *parent = nullptr); - ~QGCOnboardLogEntry(); + explicit OnboardLogEntry(uint logId, const QDateTime& dateTime = QDateTime(), uint logSize = 0, + bool received = false, QObject* parent = nullptr); + ~OnboardLogEntry(); uint id() const { return _logID; } + uint size() const { return _logSize; } + QString sizeStr() const; + QDateTime time() const { return _logTimeUTC; } + bool received() const { return _received; } + bool selected() const { return _selected; } + QString status() const { return _status; } - void setId(uint id) { if (id != _logID) { _logID = id; emit idChanged(); } } - void setSize(uint size) { if (size != _logSize) { _logSize = size; emit sizeChanged(); } } - void setTime(const QDateTime &date) { if (date != _logTimeUTC) {_logTimeUTC = date; emit timeChanged(); } } - void setReceived(bool rec) { if (rec != _received) { _received = rec; emit receivedChanged(); } } - void setSelected(bool sel) { if (sel != _selected) { _selected = sel; emit selectedChanged(); } } - void setStatus(const QString &stat) { if (stat != _status) { _status = stat; emit statusChanged(); } } + QString ftpPath() const { return _ftpPath; } // empty for LOG-protocol entries + + void setId(uint id) + { + if (id != _logID) { + _logID = id; + emit idChanged(); + } + } + + void setSize(uint size) + { + if (size != _logSize) { + _logSize = size; + emit sizeChanged(); + } + } + + void setTime(const QDateTime& date) + { + if (date != _logTimeUTC) { + _logTimeUTC = date; + emit timeChanged(); + } + } + + void setReceived(bool rec) + { + if (rec != _received) { + _received = rec; + emit receivedChanged(); + } + } + + void setSelected(bool sel) + { + if (sel != _selected) { + _selected = sel; + emit selectedChanged(); + } + } + + void setStatus(const QString& stat) + { + if (stat != _status) { + _status = stat; + emit statusChanged(); + } + } + + void setFtpPath(const QString& path) { _ftpPath = path; } signals: void idChanged(); @@ -92,4 +103,5 @@ class QGCOnboardLogEntry : public QObject bool _received = false; bool _selected = false; QString _status = QStringLiteral("Pending"); + QString _ftpPath; }; diff --git a/src/AnalyzeView/OnboardLogs/OnboardLogPage.qml b/src/AnalyzeView/OnboardLogs/OnboardLogPage.qml index 7f253f0ff15..9cfc8b3a14c 100644 --- a/src/AnalyzeView/OnboardLogs/OnboardLogPage.qml +++ b/src/AnalyzeView/OnboardLogs/OnboardLogPage.qml @@ -1,15 +1,17 @@ import QtQuick import QtQuick.Controls import QtQuick.Layouts -import Qt.labs.qmlmodels import QGroundControl +import QGroundControl.AnalyzeView import QGroundControl.Controls AnalyzePage { id: onboardLogPage pageComponent: pageComponent - pageDescription: qsTr("Onboard Logs allows you to download binary log files from your vehicle. Click Refresh to get list of available logs.") + pageDescription: OnboardLogController.transportName === "ftp" + ? qsTr("Onboard Logs lists log files on the vehicle's SD card via MAVLink FTP. Click Refresh to query the vehicle.") + : qsTr("Onboard Logs allows you to download binary log files from your vehicle. Click Refresh to get list of available logs.") Component { id: pageComponent @@ -20,81 +22,10 @@ AnalyzePage { Component.onCompleted: OnboardLogController.refresh() - QGCFlickable { + OnboardLogTable { Layout.fillWidth: true Layout.fillHeight: true - contentWidth: gridLayout.width - contentHeight: gridLayout.height - - GridLayout { - id: gridLayout - rows: OnboardLogController.model.count + 1 - columns: 5 - flow: GridLayout.TopToBottom - columnSpacing: ScreenTools.defaultFontPixelWidth - rowSpacing: 0 - - QGCCheckBox { - id: headerCheckBox - enabled: false - } - - Repeater { - model: OnboardLogController.model - - QGCCheckBox { - Binding on checkState { - value: object.selected ? Qt.Checked : Qt.Unchecked - } - - onClicked: object.selected = checked - } - } - - QGCLabel { text: qsTr("Id") } - - Repeater { - model: OnboardLogController.model - - QGCLabel { text: object.id } - } - - QGCLabel { text: qsTr("Date") } - - Repeater { - model: OnboardLogController.model - - QGCLabel { - text: { - if (!object.received) { - return "" - } - - if (object.time.getUTCFullYear() < 2010) { - return qsTr("Date Unknown") - } - - return object.time.toLocaleString(undefined) - } - } - } - - QGCLabel { text: qsTr("Size") } - - Repeater { - model: OnboardLogController.model - - QGCLabel { text: object.sizeStr } - } - - QGCLabel { text: qsTr("Status") } - - Repeater { - model: OnboardLogController.model - - QGCLabel { text: object.status } - } - } + controller: OnboardLogController } ColumnLayout { @@ -124,10 +55,13 @@ AnalyzePage { onClicked: { var logsSelected = false - for (var i = 0; i < OnboardLogController.model.count; i++) { - if (OnboardLogController.model.get(i).selected) { - logsSelected = true - break + var listModel = OnboardLogController.model + if (listModel) { + for (var i = 0; i < listModel.count; i++) { + if (listModel.get(i).selected) { + logsSelected = true + break + } } } @@ -158,7 +92,11 @@ AnalyzePage { QGCButton { Layout.fillWidth: true - enabled: !OnboardLogController.requestingList && !OnboardLogController.downloadingLogs && (OnboardLogController.model.count > 0) + visible: OnboardLogController.canErase + enabled: OnboardLogController.canErase && + !OnboardLogController.requestingList && + !OnboardLogController.downloadingLogs && + OnboardLogController.model && OnboardLogController.model.count > 0 text: qsTr("Erase All") onClicked: QGroundControl.showMessageDialog( onboardLogPage, diff --git a/src/AnalyzeView/OnboardLogs/OnboardLogTable.qml b/src/AnalyzeView/OnboardLogs/OnboardLogTable.qml new file mode 100644 index 00000000000..801c875334d --- /dev/null +++ b/src/AnalyzeView/OnboardLogs/OnboardLogTable.qml @@ -0,0 +1,76 @@ +import QtQuick +import QtQuick.Controls +import QtQuick.Layouts + +import QGroundControl +import QGroundControl.Controls + +QGCFlickable { + id: root + + required property var controller + + contentWidth: gridLayout.width + contentHeight: gridLayout.height + + GridLayout { + id: gridLayout + rows: root.controller.model.count + 1 + columns: 5 + flow: GridLayout.TopToBottom + columnSpacing: ScreenTools.defaultFontPixelWidth + rowSpacing: 0 + + QGCCheckBox { enabled: false } + + Repeater { + model: root.controller.model + + QGCCheckBox { + Binding on checkState { + value: object.selected ? Qt.Checked : Qt.Unchecked + } + onClicked: object.selected = checked + } + } + + QGCLabel { text: qsTr("Id") } + + Repeater { + model: root.controller.model + QGCLabel { text: object.id } + } + + QGCLabel { text: qsTr("Date") } + + Repeater { + model: root.controller.model + + QGCLabel { + text: { + if (!object.received) { + return "" + } + if (object.time.getUTCFullYear() < 2010) { + return qsTr("Date Unknown") + } + return object.time.toLocaleString(undefined) + } + } + } + + QGCLabel { text: qsTr("Size") } + + Repeater { + model: root.controller.model + QGCLabel { text: object.sizeStr } + } + + QGCLabel { text: qsTr("Status") } + + Repeater { + model: root.controller.model + QGCLabel { text: object.status } + } + } +} diff --git a/src/AnalyzeView/OnboardLogs/OnboardLogTransport.cc b/src/AnalyzeView/OnboardLogs/OnboardLogTransport.cc new file mode 100644 index 00000000000..2831f644ea6 --- /dev/null +++ b/src/AnalyzeView/OnboardLogs/OnboardLogTransport.cc @@ -0,0 +1,9 @@ +#include "OnboardLogTransport.h" + +#include "QmlObjectListModel.h" + +OnboardLogTransport::OnboardLogTransport(QObject* parent) + : QObject(parent), _logEntriesModel(new QmlObjectListModel(this)) +{} + +OnboardLogTransport::~OnboardLogTransport() = default; diff --git a/src/AnalyzeView/OnboardLogs/OnboardLogTransport.h b/src/AnalyzeView/OnboardLogs/OnboardLogTransport.h new file mode 100644 index 00000000000..06648b42d9c --- /dev/null +++ b/src/AnalyzeView/OnboardLogs/OnboardLogTransport.h @@ -0,0 +1,56 @@ +#pragma once + +#include +#include +#include + +class QmlObjectListModel; + +/// Common contract for an onboard-log transport (LOG protocol or MAVLink FTP). +/// Concrete subclasses (LogProtocolTransport, FtpTransport) are owned by +/// OnboardLogController, which selects one per active vehicle and forwards the +/// QML-facing surface. The base is also the type QML binds against. +class OnboardLogTransport : public QObject +{ + Q_OBJECT + Q_MOC_INCLUDE("QmlObjectListModel.h") + Q_PROPERTY(QmlObjectListModel* model READ model NOTIFY modelChanged) + Q_PROPERTY(bool requestingList READ requestingList NOTIFY requestingListChanged) + Q_PROPERTY(bool downloadingLogs READ downloadingLogs NOTIFY downloadingLogsChanged) + Q_PROPERTY(bool canErase READ canErase NOTIFY canEraseChanged) + Q_PROPERTY(QString transportName READ transportName NOTIFY transportNameChanged) + +public: + ~OnboardLogTransport() override; + + virtual QmlObjectListModel* model() const { return _logEntriesModel; } + + virtual bool requestingList() const { return _requestingLogEntries; } + + virtual bool downloadingLogs() const { return _downloadingLogs; } + + virtual bool canErase() const { return false; } + + virtual QString transportName() const = 0; + + Q_INVOKABLE virtual void refresh() = 0; + Q_INVOKABLE virtual void download(const QString& path = QString()) = 0; + Q_INVOKABLE virtual void cancel() = 0; + + Q_INVOKABLE virtual void eraseAll() {} + +signals: + void modelChanged(); + void requestingListChanged(); + void downloadingLogsChanged(); + void canEraseChanged(); + void transportNameChanged(); + void selectionChanged(); + +protected: + explicit OnboardLogTransport(QObject* parent = nullptr); + + QmlObjectListModel* _logEntriesModel = nullptr; + bool _requestingLogEntries = false; + bool _downloadingLogs = false; +}; diff --git a/src/AnalyzeView/OnboardLogsFtp/CMakeLists.txt b/src/AnalyzeView/OnboardLogsFtp/CMakeLists.txt deleted file mode 100644 index 5705726838b..00000000000 --- a/src/AnalyzeView/OnboardLogsFtp/CMakeLists.txt +++ /dev/null @@ -1,14 +0,0 @@ -# ============================================================================ -# Onboard Logs FTP Module -# Onboard log list and download via MAVLink FTP (@MAV_LOG) -# ============================================================================ - -target_sources(${CMAKE_PROJECT_NAME} - PRIVATE - OnboardLogFtpController.cc - OnboardLogFtpController.h - OnboardLogFtpEntry.cc - OnboardLogFtpEntry.h -) - -target_include_directories(${CMAKE_PROJECT_NAME} PRIVATE ${CMAKE_CURRENT_SOURCE_DIR}) diff --git a/src/AnalyzeView/OnboardLogsFtp/OnboardLogFtpController.h b/src/AnalyzeView/OnboardLogsFtp/OnboardLogFtpController.h deleted file mode 100644 index 30a89d53d6c..00000000000 --- a/src/AnalyzeView/OnboardLogsFtp/OnboardLogFtpController.h +++ /dev/null @@ -1,83 +0,0 @@ -#pragma once - -#include -#include -#include -#include -#include - -Q_DECLARE_LOGGING_CATEGORY(OnboardLogFtpControllerLog) - -class QGCOnboardLogFtpEntry; -class QmlObjectListModel; -class Vehicle; - -class OnboardLogFtpController : public QObject -{ - Q_OBJECT - QML_ELEMENT - QML_SINGLETON - Q_MOC_INCLUDE("Vehicle.h") - Q_MOC_INCLUDE("QmlObjectListModel.h") - Q_PROPERTY(QmlObjectListModel *model READ _getModel CONSTANT) - Q_PROPERTY(bool requestingList READ _getRequestingList NOTIFY requestingListChanged) - Q_PROPERTY(bool downloadingLogs READ _getDownloadingLogs NOTIFY downloadingLogsChanged) - -public: - explicit OnboardLogFtpController(QObject *parent = nullptr); - ~OnboardLogFtpController(); - - Q_INVOKABLE void refresh(); - Q_INVOKABLE void download(const QString &path = QString()); - Q_INVOKABLE void cancel(); - -signals: - void requestingListChanged(); - void downloadingLogsChanged(); - void selectionChanged(); - -private slots: - void _setActiveVehicle(Vehicle *vehicle); - void _listDirComplete(const QStringList &dirList, const QString &errorMsg); - void _downloadComplete(const QString &file, const QString &errorMsg); - void _downloadProgress(float value); - -private: - enum ListState { Idle, ListingRoot, ListingSubdir }; - - QmlObjectListModel *_getModel() const { return _logEntriesModel; } - bool _getRequestingList() const { return _requestingLogEntries; } - bool _getDownloadingLogs() const { return _downloadingLogs; } - - void _startListing(); - void _listRoot(); - void _listNextSubdir(); - uint _processFileEntries(const QStringList &dirList, const QString &subdir); - void _downloadEntry(QGCOnboardLogFtpEntry *entry); - void _downloadToDirectory(const QString &dir); - void _resetSelection(bool canceled = false); - void _setDownloading(bool active); - void _setListing(bool active); - void _finishListing(); - - QmlObjectListModel *_logEntriesModel = nullptr; - Vehicle *_vehicle = nullptr; - - bool _requestingLogEntries = false; - bool _downloadingLogs = false; - - ListState _listState = Idle; - QString _logRoot; - bool _triedFallbackRoot = false; - QStringList _dirsToList; - uint _logIdCounter = 0; - - QQueue _downloadQueue; - QGCOnboardLogFtpEntry *_currentDownloadEntry = nullptr; - QString _downloadPath; - QElapsedTimer _downloadElapsed; - size_t _downloadBytesAtLastUpdate = 0; - qreal _downloadRateAvg = 0.; - - static constexpr uint32_t kGUIRateMs = 17; -}; diff --git a/src/AnalyzeView/OnboardLogsFtp/OnboardLogFtpEntry.cc b/src/AnalyzeView/OnboardLogsFtp/OnboardLogFtpEntry.cc deleted file mode 100644 index 9164a151141..00000000000 --- a/src/AnalyzeView/OnboardLogsFtp/OnboardLogFtpEntry.cc +++ /dev/null @@ -1,23 +0,0 @@ -#include "OnboardLogFtpEntry.h" -#include "QGCFormat.h" -#include "QGCLoggingCategory.h" - -QGC_LOGGING_CATEGORY(OnboardLogFtpEntryLog, "AnalyzeView.QGCOnboardLogFtpEntry") - -QGCOnboardLogFtpEntry::QGCOnboardLogFtpEntry(uint logId, const QDateTime &dateTime, uint logSize, bool received, QObject *parent) - : QObject(parent) - , _logID(logId) - , _logSize(logSize) - , _logTimeUTC(dateTime) - , _received(received) -{ -} - -QGCOnboardLogFtpEntry::~QGCOnboardLogFtpEntry() -{ -} - -QString QGCOnboardLogFtpEntry::sizeStr() const -{ - return QGC::bigSizeToString(_logSize); -} diff --git a/src/AnalyzeView/OnboardLogsFtp/OnboardLogFtpEntry.h b/src/AnalyzeView/OnboardLogsFtp/OnboardLogFtpEntry.h deleted file mode 100644 index b18d24e9bea..00000000000 --- a/src/AnalyzeView/OnboardLogsFtp/OnboardLogFtpEntry.h +++ /dev/null @@ -1,57 +0,0 @@ -#pragma once - -#include -#include -#include -#include - -class QGCOnboardLogFtpEntry; - -Q_DECLARE_LOGGING_CATEGORY(OnboardLogFtpEntryLog) - -class QGCOnboardLogFtpEntry : public QObject -{ - Q_OBJECT - - Q_PROPERTY(uint id READ id NOTIFY idChanged) - Q_PROPERTY(QDateTime time READ time NOTIFY timeChanged) - Q_PROPERTY(uint size READ size NOTIFY sizeChanged) - Q_PROPERTY(QString sizeStr READ sizeStr NOTIFY sizeChanged) - Q_PROPERTY(bool received READ received NOTIFY receivedChanged) - Q_PROPERTY(bool selected READ selected WRITE setSelected NOTIFY selectedChanged) - Q_PROPERTY(QString status READ status NOTIFY statusChanged) - -public: - explicit QGCOnboardLogFtpEntry(uint logId, const QDateTime &dateTime = QDateTime(), uint logSize = 0, bool received = false, QObject *parent = nullptr); - ~QGCOnboardLogFtpEntry(); - - uint id() const { return _logID; } - uint size() const { return _logSize; } - QString sizeStr() const; - QDateTime time() const { return _logTimeUTC; } - bool received() const { return _received; } - bool selected() const { return _selected; } - QString status() const { return _status; } - QString ftpPath() const { return _ftpPath; } - - void setSelected(bool sel) { if (sel != _selected) { _selected = sel; emit selectedChanged(); } } - void setStatus(const QString &stat) { if (stat != _status) { _status = stat; emit statusChanged(); } } - void setFtpPath(const QString &path) { _ftpPath = path; } - -signals: - void idChanged(); - void timeChanged(); - void sizeChanged(); - void receivedChanged(); - void selectedChanged(); - void statusChanged(); - -private: - uint _logID = 0; - uint _logSize = 0; - QDateTime _logTimeUTC; - bool _received = false; - bool _selected = false; - QString _status = QStringLiteral("Pending"); - QString _ftpPath; -}; diff --git a/src/AnalyzeView/OnboardLogsFtp/OnboardLogFtpPage.qml b/src/AnalyzeView/OnboardLogsFtp/OnboardLogFtpPage.qml deleted file mode 100644 index 22e44ac6186..00000000000 --- a/src/AnalyzeView/OnboardLogsFtp/OnboardLogFtpPage.qml +++ /dev/null @@ -1,166 +0,0 @@ -import QtQuick -import QtQuick.Controls -import QtQuick.Layouts -import Qt.labs.qmlmodels - -import QGroundControl -import QGroundControl.Controls - -AnalyzePage { - id: onboardLogFtpPage - pageComponent: pageComponent - pageDescription: qsTr("Onboard Logs (FTP) lists log files on the vehicle's SD card via MAVLink FTP. Click Refresh to query the vehicle.") - - Component { - id: pageComponent - - RowLayout { - width: availableWidth - height: availableHeight - - QGCFlickable { - Layout.fillWidth: true - Layout.fillHeight: true - contentWidth: gridLayout.width - contentHeight: gridLayout.height - - GridLayout { - id: gridLayout - rows: OnboardLogFtpController.model.count + 1 - columns: 5 - flow: GridLayout.TopToBottom - columnSpacing: ScreenTools.defaultFontPixelWidth - rowSpacing: 0 - - QGCCheckBox { - id: headerCheckBox - enabled: false - } - - Repeater { - model: OnboardLogFtpController.model - - QGCCheckBox { - Binding on checkState { - value: object.selected ? Qt.Checked : Qt.Unchecked - } - - onClicked: object.selected = checked - } - } - - QGCLabel { text: qsTr("Id") } - - Repeater { - model: OnboardLogFtpController.model - - QGCLabel { text: object.id } - } - - QGCLabel { text: qsTr("Date") } - - Repeater { - model: OnboardLogFtpController.model - - QGCLabel { - text: { - if (!object.received) { - return "" - } - - if (object.time.getUTCFullYear() < 2010) { - return qsTr("Date Unknown") - } - - return object.time.toLocaleString(undefined) - } - } - } - - QGCLabel { text: qsTr("Size") } - - Repeater { - model: OnboardLogFtpController.model - - QGCLabel { text: object.sizeStr } - } - - QGCLabel { text: qsTr("Status") } - - Repeater { - model: OnboardLogFtpController.model - - QGCLabel { text: object.status } - } - } - } - - ColumnLayout { - spacing: ScreenTools.defaultFontPixelWidth - Layout.alignment: Qt.AlignTop - Layout.fillWidth: false - - QGCButton { - Layout.fillWidth: true - enabled: !OnboardLogFtpController.requestingList && !OnboardLogFtpController.downloadingLogs - text: qsTr("Refresh") - - onClicked: { - if (!QGroundControl.multiVehicleManager.activeVehicle || QGroundControl.multiVehicleManager.activeVehicle.isOfflineEditingVehicle) { - QGroundControl.showMessageDialog(onboardLogFtpPage, qsTr("Log Refresh"), qsTr("You must be connected to a vehicle in order to download logs.")) - return - } - - OnboardLogFtpController.refresh() - } - } - - QGCButton { - Layout.fillWidth: true - enabled: !OnboardLogFtpController.requestingList && !OnboardLogFtpController.downloadingLogs - text: qsTr("Download") - - onClicked: { - var logsSelected = false - for (var i = 0; i < OnboardLogFtpController.model.count; i++) { - if (OnboardLogFtpController.model.get(i).selected) { - logsSelected = true - break - } - } - - if (!logsSelected) { - QGroundControl.showMessageDialog(onboardLogFtpPage, qsTr("Log Download"), qsTr("You must select at least one log file to download.")) - return - } - - if (ScreenTools.isMobile) { - OnboardLogFtpController.download() - return - } - - fileDialog.title = qsTr("Select save directory") - fileDialog.folder = QGroundControl.settingsManager.appSettings.logSavePath - fileDialog.selectFolder = true - fileDialog.openForLoad() - } - - QGCFileDialog { - id: fileDialog - onAcceptedForLoad: (file) => { - OnboardLogFtpController.download(file) - close() - } - } - } - - QGCButton { - Layout.fillWidth: true - text: qsTr("Cancel") - enabled: OnboardLogFtpController.requestingList || OnboardLogFtpController.downloadingLogs - onClicked: OnboardLogFtpController.cancel() - } - } - } - } -} diff --git a/src/Settings/Mavlink.SettingsGroup.json b/src/Settings/Mavlink.SettingsGroup.json index 36cfd2cd889..a507bdbeee3 100644 --- a/src/Settings/Mavlink.SettingsGroup.json +++ b/src/Settings/Mavlink.SettingsGroup.json @@ -91,6 +91,17 @@ "default": false, "label": "Skip param/plan download if flying on connect", "keywords": "initial download" + }, + { + "name": "onboardLogTransport", + "shortDesc": "Transport used to download onboard logs from the vehicle.", + "longDesc": "Auto picks MAVLink FTP when the vehicle advertises that capability and the LOG protocol otherwise. Force a specific transport here when capability detection is unreliable.", + "type": "uint32", + "enumStrings": "Auto,LOG protocol,MAVLink FTP", + "enumValues": "0,1,2", + "default": 0, + "label": "Onboard log transport", + "keywords": "onboard log,download,ftp,log protocol,transport" } ] } diff --git a/src/Settings/MavlinkSettings.cc b/src/Settings/MavlinkSettings.cc index 14cd3dd3e2c..d065891a5ac 100644 --- a/src/Settings/MavlinkSettings.cc +++ b/src/Settings/MavlinkSettings.cc @@ -37,3 +37,4 @@ DECLARE_SETTINGSFACT(MavlinkSettings, forwardMavlinkAPMSupportHostName) DECLARE_SETTINGSFACT(MavlinkSettings, sendGCSHeartbeat) DECLARE_SETTINGSFACT(MavlinkSettings, gcsMavlinkSystemID) DECLARE_SETTINGSFACT(MavlinkSettings, noInitialDownloadWhenFlying) +DECLARE_SETTINGSFACT(MavlinkSettings, onboardLogTransport) diff --git a/src/Settings/MavlinkSettings.h b/src/Settings/MavlinkSettings.h index 28114c82042..046cbab9c1a 100644 --- a/src/Settings/MavlinkSettings.h +++ b/src/Settings/MavlinkSettings.h @@ -28,4 +28,6 @@ class MavlinkSettings : public SettingsGroup // Although this is a global setting it only affects ArduPilot vehicle since PX4 automatically starts the stream from the vehicle side DEFINE_SETTINGFACT(apmStartMavlinkStreams) + + DEFINE_SETTINGFACT(onboardLogTransport) }; diff --git a/test/AnalyzeView/OnboardLogDownloadTest.cc b/test/AnalyzeView/OnboardLogDownloadTest.cc index e77fe73ee3e..920a3fc6b41 100644 --- a/test/AnalyzeView/OnboardLogDownloadTest.cc +++ b/test/AnalyzeView/OnboardLogDownloadTest.cc @@ -2,11 +2,11 @@ #include -#include "OnboardLogController.h" -#include "OnboardLogEntry.h" #include "MAVLinkProtocol.h" #include "MultiSignalSpy.h" #include "MultiVehicleManager.h" +#include "OnboardLogController.h" +#include "OnboardLogEntry.h" #include "QmlObjectListModel.h" void OnboardLogDownloadTest::_downloadTest() @@ -18,21 +18,21 @@ void OnboardLogDownloadTest::_downloadTest() controller->refresh(); QVERIFY(multiSpyLogDownloadController->waitForSignal("requestingListChanged", TestTimeout::longMs())); multiSpyLogDownloadController->clearAllSignals(); - if (controller->_getRequestingList()) { + if (controller->requestingList()) { QVERIFY(multiSpyLogDownloadController->waitForSignal("requestingListChanged", TestTimeout::longMs())); - QCOMPARE(controller->_getRequestingList(), false); + QCOMPARE(controller->requestingList(), false); } multiSpyLogDownloadController->clearAllSignals(); - QmlObjectListModel* const model = controller->_getModel(); + QmlObjectListModel* const model = controller->model(); QVERIFY(model); - model->value(0)->setSelected(true); + model->value(0)->setSelected(true); const QString downloadTo = QDir::currentPath(); controller->download(downloadTo); QVERIFY(multiSpyLogDownloadController->waitForSignal("downloadingLogsChanged", TestTimeout::longMs())); multiSpyLogDownloadController->clearAllSignals(); - if (controller->_getDownloadingLogs()) { + if (controller->downloadingLogs()) { QVERIFY(multiSpyLogDownloadController->waitForSignal("downloadingLogsChanged", TestTimeout::longMs())); - QCOMPARE(controller->_getDownloadingLogs(), false); + QCOMPARE(controller->downloadingLogs(), false); } multiSpyLogDownloadController->clearAllSignals(); const QString downloadFile = QDir(downloadTo).filePath("log_0_UnknownDate.ulg");