diff --git a/src/AnalyzeView/CMakeLists.txt b/src/AnalyzeView/CMakeLists.txt index 88e0c3de644..1ae235a95d0 100644 --- a/src/AnalyzeView/CMakeLists.txt +++ b/src/AnalyzeView/CMakeLists.txt @@ -1,4 +1,4 @@ -find_package(Qt6 REQUIRED COMPONENTS Core Charts Gui Qml QmlIntegration) +find_package(Qt6 REQUIRED COMPONENTS Concurrent Core Charts Gui Qml QmlIntegration) qt_add_library(AnalyzeView STATIC GeoTagController.cc @@ -27,6 +27,7 @@ qt_add_library(AnalyzeView STATIC target_link_libraries(AnalyzeView PRIVATE + Qt6::Concurrent Qt6::Charts Qt6::Gui Qt6::Qml diff --git a/src/AnalyzeView/LogDownloadController.cc b/src/AnalyzeView/LogDownloadController.cc index 1070cffd449..ea6359919c1 100644 --- a/src/AnalyzeView/LogDownloadController.cc +++ b/src/AnalyzeView/LogDownloadController.cc @@ -8,92 +8,174 @@ ****************************************************************************/ #include "LogDownloadController.h" +#include "LogEntry.h" +#include "MAVLinkProtocol.h" #include "MultiVehicleManager.h" +#include "ParameterManager.h" #include "QGCApplication.h" +#include "QGCLoggingCategory.h" #include "QGCToolbox.h" -#include "ParameterManager.h" -#include "Vehicle.h" +#include "QmlObjectListModel.h" #include "SettingsManager.h" -#include "MAVLinkProtocol.h" -#include "LogEntry.h" -#include "QGCLoggingCategory.h" +#include "Vehicle.h" + +#include + +QGC_LOGGING_CATEGORY(LogDownloadControllerLog, "test.analyzeview.logdownloadcontroller") -#define kTimeOutMilliseconds 500 -#define kGUIRateMilliseconds 17 -#define kTableBins 512 -#define kChunkSize (kTableBins * MAVLINK_MSG_LOG_DATA_FIELD_DATA_LEN) - -QGC_LOGGING_CATEGORY(LogDownloadControllerLog, "qgc.analyzeview.logdownloadcontroller") - -//---------------------------------------------------------------------------------------- -LogDownloadController::LogDownloadController(void) - : _downloadData(nullptr) - , _vehicle(nullptr) - , _requestingLogEntries(false) - , _downloadingLogs(false) - , _retries(0) - , _apmOneBased(0) +LogDownloadController::LogDownloadController(QObject *parent) + : QObject(parent) + , _timer(new QTimer(this)) + , _logEntriesModel(new QmlObjectListModel(this)) { - MultiVehicleManager *manager = qgcApp()->toolbox()->multiVehicleManager(); - connect(manager, &MultiVehicleManager::activeVehicleChanged, this, &LogDownloadController::_setActiveVehicle); - connect(&_timer, &QTimer::timeout, this, &LogDownloadController::_processDownload); + // qCDebug(LogDownloadControllerLog) << Q_FUNC_INFO << this; + + MultiVehicleManager *const manager = qgcApp()->toolbox()->multiVehicleManager(); + (void) connect(manager, &MultiVehicleManager::activeVehicleChanged, this, &LogDownloadController::_setActiveVehicle); + (void) connect(_timer, &QTimer::timeout, this, &LogDownloadController::_processDownload); + + _timer->setSingleShot(false); + _setActiveVehicle(manager->activeVehicle()); } -//---------------------------------------------------------------------------------------- -void -LogDownloadController::_processDownload() +LogDownloadController::~LogDownloadController() +{ + // qCDebug(LogDownloadControllerLog) << Q_FUNC_INFO << this; +} + +void LogDownloadController::download(const QString &path) +{ + const QString dir = path.isEmpty() ? qgcApp()->toolbox()->settingsManager()->appSettings()->logSavePath() : path; + _downloadToDirectory(dir); +} + +void LogDownloadController::_downloadToDirectory(const QString &dir) +{ + _receivedAllEntries(); + + delete _downloadData; + _downloadData = nullptr; + + _downloadPath = dir; + if (_downloadPath.isEmpty()) { + return; + } + + if (!_downloadPath.endsWith(QDir::separator())) { + _downloadPath += QDir::separator(); + } + + QGCLogEntry *const log = _getNextSelected(); + if (log) { + log->setStatus(tr("Waiting")); + } + + _setDownloading(true); + _receivedAllData(); +} + +void LogDownloadController::_processDownload() { - if(_requestingLogEntries) { + if (_requestingLogEntries) { _findMissingEntries(); - } else if(_downloadingLogs) { + } else if (_downloadingLogs) { _findMissingData(); } } -//---------------------------------------------------------------------------------------- -void -LogDownloadController::_setActiveVehicle(Vehicle* vehicle) +void LogDownloadController::_findMissingEntries() { - if(_vehicle) { - _logEntriesModel.clearAndDeleteContents(); - disconnect(_vehicle, &Vehicle::logEntry, this, &LogDownloadController::_logEntry); - disconnect(_vehicle, &Vehicle::logData, this, &LogDownloadController::_logData); + const int num_logs = _logEntriesModel->count(); + int start = -1; + int end = -1; + for (int i = 0; i < num_logs; i++) { + const QGCLogEntry *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++) { + QGCLogEntry *const entry = _logEntriesModel->value(i); + if (entry && !entry->received()) { + entry->setStatus(tr("Error")); + } + } + + _receivedAllEntries(); + qCWarning(LogDownloadControllerLog) << "Too many errors retreiving log list. Giving up."; + return; + } + + //-- Is it a sequence or just one entry? + if (end < 0) { + end = start; + } + + start += _apmOneBased; + end += _apmOneBased; + + _requestLogList(static_cast(start), static_cast(end)); +} + +void LogDownloadController::_setActiveVehicle(Vehicle *vehicle) +{ + if (_vehicle) { + _logEntriesModel->clearAndDeleteContents(); + (void) disconnect(_vehicle, &Vehicle::logEntry, this, &LogDownloadController::_logEntry); + (void) disconnect(_vehicle, &Vehicle::logData, this, &LogDownloadController::_logData); + } + _vehicle = vehicle; - if(_vehicle) { - connect(_vehicle, &Vehicle::logEntry, this, &LogDownloadController::_logEntry); - connect(_vehicle, &Vehicle::logData, this, &LogDownloadController::_logData); + + if (_vehicle) { + (void) connect(_vehicle, &Vehicle::logEntry, this, &LogDownloadController::_logEntry); + (void) connect(_vehicle, &Vehicle::logData, this, &LogDownloadController::_logData); } } -//---------------------------------------------------------------------------------------- -void -LogDownloadController::_logEntry(uint32_t time_utc, uint32_t size, uint16_t id, uint16_t num_logs, uint16_t /*last_log_num*/) +void LogDownloadController::_logEntry(uint32_t time_utc, uint32_t size, uint16_t id, uint16_t num_logs, uint16_t last_log_num) { - //-- Do we care? - if(!_requestingLogEntries) { + Q_UNUSED(last_log_num); + + if (!_requestingLogEntries) { return; } - //-- If this is the first, pre-fill it - if(!_logEntriesModel.count() && num_logs > 0) { - //-- Is this APM? They send a first entry with bogus ID and only the - // count is valid. From now on, all entries are 1-based. - if(_vehicle->firmwareType() == MAV_AUTOPILOT_ARDUPILOTMEGA) { + + if ((_logEntriesModel->count() == 0) && (num_logs > 0)) { + if (_vehicle->firmwareType() == MAV_AUTOPILOT_ARDUPILOTMEGA) { + // APM ID starts at 1 _apmOneBased = 1; } - for(int i = 0; i < num_logs; i++) { - QGCLogEntry *entry = new QGCLogEntry(i); - _logEntriesModel.append(entry); + + for (int i = 0; i < num_logs; i++) { + QGCLogEntry *const entry = new QGCLogEntry(i); + _logEntriesModel->append(entry); } } - //-- Update this log record - if(num_logs > 0) { - //-- Skip if empty (APM first packet) - if(size || _vehicle->firmwareType() != MAV_AUTOPILOT_ARDUPILOTMEGA) { + + if (num_logs > 0) { + if ((size > 0) || (_vehicle->firmwareType() != MAV_AUTOPILOT_ARDUPILOTMEGA)) { id -= _apmOneBased; - if(id < _logEntriesModel.count()) { - QGCLogEntry* entry = _logEntriesModel.value(id); + if (id < _logEntriesModel->count()) { + QGCLogEntry *const entry = _logEntriesModel->value(id); entry->setSize(size); entry->setTime(QDateTime::fromSecsSinceEpoch(time_utc)); entry->setReceived(true); @@ -103,143 +185,49 @@ LogDownloadController::_logEntry(uint32_t time_utc, uint32_t size, uint16_t id, } } } else { - //-- No logs to list _receivedAllEntries(); } - //-- Reset retry count + _retries = 0; - //-- Do we have it all? - if(_entriesComplete()) { + + if (_entriesComplete()) { _receivedAllEntries(); } else { - //-- Reset timer - _timer.start(kTimeOutMilliseconds); - } -} - -//---------------------------------------------------------------------------------------- -bool -LogDownloadController::_entriesComplete() -{ - //-- Iterate entries and look for a gap - int num_logs = _logEntriesModel.count(); - for(int i = 0; i < num_logs; i++) { - QGCLogEntry* entry = _logEntriesModel.value(i); - if(entry) { - if(!entry->received()) { - return false; - } - } + _timer->start(kTimeOutMilliseconds); } - return true; } -//---------------------------------------------------------------------------------------- -void -LogDownloadController::_resetSelection(bool canceled) +void LogDownloadController::_receivedAllEntries() { - int num_logs = _logEntriesModel.count(); - for(int i = 0; i < num_logs; i++) { - QGCLogEntry* entry = _logEntriesModel.value(i); - if(entry) { - if(entry->selected()) { - if(canceled) { - entry->setStatus(tr("Canceled")); - } - entry->setSelected(false); - } - } - } - emit selectionChanged(); -} - -//---------------------------------------------------------------------------------------- -void -LogDownloadController::_receivedAllEntries() -{ - _timer.stop(); + _timer->stop(); _setListing(false); } -//---------------------------------------------------------------------------------------- -void -LogDownloadController::_findMissingEntries() +bool LogDownloadController::_entriesComplete() const { - int start = -1; - int end = -1; - int num_logs = _logEntriesModel.count(); - //-- Iterate entries and look for a gap - for(int i = 0; i < num_logs; i++) { - QGCLogEntry* entry = _logEntriesModel.value(i); - if(entry) { - if(!entry->received()) { - if(start < 0) - start = i; - else - end = i; - } else { - if(start >= 0) { - break; - } - } + const int num_logs = _logEntriesModel->count(); + for (int i = 0; i < num_logs; i++) { + const QGCLogEntry *const entry = _logEntriesModel->value(i); + if (!entry) { + continue; } - } - //-- Is there something missing? - if(start >= 0) { - //-- Have we tried too many times? - if(_retries++ > 2) { - for(int i = 0; i < num_logs; i++) { - QGCLogEntry* entry = _logEntriesModel.value(i); - if(entry && !entry->received()) { - entry->setStatus(tr("Error")); - } - } - //-- Give up - _receivedAllEntries(); - qCWarning(LogDownloadControllerLog) << "Too many errors retreiving log list. Giving up."; - return; - } - //-- Is it a sequence or just one entry? - if(end < 0) { - end = start; + + if (!entry->received()) { + return false; } - //-- APM "Fix" - start += _apmOneBased; - end += _apmOneBased; - //-- Request these entries again - _requestLogList((uint32_t)start, (uint32_t) end); - } else { - _receivedAllEntries(); } -} - -void LogDownloadController::_updateDataRate(void) -{ - if (_downloadData->elapsed.elapsed() >= kGUIRateMilliseconds) { - //-- Update download rate - qreal rrate = _downloadData->rate_bytes / (_downloadData->elapsed.elapsed() / 1000.0); - _downloadData->rate_avg = (_downloadData->rate_avg * 0.95) + (rrate * 0.05); - _downloadData->rate_bytes = 0; - - //-- Update status - const QString status = QString("%1 (%2/s)").arg(qgcApp()->bigSizeToString(_downloadData->written), - qgcApp()->bigSizeToString(_downloadData->rate_avg)); - _downloadData->entry->setStatus(status); - _downloadData->elapsed.start(); - } + return true; } -//---------------------------------------------------------------------------------------- -void -LogDownloadController::_logData(uint32_t ofs, uint16_t id, uint8_t count, const uint8_t* data) +void LogDownloadController::_logData(uint32_t ofs, uint16_t id, uint8_t count, const uint8_t* data) { - if(!_downloadData) { + if (!_downloadData) { return; } - //-- APM "Fix" + id -= _apmOneBased; - if(_downloadData->ID != id) { + if (_downloadData->ID != id) { qCWarning(LogDownloadControllerLog) << "Received log data for wrong log"; return; } @@ -250,47 +238,45 @@ LogDownloadController::_logData(uint32_t ofs, uint16_t id, uint8_t count, const } bool result = false; - uint32_t timeout_time = kTimeOutMilliseconds; - if(ofs <= _downloadData->entry->size()) { - const uint32_t chunk = ofs / kChunkSize; + if (ofs <= _downloadData->entry->size()) { + const uint32_t chunk = ofs / LogDownloadData::kChunkSize; if (chunk != _downloadData->current_chunk) { qCWarning(LogDownloadControllerLog) << "Ignored packet for out of order chunk actual:expected" << chunk << _downloadData->current_chunk; return; } - const uint16_t bin = (ofs - chunk*kChunkSize) / MAVLINK_MSG_LOG_DATA_FIELD_DATA_LEN; + + const uint16_t bin = (ofs - (chunk * LogDownloadData::kChunkSize)) / MAVLINK_MSG_LOG_DATA_FIELD_DATA_LEN; if (bin >= _downloadData->chunk_table.size()) { qCWarning(LogDownloadControllerLog) << "Out of range bin received"; - } else + } else { _downloadData->chunk_table.setBit(bin); + } + if (_downloadData->file.pos() != ofs) { - // Seek to correct position if (!_downloadData->file.seek(ofs)) { qCWarning(LogDownloadControllerLog) << "Error while seeking log file offset"; return; } } - //-- Write chunk to file - if(_downloadData->file.write((const char*)data, count)) { + if (_downloadData->file.write(reinterpret_cast(data), count)) { _downloadData->written += count; _downloadData->rate_bytes += count; _updateDataRate(); + result = true; - //-- reset retries _retries = 0; - //-- Reset timer - _timer.start(timeout_time); - //-- Do we have it all? - if(_logComplete()) { + + _timer->start(kTimeOutMilliseconds); + if (_logComplete()) { _downloadData->entry->setStatus(tr("Downloaded")); - //-- Check for more _receivedAllData(); } else if (_chunkComplete()) { _downloadData->advanceChunk(); _requestLogData(_downloadData->ID, - _downloadData->current_chunk*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)) { + _downloadData->current_chunk * LogDownloadData::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(); } @@ -300,65 +286,24 @@ LogDownloadController::_logData(uint32_t ofs, uint16_t id, uint8_t count, const } else { qCWarning(LogDownloadControllerLog) << "Received log offset greater than expected"; } - if(!result) { + + if (!result) { _downloadData->entry->setStatus(tr("Error")); } } - -//---------------------------------------------------------------------------------------- -bool -LogDownloadController::_chunkComplete() const +void LogDownloadController::_findMissingData() { - return _downloadData->chunkEquals(true); -} - -//---------------------------------------------------------------------------------------- -bool -LogDownloadController::_logComplete() const -{ - return _chunkComplete() && (_downloadData->current_chunk+1) == _downloadData->numChunks(); -} - -//---------------------------------------------------------------------------------------- -void -LogDownloadController::_receivedAllData() -{ - _timer.stop(); - //-- Anything queued up for download? - if(_prepareLogDownload()) { - //-- Request Log - _requestLogData(_downloadData->ID, 0, _downloadData->chunk_table.size()*MAVLINK_MSG_LOG_DATA_FIELD_DATA_LEN); - _timer.start(kTimeOutMilliseconds); - } else { - _resetSelection(); - _setDownloading(false); + if (_logComplete()) { + _receivedAllData(); + return; } -} -//---------------------------------------------------------------------------------------- -void -LogDownloadController::_findMissingData() -{ - if (_logComplete()) { - _receivedAllData(); - return; - } else if (_chunkComplete()) { + if (_chunkComplete()) { _downloadData->advanceChunk(); } _retries++; -#if 0 - // Trying the change to infinite log download. This way if retries hit 100% failure the data rate will - // slowly fall to 0 and the user can Cancel. This should work better on really crappy links. - if(_retries > 5) { - _downloadData->entry->setStatus(tr("Timed Out")); - //-- Give up - qCWarning(LogDownloadControllerLog) << "Too many errors retreiving log data. Giving up."; - _receivedAllData(); - return; - } -#endif _updateDataRate(); @@ -376,153 +321,77 @@ LogDownloadController::_findMissingData() } } - const uint32_t pos = _downloadData->current_chunk*kChunkSize + start*MAVLINK_MSG_LOG_DATA_FIELD_DATA_LEN, - len = (end - start)*MAVLINK_MSG_LOG_DATA_FIELD_DATA_LEN; + const uint32_t pos = (_downloadData->current_chunk * LogDownloadData::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 -LogDownloadController::_requestLogData(uint16_t id, uint32_t offset, uint32_t count, int retryCount) +void LogDownloadController::_updateDataRate() { - if (_vehicle) { - SharedLinkInterfacePtr sharedLink = _vehicle->vehicleLinkManager()->primaryLink().lock(); - if (sharedLink) { - - //-- APM "Fix" - id += _apmOneBased; - qCDebug(LogDownloadControllerLog) << "Request log data (id:" << id << "offset:" << offset << "size:" << count << "retryCount" << retryCount << ")"; - mavlink_message_t msg; - mavlink_msg_log_request_data_pack_chan( - qgcApp()->toolbox()->mavlinkProtocol()->getSystemId(), - qgcApp()->toolbox()->mavlinkProtocol()->getComponentId(), - sharedLink->mavlinkChannel(), - &msg, - _vehicle->id(), _vehicle->defaultComponentId(), - id, offset, count); - _vehicle->sendMessageOnLinkThreadSafe(sharedLink.get(), msg); - } + if (_downloadData->elapsed.elapsed() < kGUIRateMilliseconds) { + return; } -} -//---------------------------------------------------------------------------------------- -void -LogDownloadController::refresh(void) -{ - _logEntriesModel.clearAndDeleteContents(); - //-- Get first 50 entries - _requestLogList(0, 49); -} + const qreal rrate = _downloadData->rate_bytes / (_downloadData->elapsed.elapsed() / 1000.0); + _downloadData->rate_avg = (_downloadData->rate_avg * 0.95) + (rrate * 0.05); + _downloadData->rate_bytes = 0; -//---------------------------------------------------------------------------------------- -void -LogDownloadController::_requestLogList(uint32_t start, uint32_t end) -{ - if(_vehicle) { - qCDebug(LogDownloadControllerLog) << "Request log entry list (" << start << "through" << end << ")"; - _setListing(true); - SharedLinkInterfacePtr sharedLink = _vehicle->vehicleLinkManager()->primaryLink().lock(); - if (sharedLink) { - mavlink_message_t msg; - mavlink_msg_log_request_list_pack_chan( - qgcApp()->toolbox()->mavlinkProtocol()->getSystemId(), - qgcApp()->toolbox()->mavlinkProtocol()->getComponentId(), - sharedLink->mavlinkChannel(), - &msg, - _vehicle->id(), - _vehicle->defaultComponentId(), - start, - end); - _vehicle->sendMessageOnLinkThreadSafe(sharedLink.get(), msg); - } - //-- Wait 5 seconds before bitching about not getting anything - _timer.start(5000); - } + const QString status = QStringLiteral("%1 (%2/s)").arg(qgcApp()->bigSizeToString(_downloadData->written), + qgcApp()->bigSizeToString(_downloadData->rate_avg)); + + _downloadData->entry->setStatus(status); + _downloadData->elapsed.start(); } -//---------------------------------------------------------------------------------------- -void -LogDownloadController::download(QString path) +bool LogDownloadController::_chunkComplete() const { - QString dir = path; - if (dir.isEmpty()) { - dir = qgcApp()->toolbox()->settingsManager()->appSettings()->logSavePath(); - } - downloadToDirectory(dir); + return _downloadData->chunkEquals(true); } -void LogDownloadController::downloadToDirectory(const QString& dir) +bool LogDownloadController::_logComplete() const { - //-- Stop listing just in case - _receivedAllEntries(); - //-- Reset downloads, again just in case - delete _downloadData; - _downloadData = nullptr; - - _downloadPath = dir; - if(!_downloadPath.isEmpty()) { - if(!_downloadPath.endsWith(QDir::separator())) - _downloadPath += QDir::separator(); - //-- Iterate selected entries and shown them as waiting - int num_logs = _logEntriesModel.count(); - for(int i = 0; i < num_logs; i++) { - QGCLogEntry* entry = _logEntriesModel.value(i); - if(entry) { - if(entry->selected()) { - entry->setStatus(tr("Waiting")); - } - } - } - //-- Start download process - _setDownloading(true); - _receivedAllData(); - } + return (_chunkComplete() && ((_downloadData->current_chunk + 1) == _downloadData->numChunks())); } -//---------------------------------------------------------------------------------------- -QGCLogEntry* -LogDownloadController::_getNextSelected() +void LogDownloadController::_receivedAllData() { - //-- Iterate entries and look for a selected file - int num_logs = _logEntriesModel.count(); - for(int i = 0; i < num_logs; i++) { - QGCLogEntry* entry = _logEntriesModel.value(i); - if(entry) { - if(entry->selected()) { - return entry; - } - } + _timer->stop(); + if (_prepareLogDownload()) { + _requestLogData(_downloadData->ID, 0, _downloadData->chunk_table.size() * MAVLINK_MSG_LOG_DATA_FIELD_DATA_LEN); + _timer->start(kTimeOutMilliseconds); + } else { + _resetSelection(); + _setDownloading(false); } - return nullptr; } -//---------------------------------------------------------------------------------------- -bool -LogDownloadController::_prepareLogDownload() +bool LogDownloadController::_prepareLogDownload() { delete _downloadData; _downloadData = nullptr; - QGCLogEntry* entry = _getNextSelected(); - if(!entry) { + QGCLogEntry *const entry = _getNextSelected(); + if (!entry) { return false; } - //-- Deselect file + entry->setSelected(false); emit selectionChanged(); - bool result = false; + QString ftime; - if(entry->time().date().year() < 2010) { - ftime = tr("UnknownDate"); + if (entry->time().date().year() < 2010) { + ftime = QStringLiteral("UnknownDate"); } else { ftime = entry->time().toString(QStringLiteral("yyyy-M-d-hh-mm-ss")); } + _downloadData = new LogDownloadData(entry); - _downloadData->filename = QString("log_") + QString::number(entry->id()) + "_" + ftime; + _downloadData->filename = QStringLiteral("log_") + QString::number(entry->id()) + "_" + ftime; + if (_vehicle->firmwareType() == MAV_AUTOPILOT_PX4) { - QString loggerParam = QStringLiteral("SYS_LOGGER"); - if (_vehicle->parameterManager()->parameterExists(ParameterManager::defaultComponentId, loggerParam) && - _vehicle->parameterManager()->getParameter(ParameterManager::defaultComponentId, loggerParam)->rawValue().toInt() == 0) { + 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"; @@ -530,96 +399,250 @@ LogDownloadController::_prepareLogDownload() } else { _downloadData->filename += ".bin"; } + _downloadData->file.setFileName(_downloadPath + _downloadData->filename); - //-- Append a number to the end if the filename already exists - if (_downloadData->file.exists()){ - uint num_dups = 0; - QStringList filename_spl = _downloadData->filename.split('.'); + + if (_downloadData->file.exists()) { + uint32_t numDups = 0; + const QStringList filename_spl = _downloadData->filename.split('.'); do { - num_dups +=1; - _downloadData->file.setFileName(filename_spl[0] + '_' + QString::number(num_dups) + '.' + filename_spl[1]); + numDups +=1; + _downloadData->file.setFileName(filename_spl[0] + '_' + QString::number(numDups) + '.' + filename_spl[1]); } while( _downloadData->file.exists()); } - //-- Create file + + bool result = false; if (!_downloadData->file.open(QIODevice::WriteOnly)) { qCWarning(LogDownloadControllerLog) << "Failed to create log file:" << _downloadData->filename; + } else if (!_downloadData->file.resize(entry->size())) { + qCWarning(LogDownloadControllerLog) << "Failed to allocate space for log file:" << _downloadData->filename; } else { - //-- Preallocate file - if(!_downloadData->file.resize(entry->size())) { - qCWarning(LogDownloadControllerLog) << "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; - } + _downloadData->current_chunk = 0; + _downloadData->chunk_table = QBitArray(_downloadData->chunkBins(), false); + _downloadData->elapsed.start(); + result = true; } - if(!result) { + + if (!result) { if (_downloadData->file.exists()) { - _downloadData->file.remove(); + (void) _downloadData->file.remove(); } - _downloadData->entry->setStatus(tr("Error")); + + _downloadData->entry->setStatus(QStringLiteral("Error")); + delete _downloadData; _downloadData = nullptr; } + return result; } -//---------------------------------------------------------------------------------------- -void -LogDownloadController::_setDownloading(bool active) +void LogDownloadController::refresh() { - if (_downloadingLogs != active) { - _downloadingLogs = active; - _vehicle->vehicleLinkManager()->setCommunicationLostEnabled(!active); - emit downloadingLogsChanged(); - } + _logEntriesModel->clearAndDeleteContents(); + _requestLogList(0, 49); } -//---------------------------------------------------------------------------------------- -void -LogDownloadController::_setListing(bool active) +QGCLogEntry *LogDownloadController::_getNextSelected() const { - if (_requestingLogEntries != active) { - _requestingLogEntries = active; - _vehicle->vehicleLinkManager()->setCommunicationLostEnabled(!active); - emit requestingListChanged(); - } -} + const int numLogs = _logEntriesModel->count(); + for (int i = 0; i < numLogs; i++) { + QGCLogEntry *const entry = _logEntriesModel->value(i); + if (!entry) { + continue; + } -//---------------------------------------------------------------------------------------- -void -LogDownloadController::eraseAll(void) -{ - if(_vehicle) { - SharedLinkInterfacePtr sharedLink = _vehicle->vehicleLinkManager()->primaryLink().lock(); - if (sharedLink) { - mavlink_message_t msg; - mavlink_msg_log_erase_pack_chan( - qgcApp()->toolbox()->mavlinkProtocol()->getSystemId(), - qgcApp()->toolbox()->mavlinkProtocol()->getComponentId(), - sharedLink->mavlinkChannel(), - &msg, - qgcApp()->toolbox()->multiVehicleManager()->activeVehicle()->id(), qgcApp()->toolbox()->multiVehicleManager()->activeVehicle()->defaultComponentId()); - _vehicle->sendMessageOnLinkThreadSafe(sharedLink.get(), msg); + if (entry->selected()) { + return entry; } - refresh(); } + + return nullptr; } -//---------------------------------------------------------------------------------------- -void -LogDownloadController::cancel(void) +void LogDownloadController::cancel() { + _requestLogEnd(); _receivedAllEntries(); - if(_downloadData) { - _downloadData->entry->setStatus(tr("Canceled")); + + if (_downloadData) { + _downloadData->entry->setStatus(QStringLiteral("Canceled")); if (_downloadData->file.exists()) { _downloadData->file.remove(); } + delete _downloadData; - _downloadData = 0; + _downloadData = nullptr; } + _resetSelection(true); _setDownloading(false); } + +void LogDownloadController::_resetSelection(bool canceled) +{ + const int num_logs = _logEntriesModel->count(); + for (int i = 0; i < num_logs; i++) { + QGCLogEntry *const entry = _logEntriesModel->value(i); + if (!entry) { + continue; + } + + if (entry->selected()) { + if (canceled) { + entry->setStatus(tr("Canceled")); + } + entry->setSelected(false); + } + } + + emit selectionChanged(); +} + +void LogDownloadController::eraseAll() +{ + if (!_vehicle) { + qCWarning(LogDownloadControllerLog) << "Vehicle Unavailable"; + return; + } + + SharedLinkInterfacePtr sharedLink = _vehicle->vehicleLinkManager()->primaryLink().lock(); + if (!sharedLink) { + qCWarning(LogDownloadControllerLog) << "Link Unavailable"; + return; + } + + const MAVLinkProtocol *const mavlinkProtocol = qgcApp()->toolbox()->mavlinkProtocol(); + mavlink_message_t msg; + (void) mavlink_msg_log_erase_pack_chan( + mavlinkProtocol->getSystemId(), + mavlinkProtocol->getComponentId(), + sharedLink->mavlinkChannel(), + &msg, + _vehicle->id(), + _vehicle->defaultComponentId() + ); + + if (_vehicle->sendMessageOnLinkThreadSafe(sharedLink.get(), msg)) { + refresh(); + } else { + qCWarning(LogDownloadControllerLog) << "Failed to send"; + } +} + +void LogDownloadController::_requestLogList(uint32_t start, uint32_t end) +{ + if (!_vehicle) { + qCWarning(LogDownloadControllerLog) << "Vehicle Unavailable"; + return; + } + + SharedLinkInterfacePtr sharedLink = _vehicle->vehicleLinkManager()->primaryLink().lock(); + if (!sharedLink) { + qCWarning(LogDownloadControllerLog) << "Link Unavailable"; + return; + } + + const MAVLinkProtocol* const mavlinkProtocol = qgcApp()->toolbox()->mavlinkProtocol(); + mavlink_message_t msg{}; + (void) mavlink_msg_log_request_list_pack_chan( + mavlinkProtocol->getSystemId(), + mavlinkProtocol->getComponentId(), + sharedLink->mavlinkChannel(), + &msg, + _vehicle->id(), + _vehicle->defaultComponentId(), + start, + end + ); + + if (_vehicle->sendMessageOnLinkThreadSafe(sharedLink.get(), msg)) { + qCDebug(LogDownloadControllerLog) << "Request log entry list (" << start << "through" << end << ")"; + _setListing(true); + _timer->start(5000); + } else { + qCWarning(LogDownloadControllerLog) << "Failed to send"; + } +} + +void LogDownloadController::_requestLogData(uint16_t id, uint32_t offset, uint32_t count, int retryCount) +{ + if (!_vehicle) { + qCWarning(LogDownloadControllerLog) << "Vehicle Unavailable"; + return; + } + + SharedLinkInterfacePtr sharedLink = _vehicle->vehicleLinkManager()->primaryLink().lock(); + if (!sharedLink) { + qCWarning(LogDownloadControllerLog) << "Link Unavailable"; + return; + } + + id += _apmOneBased; + qCDebug(LogDownloadControllerLog) << "Request log data (id:" << id << "offset:" << offset << "size:" << count << "retryCount" << retryCount << ")"; + + const MAVLinkProtocol* const mavlinkProtocol = qgcApp()->toolbox()->mavlinkProtocol(); + mavlink_message_t msg{}; + (void) mavlink_msg_log_request_data_pack_chan( + mavlinkProtocol->getSystemId(), + mavlinkProtocol->getComponentId(), + sharedLink->mavlinkChannel(), + &msg, + _vehicle->id(), + _vehicle->defaultComponentId(), + id, + offset, + count + ); + + if (!_vehicle->sendMessageOnLinkThreadSafe(sharedLink.get(), msg)) { + qCWarning(LogDownloadControllerLog) << "Failed to send"; + } +} + +void LogDownloadController::_requestLogEnd() +{ + if (!_vehicle) { + qCWarning(LogDownloadControllerLog) << "Vehicle Unavailable"; + return; + } + + SharedLinkInterfacePtr sharedLink = _vehicle->vehicleLinkManager()->primaryLink().lock(); + if (!sharedLink) { + qCWarning(LogDownloadControllerLog) << "Link Unavailable"; + return; + } + + const MAVLinkProtocol* const mavlinkProtocol = qgcApp()->toolbox()->mavlinkProtocol(); + mavlink_message_t msg{}; + (void) mavlink_msg_log_request_end_pack_chan( + mavlinkProtocol->getSystemId(), + mavlinkProtocol->getComponentId(), + sharedLink->mavlinkChannel(), + &msg, + _vehicle->id(), + _vehicle->defaultComponentId() + ); + + if (!_vehicle->sendMessageOnLinkThreadSafe(sharedLink.get(), msg)) { + qCWarning(LogDownloadControllerLog) << "Failed to send"; + } +} + +void LogDownloadController::_setDownloading(bool active) +{ + if (_downloadingLogs != active) { + _downloadingLogs = active; + _vehicle->vehicleLinkManager()->setCommunicationLostEnabled(!active); + emit downloadingLogsChanged(); + } +} + +void LogDownloadController::_setListing(bool active) +{ + if (_requestingLogEntries != active) { + _requestingLogEntries = active; + _vehicle->vehicleLinkManager()->setCommunicationLostEnabled(!active); + emit requestingListChanged(); + } +} diff --git a/src/AnalyzeView/LogDownloadController.h b/src/AnalyzeView/LogDownloadController.h index 228b036a630..1807419da61 100644 --- a/src/AnalyzeView/LogDownloadController.h +++ b/src/AnalyzeView/LogDownloadController.h @@ -9,81 +9,87 @@ #pragma once -#include -#include #include +#include #include -#include "QmlObjectListModel.h" - Q_DECLARE_LOGGING_CATEGORY(LogDownloadControllerLog) -class Vehicle; -class QGCLogEntry; struct LogDownloadData; +class QGCLogEntry; +class QmlObjectListModel; +class QTimer; +class QThread; +class Vehicle; +class LogDownloadTest; -//----------------------------------------------------------------------------- class LogDownloadController : public QObject { Q_OBJECT QML_ELEMENT Q_MOC_INCLUDE("Vehicle.h") + Q_MOC_INCLUDE("QmlObjectListModel.h") + Q_PROPERTY(QmlObjectListModel *model READ model CONSTANT) + Q_PROPERTY(bool requestingList READ requestingList NOTIFY requestingListChanged) + Q_PROPERTY(bool downloadingLogs READ downloadingLogs NOTIFY downloadingLogsChanged) -public: - LogDownloadController(void); - - Q_PROPERTY(QmlObjectListModel* model READ model NOTIFY modelChanged) - Q_PROPERTY(bool requestingList READ requestingList NOTIFY requestingListChanged) - Q_PROPERTY(bool downloadingLogs READ downloadingLogs NOTIFY downloadingLogsChanged) + friend class LogDownloadTest; - QmlObjectListModel* model () { return &_logEntriesModel; } - bool requestingList () const{ return _requestingLogEntries; } - bool downloadingLogs () const{ return _downloadingLogs; } +public: + explicit LogDownloadController(QObject *parent = nullptr); + ~LogDownloadController(); - Q_INVOKABLE void refresh (); - Q_INVOKABLE void download (QString path = QString()); - Q_INVOKABLE void eraseAll (); - Q_INVOKABLE void cancel (); + QmlObjectListModel *model() const { return _logEntriesModel; } + bool requestingList() const { return _requestingLogEntries; } + bool downloadingLogs() const { return _downloadingLogs; } - void downloadToDirectory(const QString& dir); + Q_INVOKABLE void refresh(); + Q_INVOKABLE void download(const QString &path = QString()); + Q_INVOKABLE void eraseAll(); + Q_INVOKABLE void cancel(); signals: - void requestingListChanged (); - void downloadingLogsChanged (); - void modelChanged (); - void selectionChanged (); + void requestingListChanged(); + void downloadingLogsChanged(); + void selectionChanged(); 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 _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(); private: - bool _entriesComplete (); - bool _chunkComplete () const; - bool _logComplete () const; + 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 _receivedAllData (); - void _resetSelection (bool canceled = false); - void _findMissingData (); - void _requestLogList (uint32_t start, uint32_t end); - void _requestLogData (uint16_t id, uint32_t offset, uint32_t count, int retryCount = 0); - bool _prepareLogDownload(); - void _setDownloading (bool active); - void _setListing (bool active); - void _updateDataRate (); - - QGCLogEntry* _getNextSelected(); - - LogDownloadData* _downloadData; - QTimer _timer; - QmlObjectListModel _logEntriesModel; - Vehicle* _vehicle; - bool _requestingLogEntries; - bool _downloadingLogs; - int _retries; - int _apmOneBased; - QString _downloadPath; + 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(); + + QGCLogEntry *_getNextSelected() const; + + QTimer *_timer = nullptr; + QmlObjectListModel *_logEntriesModel = nullptr; + + bool _downloadingLogs = false; + bool _requestingLogEntries = false; + int _apmOneBased = 0; + int _retries = 0; + LogDownloadData *_downloadData = nullptr; + QString _downloadPath; + Vehicle *_vehicle = nullptr; + + static constexpr uint32_t kTimeOutMilliseconds = 500; + static constexpr uint32_t kGUIRateMilliseconds = 17; }; diff --git a/src/AnalyzeView/LogDownloadPage.qml b/src/AnalyzeView/LogDownloadPage.qml index 97839f7dd0b..c5adfd9451d 100644 --- a/src/AnalyzeView/LogDownloadPage.qml +++ b/src/AnalyzeView/LogDownloadPage.qml @@ -9,49 +9,43 @@ import QtQuick import QtQuick.Controls -import QtQuick.Dialogs import QtQuick.Layouts import Qt.labs.qmlmodels import QGroundControl -import QGroundControl.Palette import QGroundControl.Controls import QGroundControl.Controllers import QGroundControl.ScreenTools AnalyzePage { - id: logDownloadPage - pageComponent: pageComponent - pageDescription: qsTr("Log Download allows you to download binary log files from your vehicle. Click Refresh to get list of available logs.") - - property real _margin: ScreenTools.defaultFontPixelWidth - - QGCPalette { id: qgcPal; colorGroupEnabled: enabled } + id: logDownloadPage + pageComponent: pageComponent + pageDescription: qsTr("Log Download allows you to download binary log files from your vehicle. Click Refresh to get list of available logs.") Component { id: pageComponent RowLayout { - width: availableWidth + width: availableWidth height: availableHeight QGCFlickable { - Layout.fillWidth: true - Layout.fillHeight: true - contentWidth: gridLayout.width - contentHeight: gridLayout.height + Layout.fillWidth: true + Layout.fillHeight: true + contentWidth: gridLayout.width + contentHeight: gridLayout.height GridLayout { - id: gridLayout - rows: logController.model.count + 1 - columns: 5 - flow: GridLayout.TopToBottom - columnSpacing: ScreenTools.defaultFontPixelWidth - rowSpacing: 0 + id: gridLayout + rows: logController.model.count + 1 + columns: 5 + flow: GridLayout.TopToBottom + columnSpacing: ScreenTools.defaultFontPixelWidth + rowSpacing: 0 QGCCheckBox { - id: headerCheckBox - enabled: false + id: headerCheckBox + enabled: false } Repeater { @@ -66,21 +60,15 @@ AnalyzePage { } } - QGCLabel { - text: qsTr("Id") - } + QGCLabel { text: qsTr("Id") } Repeater { model: logController.model - QGCLabel { - text: object.id - } + QGCLabel { text: object.id } } - QGCLabel { - text: qsTr("Date") - } + QGCLabel { text: qsTr("Date") } Repeater { model: logController.model @@ -88,20 +76,16 @@ AnalyzePage { QGCLabel { text: { if (object.received) { - var d = object.time - if (d.getUTCFullYear() < 2010) - return qsTr("Date Unknown") - else - return d.toLocaleString(undefined) + const d = object.time + return (d.getUTCFullYear() < 2010) ? qsTr("Date Unknown") : d.toLocaleString(undefined) } + return "" } } } - QGCLabel { - text: qsTr("Size") - } + QGCLabel { text: qsTr("Size") } Repeater { model: logController.model @@ -109,9 +93,7 @@ AnalyzePage { QGCLabel { text: object.sizeStr } } - QGCLabel { - text: qsTr("Status") - } + QGCLabel { text: qsTr("Status") } Repeater { model: logController.model @@ -122,14 +104,14 @@ AnalyzePage { } ColumnLayout { - spacing: _margin - Layout.alignment: Qt.AlignTop - Layout.fillWidth: false + spacing: ScreenTools.defaultFontPixelWidth + Layout.alignment: Qt.AlignTop + Layout.fillWidth: false QGCButton { - Layout.fillWidth: true - enabled: !logController.requestingList && !logController.downloadingLogs - text: qsTr("Refresh") + Layout.fillWidth: true + enabled: !logController.requestingList && !logController.downloadingLogs + text: qsTr("Refresh") onClicked: { if (!QGroundControl.multiVehicleManager.activeVehicle || QGroundControl.multiVehicleManager.activeVehicle.isOfflineEditingVehicle) { @@ -141,31 +123,31 @@ AnalyzePage { } QGCButton { - Layout.fillWidth: true - enabled: !logController.requestingList && !logController.downloadingLogs - text: qsTr("Download") + Layout.fillWidth: true + enabled: !logController.requestingList && !logController.downloadingLogs + text: qsTr("Download") onClicked: { var logsSelected = false for (var i = 0; i < logController.model.count; i++) { - var o = logController.model.get(i) + const o = logController.model.get(i) if (o.selected) { logsSelected = true break } } + if (!logsSelected) { mainWindow.showMessageDialog(qsTr("Log Download"), qsTr("You must select at least one log file to download.")) return } if (ScreenTools.isMobile) { - // You can't pick folders in mobile, only default location is used logController.download() } else { - fileDialog.title = qsTr("Select save directory") - fileDialog.folder = QGroundControl.settingsManager.appSettings.logSavePath - fileDialog.selectFolder = true + fileDialog.title = qsTr("Select save directory") + fileDialog.folder = QGroundControl.settingsManager.appSettings.logSavePath + fileDialog.selectFolder = true fileDialog.openForLoad() } } @@ -180,20 +162,22 @@ AnalyzePage { } QGCButton { - Layout.fillWidth: true - enabled: !logController.requestingList && !logController.downloadingLogs && logController.model.count > 0 - text: qsTr("Erase All") - onClicked: mainWindow.showMessageDialog(qsTr("Delete All Log Files"), - qsTr("All log files will be erased permanently. Is this really what you want?"), - Dialog.Yes | Dialog.No, - function() { logController.eraseAll() }) + Layout.fillWidth: true + enabled: !logController.requestingList && !logController.downloadingLogs && (logController.model.count > 0) + text: qsTr("Erase All") + onClicked: mainWindow.showMessageDialog( + qsTr("Delete All Log Files"), + qsTr("All log files will be erased permanently. Is this really what you want?"), + Dialog.Yes | Dialog.No, + function() { logController.eraseAll() } + ) } QGCButton { - Layout.fillWidth: true - text: qsTr("Cancel") - enabled: logController.requestingList || logController.downloadingLogs - onClicked: logController.cancel() + Layout.fillWidth: true + text: qsTr("Cancel") + enabled: logController.requestingList || logController.downloadingLogs + onClicked: logController.cancel() } } } diff --git a/src/AnalyzeView/LogEntry.cc b/src/AnalyzeView/LogEntry.cc index 7e76e1cb0db..d910a6b3392 100644 --- a/src/AnalyzeView/LogEntry.cc +++ b/src/AnalyzeView/LogEntry.cc @@ -9,64 +9,62 @@ #include "LogEntry.h" #include "QGCApplication.h" -#include "MAVLinkLib.h" #include "QGCLoggingCategory.h" #include -#define kTableBins 512 -#define kChunkSize (kTableBins * MAVLINK_MSG_LOG_DATA_FIELD_DATA_LEN) - QGC_LOGGING_CATEGORY(LogEntryLog, "qgc.analyzeview.logentry") -//----------------------------------------------------------------------------- -LogDownloadData::LogDownloadData(QGCLogEntry* entry_) - : ID(entry_->id()) - , entry(entry_) - , written(0) - , rate_bytes(0) - , rate_avg(0) +LogDownloadData::LogDownloadData(QGCLogEntry *entry) + : ID(entry->id()) + , entry(entry) { + // qCDebug(LogEntryLog) << Q_FUNC_INFO << this; +} +LogDownloadData::~LogDownloadData() +{ + // qCDebug(LogEntryLog) << Q_FUNC_INFO << this; } void LogDownloadData::advanceChunk() { - current_chunk++; - chunk_table = QBitArray(chunkBins(), false); + current_chunk++; + chunk_table = QBitArray(chunkBins(), false); } -// The number of MAVLINK_MSG_LOG_DATA_FIELD_DATA_LEN bins in the current chunk uint32_t LogDownloadData::chunkBins() const { - return qMin(qCeil((entry->size() - current_chunk*kChunkSize)/static_cast(MAVLINK_MSG_LOG_DATA_FIELD_DATA_LEN)), - kTableBins); + return qMin(static_cast(qCeil(static_cast((entry->size() - (current_chunk * kChunkSize))) / static_cast(MAVLINK_MSG_LOG_DATA_FIELD_DATA_LEN))), kTableBins); } -// The number of kChunkSize chunks in the file uint32_t LogDownloadData::numChunks() const { return qCeil(entry->size() / static_cast(kChunkSize)); } -// True if all bins in the chunk have been set to val bool LogDownloadData::chunkEquals(const bool val) const { - return chunk_table == QBitArray(chunk_table.size(), val); + return (chunk_table == QBitArray(chunk_table.size(), val)); } -//---------------------------------------------------------------------------------------- -QGCLogEntry::QGCLogEntry(uint logId, const QDateTime& dateTime, uint logSize, bool received) - : _logID(logId) +/*===========================================================================*/ + +QGCLogEntry::QGCLogEntry(uint logId, const QDateTime &dateTime, uint logSize, bool received, QObject *parent) + : QObject(parent) + , _logID(logId) , _logSize(logSize) , _logTimeUTC(dateTime) , _received(received) - , _selected(false) { - _status = tr("Pending"); + // qCDebug(LogEntryLog) << Q_FUNC_INFO << this; +} + +QGCLogEntry::~QGCLogEntry() +{ + // qCDebug(LogEntryLog) << Q_FUNC_INFO << this; } -//---------------------------------------------------------------------------------------- QString QGCLogEntry::sizeStr() const { return qgcApp()->bigSizeToString(_logSize); diff --git a/src/AnalyzeView/LogEntry.h b/src/AnalyzeView/LogEntry.h index 34dc46d137f..20bc79146be 100644 --- a/src/AnalyzeView/LogEntry.h +++ b/src/AnalyzeView/LogEntry.h @@ -9,23 +9,60 @@ #pragma once -#include -#include -#include #include +#include #include #include +#include +#include #include +#include "MAVLinkLib.h" + +class QGCLogEntry; + Q_DECLARE_LOGGING_CATEGORY(LogEntryLog) -//----------------------------------------------------------------------------- +struct LogDownloadData +{ + explicit LogDownloadData(QGCLogEntry *entry); + ~LogDownloadData(); + + 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; + QGCLogEntry *entry = nullptr; + + QBitArray chunk_table; + uint32_t current_chunk = 0; + QFile file; + QString filename; + uint written = 0; + size_t rate_bytes = 0; + qreal rate_avg = 0.; + QElapsedTimer elapsed; + + static constexpr uint32_t kTableBins = 512; + static constexpr uint32_t kChunkSize = kTableBins * MAVLINK_MSG_LOG_DATA_FIELD_DATA_LEN; +}; + +/*===========================================================================*/ + class QGCLogEntry : public QObject { Q_OBJECT QML_ELEMENT - Q_PROPERTY(uint id READ id CONSTANT) + 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) @@ -34,56 +71,38 @@ class QGCLogEntry : public QObject Q_PROPERTY(QString status READ status NOTIFY statusChanged) public: - QGCLogEntry(uint logId, const QDateTime& dateTime = QDateTime(), uint logSize = 0, bool received = false); - - 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_) { _logID = id_; } - void setSize (uint size_) { _logSize = size_; emit sizeChanged(); } - void setTime (QDateTime date_) { _logTimeUTC = date_; emit timeChanged(); } - void setReceived (bool rec_) { _received = rec_; emit receivedChanged(); } - void setSelected (bool sel_) { _selected = sel_; emit selectedChanged(); } - void setStatus (QString stat_) { _status = stat_; emit statusChanged(); } + explicit QGCLogEntry(uint logId, const QDateTime &dateTime = QDateTime(), uint logSize = 0, bool received = false, QObject *parent = nullptr); + ~QGCLogEntry(); + + 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(); } } signals: - void idChanged (); - void timeChanged (); - void sizeChanged (); - void receivedChanged (); - void selectedChanged (); - void statusChanged (); + void idChanged(); + void timeChanged(); + void sizeChanged(); + void receivedChanged(); + void selectedChanged(); + void statusChanged(); private: - uint _logID; - uint _logSize; - QDateTime _logTimeUTC; - bool _received; - bool _selected; - QString _status; -}; - -struct LogDownloadData { - LogDownloadData(QGCLogEntry* entry); - - QBitArray chunk_table; - uint32_t current_chunk; - QFile file; - QString filename; - uint ID; - QGCLogEntry* entry; - uint written; - size_t rate_bytes; - qreal rate_avg; - QElapsedTimer elapsed; + uint _logID = 0; + uint _logSize = 0; + QDateTime _logTimeUTC; + bool _received = false; - void advanceChunk(); - uint32_t chunkBins() const; - uint32_t numChunks() const; - bool chunkEquals(const bool val) const; + bool _selected = false; + QString _status = QStringLiteral("Pending"); }; diff --git a/test/AnalyzeView/LogDownloadTest.cc b/test/AnalyzeView/LogDownloadTest.cc index 6acbe18a3e9..e4fb91ac34b 100644 --- a/test/AnalyzeView/LogDownloadTest.cc +++ b/test/AnalyzeView/LogDownloadTest.cc @@ -12,26 +12,20 @@ #include "LogEntry.h" #include "MockLink.h" #include "MultiSignalSpy.h" +#include "QmlObjectListModel.h" #include -LogDownloadTest::LogDownloadTest(void) +void LogDownloadTest::_downloadTest() { - -} - -void LogDownloadTest::downloadTest(void) -{ - _connectMockLink(MAV_AUTOPILOT_PX4); - LogDownloadController* controller = new LogDownloadController(); + LogDownloadController* const controller = new LogDownloadController(this); - _rgLogDownloadControllerSignals[requestingListChangedSignalIndex] = SIGNAL(requestingListChanged()); - _rgLogDownloadControllerSignals[downloadingLogsChangedSignalIndex] = SIGNAL(downloadingLogsChanged()); - _rgLogDownloadControllerSignals[modelChangedSignalIndex] = SIGNAL(modelChanged()); + _rgLogDownloadControllerSignals[requestingListChangedSignalIndex] = SIGNAL(requestingListChanged()); + _rgLogDownloadControllerSignals[downloadingLogsChangedSignalIndex] = SIGNAL(downloadingLogsChanged()); - _multiSpyLogDownloadController = new MultiSignalSpy(); + _multiSpyLogDownloadController = new MultiSignalSpy(this); QVERIFY(_multiSpyLogDownloadController->init(controller, _rgLogDownloadControllerSignals, _cLogDownloadControllerSignals)); controller->refresh(); @@ -43,14 +37,12 @@ void LogDownloadTest::downloadTest(void) } _multiSpyLogDownloadController->clearAllSignals(); - auto model = controller->model(); + QmlObjectListModel* const model = controller->model(); QVERIFY(model); - qDebug() << model->count(); model->value(0)->setSelected(true); - QString downloadTo = QDir::currentPath(); - qDebug() << "download to:" << downloadTo; - controller->downloadToDirectory(downloadTo); + const QString downloadTo = QDir::currentPath(); + controller->download(downloadTo); QVERIFY(_multiSpyLogDownloadController->waitForSignalByIndex(downloadingLogsChangedSignalIndex, 10000)); _multiSpyLogDownloadController->clearAllSignals(); if (controller->downloadingLogs()) { @@ -59,10 +51,8 @@ void LogDownloadTest::downloadTest(void) } _multiSpyLogDownloadController->clearAllSignals(); - QString downloadFile = QDir(downloadTo).filePath("log_0_UnknownDate.ulg"); + const QString downloadFile = QDir(downloadTo).filePath("log_0_UnknownDate.ulg"); QVERIFY(UnitTest::fileCompare(downloadFile, _mockLink->logDownloadFile())); QFile::remove(downloadFile); - - delete controller; } diff --git a/test/AnalyzeView/LogDownloadTest.h b/test/AnalyzeView/LogDownloadTest.h index dc524d74809..0c3d80e78a2 100644 --- a/test/AnalyzeView/LogDownloadTest.h +++ b/test/AnalyzeView/LogDownloadTest.h @@ -7,8 +7,7 @@ * ****************************************************************************/ -#ifndef LogDownloadTest_H -#define LogDownloadTest_H +#pragma once #include "UnitTest.h" @@ -17,19 +16,11 @@ class MultiSignalSpy; class LogDownloadTest : public UnitTest { Q_OBJECT - -public: - LogDownloadTest(void); - -private slots: - //void init(void); - //void cleanup(void) { _cleanup(); } - void downloadTest(void); +private slots: + void _downloadTest(); private: - // LogDownloadController signals - enum { requestingListChangedSignalIndex = 0, downloadingLogsChangedSignalIndex, @@ -38,15 +29,13 @@ private slots: }; enum { - requestingListChangedSignalMask = 1 << requestingListChangedSignalIndex, - downloadingLogsChangedSignalMask = 1 << downloadingLogsChangedSignalIndex, - modelChangedSignalIndexMask = 1 << modelChangedSignalIndex, + requestingListChangedSignalMask = 1 << requestingListChangedSignalIndex, + downloadingLogsChangedSignalMask = 1 << downloadingLogsChangedSignalIndex, + modelChangedSignalIndexMask = 1 << modelChangedSignalIndex, }; - MultiSignalSpy* _multiSpyLogDownloadController; - static const size_t _cLogDownloadControllerSignals = logDownloadControllerMaxSignalIndex; - const char* _rgLogDownloadControllerSignals[_cLogDownloadControllerSignals]; + MultiSignalSpy *_multiSpyLogDownloadController = nullptr; + static constexpr size_t _cLogDownloadControllerSignals = logDownloadControllerMaxSignalIndex; + const char *_rgLogDownloadControllerSignals[_cLogDownloadControllerSignals] = {0}; }; - -#endif diff --git a/test/CMakeLists.txt b/test/CMakeLists.txt index a25b9d0e0e6..21e7e88e0e1 100644 --- a/test/CMakeLists.txt +++ b/test/CMakeLists.txt @@ -30,7 +30,7 @@ add_qgc_test(ADSBTest) add_subdirectory(AnalyzeView) add_qgc_test(ExifParserTest) add_qgc_test(GeoTagControllerTest) -# add_qgc_test(LogDownloadTest) +add_qgc_test(LogDownloadTest) # add_qgc_test(MavlinkLogTest) add_qgc_test(PX4LogParserTest) add_qgc_test(ULogParserTest) diff --git a/test/UnitTestList.cc b/test/UnitTestList.cc index b1890490f4f..88d1e38ed0f 100644 --- a/test/UnitTestList.cc +++ b/test/UnitTestList.cc @@ -18,7 +18,7 @@ #include "ExifParserTest.h" #include "GeoTagControllerTest.h" // #include "MavlinkLogTest.h" -// #include "LogDownloadTest.h" +#include "LogDownloadTest.h" #include "PX4LogParserTest.h" #include "ULogParserTest.h" @@ -123,7 +123,7 @@ int runTests(bool stress, QStringView unitTestOptions) UT_REGISTER_TEST(ExifParserTest) UT_REGISTER_TEST(GeoTagControllerTest) // UT_REGISTER_TEST(MavlinkLogTest) - // UT_REGISTER_TEST(LogDownloadTest) + UT_REGISTER_TEST(LogDownloadTest) UT_REGISTER_TEST(PX4LogParserTest) UT_REGISTER_TEST(ULogParserTest)