13#include <QtCore/QApplicationStatic>
14#include <QtCore/QTimer>
20 , _timer(new QTimer(this))
23 qCDebug(LogDownloadControllerLog) <<
this;
26 (void) connect(_timer, &QTimer::timeout,
this, &LogDownloadController::_processDownload);
28 _timer->setSingleShot(
false);
30 _setActiveVehicle(MultiVehicleManager::instance()->activeVehicle());
35 qCDebug(LogDownloadControllerLog) <<
this;
40 const QString dir = path.isEmpty() ? SettingsManager::instance()->appSettings()->
logSavePath() : path;
41 _downloadToDirectory(dir);
44void LogDownloadController::_downloadToDirectory(
const QString &dir)
46 _receivedAllEntries();
48 _downloadData.reset();
51 if (_downloadPath.isEmpty()) {
55 if (!_downloadPath.endsWith(QDir::separator())) {
56 _downloadPath += QDir::separator();
61 log->setStatus(tr(
"Waiting"));
64 _setDownloading(
true);
68void LogDownloadController::_processDownload()
70 if (_requestingLogEntries) {
71 _findMissingEntries();
72 }
else if (_downloadingLogs) {
77void LogDownloadController::_findMissingEntries()
79 const int num_logs = _logEntriesModel->
count();
82 for (
int i = 0; i < num_logs; i++) {
88 if (!entry->received()) {
94 }
else if (start >= 0) {
100 _receivedAllEntries();
104 if (_retries++ > 2) {
105 for (
int i = 0; i < num_logs; i++) {
107 if (entry && !entry->received()) {
108 entry->setStatus(tr(
"Error"));
112 _receivedAllEntries();
113 qCWarning(LogDownloadControllerLog) <<
"Too many errors retreiving log list. Giving up.";
124 _requestLogList(
static_cast<uint32_t
>(start),
static_cast<uint32_t
>(end));
127void LogDownloadController::_setActiveVehicle(
Vehicle *vehicle)
129 if (vehicle == _vehicle) {
135 (void) disconnect(_vehicle, &
Vehicle::logEntry,
this, &LogDownloadController::_logEntry);
136 (void) disconnect(_vehicle, &
Vehicle::logData,
this, &LogDownloadController::_logData);
142 (void) connect(_vehicle, &
Vehicle::logEntry,
this, &LogDownloadController::_logEntry);
143 (void) connect(_vehicle, &
Vehicle::logData,
this, &LogDownloadController::_logData);
147void LogDownloadController::_logEntry(uint32_t time_utc, uint32_t size, uint16_t
id, uint16_t num_logs, uint16_t last_log_num)
149 Q_UNUSED(last_log_num);
151 if (!_requestingLogEntries) {
155 if ((_logEntriesModel->
count() == 0) && (num_logs > 0)) {
156 if (_vehicle->
firmwareType() == MAV_AUTOPILOT_ARDUPILOTMEGA) {
161 for (
int i = 0; i < num_logs; i++) {
163 _logEntriesModel->
append(entry);
168 if ((size > 0) || (_vehicle->
firmwareType() != MAV_AUTOPILOT_ARDUPILOTMEGA)) {
170 if (id < _logEntriesModel->count()) {
172 entry->setSize(size);
173 entry->setTime(QDateTime::fromSecsSinceEpoch(time_utc));
174 entry->setReceived(
true);
175 entry->setStatus(tr(
"Available"));
177 qCWarning(LogDownloadControllerLog) <<
"Received log entry for out-of-bound index:" << id;
181 _receivedAllEntries();
186 if (_entriesComplete()) {
187 _receivedAllEntries();
189 _timer->start(kTimeOutMs);
193void LogDownloadController::_receivedAllEntries()
199bool LogDownloadController::_entriesComplete()
const
201 const int num_logs = _logEntriesModel->
count();
202 for (
int i = 0; i < num_logs; i++) {
208 if (!entry->received()) {
216void LogDownloadController::_logData(uint32_t ofs, uint16_t
id, uint8_t count,
const uint8_t *data)
218 if (!_downloadingLogs || !_downloadData) {
223 if (_downloadData->ID !=
id) {
224 qCWarning(LogDownloadControllerLog) <<
"Received log data for wrong log";
228 if ((ofs % MAVLINK_MSG_LOG_DATA_FIELD_DATA_LEN) != 0) {
229 qCWarning(LogDownloadControllerLog) <<
"Ignored misaligned incoming packet @" << ofs;
234 if (ofs <= _downloadData->entry->size()) {
237 if (chunk != _downloadData->current_chunk) {
238 qCWarning(LogDownloadControllerLog) <<
"Ignored packet for out of order chunk actual:expected" << chunk << _downloadData->current_chunk;
243 if (bin >= _downloadData->chunk_table.size()) {
244 qCWarning(LogDownloadControllerLog) <<
"Out of range bin received";
246 _downloadData->chunk_table.setBit(bin);
249 if (_downloadData->file.pos() != ofs) {
250 if (!_downloadData->file.seek(ofs)) {
251 qCWarning(LogDownloadControllerLog) <<
"Error while seeking log file offset";
256 if (_downloadData->file.write(
reinterpret_cast<const char*
>(data), count)) {
257 _downloadData->written += count;
258 _downloadData->rate_bytes += count;
264 _timer->start(kTimeOutMs);
265 if (_logComplete()) {
266 _downloadData->entry->setStatus(tr(
"Downloaded"));
268 }
else if (_chunkComplete()) {
269 _downloadData->advanceChunk();
270 _requestLogData(_downloadData->ID,
272 _downloadData->chunk_table.size() * MAVLINK_MSG_LOG_DATA_FIELD_DATA_LEN);
273 }
else if ((bin < (_downloadData->chunk_table.size() - 1)) && _downloadData->chunk_table.at(bin + 1)) {
278 qCWarning(LogDownloadControllerLog) <<
"Error while writing log file chunk";
281 qCWarning(LogDownloadControllerLog) <<
"Received log offset greater than expected";
285 _downloadData->entry->setStatus(tr(
"Error"));
289void LogDownloadController::_findMissingData()
291 if (_logComplete()) {
296 if (_chunkComplete()) {
297 _downloadData->advanceChunk();
304 uint16_t start = 0, end = 0;
305 const int size = _downloadData->chunk_table.size();
306 for (; start < size; start++) {
307 if (!_downloadData->chunk_table.testBit(start)) {
312 for (end = start; end < size; end++) {
313 if (_downloadData->chunk_table.testBit(end)) {
319 const uint32_t len = (end - start) * MAVLINK_MSG_LOG_DATA_FIELD_DATA_LEN;
320 _requestLogData(_downloadData->ID, pos, len, _retries);
323void LogDownloadController::_updateDataRate()
325 constexpr uint kSizeUpdateThreshold = 102400;
326 const bool timeThresholdMet = _downloadData->elapsed.elapsed() >= kGUIRateMs;
327 const bool sizeThresholdMet = (_downloadData->written - _downloadData->last_status_written) >= kSizeUpdateThreshold;
329 if (!timeThresholdMet && !sizeThresholdMet) {
334 if (timeThresholdMet) {
336 const qreal rate = _downloadData->rate_bytes / (_downloadData->elapsed.elapsed() / 1000.0);
337 _downloadData->rate_avg = (_downloadData->rate_avg * 0.95) + (rate * 0.05);
338 _downloadData->rate_bytes = 0;
340 status = QStringLiteral(
"%1 (%2/s)").arg(
qgcApp()->bigSizeToString(_downloadData->written),
341 qgcApp()->bigSizeToString(_downloadData->rate_avg));
342 _downloadData->elapsed.start();
345 status = QStringLiteral(
"%1 (%2/s)").arg(
qgcApp()->bigSizeToString(_downloadData->written),
346 qgcApp()->bigSizeToString(_downloadData->rate_avg));
349 _downloadData->entry->setStatus(status);
350 _downloadData->last_status_written = _downloadData->written;
353bool LogDownloadController::_chunkComplete()
const
355 return _downloadData->chunkEquals(
true);
358bool LogDownloadController::_logComplete()
const
360 return (_chunkComplete() && ((_downloadData->current_chunk + 1) == _downloadData->numChunks()));
363void LogDownloadController::_receivedAllData()
366 if (_prepareLogDownload()) {
367 _requestLogData(_downloadData->ID, 0, _downloadData->chunk_table.size() * MAVLINK_MSG_LOG_DATA_FIELD_DATA_LEN);
368 _timer->start(kTimeOutMs);
371 _setDownloading(
false);
375bool LogDownloadController::_prepareLogDownload()
377 _downloadData.reset();
384 entry->setSelected(
false);
387 const QString ftime = (entry->time().date().year() >= 2010) ? entry->time().toString(QStringLiteral(
"yyyy-M-d-hh-mm-ss")) : QStringLiteral(
"UnknownDate");
389 _downloadData = std::make_unique<LogDownloadData>(entry);
390 _downloadData->filename = QStringLiteral(
"log_") + QString::number(entry->id()) +
"_" + ftime;
393 const QString loggerParam = QStringLiteral(
"SYS_LOGGER");
396 _downloadData->filename +=
".px4log";
398 _downloadData->filename +=
".ulg";
401 _downloadData->filename +=
".bin";
404 _downloadData->file.setFileName(_downloadPath + _downloadData->filename);
406 if (_downloadData->file.exists()) {
407 uint32_t numDups = 0;
408 const QStringList filename_spl = _downloadData->filename.split(
'.');
411 const QString filename = filename_spl[0] +
'_' + QString::number(numDups) +
'.' + filename_spl[1];
412 _downloadData->file.setFileName(filename);
413 }
while ( _downloadData->file.exists());
417 if (!_downloadData->file.open(QIODevice::WriteOnly)) {
418 qCWarning(LogDownloadControllerLog) <<
"Failed to create log file:" << _downloadData->filename;
419 }
else if (!_downloadData->file.resize(entry->size())) {
420 qCWarning(LogDownloadControllerLog) <<
"Failed to allocate space for log file:" << _downloadData->filename;
422 _downloadData->current_chunk = 0;
423 _downloadData->chunk_table = QBitArray(_downloadData->chunkBins(),
false);
424 _downloadData->elapsed.start();
429 if (_downloadData->file.exists()) {
430 (void) _downloadData->file.remove();
433 _downloadData->entry->setStatus(QStringLiteral(
"Error"));
434 _downloadData.reset();
443 _requestLogList(0, 0xffff);
446QGCLogEntry *LogDownloadController::_getNextSelected()
const
448 const int numLogs = _logEntriesModel->
count();
449 for (
int i = 0; i < numLogs; i++) {
455 if (entry->selected()) {
466 _receivedAllEntries();
469 _downloadData->entry->setStatus(QStringLiteral(
"Canceled"));
470 if (_downloadData->file.exists()) {
471 (void) _downloadData->file.remove();
474 _downloadData.reset();
477 _resetSelection(
true);
478 _setDownloading(
false);
481void LogDownloadController::_resetSelection(
bool canceled)
483 const int num_logs = _logEntriesModel->
count();
484 for (
int i = 0; i < num_logs; i++) {
490 if (entry->selected()) {
492 entry->setStatus(tr(
"Canceled"));
494 entry->setSelected(
false);
504 qCWarning(LogDownloadControllerLog) <<
"Vehicle Unavailable";
510 qCWarning(LogDownloadControllerLog) <<
"Link Unavailable";
515 (void) mavlink_msg_log_erase_pack_chan(
518 sharedLink->mavlinkChannel(),
525 qCWarning(LogDownloadControllerLog) <<
"Failed to send";
532void LogDownloadController::_requestLogList(uint32_t start, uint32_t end)
535 qCWarning(LogDownloadControllerLog) <<
"Vehicle Unavailable";
541 qCWarning(LogDownloadControllerLog) <<
"Link Unavailable";
546 (void) mavlink_msg_log_request_list_pack_chan(
549 sharedLink->mavlinkChannel(),
558 qCWarning(LogDownloadControllerLog) <<
"Failed to send";
562 qCDebug(LogDownloadControllerLog) <<
"Request log entry list (" << start <<
"through" << end <<
")";
564 _timer->start(kRequestLogListTimeoutMs);
567void LogDownloadController::_requestLogData(uint16_t
id, uint32_t offset, uint32_t count,
int retryCount)
570 qCWarning(LogDownloadControllerLog) <<
"Vehicle Unavailable";
576 qCWarning(LogDownloadControllerLog) <<
"Link Unavailable";
581 qCDebug(LogDownloadControllerLog) <<
"Request log data (id:" <<
id <<
"offset:" << offset <<
"size:" << count <<
"retryCount" << retryCount <<
")";
584 (void) mavlink_msg_log_request_data_pack_chan(
587 sharedLink->mavlinkChannel(),
597 qCWarning(LogDownloadControllerLog) <<
"Failed to send";
601void LogDownloadController::_requestLogEnd()
604 qCWarning(LogDownloadControllerLog) <<
"Vehicle Unavailable";
610 qCWarning(LogDownloadControllerLog) <<
"Link Unavailable";
615 (void) mavlink_msg_log_request_end_pack_chan(
618 sharedLink->mavlinkChannel(),
625 qCWarning(LogDownloadControllerLog) <<
"Failed to send";
629void LogDownloadController::_setDownloading(
bool active)
631 if (_downloadingLogs != active) {
632 _downloadingLogs = active;
638void LogDownloadController::_setListing(
bool active)
640 if (_requestingLogEntries != active) {
641 _requestingLogEntries = active;
649 if (_compressLogs != compress) {
650 _compressLogs = compress;
658 qCWarning(LogDownloadControllerLog) <<
"Log compression not yet implemented (decompression-only API)";
667void LogDownloadController::_handleCompressionProgress(qreal progress)
673void LogDownloadController::_handleCompressionFinished(
bool success)
std::shared_ptr< LinkInterface > SharedLinkInterfacePtr
struct __mavlink_message mavlink_message_t
#define QGC_LOGGING_CATEGORY(name, categoryStr)
void download(const QString &path=QString())
void requestingListChanged()
void downloadingLogsChanged()
void cancelCompression()
Cancel compression.
bool compressLogFile(const QString &logPath)
Compress a single log file.
void compressLogsChanged()
void setCompressLogs(bool compress)
static int getComponentId()
Get the component id of this application.
static MAVLinkProtocol * instance()
int getSystemId() const
Get the system id of this application.
void activeVehicleChanged(Vehicle *activeVehicle)
bool parameterExists(int componentId, const QString ¶mName) const
Fact * getParameter(int componentId, const QString ¶mName)
static constexpr int defaultComponentId
void append(QObject *object)
Caller maintains responsibility for object ownership and deletion.
int count() const override final
void clearAndDeleteContents() override final
Clears the list and calls deleteLater on each entry.
WeakLinkInterfacePtr primaryLink() const
void setCommunicationLostEnabled(bool communicationLostEnabled)
VehicleLinkManager * vehicleLinkManager()
void logEntry(uint32_t time_utc, uint32_t size, uint16_t id, uint16_t num_logs, uint16_t last_log_num)
MAV_AUTOPILOT firmwareType() const
bool sendMessageOnLinkThreadSafe(LinkInterface *link, mavlink_message_t message)
int defaultComponentId() const
ParameterManager * parameterManager()
void logData(uint32_t ofs, uint16_t id, uint8_t count, const uint8_t *data)
static constexpr uint32_t kChunkSize