10#include <QtConcurrent/QtConcurrent>
12#include <QtCore/QDirIterator>
13#include <QtCore/QFile>
14#include <QtCore/QFileInfo>
15#include <QtCore/QMimeDatabase>
16#include <QtCore/QMultiMap>
17#include <QtCore/QMutexLocker>
25const QStringList kImageExtensionFilters = {
26 QStringLiteral(
"*.jpg"), QStringLiteral(
"*.JPG"),
27 QStringLiteral(
"*.jpeg"), QStringLiteral(
"*.JPEG"),
28 QStringLiteral(
"*.tiff"), QStringLiteral(
"*.TIFF"),
29 QStringLiteral(
"*.tif"), QStringLiteral(
"*.TIF"),
30 QStringLiteral(
"*.dng"), QStringLiteral(
"*.DNG")
34const QSet<QString> kSupportedMimeTypes = {
35 QStringLiteral(
"image/jpeg"),
36 QStringLiteral(
"image/tiff"),
37 QStringLiteral(
"image/x-adobe-dng"),
38 QStringLiteral(
"image/x-dcraw")
42bool isSupportedImageMimeType(
const QMimeType &mimeType)
44 if (kSupportedMimeTypes.contains(mimeType.name())) {
49 for (
const QString &parent : mimeType.parentMimeTypes()) {
50 if (kSupportedMimeTypes.contains(parent)) {
56 if (mimeType.name() == QStringLiteral(
"application/octet-stream") ||
57 mimeType.name().startsWith(QStringLiteral(
"application/"))) {
65double calculateStageProgress(
double stageStart,
double stageEnd,
int completed,
int total)
70 return stageStart + (stageEnd - stageStart) * completed / total;
79const char* GeoTagController::stageName(Stage stage)
82 case Stage::Idle:
return "Idle";
83 case Stage::LoadingImages:
return "LoadingImages";
84 case Stage::ParsingExif:
return "ParsingExif";
85 case Stage::ParsingLogs:
return "ParsingLogs";
86 case Stage::Calibrating:
return "Calibrating";
87 case Stage::TaggingImages:
return "TaggingImages";
88 case Stage::Finished:
return "Finished";
98 const QList<GeoTagData> &triggers,
99 qint64 timeOffsetSecs,
100 qint64 toleranceSecs)
104 if (triggers.isEmpty() || imageTimestamps.isEmpty()) {
110 const qint64 lastImageTimestamp = imageTimestamps.last() + timeOffsetSecs;
111 const qint64 lastTriggerTimestamp = triggers.last().timestamp;
116 QMultiMap<qint64, int> imageOffsets;
117 QSet<int> invalidImageIndices;
118 for (
int i = 0; i < imageTimestamps.size(); ++i) {
119 if (imageTimestamps[i] == 0) {
120 invalidImageIndices.insert(i);
123 const qint64 adjustedTimestamp = imageTimestamps[i] + timeOffsetSecs;
124 const qint64 offset = lastImageTimestamp - adjustedTimestamp;
125 imageOffsets.insert(offset, i);
129 QSet<int> usedImageIndices;
131 for (
int triggerIdx = 0; triggerIdx < triggers.size(); ++triggerIdx) {
132 const GeoTagData &trigger = triggers[triggerIdx];
138 const qint64 triggerOffset = lastTriggerTimestamp - trigger.
timestamp;
141 int bestImageIdx = -1;
142 qint64 bestDiff = toleranceSecs + 1;
145 auto it = imageOffsets.lowerBound(triggerOffset - toleranceSecs);
147 while (it != imageOffsets.end() && it.key() <= triggerOffset + toleranceSecs) {
148 const qint64 diff = qAbs(it.key() - triggerOffset);
149 if (diff <= toleranceSecs && diff < bestDiff && !usedImageIndices.contains(it.value())) {
151 bestImageIdx = it.value();
156 if (bestImageIdx >= 0) {
159 usedImageIndices.insert(bestImageIdx);
164 for (
int i = 0; i < imageTimestamps.size(); ++i) {
165 if (!usedImageIndices.contains(i)) {
181 qCDebug(GeoTagControllerLog) <<
this;
184 (void) connect(&_exifWatcher, &QFutureWatcher<ExifResult>::progressValueChanged,
185 this, &GeoTagController::_onExifProgress);
186 (void) connect(&_exifWatcher, &QFutureWatcher<ExifResult>::finished,
187 this, &GeoTagController::_onExifFinished);
190 (void) connect(&_tagWatcher, &QFutureWatcher<TagResult>::progressValueChanged,
191 this, &GeoTagController::_onTagProgress);
192 (void) connect(&_tagWatcher, &QFutureWatcher<TagResult>::finished,
193 this, &GeoTagController::_onTagFinished);
198 qCDebug(GeoTagControllerLog) <<
this;
202 _exifWatcher.waitForFinished();
203 _tagWatcher.waitForFinished();
210 if (path.isEmpty()) {
211 _setErrorMessage(tr(
"Empty Filename."));
215 const QFileInfo logFileInfo(path);
216 if (!logFileInfo.exists() || !logFileInfo.isFile()) {
217 _setErrorMessage(tr(
"Invalid Filename."));
221 if (_logFile != path) {
226 _setErrorMessage(QString());
233 if (path.isEmpty()) {
234 _setErrorMessage(tr(
"Invalid Directory."));
238 const QFileInfo imageDirectoryInfo(path);
239 if (!imageDirectoryInfo.exists() || !imageDirectoryInfo.isDir()) {
240 _setErrorMessage(tr(
"Invalid Directory."));
244 if (_imageDirectory != path) {
245 _imageDirectory = path;
249 if (_saveDirectory.isEmpty()) {
252 _setErrorMessage(tr(
"Images have already been tagged. Existing images will be removed."));
257 _setErrorMessage(QString());
264 if (path.isEmpty()) {
265 _setErrorMessage(tr(
"Invalid Directory."));
269 const QFileInfo saveDirectoryInfo(path);
270 if (!saveDirectoryInfo.exists() || !saveDirectoryInfo.isDir()) {
271 _setErrorMessage(tr(
"Invalid Directory."));
275 if (_saveDirectory != path) {
276 _saveDirectory = path;
281 saveDir.setFilter(QDir::Files | QDir::Readable | QDir::NoSymLinks | QDir::Writable);
282 saveDir.setNameFilters(kImageExtensionFilters);
284 if (!saveDir.entryList().isEmpty()) {
285 _setErrorMessage(tr(
"The save folder already contains images."));
289 _setErrorMessage(QString());
294 if (!qFuzzyCompare(_timeOffsetSecs, offset)) {
295 _timeOffsetSecs = offset;
303 tolerance = qBound(0.1, tolerance, 60.0);
304 if (!qFuzzyCompare(_toleranceSecs, tolerance)) {
305 _toleranceSecs = tolerance;
312 if (_previewMode != preview) {
313 _previewMode = preview;
320 if (_recursiveScan != recursive) {
321 _recursiveScan = recursive;
326void GeoTagController::_setErrorMessage(
const QString &errorMsg)
328 if (errorMsg != _errorMessage) {
329 _errorMessage = errorMsg;
334void GeoTagController::_setProgress(
double progress)
349 qCWarning(GeoTagControllerLog) <<
"Tagging already in progress";
353 _setErrorMessage(QString());
360 if (_imageDirectory.isEmpty()) {
361 _setErrorMessage(tr(
"Please select an image directory."));
365 if (_logFile.isEmpty()) {
366 _setErrorMessage(tr(
"Please select a log file."));
371 _setErrorMessage(tr(
"Cannot find the image directory."));
376 _setErrorMessage(tr(
"Cannot find the save directory."));
387 _transitionTo(Stage::LoadingImages);
399 if (_exifWatcher.isRunning()) {
400 _exifWatcher.cancel();
402 if (_tagWatcher.isRunning()) {
403 _tagWatcher.cancel();
406 _finishWithError(tr(
"Tagging cancelled"));
409void GeoTagController::_transitionTo(Stage stage)
411 if (_cancel && stage != Stage::Idle && stage != Stage::Finished) {
412 _finishWithError(tr(
"Tagging cancelled"));
419 qCDebug(GeoTagControllerLog) <<
"Transitioning to stage:" << stageName(stage);
424 case Stage::LoadingImages:
428 case Stage::ParsingExif:
431 case Stage::ParsingLogs:
434 case Stage::Calibrating:
437 case Stage::TaggingImages:
440 case Stage::Finished:
446void GeoTagController::_finishWithError(
const QString &errorMsg)
448 qCDebug(GeoTagControllerLog) <<
"Finishing with error:" << errorMsg;
449 qCDebug(GeoTagControllerLog) <<
"Total processing time:" << _totalTimer.elapsed() <<
"ms";
452 _stage = Stage::Idle;
453 _setErrorMessage(errorMsg);
457void GeoTagController::_finishSuccess()
459 qCDebug(GeoTagControllerLog) <<
"Finishing successfully";
460 qCDebug(GeoTagControllerLog) <<
"Total processing time:" << _totalTimer.elapsed() <<
"ms";
463 _stage = Stage::Idle;
465 const auto matchedCount = std::min(_state.imageIndices.count(), _state.triggerIndices.count());
466 _taggedCount =
static_cast<int>(matchedCount) - _state.failedCount;
467 _skippedCount = _state.skippedCount;
468 _failedCount = _state.failedCount;
474 if (_state.failedCount > 0) {
475 _setErrorMessage(tr(
"%1 image(s) failed to tag").arg(_state.failedCount));
483void GeoTagController::_startLoadImages()
486 if (!_loadImages(errorMsg)) {
487 _finishWithError(errorMsg);
491 qCDebug(GeoTagControllerLog) <<
"Stage: loadImages took" << _stageTimer.elapsed() <<
"ms";
492 _setProgress(kLoadImagesEnd);
493 _transitionTo(Stage::ParsingExif);
496void GeoTagController::_startParseExif()
499 QFuture<ExifResult> future = QtConcurrent::mapped(_state.imageList,
500 [
this](
const QFileInfo &info) { return _parseExifForImage(info); });
502 _exifWatcher.setFuture(future);
506void GeoTagController::_onExifProgress(
int value)
508 const int total = _state.imageList.size();
509 const double progress = calculateStageProgress(kLoadImagesEnd, kParseExifEnd, value, total);
513void GeoTagController::_onExifFinished()
515 qCDebug(GeoTagControllerLog) <<
"Stage: parseExif took" << _stageTimer.elapsed() <<
"ms";
518 _finishWithError(tr(
"Tagging cancelled"));
523 _state.imageTimestamps.clear();
524 _state.imageTimestamps.reserve(_state.imageList.size());
526 const QList<ExifResult> results = _exifWatcher.future().results();
527 QList<int> failedIndices;
529 for (
int i = 0; i < results.size(); ++i) {
530 const ExifResult &result = results[i];
531 if (result.success) {
532 _state.imageTimestamps.append(result.timestamp);
535 failedIndices.append(i);
536 _state.imageTimestamps.append(0);
537 qCWarning(GeoTagControllerLog) <<
"Skipping image with EXIF error:" << result.errorMessage;
542 for (
int idx : failedIndices) {
543 if (idx < _state.imageList.size()) {
545 tr(
"Could not read EXIF timestamp"));
547 ++_state.skippedCount;
550 if (failedIndices.size() == results.size()) {
551 _finishWithError(tr(
"Could not read EXIF data from any images"));
555 if (!failedIndices.isEmpty()) {
556 qCDebug(GeoTagControllerLog) <<
"Skipped" << failedIndices.size() <<
"images with EXIF errors";
559 _setProgress(kParseExifEnd);
560 _transitionTo(Stage::ParsingLogs);
563void GeoTagController::_startParseLogs()
566 if (!_parseLogs(errorMsg)) {
567 _finishWithError(errorMsg);
571 qCDebug(GeoTagControllerLog) <<
"Stage: parseLogs took" << _stageTimer.elapsed() <<
"ms";
572 _setProgress(kParseLogsEnd);
573 _transitionTo(Stage::Calibrating);
576void GeoTagController::_startCalibrate()
579 if (!_calibrate(errorMsg)) {
580 _finishWithError(errorMsg);
585 _evictUnmatchedImages();
587 qCDebug(GeoTagControllerLog) <<
"Stage: calibrate took" << _stageTimer.elapsed() <<
"ms";
588 _setProgress(kCalibrateEnd);
589 _transitionTo(Stage::TaggingImages);
592void GeoTagController::_startTagImages()
594 const bool preview = _previewMode;
595 const QString outputDir = _saveDirectory.isEmpty()
602 if (!preview && !_validateOutputDirectory(outputDir, errorMsg)) {
603 _finishWithError(errorMsg);
608 QList<TagTask> tagTasks = _buildTagTasks(outputDir, preview, errorMsg);
609 if (tagTasks.isEmpty()) {
610 if (!errorMsg.isEmpty()) {
611 _finishWithError(errorMsg);
613 _transitionTo(Stage::Finished);
619 for (
const TagTask &task : tagTasks) {
624 QFuture<TagResult> future = QtConcurrent::mapped(tagTasks,
625 [
this](
const TagTask &task) {
return _tagImage(task); });
627 _tagWatcher.setFuture(future);
631void GeoTagController::_onTagProgress(
int value)
633 const int total = _tagWatcher.progressMaximum();
634 const double progress = calculateStageProgress(kCalibrateEnd, kTagImagesEnd, value, total);
638void GeoTagController::_onTagFinished()
640 qCDebug(GeoTagControllerLog) <<
"Stage: tagImages took" << _stageTimer.elapsed() <<
"ms";
643 _finishWithError(tr(
"Tagging cancelled"));
648 const QList<TagResult> results = _tagWatcher.future().results();
650 for (
const TagResult &result : results) {
651 if (result.success) {
653 _imageModel->
setCoordinate(result.imageIndex, result.coordinate);
656 ++_state.failedCount;
657 qCWarning(GeoTagControllerLog) <<
"Failed to tag image:" << result.fileName <<
"-" << result.errorMessage;
662 if (_state.failedCount > 0 && _state.failedCount == results.count()) {
663 _finishWithError(tr(
"All images failed to tag"));
667 _transitionTo(Stage::Finished);
674bool GeoTagController::_loadImages(QString &errorMsg)
676 _state.imageList.clear();
679 QFileInfoList candidateFiles;
680 QDirIterator::IteratorFlags flags = QDirIterator::NoIteratorFlags;
681 if (_recursiveScan) {
682 flags = QDirIterator::Subdirectories;
685 QDirIterator it(_imageDirectory, kImageExtensionFilters,
686 QDir::Files | QDir::Readable | QDir::NoSymLinks, flags);
687 while (it.hasNext()) {
689 candidateFiles.append(it.fileInfo());
693 std::sort(candidateFiles.begin(), candidateFiles.end(),
694 [](
const QFileInfo &a,
const QFileInfo &b) { return a.fileName() < b.fileName(); });
696 if (candidateFiles.isEmpty()) {
697 errorMsg = tr(
"The image directory doesn't contain supported images. Supported formats: JPEG, TIFF, DNG");
702 static const QMimeDatabase mimeDb;
703 for (
const QFileInfo &fileInfo : candidateFiles) {
704 const QMimeType mimeType = mimeDb.mimeTypeForFile(fileInfo);
705 if (isSupportedImageMimeType(mimeType)) {
706 _state.imageList.append(fileInfo);
708 qCDebug(GeoTagControllerLog) <<
"Skipping misnamed file:" << fileInfo.fileName()
709 <<
"MIME:" << mimeType.name();
713 if (_state.imageList.isEmpty()) {
714 errorMsg = tr(
"The image directory doesn't contain supported images. Supported formats: JPEG, TIFF, DNG");
719 _imageModel->
clear();
720 for (
const QFileInfo &info : _state.imageList) {
721 _imageModel->
addImage(info.absoluteFilePath());
724 qCDebug(GeoTagControllerLog) <<
"Found" << _state.imageList.count() <<
"images"
725 << (_recursiveScan ?
"(recursive)" :
"");
730GeoTagController::ExifResult GeoTagController::_parseExifForImage(
const QFileInfo &imageInfo)
733 result.success =
false;
736 result.errorMessage = tr(
"Tagging cancelled");
741 const QByteArray imageBuffer = _readImageCached(imageInfo.absoluteFilePath(), &
errorString);
742 if (imageBuffer.isEmpty()) {
743 result.errorMessage = tr(
"Geotagging failed. Couldn't open image: %1").arg(imageInfo.fileName());
748 if (!imageTime.isValid()) {
749 result.errorMessage = tr(
"Geotagging failed. Couldn't extract time from image: %1").arg(imageInfo.fileName());
753 result.timestamp = imageTime.toSecsSinceEpoch();
754 result.success =
true;
758bool GeoTagController::_parseLogs(QString &errorMsg)
760 _state.triggerList.clear();
763 if (!
logFile.open(QIODevice::ReadOnly)) {
764 errorMsg = tr(
"Geotagging failed. Couldn't open log file.");
768 const qint64 fileSize =
logFile.size();
770 errorMsg = tr(
"Geotagging failed. Log file is empty.");
775 const uchar *mappedData =
logFile.map(0, fileSize);
776 const char *data =
nullptr;
777 qint64 dataSize = fileSize;
778 QByteArray fallbackBuffer;
781 data =
reinterpret_cast<const char*
>(mappedData);
782 qCDebug(GeoTagControllerLog) <<
"Memory-mapped log file:" << fileSize <<
"bytes";
785 qCDebug(GeoTagControllerLog) <<
"Memory mapping failed, reading file into memory";
786 fallbackBuffer =
logFile.readAll();
787 if (fallbackBuffer.isEmpty()) {
788 errorMsg = tr(
"Geotagging failed. Couldn't read log file.");
791 data = fallbackBuffer.constData();
792 dataSize = fallbackBuffer.size();
796 const QString logFileLower = _logFile.toLower();
797 bool parseSuccess =
false;
800 if (logFileLower.endsWith(QStringLiteral(
".bin"))) {
801 qCDebug(GeoTagControllerLog) <<
"Parsing DataFlash log:" << _logFile;
803 }
else if (logFileLower.endsWith(QStringLiteral(
".ulg"))) {
804 qCDebug(GeoTagControllerLog) <<
"Parsing ULog:" << _logFile;
808 qCDebug(GeoTagControllerLog) <<
"Unknown extension, trying ULog parser first";
811 qCDebug(GeoTagControllerLog) <<
"ULog failed, trying DataFlash parser";
819 logFile.unmap(
const_cast<uchar*
>(mappedData));
827 qCDebug(GeoTagControllerLog) <<
"Found" << _state.triggerList.count() <<
"camera capture events";
829 if (_state.imageList.count() > _state.triggerList.count()) {
830 qCDebug(GeoTagControllerLog) <<
"Detected missing feedback packets:"
831 << (_state.imageList.count() - _state.triggerList.count()) <<
"images without triggers";
832 }
else if (_state.imageList.count() < _state.triggerList.count()) {
833 qCDebug(GeoTagControllerLog) <<
"Detected missing image frames:"
834 << (_state.triggerList.count() - _state.imageList.count()) <<
"triggers without images";
840bool GeoTagController::_calibrate(QString &errorMsg)
842 _state.imageIndices.clear();
843 _state.triggerIndices.clear();
844 _state.skippedCount = 0;
846 if (_state.triggerList.isEmpty() || _state.imageTimestamps.isEmpty()) {
847 errorMsg = tr(
"Calibration failed: No triggers or images available.");
852 const qint64 timeOffsetSec =
static_cast<qint64
>(_timeOffsetSecs);
853 const qint64 toleranceSec =
static_cast<qint64
>(_toleranceSecs);
855 _state.imageTimestamps, _state.triggerList, timeOffsetSec, toleranceSec);
862 qCDebug(GeoTagControllerLog) <<
"Calibration complete:"
863 << _state.imageIndices.count() <<
"matched,"
864 << _state.skippedCount <<
"skipped (invalid),"
869 for (
int idx : calibration.unmatchedImages) {
875 if (_state.imageIndices.isEmpty()) {
876 errorMsg = tr(
"Calibration failed: No matching triggers found for images.");
883bool GeoTagController::_validateOutputDirectory(
const QString &outputDir, QString &errorMsg)
885 const qint64 requiredSpace = _estimateOutputSize();
887 errorMsg = tr(
"Geotagging failed. Insufficient disk space. Need approximately %1 MB.")
888 .arg(requiredSpace / (1024 * 1024));
893 errorMsg = tr(
"Geotagging failed. Couldn't create output directory: %1").arg(outputDir);
900QList<GeoTagController::TagTask> GeoTagController::_buildTagTasks(
const QString &outputDir,
bool preview, QString &errorMsg)
902 const qsizetype maxIndex = std::min(_state.imageIndices.count(), _state.triggerIndices.count());
904 QList<TagTask> tasks;
905 tasks.reserve(maxIndex);
907 for (qsizetype i = 0; i < maxIndex; ++i) {
908 const int imageIndex = _state.imageIndices[i];
909 const int triggerIndex = _state.triggerIndices[i];
911 if (imageIndex >= _state.imageList.count()) {
912 errorMsg = tr(
"Geotagging failed. Requesting image #%1, but only %2 images present.")
913 .arg(imageIndex).arg(_state.imageList.count());
917 if (triggerIndex >= _state.triggerList.count()) {
918 errorMsg = tr(
"Geotagging failed. Requesting trigger #%1, but only %2 triggers present.")
919 .arg(triggerIndex).arg(_state.triggerList.count());
924 task.imageIndex = imageIndex;
925 task.imageInfo = _state.imageList.at(imageIndex);
926 task.geoTag = _state.triggerList[triggerIndex];
927 task.outputDir = outputDir;
928 task.previewMode = preview;
935qint64 GeoTagController::_estimateOutputSize()
const
937 qint64 totalSize = 0;
938 const qsizetype maxIndex = std::min(_state.imageIndices.count(), _state.triggerIndices.count());
940 for (qsizetype i = 0; i < maxIndex; ++i) {
941 const int imageIndex = _state.imageIndices[i];
942 if (imageIndex < _state.imageList.count()) {
943 totalSize += _state.imageList.at(imageIndex).size();
948 return static_cast<qint64
>(totalSize * 1.1);
951GeoTagController::TagResult GeoTagController::_tagImage(
const TagTask &task)
954 result.imageIndex = task.imageIndex;
955 result.fileName = task.imageInfo.fileName();
956 result.success =
false;
959 result.errorMessage = tr(
"Tagging cancelled");
964 QByteArray imageBuffer = _readImageCached(task.imageInfo.absoluteFilePath(), &
errorString);
965 if (imageBuffer.isEmpty()) {
966 result.errorMessage = tr(
"Geotagging failed. Couldn't open image: %1").arg(result.fileName);
971 if (!task.previewMode) {
973 imageBuffer.detach();
976 result.errorMessage = tr(
"Geotagging failed. Couldn't write EXIF to image: %1").arg(result.fileName);
982 result.errorMessage = tr(
"Geotagging failed. Couldn't save image: %1").arg(outputPath);
987 result.coordinate = task.geoTag.coordinate;
988 result.success =
true;
996QByteArray GeoTagController::_readImageCached(
const QString &path, QString *
errorString)
999 QMutexLocker locker(&_bufferMutex);
1000 auto it = _imageBuffers.constFind(path);
1001 if (it != _imageBuffers.constEnd()) {
1010 if (data.isEmpty()) {
1019 QMutexLocker locker(&_bufferMutex);
1020 _imageBuffers.insert(path, data);
1026void GeoTagController::_evictUnmatchedImages()
1028 QSet<QString> matchedPaths;
1029 for (
int idx : _state.imageIndices) {
1030 if (idx < _state.imageList.count()) {
1031 matchedPaths.insert(_state.imageList[idx].absoluteFilePath());
1035 QMutexLocker locker(&_bufferMutex);
1036 auto it = _imageBuffers.begin();
1037 while (it != _imageBuffers.end()) {
1038 if (!matchedPaths.contains(it.key())) {
1039 it = _imageBuffers.erase(it);
1045 qCDebug(GeoTagControllerLog) <<
"Evicted unmatched images, cache size:" << _imageBuffers.count();
1048void GeoTagController::_clearImageCache()
1050 QMutexLocker locker(&_bufferMutex);
1051 _imageBuffers.clear();
#define QGC_LOGGING_CATEGORY(name, categoryStr)
void setPreviewMode(bool preview)
void setTimeOffsetSecs(double offset)
void setLogFile(const QString &file)
void recursiveScanChanged(bool recursiveScan)
void timeOffsetSecsChanged(double timeOffsetSecs)
void previewModeChanged(bool previewMode)
void saveDirectoryChanged(const QString &saveDirectory)
void imageDirectoryChanged(const QString &imageDirectory)
void setRecursiveScan(bool recursive)
Q_INVOKABLE void cancelTagging()
void toleranceSecsChanged(double toleranceSecs)
GeoTagController(QObject *parent=nullptr)
void progressChanged(double progress)
~GeoTagController() override
void logFileChanged(const QString &logFile)
void errorMessageChanged(const QString &errorMessage)
void taggingCompleteChanged()
void setImageDirectory(const QString &dir)
void setSaveDirectory(const QString &dir)
Q_INVOKABLE void startTagging()
void setToleranceSecs(double tolerance)
Model for displaying geotagging image status in QML.
void setCoordinate(int index, const QGeoCoordinate &coordinate)
void setStatus(int index, Status status, const QString &errorMessage=QString())
void addImage(const QString &filePath)
bool getTagsFromLog(const char *data, qint64 size, QList< GeoTagData > &cameraFeedback, QString &errorMessage)
QDateTime readTime(const QByteArray &buffer)
bool write(QByteArray &buffer, const GeoTagData &geotag)
CalibrationResult calibrate(const QList< qint64 > &imageTimestamps, const QList< GeoTagData > &triggers, qint64 timeOffsetSecs, qint64 toleranceSecs)
QByteArray readFile(const QString &filePath, QString *errorString, qint64 maxBytes)
Read file contents, transparently decompressing .gz/.xz/.zst/.bz2/.lz4 files.
bool atomicWrite(const QString &filePath, const QByteArray &data)
QString toLocalPath(const QString &urlOrPath)
bool hasSufficientDiskSpace(const QString &path, qint64 requiredBytes, double margin)
bool ensureDirectoryExists(const QString &path)
QString joinPath(const QString &dir, const QString &name)
bool exists(const QString &path)
bool getTagsFromLog(const char *data, qint64 size, QList< GeoTagData > &cameraFeedback, QString &errorMessage)
Result of timestamp-based calibration/matching.
QList< int > imageIndices
Matched image indices (parallel with triggerIndices)
QList< int > triggerIndices
Matched trigger indices (parallel with imageIndices)
int skippedTriggers
Triggers skipped due to invalid data.
QList< int > unmatchedImages
Image indices with no matching trigger.
QGeoCoordinate coordinate
qint64 timestamp
Seconds since epoch.