From cb220d152238ee1931bd943da44083954117865a Mon Sep 17 00:00:00 2001 From: Holden Ramsey Date: Mon, 23 Mar 2026 15:36:02 -0400 Subject: [PATCH] fix(AnalyzeView): Fix onboard log download path and refactor controller Fix duplicate filenames losing download directory prefix, causing logs to land in home directory instead of the selected path. Also: - Add retry limit for data downloads (was infinite) - Fix seek failure silently dropping error status - Ensure download directory exists before writing - Extract MAVLink send boilerplate into helper template - Flatten _logData with early returns, removing nested result flag - Remove dead compression API stubs and unused members - Make header checkbox a select-all toggle - Guard auto-refresh on page load behind vehicle check - Fix error logs to print actual file path, not bare filename - Name retry constants, fix typo, remove unused QML import - Simplify duplicate status string in _updateDataRate - Enable debug logging in OnboardLogEntry ctors/dtors --- .../OnboardLogs/OnboardLogController.cc | 301 +++++++----------- .../OnboardLogs/OnboardLogController.h | 30 +- .../OnboardLogs/OnboardLogEntry.cc | 8 +- .../OnboardLogs/OnboardLogPage.qml | 14 +- 4 files changed, 130 insertions(+), 223 deletions(-) diff --git a/src/AnalyzeView/OnboardLogs/OnboardLogController.cc b/src/AnalyzeView/OnboardLogs/OnboardLogController.cc index 30219b2a09b..3a8c9cf88c3 100644 --- a/src/AnalyzeView/OnboardLogs/OnboardLogController.cc +++ b/src/AnalyzeView/OnboardLogs/OnboardLogController.cc @@ -56,9 +56,9 @@ void OnboardLogController::_downloadToDirectory(const QString &dir) _downloadPath += QDir::separator(); } - QGCOnboardLogEntry *const log = _getNextSelected(); - if (log) { - log->setStatus(tr("Waiting")); + if (!QDir().mkpath(_downloadPath)) { + qCWarning(OnboardLogControllerLog) << "Failed to create download directory:" << _downloadPath; + return; } _setDownloading(true); @@ -101,7 +101,7 @@ void OnboardLogController::_findMissingEntries() return; } - if (_retries++ > 2) { + if (_retries++ > kMaxEntryRetries) { for (int i = 0; i < num_logs; i++) { QGCOnboardLogEntry *const entry = _logEntriesModel->value(i); if (entry && !entry->received()) { @@ -110,7 +110,7 @@ void OnboardLogController::_findMissingEntries() } _receivedAllEntries(); - qCWarning(OnboardLogControllerLog) << "Too many errors retreiving log list. Giving up."; + qCWarning(OnboardLogControllerLog) << "Too many errors retrieving log list. Giving up."; return; } @@ -230,59 +230,53 @@ void OnboardLogController::_logData(uint32_t ofs, uint16_t id, uint8_t count, co 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 (ofs > _downloadData->entry->size()) { + qCWarning(OnboardLogControllerLog) << "Received log offset greater than expected"; + _abortDownload(); + return; + } - if (_downloadData->file.pos() != ofs) { - if (!_downloadData->file.seek(ofs)) { - qCWarning(OnboardLogControllerLog) << "Error while seeking log file offset"; - return; - } - } + const uint32_t chunk = ofs / OnboardLogDownloadData::kChunkSize; + if (chunk != _downloadData->current_chunk) { + qCWarning(OnboardLogControllerLog) << "Ignored packet for out of order chunk actual:expected" << chunk << _downloadData->current_chunk; + 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"; - } + 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 { - qCWarning(OnboardLogControllerLog) << "Received log offset greater than expected"; + _downloadData->chunk_table.setBit(bin); } - if (!result) { - _downloadData->entry->setStatus(tr("Error")); + if ((_downloadData->file.pos() != ofs) && !_downloadData->file.seek(ofs)) { + qCWarning(OnboardLogControllerLog) << "Error while seeking log file offset"; + _abortDownload(); + return; + } + + if (!_downloadData->file.write(reinterpret_cast(data), count)) { + qCWarning(OnboardLogControllerLog) << "Error while writing log file chunk"; + _abortDownload(); + return; + } + + _downloadData->written += count; + _downloadData->rate_bytes += count; + _updateDataRate(); + _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)) { + _findMissingData(); } } @@ -297,7 +291,11 @@ void OnboardLogController::_findMissingData() _downloadData->advanceChunk(); } - _retries++; + if (_retries++ > kMaxDataRetries) { + qCWarning(OnboardLogControllerLog) << "Too many errors downloading log data. Giving up."; + _abortDownload(); + return; + } _updateDataRate(); @@ -330,23 +328,15 @@ void OnboardLogController::_updateDataRate() 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(qgcApp()->bigSizeToString(_downloadData->written), - qgcApp()->bigSizeToString(_downloadData->rate_avg)); _downloadData->elapsed.start(); - } else { - // Update size only, keep previous rate - status = QStringLiteral("%1 (%2/s)").arg(qgcApp()->bigSizeToString(_downloadData->written), - qgcApp()->bigSizeToString(_downloadData->rate_avg)); } - _downloadData->entry->setStatus(status); + _downloadData->entry->setStatus(QStringLiteral("%1 (%2/s)").arg(qgcApp()->bigSizeToString(_downloadData->written), + qgcApp()->bigSizeToString(_downloadData->rate_avg))); _downloadData->last_status_written = _downloadData->written; } @@ -360,6 +350,25 @@ bool OnboardLogController::_logComplete() const return (_chunkComplete() && ((_downloadData->current_chunk + 1) == _downloadData->numChunks())); } +void OnboardLogController::_abortDownload() +{ + _timer->stop(); + + if (_downloadData) { + _downloadData->entry->setStatus(tr("Error")); + if (_downloadData->file.isOpen()) { + _downloadData->file.close(); + } + if (_downloadData->file.exists()) { + (void) _downloadData->file.remove(); + } + _downloadData.reset(); + } + + _resetSelection(true); + _setDownloading(false); +} + void OnboardLogController::_receivedAllData() { _timer->stop(); @@ -415,9 +424,9 @@ bool OnboardLogController::_prepareLogDownload() bool result = false; if (!_downloadData->file.open(QIODevice::WriteOnly)) { - qCWarning(OnboardLogControllerLog) << "Failed to create log file:" << _downloadData->filename; + qCWarning(OnboardLogControllerLog) << "Failed to create log file:" << _downloadData->file.fileName(); } else if (!_downloadData->file.resize(entry->size())) { - qCWarning(OnboardLogControllerLog) << "Failed to allocate space for log file:" << _downloadData->filename; + qCWarning(OnboardLogControllerLog) << "Failed to allocate space for log file:" << _downloadData->file.fileName(); } else { _downloadData->current_chunk = 0; _downloadData->chunk_table = QBitArray(_downloadData->chunkBins(), false); @@ -498,132 +507,71 @@ void OnboardLogController::_resetSelection(bool canceled) emit selectionChanged(); } -void OnboardLogController::eraseAll() +template +bool OnboardLogController::_sendMavlinkMessage(PackFn packFn) { if (!_vehicle) { qCWarning(OnboardLogControllerLog) << "Vehicle Unavailable"; - return; + return false; } SharedLinkInterfacePtr sharedLink = _vehicle->vehicleLinkManager()->primaryLink().lock(); if (!sharedLink) { qCWarning(OnboardLogControllerLog) << "Link Unavailable"; - return; + return false; } mavlink_message_t msg{}; - (void) mavlink_msg_log_erase_pack_chan( - MAVLinkProtocol::instance()->getSystemId(), - MAVLinkProtocol::getComponentId(), - sharedLink->mavlinkChannel(), - &msg, - _vehicle->id(), - _vehicle->defaultComponentId() - ); + packFn(MAVLinkProtocol::instance()->getSystemId(), + MAVLinkProtocol::getComponentId(), + sharedLink->mavlinkChannel(), + &msg, + _vehicle->id(), + _vehicle->defaultComponentId()); if (!_vehicle->sendMessageOnLinkThreadSafe(sharedLink.get(), msg)) { qCWarning(OnboardLogControllerLog) << "Failed to send"; - return; + return false; } - refresh(); + return true; } -void OnboardLogController::_requestLogList(uint32_t start, uint32_t end) +void OnboardLogController::eraseAll() { - if (!_vehicle) { - qCWarning(OnboardLogControllerLog) << "Vehicle Unavailable"; - return; - } - - SharedLinkInterfacePtr sharedLink = _vehicle->vehicleLinkManager()->primaryLink().lock(); - if (!sharedLink) { - qCWarning(OnboardLogControllerLog) << "Link Unavailable"; - return; + if (_sendMavlinkMessage([](uint8_t sysid, uint8_t compid, uint8_t chan, mavlink_message_t *msg, uint8_t tgt_sys, uint8_t tgt_comp) { + (void) mavlink_msg_log_erase_pack_chan(sysid, compid, chan, msg, tgt_sys, tgt_comp); + })) { + refresh(); } +} - 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(OnboardLogControllerLog) << "Failed to send"; - return; +void OnboardLogController::_requestLogList(uint32_t start, uint32_t end) +{ + if (_sendMavlinkMessage([start, end](uint8_t sysid, uint8_t compid, uint8_t chan, mavlink_message_t *msg, uint8_t tgt_sys, uint8_t tgt_comp) { + (void) mavlink_msg_log_request_list_pack_chan(sysid, compid, chan, msg, tgt_sys, tgt_comp, start, end); + })) { + qCDebug(OnboardLogControllerLog) << "Request onboard log entry list (" << start << "through" << end << ")"; + _setListing(true); + _timer->start(kRequestLogListTimeoutMs); } - - qCDebug(OnboardLogControllerLog) << "Request onboard log entry list (" << start << "through" << end << ")"; - _setListing(true); - _timer->start(kRequestLogListTimeoutMs); } void OnboardLogController::_requestLogData(uint16_t id, uint32_t offset, uint32_t count, int retryCount) { - if (!_vehicle) { - qCWarning(OnboardLogControllerLog) << "Vehicle Unavailable"; - return; - } - - SharedLinkInterfacePtr sharedLink = _vehicle->vehicleLinkManager()->primaryLink().lock(); - if (!sharedLink) { - qCWarning(OnboardLogControllerLog) << "Link Unavailable"; - return; - } - - 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 - ); + const uint16_t mavId = id + _apmOffset; + qCDebug(OnboardLogControllerLog) << "Request log data (id:" << mavId << "offset:" << offset << "size:" << count << "retryCount" << retryCount << ")"; - if (!_vehicle->sendMessageOnLinkThreadSafe(sharedLink.get(), msg)) { - qCWarning(OnboardLogControllerLog) << "Failed to send"; - } + _sendMavlinkMessage([mavId, offset, count](uint8_t sysid, uint8_t compid, uint8_t chan, mavlink_message_t *msg, uint8_t tgt_sys, uint8_t tgt_comp) { + (void) mavlink_msg_log_request_data_pack_chan(sysid, compid, chan, msg, tgt_sys, tgt_comp, mavId, offset, count); + }); } void OnboardLogController::_requestLogEnd() { - 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_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"; - } + _sendMavlinkMessage([](uint8_t sysid, uint8_t compid, uint8_t chan, mavlink_message_t *msg, uint8_t tgt_sys, uint8_t tgt_comp) { + (void) mavlink_msg_log_request_end_pack_chan(sysid, compid, chan, msg, tgt_sys, tgt_comp); + }); } void OnboardLogController::_setDownloading(bool active) @@ -644,34 +592,3 @@ void OnboardLogController::_setListing(bool active) } } -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 -} diff --git a/src/AnalyzeView/OnboardLogs/OnboardLogController.h b/src/AnalyzeView/OnboardLogs/OnboardLogController.h index 0bf1cf74dd6..bb8dff1799c 100644 --- a/src/AnalyzeView/OnboardLogs/OnboardLogController.h +++ b/src/AnalyzeView/OnboardLogs/OnboardLogController.h @@ -10,7 +10,6 @@ struct OnboardLogDownloadData; class QGCOnboardLogEntry; class QmlObjectListModel; class QTimer; -class QThread; class Vehicle; class OnboardLogDownloadTest; @@ -24,9 +23,6 @@ class OnboardLogController : public QObject 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; @@ -39,33 +35,16 @@ class OnboardLogController : public QObject 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); - - /// Cancel compression - Q_INVOKABLE void cancelCompression(); - signals: void requestingListChanged(); void downloadingLogsChanged(); void selectionChanged(); - 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: QmlObjectListModel *_getModel() const { return _logEntriesModel; } @@ -79,6 +58,7 @@ private slots: void _downloadToDirectory(const QString &dir); void _findMissingData(); void _findMissingEntries(); + void _abortDownload(); void _receivedAllData(); void _receivedAllEntries(); void _requestLogData(uint16_t id, uint32_t offset, uint32_t count, int retryCount = 0); @@ -91,6 +71,9 @@ private slots: QGCOnboardLogEntry *_getNextSelected() const; + template + bool _sendMavlinkMessage(PackFn packFn); + QTimer *_timer = nullptr; QmlObjectListModel *_logEntriesModel = nullptr; @@ -101,11 +84,10 @@ private slots: 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; + static constexpr int kMaxEntryRetries = 2; + static constexpr int kMaxDataRetries = 5; }; diff --git a/src/AnalyzeView/OnboardLogs/OnboardLogEntry.cc b/src/AnalyzeView/OnboardLogs/OnboardLogEntry.cc index e5125030dbb..8af19c88002 100644 --- a/src/AnalyzeView/OnboardLogs/OnboardLogEntry.cc +++ b/src/AnalyzeView/OnboardLogs/OnboardLogEntry.cc @@ -10,12 +10,12 @@ OnboardLogDownloadData::OnboardLogDownloadData(QGCOnboardLogEntry * const logEnt : ID(logEntry->id()) , entry(logEntry) { - // qCDebug(OnboardLogEntryLog) << Q_FUNC_INFO << this; + qCDebug(OnboardLogEntryLog) << this; } OnboardLogDownloadData::~OnboardLogDownloadData() { - // qCDebug(OnboardLogEntryLog) << Q_FUNC_INFO << this; + qCDebug(OnboardLogEntryLog) << this; } void OnboardLogDownloadData::advanceChunk() @@ -50,12 +50,12 @@ QGCOnboardLogEntry::QGCOnboardLogEntry(uint logId, const QDateTime &dateTime, ui , _logTimeUTC(dateTime) , _received(received) { - // qCDebug(OnboardLogEntryLog) << Q_FUNC_INFO << this; + qCDebug(OnboardLogEntryLog) << this; } QGCOnboardLogEntry::~QGCOnboardLogEntry() { - // qCDebug(OnboardLogEntryLog) << Q_FUNC_INFO << this; + qCDebug(OnboardLogEntryLog) << this; } QString QGCOnboardLogEntry::sizeStr() const diff --git a/src/AnalyzeView/OnboardLogs/OnboardLogPage.qml b/src/AnalyzeView/OnboardLogs/OnboardLogPage.qml index 7f253f0ff15..4bb552c2014 100644 --- a/src/AnalyzeView/OnboardLogs/OnboardLogPage.qml +++ b/src/AnalyzeView/OnboardLogs/OnboardLogPage.qml @@ -1,7 +1,6 @@ import QtQuick import QtQuick.Controls import QtQuick.Layouts -import Qt.labs.qmlmodels import QGroundControl import QGroundControl.Controls @@ -18,7 +17,11 @@ AnalyzePage { width: availableWidth height: availableHeight - Component.onCompleted: OnboardLogController.refresh() + Component.onCompleted: { + if (QGroundControl.multiVehicleManager.activeVehicle && !QGroundControl.multiVehicleManager.activeVehicle.isOfflineEditingVehicle) { + OnboardLogController.refresh() + } + } QGCFlickable { Layout.fillWidth: true @@ -36,7 +39,12 @@ AnalyzePage { QGCCheckBox { id: headerCheckBox - enabled: false + enabled: OnboardLogController.model.count > 0 + onClicked: { + for (var i = 0; i < OnboardLogController.model.count; i++) { + OnboardLogController.model.get(i).selected = checked + } + } } Repeater {