9#include <QtCore/QDirIterator>
10#include <QtCore/QFile>
11#include <QtCore/QFileInfo>
12#include <QtCore/QSettings>
13#include <QtNetwork/QNetworkReply>
28 const QFileInfo fi(filePath);
29 _name = fi.baseName();
32 QString sideCar = filePath;
34 const QFileInfo sc(sideCar);
35 _uploaded = sc.exists();
39MAVLinkLogFiles::~MAVLinkLogFiles()
44void MAVLinkLogFiles::setSize(quint32 size)
52void MAVLinkLogFiles::setSelected(
bool selected)
54 if (selected != _selected) {
60void MAVLinkLogFiles::setUploading(
bool uploading)
62 if (uploading != _uploading) {
63 _uploading = uploading;
68void MAVLinkLogFiles::setProgress(qreal progress)
70 if (progress != _progress) {
76void MAVLinkLogFiles::setWriting(
bool writing)
78 if (writing != _writing) {
84void MAVLinkLogFiles::setUploaded(
bool uploaded)
86 if (uploaded != _uploaded) {
108 if (_file.isOpen()) {
115 _fileName = _fileName.asprintf(
117 path.toLatin1().constData(),
119 QDateTime::currentDateTime().toString(
"yyyy-MM-dd-hh-mm-ss-zzz").toLocal8Bit().constData(),
120 manager->logExtension().toLocal8Bit().constData()
123 _file.setFileName(_fileName);
124 if (!_file.open(QIODevice::WriteOnly)) {
125 qCWarning(MAVLinkLogManagerLog) <<
"Failed to open file for writing:" << _file.errorString();
130 _record->setWriting(
true);
136bool MAVLinkLogProcessor::_checkSequence(uint16_t seq,
int &num_drops)
141 if (_sequence == -1) {
146 if (
static_cast<uint16_t
>(_sequence) == seq) {
150 if (seq >
static_cast<uint16_t
>(_sequence)) {
152 if ((seq - _sequence) > kSequenceSize) {
156 num_drops = seq - _sequence - 1;
157 _numDrops += num_drops;
162 if ((_sequence - seq) > kSequenceSize) {
163 num_drops = (1 << 16) - _sequence - 1 + seq;
164 _numDrops += num_drops;
172void MAVLinkLogProcessor::_writeData(
const void *data,
int len)
178 const qint64 bytesWritten = _file.write(
reinterpret_cast<const char*
>(data), len);
179 if (bytesWritten != len) {
181 qCDebug(MAVLinkLogManagerLog) <<
"File IO error:" << len <<
"bytes into" << _fileName;
187 _record->setSize(_written);
191QByteArray MAVLinkLogProcessor::_writeUlogMessage(QByteArray &data)
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()) {
202 _writeData(data.constData(), message_length);
203 (void) data.remove(0, message_length);
215 while (_checkSequence(sequence, num_drops)) {
217 if (data.size() < 16) {
218 qCWarning(MAVLinkLogManagerLog) <<
"Corrupt log header. Canceling log download.";
222 _writeData(data.constData(), 16);
223 (void) data.remove(0, 16);
228 if (_gotHeader && (num_drops > 0)) {
229 if (num_drops > 25) {
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));
241 (void) _writeUlogMessage(_ulogMessage);
242 _ulogMessage.clear();
244 if (first_message == 255) {
248 if (first_message > 0) {
249 (void) data.remove(0, first_message);
254 if ((first_message == 255) && (!_ulogMessage.isEmpty())) {
255 (void) _ulogMessage.append(data);
259 if (_ulogMessage.length()) {
260 _writeData(_ulogMessage.constData(), _ulogMessage.length());
262 _writeData(data.left(first_message).constData(), first_message);
264 _ulogMessage.clear();
268 (void) data.remove(0, first_message);
271 _ulogMessage = _writeUlogMessage(data);
280MAVLinkLogManager::MAVLinkLogManager(
Vehicle *vehicle, QObject *parent)
283 , _networkManager(new QNetworkAccessManager(this))
285 , _ulogExtension(QStringLiteral(
".") +
SettingsManager::instance()->appSettings()->logFileExtension)
288 qCDebug(MAVLinkLogManagerLog) <<
this;
293 settings.beginGroup(kMAVLinkLogGroup);
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());
309 qCWarning(MAVLinkLogManagerLog) <<
"Could not create MAVLink log download path:" << _logPath;
310 _loggingDisabled =
true;
313 if (!_loggingDisabled) {
314 const QString filter =
"*" + _ulogExtension;
315 QDirIterator it(_logPath, QStringList() << filter, QDir::Files);
316 while (it.hasNext()) {
320 qCDebug(MAVLinkLogManagerLog) <<
"MAVLink logs directory:" << _logPath;
321 if (_vehicle->px4Firmware()) {
322 _loggingDenied =
false;
326 emit canStartLogChanged();
331MAVLinkLogManager::~MAVLinkLogManager()
335 qCDebug(MAVLinkLogManagerLog) <<
this;
338void MAVLinkLogManager::setEmailAddress(
const QString &email)
340 if (email != _emailAddress) {
341 _emailAddress = email;
343 settings.beginGroup(kMAVLinkLogGroup);
344 settings.setValue(kEmailAddressKey, email);
349void MAVLinkLogManager::setDescription(
const QString &description)
351 if (description != _description) {
352 _description = description;
354 settings.beginGroup(kMAVLinkLogGroup);
355 settings.setValue(kDescriptionsKey, description);
360void MAVLinkLogManager::setUploadURL(
const QString &url)
362 if (url != _uploadURL) {
363 _uploadURL = url.isEmpty() ? kDefaultPx4URL : url;
366 settings.beginGroup(kMAVLinkLogGroup);
367 settings.setValue(kPx4URLKey, _uploadURL);
372void MAVLinkLogManager::setFeedback(
const QString &fb)
374 if (fb != _feedback) {
380void MAVLinkLogManager::setVideoURL(
const QString &url)
382 if (url != _videoURL) {
385 settings.beginGroup(kMAVLinkLogGroup);
386 settings.setValue(kVideoURLKey, url);
391void MAVLinkLogManager::setEnableAutoUpload(
bool enable)
393 if (enable != _enableAutoUpload) {
394 _enableAutoUpload = enable;
396 settings.beginGroup(kMAVLinkLogGroup);
397 settings.setValue(kEnableAutoUploadKey, enable);
402void MAVLinkLogManager::setEnableAutoStart(
bool enable)
404 if (enable != _enableAutoStart) {
405 _enableAutoStart = enable;
407 settings.beginGroup(kMAVLinkLogGroup);
408 settings.setValue(kEnableAutoStartKey, enable);
413void MAVLinkLogManager::setDeleteAfterUpload(
bool enable)
415 if (enable != _deleteAfterUpload) {
416 _deleteAfterUpload = enable;
418 settings.beginGroup(kMAVLinkLogGroup);
419 settings.setValue(kEnableDeletetKey, enable);
424void MAVLinkLogManager::setWindSpeed(
int speed)
426 if (speed != _windSpeed) {
429 settings.beginGroup(kMAVLinkLogGroup);
430 settings.setValue(kWindSpeedKey, speed);
435void MAVLinkLogManager::setRating(
const QString &rate)
437 if (rate != _rating) {
440 settings.beginGroup(kMAVLinkLogGroup);
441 settings.setValue(kRateKey, rate);
446void MAVLinkLogManager::setPublicLog(
bool pub)
448 if (pub != _publicLog) {
451 settings.beginGroup(kMAVLinkLogGroup);
452 settings.setValue(kPublicLogKey, pub);
457void MAVLinkLogManager::uploadLog()
459 if (_currentLogfile) {
460 _currentLogfile->setUploading(
false);
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";
470 if (!_currentLogfile->selected()) {
475 _currentLogfile->setSelected(
false);
476 if (_currentLogfile->uploaded() || _emailAddress.isEmpty() || _uploadURL.isEmpty()) {
480 _currentLogfile->setUploading(
true);
481 _currentLogfile->setProgress(0.0);
482 const QString filePath = _makeFilename(_currentLogfile->name());
483 (void) _sendLog(filePath);
488 _currentLogfile =
nullptr;
494 const int count = _logFiles->
count();
496 _logFiles->
append(newLog);
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);
508 _logFiles->
append(newLog);
511int MAVLinkLogManager::_getFirstSelected()
const
513 for (
int i = 0; i < _logFiles->
count(); i++) {
514 const MAVLinkLogFiles *
const f = qobject_cast<const MAVLinkLogFiles*>(_logFiles->
get(i));
516 qCWarning(MAVLinkLogManagerLog) <<
"Internal error";
528void MAVLinkLogManager::deleteLog()
531 const int idx = _getFirstSelected();
543 QString filePath = _makeFilename(log->name());
544 QFile gone(filePath);
545 if (!gone.remove()) {
546 qCWarning(MAVLinkLogManagerLog) <<
"Could not delete MAVLink log file:" << _logPath;
550 QFile sgone(filePath);
551 if (sgone.exists()) {
552 (void) sgone.remove();
561void MAVLinkLogManager::cancelUpload()
563 for (
int i = 0; i < _logFiles->
count(); i++) {
566 qCWarning(MAVLinkLogManagerLog) <<
"Internal error";
570 if (pLogFile->selected() && (pLogFile != _currentLogfile)) {
571 pLogFile->setSelected(
false);
575 if (_currentLogfile) {
580void MAVLinkLogManager::startLogging()
582 AppSettings *
const appSettings = SettingsManager::instance()->appSettings();
587 if (!_vehicle || !_vehicle->
px4Firmware() || _loggingDenied) {
591 if (!_createNewLog()) {
600void MAVLinkLogManager::stopLogging()
606 if (!_logProcessor) {
610 _logProcessor->
close();
611 if (_logProcessor->
record()) {
612 _logProcessor->
record()->setWriting(
false);
613 if (_enableAutoUpload) {
614 _logProcessor->
record()->setSelected(
true);
621 delete _logProcessor;
622 _logProcessor =
nullptr;
627QHttpPart MAVLinkLogManager::_createFormPart(QStringView name, QStringView value)
630 formPart.setHeader(QNetworkRequest::ContentDispositionHeader, QStringLiteral(
"form-data; name=\"%1\"").arg(name));
631 formPart.setBody(value.toUtf8());
635bool MAVLinkLogManager::_sendLog(
const QString &logFile)
637 QString defaultDescription = _description;
638 if (_description.isEmpty()) {
639 qCWarning(MAVLinkLogManagerLog) <<
"Log description missing. Using defaults.";
640 defaultDescription = kDefaultDescr;
643 if (_emailAddress.isEmpty()) {
644 qCWarning(MAVLinkLogManagerLog) <<
"User email missing.";
648 if (_uploadURL.isEmpty()) {
649 qCWarning(MAVLinkLogManagerLog) <<
"Upload URL missing.";
653 const QFileInfo fi(logFile);
655 qCWarning(MAVLinkLogManagerLog) <<
"Log file missing:" << logFile;
659 QFile *file =
new QFile(logFile,
this);
660 if (!file || !file->open(QIODevice::ReadOnly)) {
663 qCWarning(MAVLinkLogManagerLog) <<
"Could not open log file:" << logFile;
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");
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);
686 QHttpPart feedbackPart;
687 if (_feedback.isEmpty()) {
688 feedbackPart = _createFormPart(QString(kFeedback), u
"None Given");
690 feedbackPart = _createFormPart(QString(kFeedback), _feedback);
692 multiPart->append(feedbackPart);
695 if(_videoURL.isEmpty()) {
696 videoPart = _createFormPart(QString(kVideoURL), u
"None");
698 videoPart = _createFormPart(QString(kVideoURL), _videoURL);
700 multiPart->append(videoPart);
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);
709 QNetworkRequest request(QUrl::fromUserInput(_uploadURL));
710 request.setAttribute(QNetworkRequest::RedirectPolicyAttribute,
true);
711 QNetworkReply *
const reply = _networkManager->post(request, multiPart);
713 (void) connect(reply, &QNetworkReply::finished,
this, &MAVLinkLogManager::_uploadFinished);
714 (void) connect(reply, &QNetworkReply::uploadProgress,
this, &MAVLinkLogManager::_uploadProgress);
716 if (MAVLinkLogManagerLog().isDebugEnabled()) {
717 (void) connect(reply, &QNetworkReply::readyRead,
this, &MAVLinkLogManager::_dataAvailable);
721 multiPart->setParent(reply);
722 qCDebug(MAVLinkLogManagerLog) <<
"Log" << fi.baseName() <<
"Uploading." << fi.size() <<
"bytes.";
727bool MAVLinkLogManager::_processUploadResponse(
int http_code,
const QByteArray &data)
729 qCDebug(MAVLinkLogManagerLog) <<
"Uploaded response:" << QString::fromUtf8(data);
732 return (http_code == 200);
735void MAVLinkLogManager::_dataAvailable()
737 QNetworkReply *
const reply = qobject_cast<QNetworkReply*>(sender());
742 const QByteArray data = reply->readAll();
743 qCDebug(MAVLinkLogManagerLog) <<
"Uploaded response data:" << QString::fromUtf8(data);
746void MAVLinkLogManager::_uploadFinished()
748 QNetworkReply *
const reply = qobject_cast<QNetworkReply*>(sender());
753 const int http_code = reply->attribute(QNetworkRequest::HttpStatusCodeAttribute).toInt();
754 const QByteArray data = reply->readAll();
756 if (_processUploadResponse(http_code, data)) {
757 qCDebug(MAVLinkLogManagerLog) <<
"Log uploaded.";
759 if (_deleteAfterUpload) {
760 if (_currentLogfile) {
761 _deleteLog(_currentLogfile);
762 _currentLogfile =
nullptr;
764 }
else if (_currentLogfile) {
765 _currentLogfile->setUploaded(
true);
766 QString sideCar = _makeFilename(_currentLogfile->name());
769 QFile file(sideCar.toLatin1().constData());
770 if (file.open(QIODevice::WriteOnly)) {
775 qCWarning(MAVLinkLogManagerLog) << QString(
"Log Upload Error: %1 status: %2").arg(reply->errorString(), reply->attribute(QNetworkRequest::HttpStatusCodeAttribute).toString());
779 reply->deleteLater();
783void MAVLinkLogManager::_uploadProgress(qint64 bytesSent, qint64 bytesTotal)
786 const qreal progress =
static_cast<qreal
>(bytesSent) /
static_cast<qreal
>(bytesTotal);
787 if (_currentLogfile) {
788 _currentLogfile->setProgress(progress);
792 qCDebug(MAVLinkLogManagerLog) << bytesSent <<
"of" << bytesTotal;
795void MAVLinkLogManager::_mavlinkLogData(
Vehicle* , uint8_t , uint8_t , uint16_t sequence, uint8_t first_message,
const QByteArray &data,
bool )
797 if (!_logProcessor || !_logProcessor->
valid()) {
798 qCDebug(MAVLinkLogManagerLog) <<
"MAVLink log data received when not expected.";
806 qCWarning(MAVLinkLogManagerLog) <<
"Error writing MAVLink log file:" << _logProcessor->
fileName();
807 delete _logProcessor;
808 _logProcessor =
nullptr;
814void MAVLinkLogManager::_mavCommandResult(
int vehicleId,
int component,
int command,
int result,
int failureCode)
816 Q_UNUSED(vehicleId); Q_UNUSED(component); Q_UNUSED(failureCode)
818 if ((command != MAV_CMD_LOGGING_START) && (command != MAV_CMD_LOGGING_STOP)) {
822 if (result == MAV_RESULT_ACCEPTED) {
826 if (command == MAV_CMD_LOGGING_STOP) {
827 qCWarning(MAVLinkLogManagerLog) <<
"Stop MAVLink log command failed.";
831 if (result == MAV_RESULT_DENIED) {
832 _loggingDenied =
true;
833 qCWarning(MAVLinkLogManagerLog) <<
"Start MAVLink log command denied.";
835 qCWarning(MAVLinkLogManagerLog) <<
"Start MAVLink log command failed:" << result;
841void MAVLinkLogManager::_discardLog()
844 _logProcessor->
close();
845 if (_logProcessor->
record()) {
846 _deleteLog(_logProcessor->
record());
848 delete _logProcessor;
849 _logProcessor =
nullptr;
856bool MAVLinkLogManager::_createNewLog()
858 delete _logProcessor;
861 if (_logProcessor->
create(
this, _logPath,
static_cast<uint8_t
>(_vehicle->
id()))) {
862 _insertNewLog(_logProcessor->
record());
865 qCWarning(MAVLinkLogManagerLog) <<
"Could not create MAVLink log file:" << _logProcessor->
fileName();
866 delete _logProcessor;
867 _logProcessor =
nullptr;
870 return (_logProcessor !=
nullptr);
873void MAVLinkLogManager::_armedChanged(
bool armed)
880 if (_enableAutoStart) {
886 if (_logRunning && _enableAutoStart) {
891QString MAVLinkLogManager::_makeFilename(
const QString &baseName)
const
893 QString filePath = _logPath;
895 filePath += baseName;
896 filePath += _ulogExtension;
static constexpr const char * kSidecarExtension
#define QGC_LOGGING_CATEGORY(name, categoryStr)
Fact *disableAllPersistence READ disableAllPersistence CONSTANT Fact * disableAllPersistence()
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)
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 * 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.
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)
void mavCommandResult(int vehicleId, int targetComponent, int command, int ackResult, int failureCode)
bool ensureDirectoryExists(const QString &path)
void configureProxy(QNetworkAccessManager *manager)
Set up default proxy configuration on a network manager.