QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
MAVLinkLogManager.cc
Go to the documentation of this file.
1#include "MAVLinkLogManager.h"
2#include "QGCFileHelper.h"
5#include "SettingsManager.h"
6#include "AppSettings.h"
7#include "Vehicle.h"
8
9#include <QtCore/QDirIterator>
10#include <QtCore/QFile>
11#include <QtCore/QFileInfo>
12#include <QtCore/QSettings>
13#include <QtNetwork/QNetworkReply>
14
15#include "QGCNetworkHelper.h"
16
17QGC_LOGGING_CATEGORY(MAVLinkLogManagerLog, "Vehicle.MAVLinkLogManager")
18
19static constexpr const char *kSidecarExtension = ".uploaded";
20
21MAVLinkLogFiles::MAVLinkLogFiles(MAVLinkLogManager *manager, const QString &filePath, bool newFile)
22 : QObject(manager)
23{
24 // qCDebug(MAVLinkLogManagerLog) << Q_FUNC_INFO << this;
25
27
28 const QFileInfo fi(filePath);
29 _name = fi.baseName();
30 if (!newFile) {
31 _size = fi.size();
32 QString sideCar = filePath;
33 sideCar = sideCar.replace(manager->logExtension(), kSidecarExtension);
34 const QFileInfo sc(sideCar);
35 _uploaded = sc.exists();
36 }
37}
38
39MAVLinkLogFiles::~MAVLinkLogFiles()
40{
41 // qCDebug(MAVLinkLogManagerLog) << Q_FUNC_INFO << this;
42}
43
44void MAVLinkLogFiles::setSize(quint32 size)
45{
46 if (size != _size) {
47 _size = size;
48 emit sizeChanged();
49 }
50}
51
52void MAVLinkLogFiles::setSelected(bool selected)
53{
54 if (selected != _selected) {
55 _selected = selected;
56 emit selectedChanged();
57 }
58}
59
60void MAVLinkLogFiles::setUploading(bool uploading)
61{
62 if (uploading != _uploading) {
63 _uploading = uploading;
64 emit uploadingChanged();
65 }
66}
67
68void MAVLinkLogFiles::setProgress(qreal progress)
69{
70 if (progress != _progress) {
71 _progress = progress;
72 emit progressChanged();
73 }
74}
75
76void MAVLinkLogFiles::setWriting(bool writing)
77{
78 if (writing != _writing) {
79 _writing = writing;
80 emit writingChanged();
81 }
82}
83
84void MAVLinkLogFiles::setUploaded(bool uploaded)
85{
86 if (uploaded != _uploaded) {
87 _uploaded = uploaded;
88 emit uploadedChanged();
89 }
90}
91
92/*===========================================================================*/
93
95{
96 // qCDebug(MAVLinkLogManagerLog) << Q_FUNC_INFO << this;
97}
98
100{
101 close();
102
103 // qCDebug(MAVLinkLogManagerLog) << Q_FUNC_INFO << this;
104}
105
107{
108 if (_file.isOpen()) {
109 _file.close();
110 }
111}
112
113bool MAVLinkLogProcessor::create(MAVLinkLogManager *manager, QStringView path, uint8_t id)
114{
115 _fileName = _fileName.asprintf(
116 "%s/%03d-%s%s",
117 path.toLatin1().constData(),
118 id,
119 QDateTime::currentDateTime().toString("yyyy-MM-dd-hh-mm-ss-zzz").toLocal8Bit().constData(),
120 manager->logExtension().toLocal8Bit().constData()
121 );
122
123 _file.setFileName(_fileName);
124 if (!_file.open(QIODevice::WriteOnly)) {
125 qCWarning(MAVLinkLogManagerLog) << "Failed to open file for writing:" << _file.errorString();
126 return false;
127 }
128
129 _record = new MAVLinkLogFiles(manager, _fileName, true);
130 _record->setWriting(true);
131 _sequence = -1;
132
133 return true;
134}
135
136bool MAVLinkLogProcessor::_checkSequence(uint16_t seq, int &num_drops)
137{
138 num_drops = 0;
139 //-- Check if a sequence is newer than the one previously received and if
140 // there were dropped messages between the last one and this.
141 if (_sequence == -1) {
142 _sequence = seq;
143 return true;
144 }
145
146 if (static_cast<uint16_t>(_sequence) == seq) {
147 return false;
148 }
149
150 if (seq > static_cast<uint16_t>(_sequence)) {
151 // Account for wrap-arounds, sequence is 2 bytes
152 if ((seq - _sequence) > kSequenceSize) { // Assume reordered
153 return false;
154 }
155
156 num_drops = seq - _sequence - 1;
157 _numDrops += num_drops;
158 _sequence = seq;
159 return true;
160 }
161
162 if ((_sequence - seq) > kSequenceSize) {
163 num_drops = (1 << 16) - _sequence - 1 + seq;
164 _numDrops += num_drops;
165 _sequence = seq;
166 return true;
167 }
168
169 return false;
170}
171
172void MAVLinkLogProcessor::_writeData(const void *data, int len)
173{
174 if (_error) {
175 return;
176 }
177
178 const qint64 bytesWritten = _file.write(reinterpret_cast<const char*>(data), len);
179 if (bytesWritten != len) {
180 _error = true;
181 qCDebug(MAVLinkLogManagerLog) << "File IO error:" << len << "bytes into" << _fileName;
182 return;
183 }
184
185 _written += len;
186 if (_record) {
187 _record->setSize(_written);
188 }
189}
190
191QByteArray MAVLinkLogProcessor::_writeUlogMessage(QByteArray &data)
192{
193 // Write ulog data w/o integrity checking, assuming data starts with a
194 // valid ulog message. returns the remaining data at the end.
195 while (data.length() > 2) {
196 const uint8_t *const ptr = reinterpret_cast<const uint8_t*>(data.constData());
197 const int message_length = ptr[0] + (ptr[1] * 256) + kUlogMessageHeader;
198 if (message_length > data.length()) {
199 break;
200 }
201
202 _writeData(data.constData(), message_length);
203 (void) data.remove(0, message_length);
204 }
205
206 return data;
207}
208
209bool MAVLinkLogProcessor::processStreamData(uint16_t sequence, uint8_t first_message, const QByteArray &in)
210{
211 int num_drops = 0;
212 _error = false;
213
214 QByteArray data(in);
215 while (_checkSequence(sequence, num_drops)) {
216 if (!_gotHeader) {
217 if (data.size() < 16) {
218 qCWarning(MAVLinkLogManagerLog) << "Corrupt log header. Canceling log download.";
219 return false;
220 }
221
222 _writeData(data.constData(), 16);
223 (void) data.remove(0, 16);
224 _gotHeader = true;
225 // What about data start offset now that we removed 16 bytes off the start?
226 }
227
228 if (_gotHeader && (num_drops > 0)) {
229 if (num_drops > 25) {
230 num_drops = 25;
231 }
232
233 // Write a dropout message. We don't really know the actual duration,
234 // so just use the number of drops * 10 ms
235 const uint8_t duration = static_cast<uint8_t>(num_drops) * 10;
236 const uint8_t bogus[] = {2, 0, 79, duration, 0};
237 _writeData(bogus, sizeof(bogus));
238 }
239
240 if (num_drops > 0) {
241 (void) _writeUlogMessage(_ulogMessage);
242 _ulogMessage.clear();
243
244 if (first_message == 255) {
245 break;
246 }
247
248 if (first_message > 0) {
249 (void) data.remove(0, first_message);
250 first_message = 0;
251 }
252 }
253
254 if ((first_message == 255) && (!_ulogMessage.isEmpty())) {
255 (void) _ulogMessage.append(data);
256 break;
257 }
258
259 if (_ulogMessage.length()) {
260 _writeData(_ulogMessage.constData(), _ulogMessage.length());
261 if (first_message) {
262 _writeData(data.left(first_message).constData(), first_message);
263 }
264 _ulogMessage.clear();
265 }
266
267 if (first_message) {
268 (void) data.remove(0, first_message);
269 }
270
271 _ulogMessage = _writeUlogMessage(data);
272 break;
273 }
274
275 return !_error;
276}
277
278/*===========================================================================*/
279
280MAVLinkLogManager::MAVLinkLogManager(Vehicle *vehicle, QObject *parent)
281 : QObject(parent)
282 , _vehicle(vehicle)
283 , _networkManager(new QNetworkAccessManager(this))
284 , _logFiles(new QmlObjectListModel(this))
285 , _ulogExtension(QStringLiteral(".") + SettingsManager::instance()->appSettings()->logFileExtension)
286 , _logPath(SettingsManager::instance()->appSettings()->logSavePath())
287{
288 qCDebug(MAVLinkLogManagerLog) << this;
289
290 QGCNetworkHelper::configureProxy(_networkManager);
291
292 QSettings settings;
293 settings.beginGroup(kMAVLinkLogGroup);
294
295 setEmailAddress(settings.value(kEmailAddressKey, QString()).toString());
296 setDescription(settings.value(kDescriptionsKey, QString(kDefaultDescr)).toString());
297 setUploadURL(settings.value(kPx4URLKey, QString(kDefaultPx4URL)).toString());
298 setVideoURL(settings.value(kVideoURLKey, QString()).toString());
299 setEnableAutoUpload(settings.value(kEnableAutoUploadKey, true).toBool());
300 setEnableAutoStart(settings.value(kEnableAutoStartKey, false).toBool());
301 setDeleteAfterUpload(settings.value(kEnableDeletetKey, false).toBool());
302 setWindSpeed(settings.value(kWindSpeedKey, -1).toInt());
303 setRating(settings.value(kRateKey, "notset").toString());
304 setPublicLog(settings.value(kPublicLogKey, true).toBool());
305
306 settings.endGroup();
307
309 qCWarning(MAVLinkLogManagerLog) << "Could not create MAVLink log download path:" << _logPath;
310 _loggingDisabled = true;
311 }
312
313 if (!_loggingDisabled) {
314 const QString filter = "*" + _ulogExtension;
315 QDirIterator it(_logPath, QStringList() << filter, QDir::Files);
316 while (it.hasNext()) {
317 _insertNewLog(new MAVLinkLogFiles(this, it.next()));
318 }
319
320 qCDebug(MAVLinkLogManagerLog) << "MAVLink logs directory:" << _logPath;
321 if (_vehicle->px4Firmware()) {
322 _loggingDenied = false;
323 (void) connect(_vehicle, &Vehicle::armedChanged, this, &MAVLinkLogManager::_armedChanged);
324 (void) connect(_vehicle, &Vehicle::mavlinkLogData, this, &MAVLinkLogManager::_mavlinkLogData);
325 (void) connect(_vehicle, &Vehicle::mavCommandResult, this, &MAVLinkLogManager::_mavCommandResult);
326 emit canStartLogChanged();
327 }
328 }
329}
330
331MAVLinkLogManager::~MAVLinkLogManager()
332{
333 _logFiles->clearAndDeleteContents();
334
335 qCDebug(MAVLinkLogManagerLog) << this;
336}
337
338void MAVLinkLogManager::setEmailAddress(const QString &email)
339{
340 if (email != _emailAddress) {
341 _emailAddress = email;
342 QSettings settings;
343 settings.beginGroup(kMAVLinkLogGroup);
344 settings.setValue(kEmailAddressKey, email);
345 emit emailAddressChanged();
346 }
347}
348
349void MAVLinkLogManager::setDescription(const QString &description)
350{
351 if (description != _description) {
352 _description = description;
353 QSettings settings;
354 settings.beginGroup(kMAVLinkLogGroup);
355 settings.setValue(kDescriptionsKey, description);
356 emit descriptionChanged();
357 }
358}
359
360void MAVLinkLogManager::setUploadURL(const QString &url)
361{
362 if (url != _uploadURL) {
363 _uploadURL = url.isEmpty() ? kDefaultPx4URL : url;
364
365 QSettings settings;
366 settings.beginGroup(kMAVLinkLogGroup);
367 settings.setValue(kPx4URLKey, _uploadURL);
368 emit uploadURLChanged();
369 }
370}
371
372void MAVLinkLogManager::setFeedback(const QString &fb)
373{
374 if (fb != _feedback) {
375 _feedback = fb;
376 emit feedbackChanged();
377 }
378}
379
380void MAVLinkLogManager::setVideoURL(const QString &url)
381{
382 if (url != _videoURL) {
383 _videoURL = url;
384 QSettings settings;
385 settings.beginGroup(kMAVLinkLogGroup);
386 settings.setValue(kVideoURLKey, url);
387 emit videoURLChanged();
388 }
389}
390
391void MAVLinkLogManager::setEnableAutoUpload(bool enable)
392{
393 if (enable != _enableAutoUpload) {
394 _enableAutoUpload = enable;
395 QSettings settings;
396 settings.beginGroup(kMAVLinkLogGroup);
397 settings.setValue(kEnableAutoUploadKey, enable);
399 }
400}
401
402void MAVLinkLogManager::setEnableAutoStart(bool enable)
403{
404 if (enable != _enableAutoStart) {
405 _enableAutoStart = enable;
406 QSettings settings;
407 settings.beginGroup(kMAVLinkLogGroup);
408 settings.setValue(kEnableAutoStartKey, enable);
410 }
411}
412
413void MAVLinkLogManager::setDeleteAfterUpload(bool enable)
414{
415 if (enable != _deleteAfterUpload) {
416 _deleteAfterUpload = enable;
417 QSettings settings;
418 settings.beginGroup(kMAVLinkLogGroup);
419 settings.setValue(kEnableDeletetKey, enable);
421 }
422}
423
424void MAVLinkLogManager::setWindSpeed(int speed)
425{
426 if (speed != _windSpeed) {
427 _windSpeed = speed;
428 QSettings settings;
429 settings.beginGroup(kMAVLinkLogGroup);
430 settings.setValue(kWindSpeedKey, speed);
431 emit windSpeedChanged();
432 }
433}
434
435void MAVLinkLogManager::setRating(const QString &rate)
436{
437 if (rate != _rating) {
438 _rating = rate;
439 QSettings settings;
440 settings.beginGroup(kMAVLinkLogGroup);
441 settings.setValue(kRateKey, rate);
442 emit ratingChanged();
443 }
444}
445
446void MAVLinkLogManager::setPublicLog(bool pub)
447{
448 if (pub != _publicLog) {
449 _publicLog = pub;
450 QSettings settings;
451 settings.beginGroup(kMAVLinkLogGroup);
452 settings.setValue(kPublicLogKey, pub);
453 emit publicLogChanged();
454 }
455}
456
457void MAVLinkLogManager::uploadLog()
458{
459 if (_currentLogfile) {
460 _currentLogfile->setUploading(false);
461 }
462
463 for (int i = 0; i < _logFiles->count(); i++) {
464 _currentLogfile = qobject_cast<MAVLinkLogFiles*>(_logFiles->get(i));
465 if (!_currentLogfile) {
466 qCWarning(MAVLinkLogManagerLog) << "Internal error";
467 continue;
468 }
469
470 if (!_currentLogfile->selected()) {
471 continue;
472
473 }
474
475 _currentLogfile->setSelected(false);
476 if (_currentLogfile->uploaded() || _emailAddress.isEmpty() || _uploadURL.isEmpty()) {
477 continue;
478 }
479
480 _currentLogfile->setUploading(true);
481 _currentLogfile->setProgress(0.0);
482 const QString filePath = _makeFilename(_currentLogfile->name());
483 (void) _sendLog(filePath);
484 emit uploadingChanged();
485 return;
486 }
487
488 _currentLogfile = nullptr;
489 emit uploadingChanged();
490}
491
492void MAVLinkLogManager::_insertNewLog(MAVLinkLogFiles *newLog)
493{
494 const int count = _logFiles->count();
495 if (!count) {
496 _logFiles->append(newLog);
497 return;
498 }
499
500 for (int i = 0; i < count; i++) {
501 const MAVLinkLogFiles *const f = qobject_cast<const MAVLinkLogFiles*>(_logFiles->get(i));
502 if (newLog->name() < f->name()) {
503 (void) _logFiles->insert(i, newLog);
504 return;
505 }
506 }
507
508 _logFiles->append(newLog);
509}
510
511int MAVLinkLogManager::_getFirstSelected() const
512{
513 for (int i = 0; i < _logFiles->count(); i++) {
514 const MAVLinkLogFiles *const f = qobject_cast<const MAVLinkLogFiles*>(_logFiles->get(i));
515 if (!f) {
516 qCWarning(MAVLinkLogManagerLog) << "Internal error";
517 continue;
518 }
519
520 if (f->selected()) {
521 return i;
522 }
523 }
524
525 return -1;
526}
527
528void MAVLinkLogManager::deleteLog()
529{
530 while (true) {
531 const int idx = _getFirstSelected();
532 if (idx < 0) {
533 break;
534 }
535
536 MAVLinkLogFiles *const log = qobject_cast<MAVLinkLogFiles*>(_logFiles->get(idx));
537 _deleteLog(log);
538 }
539}
540
541void MAVLinkLogManager::_deleteLog(MAVLinkLogFiles *log)
542{
543 QString filePath = _makeFilename(log->name());
544 QFile gone(filePath);
545 if (!gone.remove()) {
546 qCWarning(MAVLinkLogManagerLog) << "Could not delete MAVLink log file:" << _logPath;
547 }
548
549 filePath.replace(_ulogExtension, kSidecarExtension);
550 QFile sgone(filePath);
551 if (sgone.exists()) {
552 (void) sgone.remove();
553 }
554
555 (void) _logFiles->removeOne(log);
556 delete log;
557
558 emit logFilesChanged();
559}
560
561void MAVLinkLogManager::cancelUpload()
562{
563 for (int i = 0; i < _logFiles->count(); i++) {
564 MAVLinkLogFiles *const pLogFile = qobject_cast<MAVLinkLogFiles*>(_logFiles->get(i));
565 if (!pLogFile) {
566 qCWarning(MAVLinkLogManagerLog) << "Internal error";
567 continue;
568 }
569
570 if (pLogFile->selected() && (pLogFile != _currentLogfile)) {
571 pLogFile->setSelected(false);
572 }
573 }
574
575 if (_currentLogfile) {
576 emit abortUpload();
577 }
578}
579
580void MAVLinkLogManager::startLogging()
581{
582 AppSettings *const appSettings = SettingsManager::instance()->appSettings();
583 if (appSettings->disableAllPersistence()->rawValue().toBool()) {
584 return;
585 }
586
587 if (!_vehicle || !_vehicle->px4Firmware() || _loggingDenied) {
588 return;
589 }
590
591 if (!_createNewLog()) {
592 return;
593 }
594
595 _vehicle->startMavlinkLog();
596 _logRunning = true;
597 emit logRunningChanged();
598}
599
600void MAVLinkLogManager::stopLogging()
601{
602 if (_vehicle && _vehicle->px4Firmware()) {
603 _vehicle->stopMavlinkLog();
604 }
605
606 if (!_logProcessor) {
607 return;
608 }
609
610 _logProcessor->close();
611 if (_logProcessor->record()) {
612 _logProcessor->record()->setWriting(false);
613 if (_enableAutoUpload) {
614 _logProcessor->record()->setSelected(true);
615 if (!uploading()) {
616 uploadLog();
617 }
618 }
619 }
620
621 delete _logProcessor;
622 _logProcessor = nullptr;
623 _logRunning = false;
624 emit logRunningChanged();
625}
626
627QHttpPart MAVLinkLogManager::_createFormPart(QStringView name, QStringView value)
628{
629 QHttpPart formPart;
630 formPart.setHeader(QNetworkRequest::ContentDispositionHeader, QStringLiteral("form-data; name=\"%1\"").arg(name));
631 formPart.setBody(value.toUtf8());
632 return formPart;
633}
634
635bool MAVLinkLogManager::_sendLog(const QString &logFile)
636{
637 QString defaultDescription = _description;
638 if (_description.isEmpty()) {
639 qCWarning(MAVLinkLogManagerLog) << "Log description missing. Using defaults.";
640 defaultDescription = kDefaultDescr;
641 }
642
643 if (_emailAddress.isEmpty()) {
644 qCWarning(MAVLinkLogManagerLog) << "User email missing.";
645 return false;
646 }
647
648 if (_uploadURL.isEmpty()) {
649 qCWarning(MAVLinkLogManagerLog) << "Upload URL missing.";
650 return false;
651 }
652
653 const QFileInfo fi(logFile);
654 if (!fi.exists()) {
655 qCWarning(MAVLinkLogManagerLog) << "Log file missing:" << logFile;
656 return false;
657 }
658
659 QFile *file = new QFile(logFile, this);
660 if (!file || !file->open(QIODevice::ReadOnly)) {
661 delete file;
662 file = nullptr;
663 qCWarning(MAVLinkLogManagerLog) << "Could not open log file:" << logFile;
664 return false;
665 }
666
667 QHttpMultiPart *const multiPart = new QHttpMultiPart(QHttpMultiPart::FormDataType);
668 const QHttpPart emailPart = _createFormPart(u"email", _emailAddress);
669 const QHttpPart descriptionPart = _createFormPart(u"description", _description);
670 const QHttpPart sourcePart = _createFormPart(u"source", u"QGroundControl");
671 const QHttpPart versionPart = _createFormPart(u"version", QCoreApplication::applicationVersion());
672 const QHttpPart typePart = _createFormPart(u"type", u"flightreport");
673 const QHttpPart windPart = _createFormPart(u"windSpeed", QString::number(_windSpeed));
674 const QHttpPart ratingPart = _createFormPart(u"rating", _rating);
675 const QHttpPart publicPart = _createFormPart(u"public", _publicLog ? u"true" : u"false");
676
677 multiPart->append(emailPart);
678 multiPart->append(descriptionPart);
679 multiPart->append(sourcePart);
680 multiPart->append(versionPart);
681 multiPart->append(typePart);
682 multiPart->append(windPart);
683 multiPart->append(ratingPart);
684 multiPart->append(publicPart);
685
686 QHttpPart feedbackPart;
687 if (_feedback.isEmpty()) {
688 feedbackPart = _createFormPart(QString(kFeedback), u"None Given");
689 } else {
690 feedbackPart = _createFormPart(QString(kFeedback), _feedback);
691 }
692 multiPart->append(feedbackPart);
693
694 QHttpPart videoPart;
695 if(_videoURL.isEmpty()) {
696 videoPart = _createFormPart(QString(kVideoURL), u"None");
697 } else {
698 videoPart = _createFormPart(QString(kVideoURL), _videoURL);
699 }
700 multiPart->append(videoPart);
701
702 QHttpPart logPart;
703 logPart.setHeader(QNetworkRequest::ContentTypeHeader, "application/octet-stream");
704 logPart.setHeader(QNetworkRequest::ContentDispositionHeader, QStringLiteral("form-data; name=\"filearg\"; filename=\"%1\"").arg(fi.fileName()));
705 logPart.setBodyDevice(file);
706 multiPart->append(logPart);
707 file->setParent(multiPart);
708
709 QNetworkRequest request(QUrl::fromUserInput(_uploadURL));
710 request.setAttribute(QNetworkRequest::RedirectPolicyAttribute, true);
711 QNetworkReply *const reply = _networkManager->post(request, multiPart);
712 (void) connect(this, &MAVLinkLogManager::abortUpload, reply, &QNetworkReply::abort);
713 (void) connect(reply, &QNetworkReply::finished, this, &MAVLinkLogManager::_uploadFinished);
714 (void) connect(reply, &QNetworkReply::uploadProgress, this, &MAVLinkLogManager::_uploadProgress);
715#ifdef QT_DEBUG
716 if (MAVLinkLogManagerLog().isDebugEnabled()) {
717 (void) connect(reply, &QNetworkReply::readyRead, this, &MAVLinkLogManager::_dataAvailable);
718 }
719#endif
720
721 multiPart->setParent(reply);
722 qCDebug(MAVLinkLogManagerLog) << "Log" << fi.baseName() << "Uploading." << fi.size() << "bytes.";
723
724 return true;
725}
726
727bool MAVLinkLogManager::_processUploadResponse(int http_code, const QByteArray &data)
728{
729 qCDebug(MAVLinkLogManagerLog) << "Uploaded response:" << QString::fromUtf8(data);
730 emit readyRead(data);
731
732 return (http_code == 200);
733}
734
735void MAVLinkLogManager::_dataAvailable()
736{
737 QNetworkReply *const reply = qobject_cast<QNetworkReply*>(sender());
738 if (!reply) {
739 return;
740 }
741
742 const QByteArray data = reply->readAll();
743 qCDebug(MAVLinkLogManagerLog) << "Uploaded response data:" << QString::fromUtf8(data);
744}
745
746void MAVLinkLogManager::_uploadFinished()
747{
748 QNetworkReply *const reply = qobject_cast<QNetworkReply*>(sender());
749 if (!reply) {
750 return;
751 }
752
753 const int http_code = reply->attribute(QNetworkRequest::HttpStatusCodeAttribute).toInt();
754 const QByteArray data = reply->readAll();
755
756 if (_processUploadResponse(http_code, data)) {
757 qCDebug(MAVLinkLogManagerLog) << "Log uploaded.";
758 emit succeed();
759 if (_deleteAfterUpload) {
760 if (_currentLogfile) {
761 _deleteLog(_currentLogfile);
762 _currentLogfile = nullptr;
763 }
764 } else if (_currentLogfile) {
765 _currentLogfile->setUploaded(true);
766 QString sideCar = _makeFilename(_currentLogfile->name());
767 (void) sideCar.replace(_ulogExtension, kSidecarExtension);
768
769 QFile file(sideCar.toLatin1().constData());
770 if (file.open(QIODevice::WriteOnly)) {
771 file.close();
772 }
773 }
774 } else {
775 qCWarning(MAVLinkLogManagerLog) << QString("Log Upload Error: %1 status: %2").arg(reply->errorString(), reply->attribute(QNetworkRequest::HttpStatusCodeAttribute).toString());
776 emit failed();
777 }
778
779 reply->deleteLater();
780 uploadLog();
781}
782
783void MAVLinkLogManager::_uploadProgress(qint64 bytesSent, qint64 bytesTotal)
784{
785 if (bytesTotal) {
786 const qreal progress = static_cast<qreal>(bytesSent) / static_cast<qreal>(bytesTotal);
787 if (_currentLogfile) {
788 _currentLogfile->setProgress(progress);
789 }
790 }
791
792 qCDebug(MAVLinkLogManagerLog) << bytesSent << "of" << bytesTotal;
793}
794
795void MAVLinkLogManager::_mavlinkLogData(Vehicle* /*vehicle*/, uint8_t /*target_system*/, uint8_t /*target_component*/, uint16_t sequence, uint8_t first_message, const QByteArray &data, bool /*acked*/)
796{
797 if (!_logProcessor || !_logProcessor->valid()) {
798 qCDebug(MAVLinkLogManagerLog) << "MAVLink log data received when not expected.";
799 return;
800 }
801
802 if (_logProcessor->processStreamData(sequence, first_message, data)) {
803 return;
804 }
805
806 qCWarning(MAVLinkLogManagerLog) << "Error writing MAVLink log file:" << _logProcessor->fileName();
807 delete _logProcessor;
808 _logProcessor = nullptr;
809 _logRunning = false;
810 _vehicle->stopMavlinkLog();
811 emit logRunningChanged();
812}
813
814void MAVLinkLogManager::_mavCommandResult(int vehicleId, int component, int command, int result, int failureCode)
815{
816 Q_UNUSED(vehicleId); Q_UNUSED(component); Q_UNUSED(failureCode)
817
818 if ((command != MAV_CMD_LOGGING_START) && (command != MAV_CMD_LOGGING_STOP)) {
819 return;
820 }
821
822 if (result == MAV_RESULT_ACCEPTED) {
823 return;
824 }
825
826 if (command == MAV_CMD_LOGGING_STOP) {
827 qCWarning(MAVLinkLogManagerLog) << "Stop MAVLink log command failed.";
828 return;
829 }
830
831 if (result == MAV_RESULT_DENIED) {
832 _loggingDenied = true;
833 qCWarning(MAVLinkLogManagerLog) << "Start MAVLink log command denied.";
834 } else {
835 qCWarning(MAVLinkLogManagerLog) << "Start MAVLink log command failed:" << result;
836 }
837
838 _discardLog();
839}
840
841void MAVLinkLogManager::_discardLog()
842{
843 if (_logProcessor) {
844 _logProcessor->close();
845 if (_logProcessor->record()) {
846 _deleteLog(_logProcessor->record());
847 }
848 delete _logProcessor;
849 _logProcessor = nullptr;
850 }
851
852 _logRunning = false;
853 emit logRunningChanged();
854}
855
856bool MAVLinkLogManager::_createNewLog()
857{
858 delete _logProcessor;
859 _logProcessor = new MAVLinkLogProcessor();
860
861 if (_logProcessor->create(this, _logPath, static_cast<uint8_t>(_vehicle->id()))) {
862 _insertNewLog(_logProcessor->record());
863 emit logFilesChanged();
864 } else {
865 qCWarning(MAVLinkLogManagerLog) << "Could not create MAVLink log file:" << _logProcessor->fileName();
866 delete _logProcessor;
867 _logProcessor = nullptr;
868 }
869
870 return (_logProcessor != nullptr);
871}
872
873void MAVLinkLogManager::_armedChanged(bool armed)
874{
875 if (!_vehicle || !_vehicle->px4Firmware()) {
876 return;
877 }
878
879 if (armed) {
880 if (_enableAutoStart) {
881 startLogging();
882 }
883 return;
884 }
885
886 if (_logRunning && _enableAutoStart) {
887 stopLogging();
888 }
889}
890
891QString MAVLinkLogManager::_makeFilename(const QString &baseName) const
892{
893 QString filePath = _logPath;
894 filePath += "/";
895 filePath += baseName;
896 filePath += _ulogExtension;
897 return filePath;
898}
static constexpr const char * kSidecarExtension
#define QGC_LOGGING_CATEGORY(name, categoryStr)
Application Settings.
Definition AppSettings.h:9
Fact *disableAllPersistence READ disableAllPersistence CONSTANT Fact * disableAllPersistence()
void uploadingChanged()
void writingChanged()
void selectedChanged()
void progressChanged()
void uploadedChanged()
void logRunningChanged()
void enableAutoUploadChanged()
void selectedCountChanged()
void readyRead(const QByteArray &data)
void emailAddressChanged()
void descriptionChanged()
void deleteAfterUploadChanged()
void enableAutoStartChanged()
bool create(MAVLinkLogManager *manager, QStringView path, uint8_t id)
QString fileName() const
bool processStreamData(uint16_t _sequence, uint8_t first_message, const QByteArray &in)
MAVLinkLogFiles * record()
void append(QObject *object)
Caller maintains responsibility for object ownership and deletion.
QObject * get(int index)
QObject * removeOne(const QObject *object) override final
int count() const override final
void clearAndDeleteContents() override final
Clears the list and calls deleteLater on each entry.
void insert(int index, QObject *object)
Provides access to all app settings.
bool px4Firmware() const
Definition Vehicle.h:495
void armedChanged(bool armed)
void mavlinkLogData(Vehicle *vehicle, uint8_t target_system, uint8_t target_component, uint16_t sequence, uint8_t first_message, QByteArray data, bool acked)
int id() const
Definition Vehicle.h:425
void stopMavlinkLog()
Definition Vehicle.cc:3376
void mavCommandResult(int vehicleId, int targetComponent, int command, int ackResult, int failureCode)
void startMavlinkLog()
Definition Vehicle.cc:3371
bool ensureDirectoryExists(const QString &path)
void configureProxy(QNetworkAccessManager *manager)
Set up default proxy configuration on a network manager.