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