QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
OnboardLogController.cc
Go to the documentation of this file.
2#include "AppSettings.h"
3#include "OnboardLogEntry.h"
4#include "MAVLinkLib.h"
5#include "MAVLinkProtocol.h"
7#include "ParameterManager.h"
8#include "QGCFormat.h"
10#include "QmlObjectListModel.h"
11#include "SettingsManager.h"
12#include "Vehicle.h"
13#include "VehicleLinkManager.h"
14
15#include <algorithm>
16
17#include <QtCore/QApplicationStatic>
18#include <QtCore/QTimer>
19
20QGC_LOGGING_CATEGORY(OnboardLogControllerLog, "AnalyzeView.OnboardLogController")
21
23 : QObject(parent)
24 , _timer(new QTimer(this))
25 , _logEntriesModel(new QmlObjectListModel(this))
26{
27 qCDebug(OnboardLogControllerLog) << this;
28
29 (void) connect(MultiVehicleManager::instance(), &MultiVehicleManager::activeVehicleChanged, this, &OnboardLogController::_setActiveVehicle);
30 (void) connect(_timer, &QTimer::timeout, this, &OnboardLogController::_processDownload);
31
32 _timer->setSingleShot(false);
33
34 _setActiveVehicle(MultiVehicleManager::instance()->activeVehicle());
35}
36
38{
39 qCDebug(OnboardLogControllerLog) << this;
40}
41
42void OnboardLogController::download(const QString &path)
43{
44 const QString dir = path.isEmpty() ? SettingsManager::instance()->appSettings()->logSavePath() : path;
45 _downloadToDirectory(dir);
46}
47
48void OnboardLogController::_downloadToDirectory(const QString &dir)
49{
50 _receivedAllEntries();
51
52 _downloadData.reset();
53
54 _downloadPath = dir;
55 if (_downloadPath.isEmpty()) {
56 return;
57 }
58
59 if (!_downloadPath.endsWith(QDir::separator())) {
60 _downloadPath += QDir::separator();
61 }
62
63 QGCOnboardLogEntry *const log = _getNextSelected();
64 if (log) {
65 log->setStatus(tr("Waiting"));
66 }
67
68 _setDownloading(true);
69 _receivedAllData();
70}
71
72void OnboardLogController::_processDownload()
73{
74 if (_requestingLogEntries) {
75 _findMissingEntries();
76 } else if (_downloadingLogs) {
77 _findMissingData();
78 }
79}
80
81void OnboardLogController::_findMissingEntries()
82{
83 const int num_logs = _logEntriesModel->count();
84 int start = -1;
85 int end = -1;
86 for (int i = 0; i < num_logs; i++) {
87 const QGCOnboardLogEntry *const entry = _logEntriesModel->value<const QGCOnboardLogEntry*>(i);
88 if (!entry) {
89 continue;
90 }
91
92 if (!entry->received()) {
93 if (start < 0) {
94 start = i;
95 } else {
96 end = i;
97 }
98 } else if (start >= 0) {
99 break;
100 }
101 }
102
103 if (start < 0) {
104 _receivedAllEntries();
105 return;
106 }
107
108 if (_retries++ > 2) {
109 for (int i = 0; i < num_logs; i++) {
110 QGCOnboardLogEntry *const entry = _logEntriesModel->value<QGCOnboardLogEntry*>(i);
111 if (entry && !entry->received()) {
112 entry->setStatus(tr("Error"));
113 }
114 }
115
116 _receivedAllEntries();
117 qCWarning(OnboardLogControllerLog) << "Too many errors retreiving log list. Giving up.";
118 return;
119 }
120
121 if (end < 0) {
122 end = start;
123 }
124
125 start += _apmOffset;
126 end += _apmOffset;
127
128 _requestLogList(static_cast<uint32_t>(start), static_cast<uint32_t>(end));
129}
130
131void OnboardLogController::_setActiveVehicle(Vehicle *vehicle)
132{
133 if (vehicle == _vehicle) {
134 return;
135 }
136
137 if (_vehicle) {
138 _logEntriesModel->clearAndDeleteContents();
139 (void) disconnect(_vehicle, &Vehicle::logEntry, this, &OnboardLogController::_logEntry);
140 (void) disconnect(_vehicle, &Vehicle::logData, this, &OnboardLogController::_logData);
141 }
142
143 _vehicle = vehicle;
144
145 if (_vehicle) {
146 (void) connect(_vehicle, &Vehicle::logEntry, this, &OnboardLogController::_logEntry);
147 (void) connect(_vehicle, &Vehicle::logData, this, &OnboardLogController::_logData);
148 }
149}
150
151void OnboardLogController::_logEntry(uint32_t time_utc, uint32_t size, uint16_t id, uint16_t num_logs, uint16_t last_log_num)
152{
153 Q_UNUSED(last_log_num);
154
155 if (!_requestingLogEntries) {
156 return;
157 }
158
159 if ((_logEntriesModel->count() == 0) && (num_logs > 0)) {
160 if (_vehicle->firmwareType() == MAV_AUTOPILOT_ARDUPILOTMEGA) {
161 // APM ID starts at 1
162 _apmOffset = 1;
163 }
164
165 for (int i = 0; i < num_logs; i++) {
166 QGCOnboardLogEntry *const entry = new QGCOnboardLogEntry(i);
168 _logEntriesModel->append(entry);
169 }
170 }
171
172 if (num_logs > 0) {
173 if ((size > 0) || (_vehicle->firmwareType() != MAV_AUTOPILOT_ARDUPILOTMEGA)) {
174 id -= _apmOffset;
175 if (id < _logEntriesModel->count()) {
176 QGCOnboardLogEntry *const entry = _logEntriesModel->value<QGCOnboardLogEntry*>(id);
177 entry->setSize(size);
178 entry->setTime(QDateTime::fromSecsSinceEpoch(time_utc));
179 entry->setReceived(true);
180 entry->setStatus(tr("Available"));
181 } else {
182 qCWarning(OnboardLogControllerLog) << "Received onboard log entry for out-of-bound index:" << id;
183 }
184 }
185 } else {
186 _receivedAllEntries();
187 }
188
189 _retries = 0;
190
191 if (_entriesComplete()) {
192 _receivedAllEntries();
193 } else {
194 _timer->start(kTimeOutMs);
195 }
196}
197
198void OnboardLogController::_receivedAllEntries()
199{
200 _timer->stop();
201 _setListing(false);
202}
203
204bool OnboardLogController::_entriesComplete() const
205{
206 const int num_logs = _logEntriesModel->count();
207 for (int i = 0; i < num_logs; i++) {
208 const QGCOnboardLogEntry *const entry = _logEntriesModel->value<const QGCOnboardLogEntry*>(i);
209 if (!entry) {
210 continue;
211 }
212
213 if (!entry->received()) {
214 return false;
215 }
216 }
217
218 return true;
219}
220
221void OnboardLogController::_logData(uint32_t ofs, uint16_t id, uint8_t count, const uint8_t *data)
222{
223 if (!_downloadingLogs || !_downloadData) {
224 return;
225 }
226
227 id -= _apmOffset;
228 if (_downloadData->ID != id) {
229 qCWarning(OnboardLogControllerLog) << "Received log data for wrong log";
230 return;
231 }
232
233 if ((ofs % MAVLINK_MSG_LOG_DATA_FIELD_DATA_LEN) != 0) {
234 qCWarning(OnboardLogControllerLog) << "Ignored misaligned incoming packet @" << ofs;
235 return;
236 }
237
238 bool result = false;
239 if (ofs <= _downloadData->entry->size()) {
240 const uint32_t chunk = ofs / OnboardLogDownloadData::kChunkSize;
241 // qCDebug(OnboardLogControllerLog) << "Received data - Offset:" << ofs << "Chunk:" << chunk;
242 if (chunk != _downloadData->current_chunk) {
243 qCWarning(OnboardLogControllerLog) << "Ignored packet for out of order chunk actual:expected" << chunk << _downloadData->current_chunk;
244 return;
245 }
246
247 const uint16_t bin = (ofs - (chunk * OnboardLogDownloadData::kChunkSize)) / MAVLINK_MSG_LOG_DATA_FIELD_DATA_LEN;
248 if (bin >= _downloadData->chunk_table.size()) {
249 qCWarning(OnboardLogControllerLog) << "Out of range bin received";
250 } else {
251 _downloadData->chunk_table.setBit(bin);
252 }
253
254 if (_downloadData->file.pos() != ofs) {
255 if (!_downloadData->file.seek(ofs)) {
256 qCWarning(OnboardLogControllerLog) << "Error while seeking log file offset";
257 return;
258 }
259 }
260
261 if (_downloadData->file.write(reinterpret_cast<const char*>(data), count)) {
262 _downloadData->written += count;
263 _downloadData->rate_bytes += count;
264 _updateDataRate();
265
266 result = true;
267 _retries = 0;
268
269 _timer->start(kTimeOutMs);
270 if (_logComplete()) {
271 _downloadData->entry->setStatus(tr("Downloaded"));
272 _receivedAllData();
273 } else if (_chunkComplete()) {
274 _downloadData->advanceChunk();
275 _requestLogData(_downloadData->ID,
276 _downloadData->current_chunk * OnboardLogDownloadData::kChunkSize,
277 _downloadData->chunk_table.size() * MAVLINK_MSG_LOG_DATA_FIELD_DATA_LEN);
278 } else if ((bin < (_downloadData->chunk_table.size() - 1)) && _downloadData->chunk_table.at(bin + 1)) {
279 // Likely to be grabbing fragments and got to the end of a gap
280 _findMissingData();
281 }
282 } else {
283 qCWarning(OnboardLogControllerLog) << "Error while writing log file chunk";
284 }
285 } else {
286 qCWarning(OnboardLogControllerLog) << "Received log offset greater than expected";
287 }
288
289 if (!result) {
290 _downloadData->entry->setStatus(tr("Error"));
291 }
292}
293
294void OnboardLogController::_findMissingData()
295{
296 if (_logComplete()) {
297 _receivedAllData();
298 return;
299 }
300
301 if (_chunkComplete()) {
302 _downloadData->advanceChunk();
303 }
304
305 _retries++;
306
307 _updateDataRate();
308
309 uint16_t start = 0, end = 0;
310 const int size = _downloadData->chunk_table.size();
311 for (; start < size; start++) {
312 if (!_downloadData->chunk_table.testBit(start)) {
313 break;
314 }
315 }
316
317 for (end = start; end < size; end++) {
318 if (_downloadData->chunk_table.testBit(end)) {
319 break;
320 }
321 }
322
323 const uint32_t pos = (_downloadData->current_chunk * OnboardLogDownloadData::kChunkSize) + (start * MAVLINK_MSG_LOG_DATA_FIELD_DATA_LEN);
324 const uint32_t len = (end - start) * MAVLINK_MSG_LOG_DATA_FIELD_DATA_LEN;
325 _requestLogData(_downloadData->ID, pos, len, _retries);
326}
327
328void OnboardLogController::_updateDataRate()
329{
330 constexpr uint kSizeUpdateThreshold = 102400; // 0.1 MB
331 const bool timeThresholdMet = _downloadData->elapsed.elapsed() >= kGUIRateMs;
332 const bool sizeThresholdMet = (_downloadData->written - _downloadData->last_status_written) >= kSizeUpdateThreshold;
333
334 if (!timeThresholdMet && !sizeThresholdMet) {
335 return;
336 }
337
338 QString status;
339 if (timeThresholdMet) {
340 // Update both rate and size
341 const qreal rate = _downloadData->rate_bytes / (_downloadData->elapsed.elapsed() / 1000.0);
342 _downloadData->rate_avg = (_downloadData->rate_avg * 0.95) + (rate * 0.05);
343 _downloadData->rate_bytes = 0;
344
345 status = QStringLiteral("%1 (%2/s)").arg(QGC::bigSizeToString(_downloadData->written),
346 QGC::bigSizeToString(_downloadData->rate_avg));
347 _downloadData->elapsed.start();
348 } else {
349 // Update size only, keep previous rate
350 status = QStringLiteral("%1 (%2/s)").arg(QGC::bigSizeToString(_downloadData->written),
351 QGC::bigSizeToString(_downloadData->rate_avg));
352 }
353
354 _downloadData->entry->setStatus(status);
355 _downloadData->last_status_written = _downloadData->written;
356}
357
358bool OnboardLogController::_chunkComplete() const
359{
360 return _downloadData->chunkEquals(true);
361}
362
363bool OnboardLogController::_logComplete() const
364{
365 return (_chunkComplete() && ((_downloadData->current_chunk + 1) == _downloadData->numChunks()));
366}
367
368void OnboardLogController::_receivedAllData()
369{
370 _timer->stop();
371 if (_prepareLogDownload()) {
372 _requestLogData(_downloadData->ID, 0, _downloadData->chunk_table.size() * MAVLINK_MSG_LOG_DATA_FIELD_DATA_LEN);
373 _timer->start(kTimeOutMs);
374 } else {
375 _resetSelection();
376 _setDownloading(false);
377 }
378}
379
380bool OnboardLogController::_prepareLogDownload()
381{
382 _downloadData.reset();
383
384 QGCOnboardLogEntry *const entry = _getNextSelected();
385 if (!entry) {
386 return false;
387 }
388
389 entry->setSelected(false);
390 emit selectionChanged();
391
392 const QString ftime = (entry->time().date().year() >= 2010) ? entry->time().toString(QStringLiteral("yyyy-M-d-hh-mm-ss")) : QStringLiteral("UnknownDate");
393
394 _downloadData = std::make_unique<OnboardLogDownloadData>(entry);
395 _downloadData->filename = QStringLiteral("log_") + QString::number(entry->id()) + "_" + ftime;
396
397 if (_vehicle->firmwareType() == MAV_AUTOPILOT_PX4) {
398 const QString loggerParam = QStringLiteral("SYS_LOGGER");
399 ParameterManager *const parameterManager = _vehicle->parameterManager();
400 if (parameterManager->parameterExists(ParameterManager::defaultComponentId, loggerParam) && parameterManager->getParameter(ParameterManager::defaultComponentId, loggerParam)->rawValue().toInt() == 0) {
401 _downloadData->filename += ".px4log";
402 } else {
403 _downloadData->filename += ".ulg";
404 }
405 } else {
406 _downloadData->filename += ".bin";
407 }
408
409 _downloadData->file.setFileName(_downloadPath + _downloadData->filename);
410
411 if (_downloadData->file.exists()) {
412 uint32_t numDups = 0;
413 const QStringList filename_spl = _downloadData->filename.split('.');
414 do {
415 numDups += 1;
416 const QString filename = filename_spl[0] + '_' + QString::number(numDups) + '.' + filename_spl[1];
417 _downloadData->file.setFileName(_downloadPath + filename);
418 } while ( _downloadData->file.exists());
419 }
420
421 bool result = false;
422 if (!_downloadData->file.open(QIODevice::WriteOnly)) {
423 qCWarning(OnboardLogControllerLog) << "Failed to create log file:" << _downloadData->filename;
424 } else if (!_downloadData->file.resize(entry->size())) {
425 qCWarning(OnboardLogControllerLog) << "Failed to allocate space for log file:" << _downloadData->filename;
426 } else {
427 _downloadData->current_chunk = 0;
428 _downloadData->chunk_table = QBitArray(_downloadData->chunkBins(), false);
429 _downloadData->elapsed.start();
430 result = true;
431 }
432
433 if (!result) {
434 if (_downloadData->file.exists()) {
435 (void) _downloadData->file.remove();
436 }
437
438 _downloadData->entry->setStatus(QStringLiteral("Error"));
439 _downloadData.reset();
440 }
441
442 return result;
443}
444
446{
447 _logEntriesModel->clearAndDeleteContents();
448 emit selectionChanged();
449 _requestLogList(0, 0xffff);
450}
451
452QGCOnboardLogEntry *OnboardLogController::_getNextSelected() const
453{
454 const int numLogs = _logEntriesModel->count();
455 for (int i = 0; i < numLogs; i++) {
456 QGCOnboardLogEntry *const entry = _logEntriesModel->value<QGCOnboardLogEntry*>(i);
457 if (!entry) {
458 continue;
459 }
460
461 if (entry->selected()) {
462 return entry;
463 }
464 }
465
466 return nullptr;
467}
468
470{
471 _requestLogEnd();
472 _receivedAllEntries();
473
474 if (_downloadData) {
475 _downloadData->entry->setStatus(QStringLiteral("Canceled"));
476 if (_downloadData->file.exists()) {
477 (void) _downloadData->file.remove();
478 }
479
480 _downloadData.reset();
481 }
482
483 _resetSelection(true);
484 _setDownloading(false);
485}
486
488{
489 const int count = _logEntriesModel->count();
490 for (int i = 0; i < count; i++) {
491 QGCOnboardLogEntry *const entry = _logEntriesModel->value<QGCOnboardLogEntry*>(i);
492 if (!entry || !entry->received()) {
493 continue;
494 }
495
496 if (entry->selected() != select) {
497 // Block per-entry signals to avoid O(n²) allLogsSelected() re-evaluations.
498 // A single selectionChanged() is emitted after the loop.
499 QSignalBlocker blocker(entry);
500 entry->setSelected(select);
501 }
502 }
503 emit selectionChanged();
504}
505
507{
508 int selected = 0;
509 const int count = _logEntriesModel->count();
510 for (int i = 0; i < count; i++) {
511 const QGCOnboardLogEntry *const entry = _logEntriesModel->value<const QGCOnboardLogEntry*>(i);
512 if (entry && entry->received() && entry->selected()) {
513 selected++;
514 }
515 }
516
517 return selected;
518}
519
521{
522 int selectable = 0;
523 int selected = 0;
524 const int count = _logEntriesModel->count();
525 for (int i = 0; i < count; i++) {
526 const QGCOnboardLogEntry *const entry = _logEntriesModel->value<const QGCOnboardLogEntry*>(i);
527 if (entry && entry->received()) {
528 selectable++;
529 if (entry->selected()) {
530 selected++;
531 }
532 }
533 }
534
535 return (selectable > 0) && (selected == selectable);
536}
537
539{
540 setSortAscending(!_sortAscending);
541}
542
544{
545 if (_sortAscending == ascending) {
546 return;
547 }
548
549 _sortAscending = ascending;
550 _sortEntriesByTimestamp();
552}
553
554void OnboardLogController::_resetSelection(bool canceled)
555{
556 const int num_logs = _logEntriesModel->count();
557 for (int i = 0; i < num_logs; i++) {
558 QGCOnboardLogEntry *const entry = _logEntriesModel->value<QGCOnboardLogEntry*>(i);
559 if (!entry) {
560 continue;
561 }
562
563 if (entry->selected()) {
564 if (canceled) {
565 entry->setStatus(tr("Canceled"));
566 }
567 entry->setSelected(false);
568 }
569 }
570
571 emit selectionChanged();
572}
573
574void OnboardLogController::_sortEntriesByTimestamp()
575{
576 QObjectList sortedEntries = *_logEntriesModel->objectList();
577 std::stable_sort(sortedEntries.begin(), sortedEntries.end(), [this](const QObject *lhsObj, const QObject *rhsObj) {
578 const QGCOnboardLogEntry *const lhs = qobject_cast<const QGCOnboardLogEntry*>(lhsObj);
579 const QGCOnboardLogEntry *const rhs = qobject_cast<const QGCOnboardLogEntry*>(rhsObj);
580 if (lhs == rhs) {
581 return false;
582 }
583 if (!lhs) {
584 return false;
585 }
586 if (!rhs) {
587 return true;
588 }
589
590 const bool lhsHasTime = lhs->received() && (lhs->time().toSecsSinceEpoch() > 0);
591 const bool rhsHasTime = rhs->received() && (rhs->time().toSecsSinceEpoch() > 0);
592 if (lhsHasTime != rhsHasTime) {
593 // Keep entries with valid timestamps grouped first.
594 return lhsHasTime;
595 }
596
597 if (lhsHasTime && rhsHasTime) {
598 if (lhs->time() == rhs->time()) {
599 return _sortAscending ? (lhs->id() < rhs->id()) : (lhs->id() > rhs->id());
600 }
601
602 return _sortAscending ? (lhs->time() < rhs->time()) : (lhs->time() > rhs->time());
603 }
604
605 // Fallback for entries with missing/invalid time.
606 return _sortAscending ? (lhs->id() < rhs->id()) : (lhs->id() > rhs->id());
607 });
608
609 (void) _logEntriesModel->swapObjectList(sortedEntries);
610}
611
613{
614 if (!_vehicle) {
615 qCWarning(OnboardLogControllerLog) << "Vehicle Unavailable";
616 return;
617 }
618
619 SharedLinkInterfacePtr sharedLink = _vehicle->vehicleLinkManager()->primaryLink().lock();
620 if (!sharedLink) {
621 qCWarning(OnboardLogControllerLog) << "Link Unavailable";
622 return;
623 }
624
625 mavlink_message_t msg{};
626 (void) mavlink_msg_log_erase_pack_chan(
629 sharedLink->mavlinkChannel(),
630 &msg,
631 _vehicle->id(),
632 _vehicle->defaultComponentId()
633 );
634
635 if (!_vehicle->sendMessageOnLinkThreadSafe(sharedLink.get(), msg)) {
636 qCWarning(OnboardLogControllerLog) << "Failed to send";
637 return;
638 }
639
640 refresh();
641}
642
643void OnboardLogController::_requestLogList(uint32_t start, uint32_t end)
644{
645 if (!_vehicle) {
646 qCWarning(OnboardLogControllerLog) << "Vehicle Unavailable";
647 return;
648 }
649
650 SharedLinkInterfacePtr sharedLink = _vehicle->vehicleLinkManager()->primaryLink().lock();
651 if (!sharedLink) {
652 qCWarning(OnboardLogControllerLog) << "Link Unavailable";
653 return;
654 }
655
656 mavlink_message_t msg{};
657 (void) mavlink_msg_log_request_list_pack_chan(
660 sharedLink->mavlinkChannel(),
661 &msg,
662 _vehicle->id(),
663 _vehicle->defaultComponentId(),
664 start,
665 end
666 );
667
668 if (!_vehicle->sendMessageOnLinkThreadSafe(sharedLink.get(), msg)) {
669 qCWarning(OnboardLogControllerLog) << "Failed to send";
670 return;
671 }
672
673 qCDebug(OnboardLogControllerLog) << "Request onboard log entry list (" << start << "through" << end << ")";
674 _setListing(true);
675 _timer->start(kRequestLogListTimeoutMs);
676}
677
678void OnboardLogController::_requestLogData(uint16_t id, uint32_t offset, uint32_t count, int retryCount)
679{
680 if (!_vehicle) {
681 qCWarning(OnboardLogControllerLog) << "Vehicle Unavailable";
682 return;
683 }
684
685 SharedLinkInterfacePtr sharedLink = _vehicle->vehicleLinkManager()->primaryLink().lock();
686 if (!sharedLink) {
687 qCWarning(OnboardLogControllerLog) << "Link Unavailable";
688 return;
689 }
690
691 id += _apmOffset;
692 qCDebug(OnboardLogControllerLog) << "Request log data (id:" << id << "offset:" << offset << "size:" << count << "retryCount" << retryCount << ")";
693
694 mavlink_message_t msg{};
695 (void) mavlink_msg_log_request_data_pack_chan(
698 sharedLink->mavlinkChannel(),
699 &msg,
700 _vehicle->id(),
701 _vehicle->defaultComponentId(),
702 id,
703 offset,
704 count
705 );
706
707 if (!_vehicle->sendMessageOnLinkThreadSafe(sharedLink.get(), msg)) {
708 qCWarning(OnboardLogControllerLog) << "Failed to send";
709 }
710}
711
712void OnboardLogController::_requestLogEnd()
713{
714 if (!_vehicle) {
715 qCWarning(OnboardLogControllerLog) << "Vehicle Unavailable";
716 return;
717 }
718
719 SharedLinkInterfacePtr sharedLink = _vehicle->vehicleLinkManager()->primaryLink().lock();
720 if (!sharedLink) {
721 qCWarning(OnboardLogControllerLog) << "Link Unavailable";
722 return;
723 }
724
725 mavlink_message_t msg{};
726 (void) mavlink_msg_log_request_end_pack_chan(
729 sharedLink->mavlinkChannel(),
730 &msg,
731 _vehicle->id(),
732 _vehicle->defaultComponentId()
733 );
734
735 if (!_vehicle->sendMessageOnLinkThreadSafe(sharedLink.get(), msg)) {
736 qCWarning(OnboardLogControllerLog) << "Failed to send";
737 }
738}
739
740void OnboardLogController::_setDownloading(bool active)
741{
742 if (_downloadingLogs != active) {
743 _downloadingLogs = active;
746 }
747}
748
749void OnboardLogController::_setListing(bool active)
750{
751 if (_requestingLogEntries != active) {
752 _requestingLogEntries = active;
754 if (!active) {
755 _sortEntriesByTimestamp();
756 }
758 }
759}
760
762{
763 if (_compressLogs != compress) {
764 _compressLogs = compress;
765 emit compressLogsChanged();
766 }
767}
768
769bool OnboardLogController::compressLogFile(const QString &logPath)
770{
771 Q_UNUSED(logPath)
772 qCWarning(OnboardLogControllerLog) << "Log compression not yet implemented (decompression-only API)";
773 return false;
774}
775
777{
778 // Not implemented - compression API is decompression-only
779}
780
781void OnboardLogController::_handleCompressionProgress(qreal progress)
782{
783 Q_UNUSED(progress)
784 // Not implemented - compression API is decompression-only
785}
786
787void OnboardLogController::_handleCompressionFinished(bool success)
788{
789 Q_UNUSED(success)
790 // Not implemented - compression API is decompression-only
791}
std::shared_ptr< LinkInterface > SharedLinkInterfacePtr
struct __mavlink_message mavlink_message_t
#define QGC_LOGGING_CATEGORY(name, categoryStr)
QString logSavePath()
QVariant rawValue() const
Value after translation.
Definition Fact.h:85
static int getComponentId()
static MAVLinkProtocol * instance()
int getSystemId() const
static MultiVehicleManager * instance()
void activeVehicleChanged(Vehicle *activeVehicle)
Q_INVOKABLE int selectedCount() const
Q_INVOKABLE void selectAll(bool select)
Q_INVOKABLE void eraseAll()
Q_INVOKABLE void download(const QString &path=QString())
Q_INVOKABLE void toggleSortByDate()
void setCompressLogs(bool compress)
void setSortAscending(bool ascending)
Q_INVOKABLE bool compressLogFile(const QString &logPath)
Compress a single log file.
Q_INVOKABLE void cancelCompression()
Cancel compression.
bool parameterExists(int componentId, const QString &paramName) const
Fact * getParameter(int componentId, const QString &paramName)
static constexpr int defaultComponentId
bool received() const
void setStatus(const QString &stat)
void setSelected(bool sel)
bool selected() const
void setSize(uint size)
void setTime(const QDateTime &date)
void setReceived(bool rec)
QDateTime time() const
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.
QList< QObject * > * objectList()
static SettingsManager * instance()
AppSettings * appSettings() const
WeakLinkInterfacePtr primaryLink() const
void setCommunicationLostEnabled(bool communicationLostEnabled)
VehicleLinkManager * vehicleLinkManager()
Definition Vehicle.h:575
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:1389
int defaultComponentId() const
Definition Vehicle.h:670
ParameterManager * parameterManager()
Definition Vehicle.h:573
void logData(uint32_t ofs, uint16_t id, uint8_t count, const uint8_t *data)
QString bigSizeToString(quint64 size)
Byte size with unit: B, KB, MB, GB, TB. 1 fractional digit above 1 KB.
Definition QGCFormat.cc:20
static const uint32_t kChunkSize