QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
LogDownloadController.cc
Go to the documentation of this file.
2#include "AppSettings.h"
3#include "LogEntry.h"
4#include "MAVLinkProtocol.h"
6#include "ParameterManager.h"
7#include "QGCApplication.h"
10#include "SettingsManager.h"
11#include "Vehicle.h"
12
13#include <QtCore/QApplicationStatic>
14#include <QtCore/QTimer>
15
16QGC_LOGGING_CATEGORY(LogDownloadControllerLog, "AnalyzeView.LogDownloadController")
17
19 : QObject(parent)
20 , _timer(new QTimer(this))
21 , _logEntriesModel(new QmlObjectListModel(this))
22{
23 qCDebug(LogDownloadControllerLog) << this;
24
25 (void) connect(MultiVehicleManager::instance(), &MultiVehicleManager::activeVehicleChanged, this, &LogDownloadController::_setActiveVehicle);
26 (void) connect(_timer, &QTimer::timeout, this, &LogDownloadController::_processDownload);
27
28 _timer->setSingleShot(false);
29
30 _setActiveVehicle(MultiVehicleManager::instance()->activeVehicle());
31}
32
34{
35 qCDebug(LogDownloadControllerLog) << this;
36}
37
38void LogDownloadController::download(const QString &path)
39{
40 const QString dir = path.isEmpty() ? SettingsManager::instance()->appSettings()->logSavePath() : path;
41 _downloadToDirectory(dir);
42}
43
44void LogDownloadController::_downloadToDirectory(const QString &dir)
45{
46 _receivedAllEntries();
47
48 _downloadData.reset();
49
50 _downloadPath = dir;
51 if (_downloadPath.isEmpty()) {
52 return;
53 }
54
55 if (!_downloadPath.endsWith(QDir::separator())) {
56 _downloadPath += QDir::separator();
57 }
58
59 QGCLogEntry *const log = _getNextSelected();
60 if (log) {
61 log->setStatus(tr("Waiting"));
62 }
63
64 _setDownloading(true);
65 _receivedAllData();
66}
67
68void LogDownloadController::_processDownload()
69{
70 if (_requestingLogEntries) {
71 _findMissingEntries();
72 } else if (_downloadingLogs) {
73 _findMissingData();
74 }
75}
76
77void LogDownloadController::_findMissingEntries()
78{
79 const int num_logs = _logEntriesModel->count();
80 int start = -1;
81 int end = -1;
82 for (int i = 0; i < num_logs; i++) {
83 const QGCLogEntry *const entry = _logEntriesModel->value<const QGCLogEntry*>(i);
84 if (!entry) {
85 continue;
86 }
87
88 if (!entry->received()) {
89 if (start < 0) {
90 start = i;
91 } else {
92 end = i;
93 }
94 } else if (start >= 0) {
95 break;
96 }
97 }
98
99 if (start < 0) {
100 _receivedAllEntries();
101 return;
102 }
103
104 if (_retries++ > 2) {
105 for (int i = 0; i < num_logs; i++) {
106 QGCLogEntry *const entry = _logEntriesModel->value<QGCLogEntry*>(i);
107 if (entry && !entry->received()) {
108 entry->setStatus(tr("Error"));
109 }
110 }
111
112 _receivedAllEntries();
113 qCWarning(LogDownloadControllerLog) << "Too many errors retreiving log list. Giving up.";
114 return;
115 }
116
117 if (end < 0) {
118 end = start;
119 }
120
121 start += _apmOffset;
122 end += _apmOffset;
123
124 _requestLogList(static_cast<uint32_t>(start), static_cast<uint32_t>(end));
125}
126
127void LogDownloadController::_setActiveVehicle(Vehicle *vehicle)
128{
129 if (vehicle == _vehicle) {
130 return;
131 }
132
133 if (_vehicle) {
134 _logEntriesModel->clearAndDeleteContents();
135 (void) disconnect(_vehicle, &Vehicle::logEntry, this, &LogDownloadController::_logEntry);
136 (void) disconnect(_vehicle, &Vehicle::logData, this, &LogDownloadController::_logData);
137 }
138
139 _vehicle = vehicle;
140
141 if (_vehicle) {
142 (void) connect(_vehicle, &Vehicle::logEntry, this, &LogDownloadController::_logEntry);
143 (void) connect(_vehicle, &Vehicle::logData, this, &LogDownloadController::_logData);
144 }
145}
146
147void LogDownloadController::_logEntry(uint32_t time_utc, uint32_t size, uint16_t id, uint16_t num_logs, uint16_t last_log_num)
148{
149 Q_UNUSED(last_log_num);
150
151 if (!_requestingLogEntries) {
152 return;
153 }
154
155 if ((_logEntriesModel->count() == 0) && (num_logs > 0)) {
156 if (_vehicle->firmwareType() == MAV_AUTOPILOT_ARDUPILOTMEGA) {
157 // APM ID starts at 1
158 _apmOffset = 1;
159 }
160
161 for (int i = 0; i < num_logs; i++) {
162 QGCLogEntry *const entry = new QGCLogEntry(i);
163 _logEntriesModel->append(entry);
164 }
165 }
166
167 if (num_logs > 0) {
168 if ((size > 0) || (_vehicle->firmwareType() != MAV_AUTOPILOT_ARDUPILOTMEGA)) {
169 id -= _apmOffset;
170 if (id < _logEntriesModel->count()) {
171 QGCLogEntry *const entry = _logEntriesModel->value<QGCLogEntry*>(id);
172 entry->setSize(size);
173 entry->setTime(QDateTime::fromSecsSinceEpoch(time_utc));
174 entry->setReceived(true);
175 entry->setStatus(tr("Available"));
176 } else {
177 qCWarning(LogDownloadControllerLog) << "Received log entry for out-of-bound index:" << id;
178 }
179 }
180 } else {
181 _receivedAllEntries();
182 }
183
184 _retries = 0;
185
186 if (_entriesComplete()) {
187 _receivedAllEntries();
188 } else {
189 _timer->start(kTimeOutMs);
190 }
191}
192
193void LogDownloadController::_receivedAllEntries()
194{
195 _timer->stop();
196 _setListing(false);
197}
198
199bool LogDownloadController::_entriesComplete() const
200{
201 const int num_logs = _logEntriesModel->count();
202 for (int i = 0; i < num_logs; i++) {
203 const QGCLogEntry *const entry = _logEntriesModel->value<const QGCLogEntry*>(i);
204 if (!entry) {
205 continue;
206 }
207
208 if (!entry->received()) {
209 return false;
210 }
211 }
212
213 return true;
214}
215
216void LogDownloadController::_logData(uint32_t ofs, uint16_t id, uint8_t count, const uint8_t *data)
217{
218 if (!_downloadingLogs || !_downloadData) {
219 return;
220 }
221
222 id -= _apmOffset;
223 if (_downloadData->ID != id) {
224 qCWarning(LogDownloadControllerLog) << "Received log data for wrong log";
225 return;
226 }
227
228 if ((ofs % MAVLINK_MSG_LOG_DATA_FIELD_DATA_LEN) != 0) {
229 qCWarning(LogDownloadControllerLog) << "Ignored misaligned incoming packet @" << ofs;
230 return;
231 }
232
233 bool result = false;
234 if (ofs <= _downloadData->entry->size()) {
235 const uint32_t chunk = ofs / LogDownloadData::kChunkSize;
236 // qCDebug(LogDownloadControllerLog) << "Received data - Offset:" << ofs << "Chunk:" << chunk;
237 if (chunk != _downloadData->current_chunk) {
238 qCWarning(LogDownloadControllerLog) << "Ignored packet for out of order chunk actual:expected" << chunk << _downloadData->current_chunk;
239 return;
240 }
241
242 const uint16_t bin = (ofs - (chunk * LogDownloadData::kChunkSize)) / MAVLINK_MSG_LOG_DATA_FIELD_DATA_LEN;
243 if (bin >= _downloadData->chunk_table.size()) {
244 qCWarning(LogDownloadControllerLog) << "Out of range bin received";
245 } else {
246 _downloadData->chunk_table.setBit(bin);
247 }
248
249 if (_downloadData->file.pos() != ofs) {
250 if (!_downloadData->file.seek(ofs)) {
251 qCWarning(LogDownloadControllerLog) << "Error while seeking log file offset";
252 return;
253 }
254 }
255
256 if (_downloadData->file.write(reinterpret_cast<const char*>(data), count)) {
257 _downloadData->written += count;
258 _downloadData->rate_bytes += count;
259 _updateDataRate();
260
261 result = true;
262 _retries = 0;
263
264 _timer->start(kTimeOutMs);
265 if (_logComplete()) {
266 _downloadData->entry->setStatus(tr("Downloaded"));
267 _receivedAllData();
268 } else if (_chunkComplete()) {
269 _downloadData->advanceChunk();
270 _requestLogData(_downloadData->ID,
271 _downloadData->current_chunk * LogDownloadData::kChunkSize,
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)) {
274 // Likely to be grabbing fragments and got to the end of a gap
275 _findMissingData();
276 }
277 } else {
278 qCWarning(LogDownloadControllerLog) << "Error while writing log file chunk";
279 }
280 } else {
281 qCWarning(LogDownloadControllerLog) << "Received log offset greater than expected";
282 }
283
284 if (!result) {
285 _downloadData->entry->setStatus(tr("Error"));
286 }
287}
288
289void LogDownloadController::_findMissingData()
290{
291 if (_logComplete()) {
292 _receivedAllData();
293 return;
294 }
295
296 if (_chunkComplete()) {
297 _downloadData->advanceChunk();
298 }
299
300 _retries++;
301
302 _updateDataRate();
303
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)) {
308 break;
309 }
310 }
311
312 for (end = start; end < size; end++) {
313 if (_downloadData->chunk_table.testBit(end)) {
314 break;
315 }
316 }
317
318 const uint32_t pos = (_downloadData->current_chunk * LogDownloadData::kChunkSize) + (start * MAVLINK_MSG_LOG_DATA_FIELD_DATA_LEN);
319 const uint32_t len = (end - start) * MAVLINK_MSG_LOG_DATA_FIELD_DATA_LEN;
320 _requestLogData(_downloadData->ID, pos, len, _retries);
321}
322
323void LogDownloadController::_updateDataRate()
324{
325 constexpr uint kSizeUpdateThreshold = 102400; // 0.1 MB
326 const bool timeThresholdMet = _downloadData->elapsed.elapsed() >= kGUIRateMs;
327 const bool sizeThresholdMet = (_downloadData->written - _downloadData->last_status_written) >= kSizeUpdateThreshold;
328
329 if (!timeThresholdMet && !sizeThresholdMet) {
330 return;
331 }
332
333 QString status;
334 if (timeThresholdMet) {
335 // Update both rate and size
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;
339
340 status = QStringLiteral("%1 (%2/s)").arg(qgcApp()->bigSizeToString(_downloadData->written),
341 qgcApp()->bigSizeToString(_downloadData->rate_avg));
342 _downloadData->elapsed.start();
343 } else {
344 // Update size only, keep previous rate
345 status = QStringLiteral("%1 (%2/s)").arg(qgcApp()->bigSizeToString(_downloadData->written),
346 qgcApp()->bigSizeToString(_downloadData->rate_avg));
347 }
348
349 _downloadData->entry->setStatus(status);
350 _downloadData->last_status_written = _downloadData->written;
351}
352
353bool LogDownloadController::_chunkComplete() const
354{
355 return _downloadData->chunkEquals(true);
356}
357
358bool LogDownloadController::_logComplete() const
359{
360 return (_chunkComplete() && ((_downloadData->current_chunk + 1) == _downloadData->numChunks()));
361}
362
363void LogDownloadController::_receivedAllData()
364{
365 _timer->stop();
366 if (_prepareLogDownload()) {
367 _requestLogData(_downloadData->ID, 0, _downloadData->chunk_table.size() * MAVLINK_MSG_LOG_DATA_FIELD_DATA_LEN);
368 _timer->start(kTimeOutMs);
369 } else {
370 _resetSelection();
371 _setDownloading(false);
372 }
373}
374
375bool LogDownloadController::_prepareLogDownload()
376{
377 _downloadData.reset();
378
379 QGCLogEntry *const entry = _getNextSelected();
380 if (!entry) {
381 return false;
382 }
383
384 entry->setSelected(false);
385 emit selectionChanged();
386
387 const QString ftime = (entry->time().date().year() >= 2010) ? entry->time().toString(QStringLiteral("yyyy-M-d-hh-mm-ss")) : QStringLiteral("UnknownDate");
388
389 _downloadData = std::make_unique<LogDownloadData>(entry);
390 _downloadData->filename = QStringLiteral("log_") + QString::number(entry->id()) + "_" + ftime;
391
392 if (_vehicle->firmwareType() == MAV_AUTOPILOT_PX4) {
393 const QString loggerParam = QStringLiteral("SYS_LOGGER");
394 ParameterManager *const parameterManager = _vehicle->parameterManager();
395 if (parameterManager->parameterExists(ParameterManager::defaultComponentId, loggerParam) && parameterManager->getParameter(ParameterManager::defaultComponentId, loggerParam)->rawValue().toInt() == 0) {
396 _downloadData->filename += ".px4log";
397 } else {
398 _downloadData->filename += ".ulg";
399 }
400 } else {
401 _downloadData->filename += ".bin";
402 }
403
404 _downloadData->file.setFileName(_downloadPath + _downloadData->filename);
405
406 if (_downloadData->file.exists()) {
407 uint32_t numDups = 0;
408 const QStringList filename_spl = _downloadData->filename.split('.');
409 do {
410 numDups += 1;
411 const QString filename = filename_spl[0] + '_' + QString::number(numDups) + '.' + filename_spl[1];
412 _downloadData->file.setFileName(filename);
413 } while ( _downloadData->file.exists());
414 }
415
416 bool result = false;
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;
421 } else {
422 _downloadData->current_chunk = 0;
423 _downloadData->chunk_table = QBitArray(_downloadData->chunkBins(), false);
424 _downloadData->elapsed.start();
425 result = true;
426 }
427
428 if (!result) {
429 if (_downloadData->file.exists()) {
430 (void) _downloadData->file.remove();
431 }
432
433 _downloadData->entry->setStatus(QStringLiteral("Error"));
434 _downloadData.reset();
435 }
436
437 return result;
438}
439
441{
442 _logEntriesModel->clearAndDeleteContents();
443 _requestLogList(0, 0xffff);
444}
445
446QGCLogEntry *LogDownloadController::_getNextSelected() const
447{
448 const int numLogs = _logEntriesModel->count();
449 for (int i = 0; i < numLogs; i++) {
450 QGCLogEntry *const entry = _logEntriesModel->value<QGCLogEntry*>(i);
451 if (!entry) {
452 continue;
453 }
454
455 if (entry->selected()) {
456 return entry;
457 }
458 }
459
460 return nullptr;
461}
462
464{
465 _requestLogEnd();
466 _receivedAllEntries();
467
468 if (_downloadData) {
469 _downloadData->entry->setStatus(QStringLiteral("Canceled"));
470 if (_downloadData->file.exists()) {
471 (void) _downloadData->file.remove();
472 }
473
474 _downloadData.reset();
475 }
476
477 _resetSelection(true);
478 _setDownloading(false);
479}
480
481void LogDownloadController::_resetSelection(bool canceled)
482{
483 const int num_logs = _logEntriesModel->count();
484 for (int i = 0; i < num_logs; i++) {
485 QGCLogEntry *const entry = _logEntriesModel->value<QGCLogEntry*>(i);
486 if (!entry) {
487 continue;
488 }
489
490 if (entry->selected()) {
491 if (canceled) {
492 entry->setStatus(tr("Canceled"));
493 }
494 entry->setSelected(false);
495 }
496 }
497
498 emit selectionChanged();
499}
500
502{
503 if (!_vehicle) {
504 qCWarning(LogDownloadControllerLog) << "Vehicle Unavailable";
505 return;
506 }
507
508 SharedLinkInterfacePtr sharedLink = _vehicle->vehicleLinkManager()->primaryLink().lock();
509 if (!sharedLink) {
510 qCWarning(LogDownloadControllerLog) << "Link Unavailable";
511 return;
512 }
513
514 mavlink_message_t msg{};
515 (void) mavlink_msg_log_erase_pack_chan(
518 sharedLink->mavlinkChannel(),
519 &msg,
520 _vehicle->id(),
521 _vehicle->defaultComponentId()
522 );
523
524 if (!_vehicle->sendMessageOnLinkThreadSafe(sharedLink.get(), msg)) {
525 qCWarning(LogDownloadControllerLog) << "Failed to send";
526 return;
527 }
528
529 refresh();
530}
531
532void LogDownloadController::_requestLogList(uint32_t start, uint32_t end)
533{
534 if (!_vehicle) {
535 qCWarning(LogDownloadControllerLog) << "Vehicle Unavailable";
536 return;
537 }
538
539 SharedLinkInterfacePtr sharedLink = _vehicle->vehicleLinkManager()->primaryLink().lock();
540 if (!sharedLink) {
541 qCWarning(LogDownloadControllerLog) << "Link Unavailable";
542 return;
543 }
544
545 mavlink_message_t msg{};
546 (void) mavlink_msg_log_request_list_pack_chan(
549 sharedLink->mavlinkChannel(),
550 &msg,
551 _vehicle->id(),
552 _vehicle->defaultComponentId(),
553 start,
554 end
555 );
556
557 if (!_vehicle->sendMessageOnLinkThreadSafe(sharedLink.get(), msg)) {
558 qCWarning(LogDownloadControllerLog) << "Failed to send";
559 return;
560 }
561
562 qCDebug(LogDownloadControllerLog) << "Request log entry list (" << start << "through" << end << ")";
563 _setListing(true);
564 _timer->start(kRequestLogListTimeoutMs);
565}
566
567void LogDownloadController::_requestLogData(uint16_t id, uint32_t offset, uint32_t count, int retryCount)
568{
569 if (!_vehicle) {
570 qCWarning(LogDownloadControllerLog) << "Vehicle Unavailable";
571 return;
572 }
573
574 SharedLinkInterfacePtr sharedLink = _vehicle->vehicleLinkManager()->primaryLink().lock();
575 if (!sharedLink) {
576 qCWarning(LogDownloadControllerLog) << "Link Unavailable";
577 return;
578 }
579
580 id += _apmOffset;
581 qCDebug(LogDownloadControllerLog) << "Request log data (id:" << id << "offset:" << offset << "size:" << count << "retryCount" << retryCount << ")";
582
583 mavlink_message_t msg{};
584 (void) mavlink_msg_log_request_data_pack_chan(
587 sharedLink->mavlinkChannel(),
588 &msg,
589 _vehicle->id(),
590 _vehicle->defaultComponentId(),
591 id,
592 offset,
593 count
594 );
595
596 if (!_vehicle->sendMessageOnLinkThreadSafe(sharedLink.get(), msg)) {
597 qCWarning(LogDownloadControllerLog) << "Failed to send";
598 }
599}
600
601void LogDownloadController::_requestLogEnd()
602{
603 if (!_vehicle) {
604 qCWarning(LogDownloadControllerLog) << "Vehicle Unavailable";
605 return;
606 }
607
608 SharedLinkInterfacePtr sharedLink = _vehicle->vehicleLinkManager()->primaryLink().lock();
609 if (!sharedLink) {
610 qCWarning(LogDownloadControllerLog) << "Link Unavailable";
611 return;
612 }
613
614 mavlink_message_t msg{};
615 (void) mavlink_msg_log_request_end_pack_chan(
618 sharedLink->mavlinkChannel(),
619 &msg,
620 _vehicle->id(),
621 _vehicle->defaultComponentId()
622 );
623
624 if (!_vehicle->sendMessageOnLinkThreadSafe(sharedLink.get(), msg)) {
625 qCWarning(LogDownloadControllerLog) << "Failed to send";
626 }
627}
628
629void LogDownloadController::_setDownloading(bool active)
630{
631 if (_downloadingLogs != active) {
632 _downloadingLogs = active;
635 }
636}
637
638void LogDownloadController::_setListing(bool active)
639{
640 if (_requestingLogEntries != active) {
641 _requestingLogEntries = active;
644 }
645}
646
648{
649 if (_compressLogs != compress) {
650 _compressLogs = compress;
651 emit compressLogsChanged();
652 }
653}
654
655bool LogDownloadController::compressLogFile(const QString &logPath)
656{
657 Q_UNUSED(logPath)
658 qCWarning(LogDownloadControllerLog) << "Log compression not yet implemented (decompression-only API)";
659 return false;
660}
661
663{
664 // Not implemented - compression API is decompression-only
665}
666
667void LogDownloadController::_handleCompressionProgress(qreal progress)
668{
669 Q_UNUSED(progress)
670 // Not implemented - compression API is decompression-only
671}
672
673void LogDownloadController::_handleCompressionFinished(bool success)
674{
675 Q_UNUSED(success)
676 // Not implemented - compression API is decompression-only
677}
std::shared_ptr< LinkInterface > SharedLinkInterfacePtr
#define qgcApp()
struct __mavlink_message mavlink_message_t
#define QGC_LOGGING_CATEGORY(name, categoryStr)
QString logSavePath()
void download(const QString &path=QString())
void cancelCompression()
Cancel compression.
bool compressLogFile(const QString &logPath)
Compress a single log file.
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 &paramName) const
Fact * getParameter(int componentId, const QString &paramName)
static constexpr int defaultComponentId
void append(QObject *object)
Caller maintains responsibility for object ownership and deletion.
T value(int index) const
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()
Definition Vehicle.h:580
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
Definition Vehicle.h:427
int id() const
Definition Vehicle.h:425
bool sendMessageOnLinkThreadSafe(LinkInterface *link, mavlink_message_t message)
Definition Vehicle.cc:1470
int defaultComponentId() const
Definition Vehicle.h:711
ParameterManager * parameterManager()
Definition Vehicle.h:578
void logData(uint32_t ofs, uint16_t id, uint8_t count, const uint8_t *data)
static constexpr uint32_t kChunkSize
Definition LogEntry.h:47