9#include <QtConcurrent/QtConcurrent>
11#include <QtCore/QDirIterator>
12#include <QtCore/QFile>
13#include <QtCore/QFileInfo>
14#include <QtCore/QMimeDatabase>
15#include <QtCore/QMultiMap>
16#include <QtCore/QMutexLocker>
24const QStringList kImageExtensionFilters = {
25 QStringLiteral(
"*.jpg"), QStringLiteral(
"*.JPG"),
26 QStringLiteral(
"*.jpeg"), QStringLiteral(
"*.JPEG"),
27 QStringLiteral(
"*.tiff"), QStringLiteral(
"*.TIFF"),
28 QStringLiteral(
"*.tif"), QStringLiteral(
"*.TIF"),
29 QStringLiteral(
"*.dng"), QStringLiteral(
"*.DNG")
33const QSet<QString> kSupportedMimeTypes = {
34 QStringLiteral(
"image/jpeg"),
35 QStringLiteral(
"image/tiff"),
36 QStringLiteral(
"image/x-adobe-dng"),
37 QStringLiteral(
"image/x-dcraw")
41bool isSupportedImageMimeType(
const QMimeType &mimeType)
43 if (kSupportedMimeTypes.contains(mimeType.name())) {
48 for (
const QString &parent : mimeType.parentMimeTypes()) {
49 if (kSupportedMimeTypes.contains(parent)) {
55 if (mimeType.name() == QStringLiteral(
"application/octet-stream") ||
56 mimeType.name().startsWith(QStringLiteral(
"application/"))) {
64double calculateStageProgress(
double stageStart,
double stageEnd,
int completed,
int total)
69 return stageStart + (stageEnd - stageStart) * completed / total;
78const char* GeoTagController::stageName(Stage stage)
81 case Stage::Idle:
return "Idle";
82 case Stage::LoadingImages:
return "LoadingImages";
83 case Stage::ParsingExif:
return "ParsingExif";
84 case Stage::ParsingLogs:
return "ParsingLogs";
85 case Stage::Calibrating:
return "Calibrating";
86 case Stage::TaggingImages:
return "TaggingImages";
87 case Stage::Finished:
return "Finished";
97 const QList<GeoTagData> &triggers,
98 qint64 timeOffsetSecs,
103 if (triggers.isEmpty() || imageTimestamps.isEmpty()) {
109 const qint64 lastImageTimestamp = imageTimestamps.last() + timeOffsetSecs;
110 const qint64 lastTriggerTimestamp = triggers.last().timestamp;
115 QMultiMap<qint64, int> imageOffsets;
116 QSet<int> invalidImageIndices;
117 for (
int i = 0; i < imageTimestamps.size(); ++i) {
118 if (imageTimestamps[i] == 0) {
119 invalidImageIndices.insert(i);
122 const qint64 adjustedTimestamp = imageTimestamps[i] + timeOffsetSecs;
123 const qint64 offset = lastImageTimestamp - adjustedTimestamp;
124 imageOffsets.insert(offset, i);
128 QSet<int> usedImageIndices;
130 for (
int triggerIdx = 0; triggerIdx < triggers.size(); ++triggerIdx) {
131 const GeoTagData &trigger = triggers[triggerIdx];
137 const qint64 triggerOffset = lastTriggerTimestamp - trigger.
timestamp;
140 int bestImageIdx = -1;
141 qint64 bestDiff = toleranceSecs + 1;
144 auto it = imageOffsets.lowerBound(triggerOffset - toleranceSecs);
146 while (it != imageOffsets.end() && it.key() <= triggerOffset + toleranceSecs) {
147 const qint64 diff = qAbs(it.key() - triggerOffset);
148 if (diff <= toleranceSecs && diff < bestDiff && !usedImageIndices.contains(it.value())) {
150 bestImageIdx = it.value();
155 if (bestImageIdx >= 0) {
158 usedImageIndices.insert(bestImageIdx);
163 for (
int i = 0; i < imageTimestamps.size(); ++i) {
164 if (!usedImageIndices.contains(i)) {
176GeoTagController::GeoTagController(QObject *parent)
180 qCDebug(GeoTagControllerLog) <<
this;
183 (void) connect(&_exifWatcher, &QFutureWatcher<ExifResult>::progressValueChanged,
184 this, &GeoTagController::_onExifProgress);
185 (void) connect(&_exifWatcher, &QFutureWatcher<ExifResult>::finished,
186 this, &GeoTagController::_onExifFinished);
189 (void) connect(&_tagWatcher, &QFutureWatcher<TagResult>::progressValueChanged,
190 this, &GeoTagController::_onTagProgress);
191 (void) connect(&_tagWatcher, &QFutureWatcher<TagResult>::finished,
192 this, &GeoTagController::_onTagFinished);
195GeoTagController::~GeoTagController()
197 qCDebug(GeoTagControllerLog) <<
this;
201 _exifWatcher.waitForFinished();
202 _tagWatcher.waitForFinished();
205void GeoTagController::setLogFile(
const QString &file)
209 if (path.isEmpty()) {
210 _setErrorMessage(tr(
"Empty Filename."));
214 const QFileInfo logFileInfo(path);
215 if (!logFileInfo.exists() || !logFileInfo.isFile()) {
216 _setErrorMessage(tr(
"Invalid Filename."));
220 if (_logFile != path) {
225 _setErrorMessage(QString());
228void GeoTagController::setImageDirectory(
const QString &dir)
232 if (path.isEmpty()) {
233 _setErrorMessage(tr(
"Invalid Directory."));
237 const QFileInfo imageDirectoryInfo(path);
238 if (!imageDirectoryInfo.exists() || !imageDirectoryInfo.isDir()) {
239 _setErrorMessage(tr(
"Invalid Directory."));
243 if (_imageDirectory != path) {
244 _imageDirectory = path;
248 if (_saveDirectory.isEmpty()) {
251 _setErrorMessage(tr(
"Images have already been tagged. Existing images will be removed."));
256 _setErrorMessage(QString());
259void GeoTagController::setSaveDirectory(
const QString &dir)
263 if (path.isEmpty()) {
264 _setErrorMessage(tr(
"Invalid Directory."));
268 const QFileInfo saveDirectoryInfo(path);
269 if (!saveDirectoryInfo.exists() || !saveDirectoryInfo.isDir()) {
270 _setErrorMessage(tr(
"Invalid Directory."));
274 if (_saveDirectory != path) {
275 _saveDirectory = path;
280 saveDir.setFilter(QDir::Files | QDir::Readable | QDir::NoSymLinks | QDir::Writable);
281 saveDir.setNameFilters(kImageExtensionFilters);
283 if (!saveDir.entryList().isEmpty()) {
284 _setErrorMessage(tr(
"The save folder already contains images."));
288 _setErrorMessage(QString());
291void GeoTagController::setTimeOffsetSecs(
double offset)
293 if (!qFuzzyCompare(_timeOffsetSecs, offset)) {
294 _timeOffsetSecs = offset;
299void GeoTagController::setToleranceSecs(
double tolerance)
302 tolerance = qBound(0.1, tolerance, 60.0);
303 if (!qFuzzyCompare(_toleranceSecs, tolerance)) {
304 _toleranceSecs = tolerance;
309void GeoTagController::setPreviewMode(
bool preview)
311 if (_previewMode != preview) {
312 _previewMode = preview;
317void GeoTagController::setRecursiveScan(
bool recursive)
319 if (_recursiveScan != recursive) {
320 _recursiveScan = recursive;
325void GeoTagController::_setErrorMessage(
const QString &errorMsg)
327 if (errorMsg != _errorMessage) {
328 _errorMessage = errorMsg;
333void GeoTagController::_setProgress(
double progress)
335 if (progress != _progress) {
336 _progress = progress;
345void GeoTagController::startTagging()
348 qCWarning(GeoTagControllerLog) <<
"Tagging already in progress";
352 _setErrorMessage(QString());
359 if (_imageDirectory.isEmpty()) {
360 _setErrorMessage(tr(
"Please select an image directory."));
364 if (_logFile.isEmpty()) {
365 _setErrorMessage(tr(
"Please select a log file."));
370 _setErrorMessage(tr(
"Cannot find the image directory."));
375 _setErrorMessage(tr(
"Cannot find the save directory."));
386 _transitionTo(Stage::LoadingImages);
389void GeoTagController::cancelTagging()
398 if (_exifWatcher.isRunning()) {
399 _exifWatcher.cancel();
401 if (_tagWatcher.isRunning()) {
402 _tagWatcher.cancel();
405 _finishWithError(tr(
"Tagging cancelled"));
408void GeoTagController::_transitionTo(Stage stage)
410 if (_cancel && stage != Stage::Idle && stage != Stage::Finished) {
411 _finishWithError(tr(
"Tagging cancelled"));
418 qCDebug(GeoTagControllerLog) <<
"Transitioning to stage:" << stageName(stage);
423 case Stage::LoadingImages:
427 case Stage::ParsingExif:
430 case Stage::ParsingLogs:
433 case Stage::Calibrating:
436 case Stage::TaggingImages:
439 case Stage::Finished:
445void GeoTagController::_finishWithError(
const QString &errorMsg)
447 qCDebug(GeoTagControllerLog) <<
"Finishing with error:" << errorMsg;
448 qCDebug(GeoTagControllerLog) <<
"Total processing time:" << _totalTimer.elapsed() <<
"ms";
451 _stage = Stage::Idle;
452 _setErrorMessage(errorMsg);
456void GeoTagController::_finishSuccess()
458 qCDebug(GeoTagControllerLog) <<
"Finishing successfully";
459 qCDebug(GeoTagControllerLog) <<
"Total processing time:" << _totalTimer.elapsed() <<
"ms";
462 _stage = Stage::Idle;
464 const auto matchedCount = std::min(_state.imageIndices.count(), _state.triggerIndices.count());
465 _taggedCount =
static_cast<int>(matchedCount) - _state.failedCount;
466 _skippedCount = _state.skippedCount;
467 _failedCount = _state.failedCount;
473 if (_state.failedCount > 0) {
474 _setErrorMessage(tr(
"%1 image(s) failed to tag").arg(_state.failedCount));
482void GeoTagController::_startLoadImages()
485 if (!_loadImages(errorMsg)) {
486 _finishWithError(errorMsg);
490 qCDebug(GeoTagControllerLog) <<
"Stage: loadImages took" << _stageTimer.elapsed() <<
"ms";
491 _setProgress(kLoadImagesEnd);
492 _transitionTo(Stage::ParsingExif);
495void GeoTagController::_startParseExif()
498 QFuture<ExifResult> future = QtConcurrent::mapped(_state.imageList,
499 [
this](
const QFileInfo &info) { return _parseExifForImage(info); });
501 _exifWatcher.setFuture(future);
505void GeoTagController::_onExifProgress(
int value)
507 const int total = _state.imageList.size();
508 const double progress = calculateStageProgress(kLoadImagesEnd, kParseExifEnd, value, total);
509 _setProgress(progress);
512void GeoTagController::_onExifFinished()
514 qCDebug(GeoTagControllerLog) <<
"Stage: parseExif took" << _stageTimer.elapsed() <<
"ms";
517 _finishWithError(tr(
"Tagging cancelled"));
522 _state.imageTimestamps.clear();
523 _state.imageTimestamps.reserve(_state.imageList.size());
525 const QList<ExifResult> results = _exifWatcher.future().results();
526 QList<int> failedIndices;
528 for (
int i = 0; i < results.size(); ++i) {
529 const ExifResult &result = results[i];
530 if (result.success) {
531 _state.imageTimestamps.append(result.timestamp);
534 failedIndices.append(i);
535 _state.imageTimestamps.append(0);
536 qCWarning(GeoTagControllerLog) <<
"Skipping image with EXIF error:" << result.errorMessage;
541 for (
int idx : failedIndices) {
542 if (idx < _state.imageList.size()) {
543 _imageModel->setStatus(idx, GeoTagImageModel::Skipped,
544 tr(
"Could not read EXIF timestamp"));
546 ++_state.skippedCount;
549 if (failedIndices.size() == results.size()) {
550 _finishWithError(tr(
"Could not read EXIF data from any images"));
554 if (!failedIndices.isEmpty()) {
555 qCDebug(GeoTagControllerLog) <<
"Skipped" << failedIndices.size() <<
"images with EXIF errors";
558 _setProgress(kParseExifEnd);
559 _transitionTo(Stage::ParsingLogs);
562void GeoTagController::_startParseLogs()
565 if (!_parseLogs(errorMsg)) {
566 _finishWithError(errorMsg);
570 qCDebug(GeoTagControllerLog) <<
"Stage: parseLogs took" << _stageTimer.elapsed() <<
"ms";
571 _setProgress(kParseLogsEnd);
572 _transitionTo(Stage::Calibrating);
575void GeoTagController::_startCalibrate()
578 if (!_calibrate(errorMsg)) {
579 _finishWithError(errorMsg);
584 _evictUnmatchedImages();
586 qCDebug(GeoTagControllerLog) <<
"Stage: calibrate took" << _stageTimer.elapsed() <<
"ms";
587 _setProgress(kCalibrateEnd);
588 _transitionTo(Stage::TaggingImages);
591void GeoTagController::_startTagImages()
593 const bool preview = _previewMode;
594 const QString outputDir = _saveDirectory.isEmpty()
601 if (!preview && !_validateOutputDirectory(outputDir, errorMsg)) {
602 _finishWithError(errorMsg);
607 QList<TagTask> tagTasks = _buildTagTasks(outputDir, preview, errorMsg);
608 if (tagTasks.isEmpty()) {
609 if (!errorMsg.isEmpty()) {
610 _finishWithError(errorMsg);
612 _transitionTo(Stage::Finished);
618 for (
const TagTask &task : tagTasks) {
619 _imageModel->setStatus(task.imageIndex, GeoTagImageModel::Processing);
623 QFuture<TagResult> future = QtConcurrent::mapped(tagTasks,
624 [
this](
const TagTask &task) {
return _tagImage(task); });
626 _tagWatcher.setFuture(future);
630void GeoTagController::_onTagProgress(
int value)
632 const int total = _tagWatcher.progressMaximum();
633 const double progress = calculateStageProgress(kCalibrateEnd, kTagImagesEnd, value, total);
634 _setProgress(progress);
637void GeoTagController::_onTagFinished()
639 qCDebug(GeoTagControllerLog) <<
"Stage: tagImages took" << _stageTimer.elapsed() <<
"ms";
642 _finishWithError(tr(
"Tagging cancelled"));
647 const QList<TagResult> results = _tagWatcher.future().results();
649 for (
const TagResult &result : results) {
650 if (result.success) {
651 _imageModel->setStatus(result.imageIndex, GeoTagImageModel::Tagged);
652 _imageModel->setCoordinate(result.imageIndex, result.coordinate);
654 _imageModel->setStatus(result.imageIndex, GeoTagImageModel::Failed, result.errorMessage);
655 ++_state.failedCount;
656 qCWarning(GeoTagControllerLog) <<
"Failed to tag image:" << result.fileName <<
"-" << result.errorMessage;
661 if (_state.failedCount > 0 && _state.failedCount == results.count()) {
662 _finishWithError(tr(
"All images failed to tag"));
666 _transitionTo(Stage::Finished);
673bool GeoTagController::_loadImages(QString &errorMsg)
675 _state.imageList.clear();
678 QFileInfoList candidateFiles;
679 QDirIterator::IteratorFlags flags = QDirIterator::NoIteratorFlags;
680 if (_recursiveScan) {
681 flags = QDirIterator::Subdirectories;
684 QDirIterator it(_imageDirectory, kImageExtensionFilters,
685 QDir::Files | QDir::Readable | QDir::NoSymLinks, flags);
686 while (it.hasNext()) {
688 candidateFiles.append(it.fileInfo());
692 std::sort(candidateFiles.begin(), candidateFiles.end(),
693 [](
const QFileInfo &a,
const QFileInfo &b) { return a.fileName() < b.fileName(); });
695 if (candidateFiles.isEmpty()) {
696 errorMsg = tr(
"The image directory doesn't contain supported images. Supported formats: JPEG, TIFF, DNG");
701 static const QMimeDatabase mimeDb;
702 for (
const QFileInfo &fileInfo : candidateFiles) {
703 const QMimeType mimeType = mimeDb.mimeTypeForFile(fileInfo);
704 if (isSupportedImageMimeType(mimeType)) {
705 _state.imageList.append(fileInfo);
707 qCDebug(GeoTagControllerLog) <<
"Skipping misnamed file:" << fileInfo.fileName()
708 <<
"MIME:" << mimeType.name();
712 if (_state.imageList.isEmpty()) {
713 errorMsg = tr(
"The image directory doesn't contain supported images. Supported formats: JPEG, TIFF, DNG");
718 _imageModel->clear();
719 for (
const QFileInfo &info : _state.imageList) {
720 _imageModel->addImage(info.absoluteFilePath());
723 qCDebug(GeoTagControllerLog) <<
"Found" << _state.imageList.count() <<
"images"
724 << (_recursiveScan ?
"(recursive)" :
"");
729GeoTagController::ExifResult GeoTagController::_parseExifForImage(
const QFileInfo &imageInfo)
732 result.success =
false;
735 result.errorMessage = tr(
"Tagging cancelled");
740 const QByteArray imageBuffer = _readImageCached(imageInfo.absoluteFilePath(), &
errorString);
741 if (imageBuffer.isEmpty()) {
742 result.errorMessage = tr(
"Geotagging failed. Couldn't open image: %1").arg(imageInfo.fileName());
747 if (!imageTime.isValid()) {
748 result.errorMessage = tr(
"Geotagging failed. Couldn't extract time from image: %1").arg(imageInfo.fileName());
752 result.timestamp = imageTime.toSecsSinceEpoch();
753 result.success =
true;
757bool GeoTagController::_parseLogs(QString &errorMsg)
759 _state.triggerList.clear();
761 QFile logFile(_logFile);
762 if (!logFile.open(QIODevice::ReadOnly)) {
763 errorMsg = tr(
"Geotagging failed. Couldn't open log file.");
767 const qint64 fileSize = logFile.size();
769 errorMsg = tr(
"Geotagging failed. Log file is empty.");
774 const uchar *mappedData = logFile.map(0, fileSize);
775 const char *data =
nullptr;
776 qint64 dataSize = fileSize;
777 QByteArray fallbackBuffer;
780 data =
reinterpret_cast<const char*
>(mappedData);
781 qCDebug(GeoTagControllerLog) <<
"Memory-mapped log file:" << fileSize <<
"bytes";
784 qCDebug(GeoTagControllerLog) <<
"Memory mapping failed, reading file into memory";
785 fallbackBuffer = logFile.readAll();
786 if (fallbackBuffer.isEmpty()) {
787 errorMsg = tr(
"Geotagging failed. Couldn't read log file.");
790 data = fallbackBuffer.constData();
791 dataSize = fallbackBuffer.size();
795 const QString logFileLower = _logFile.toLower();
796 bool parseSuccess =
false;
799 if (logFileLower.endsWith(QStringLiteral(
".bin"))) {
800 qCDebug(GeoTagControllerLog) <<
"Parsing DataFlash log:" << _logFile;
802 }
else if (logFileLower.endsWith(QStringLiteral(
".ulg"))) {
803 qCDebug(GeoTagControllerLog) <<
"Parsing ULog:" << _logFile;
807 qCDebug(GeoTagControllerLog) <<
"Unknown extension, trying ULog parser first";
810 qCDebug(GeoTagControllerLog) <<
"ULog failed, trying DataFlash parser";
818 logFile.unmap(
const_cast<uchar*
>(mappedData));
826 qCDebug(GeoTagControllerLog) <<
"Found" << _state.triggerList.count() <<
"camera capture events";
828 if (_state.imageList.count() > _state.triggerList.count()) {
829 qCDebug(GeoTagControllerLog) <<
"Detected missing feedback packets:"
830 << (_state.imageList.count() - _state.triggerList.count()) <<
"images without triggers";
831 }
else if (_state.imageList.count() < _state.triggerList.count()) {
832 qCDebug(GeoTagControllerLog) <<
"Detected missing image frames:"
833 << (_state.triggerList.count() - _state.imageList.count()) <<
"triggers without images";
839bool GeoTagController::_calibrate(QString &errorMsg)
841 _state.imageIndices.clear();
842 _state.triggerIndices.clear();
843 _state.skippedCount = 0;
845 if (_state.triggerList.isEmpty() || _state.imageTimestamps.isEmpty()) {
846 errorMsg = tr(
"Calibration failed: No triggers or images available.");
851 const qint64 timeOffsetSec =
static_cast<qint64
>(_timeOffsetSecs);
852 const qint64 toleranceSec =
static_cast<qint64
>(_toleranceSecs);
854 _state.imageTimestamps, _state.triggerList, timeOffsetSec, toleranceSec);
861 qCDebug(GeoTagControllerLog) <<
"Calibration complete:"
862 << _state.imageIndices.count() <<
"matched,"
863 << _state.skippedCount <<
"skipped (invalid),"
868 for (
int idx : calibration.unmatchedImages) {
869 _imageModel->setStatus(idx, GeoTagImageModel::Skipped, tr(
"No matching trigger"));
874 if (_state.imageIndices.isEmpty()) {
875 errorMsg = tr(
"Calibration failed: No matching triggers found for images.");
882bool GeoTagController::_validateOutputDirectory(
const QString &outputDir, QString &errorMsg)
884 const qint64 requiredSpace = _estimateOutputSize();
886 errorMsg = tr(
"Geotagging failed. Insufficient disk space. Need approximately %1 MB.")
887 .arg(requiredSpace / (1024 * 1024));
892 errorMsg = tr(
"Geotagging failed. Couldn't create output directory: %1").arg(outputDir);
899QList<GeoTagController::TagTask> GeoTagController::_buildTagTasks(
const QString &outputDir,
bool preview, QString &errorMsg)
901 const qsizetype maxIndex = std::min(_state.imageIndices.count(), _state.triggerIndices.count());
903 QList<TagTask> tasks;
904 tasks.reserve(maxIndex);
906 for (qsizetype i = 0; i < maxIndex; ++i) {
907 const int imageIndex = _state.imageIndices[i];
908 const int triggerIndex = _state.triggerIndices[i];
910 if (imageIndex >= _state.imageList.count()) {
911 errorMsg = tr(
"Geotagging failed. Requesting image #%1, but only %2 images present.")
912 .arg(imageIndex).arg(_state.imageList.count());
916 if (triggerIndex >= _state.triggerList.count()) {
917 errorMsg = tr(
"Geotagging failed. Requesting trigger #%1, but only %2 triggers present.")
918 .arg(triggerIndex).arg(_state.triggerList.count());
923 task.imageIndex = imageIndex;
924 task.imageInfo = _state.imageList.at(imageIndex);
925 task.geoTag = _state.triggerList[triggerIndex];
926 task.outputDir = outputDir;
927 task.previewMode = preview;
934qint64 GeoTagController::_estimateOutputSize()
const
936 qint64 totalSize = 0;
937 const qsizetype maxIndex = std::min(_state.imageIndices.count(), _state.triggerIndices.count());
939 for (qsizetype i = 0; i < maxIndex; ++i) {
940 const int imageIndex = _state.imageIndices[i];
941 if (imageIndex < _state.imageList.count()) {
942 totalSize += _state.imageList.at(imageIndex).size();
947 return static_cast<qint64
>(totalSize * 1.1);
950GeoTagController::TagResult GeoTagController::_tagImage(
const TagTask &task)
953 result.imageIndex = task.imageIndex;
954 result.fileName = task.imageInfo.fileName();
955 result.success =
false;
958 result.errorMessage = tr(
"Tagging cancelled");
963 QByteArray imageBuffer = _readImageCached(task.imageInfo.absoluteFilePath(), &
errorString);
964 if (imageBuffer.isEmpty()) {
965 result.errorMessage = tr(
"Geotagging failed. Couldn't open image: %1").arg(result.fileName);
970 if (!task.previewMode) {
972 imageBuffer.detach();
975 result.errorMessage = tr(
"Geotagging failed. Couldn't write EXIF to image: %1").arg(result.fileName);
981 result.errorMessage = tr(
"Geotagging failed. Couldn't save image: %1").arg(outputPath);
986 result.coordinate = task.geoTag.coordinate;
987 result.success =
true;
995QByteArray GeoTagController::_readImageCached(
const QString &path, QString *
errorString)
998 QMutexLocker locker(&_bufferMutex);
999 auto it = _imageBuffers.constFind(path);
1000 if (it != _imageBuffers.constEnd()) {
1009 if (data.isEmpty()) {
1018 QMutexLocker locker(&_bufferMutex);
1019 _imageBuffers.insert(path, data);
1025void GeoTagController::_evictUnmatchedImages()
1027 QSet<QString> matchedPaths;
1028 for (
int idx : _state.imageIndices) {
1029 if (idx < _state.imageList.count()) {
1030 matchedPaths.insert(_state.imageList[idx].absoluteFilePath());
1034 QMutexLocker locker(&_bufferMutex);
1035 auto it = _imageBuffers.begin();
1036 while (it != _imageBuffers.end()) {
1037 if (!matchedPaths.contains(it.key())) {
1038 it = _imageBuffers.erase(it);
1044 qCDebug(GeoTagControllerLog) <<
"Evicted unmatched images, cache size:" << _imageBuffers.count();
1047void GeoTagController::_clearImageCache()
1049 QMutexLocker locker(&_bufferMutex);
1050 _imageBuffers.clear();
#define QGC_LOGGING_CATEGORY(name, categoryStr)
void recursiveScanChanged(bool recursiveScan)
void timeOffsetSecsChanged(double timeOffsetSecs)
void previewModeChanged(bool previewMode)
void saveDirectoryChanged(const QString &saveDirectory)
void imageDirectoryChanged(const QString &imageDirectory)
void toleranceSecsChanged(double toleranceSecs)
void progressChanged(double progress)
void logFileChanged(const QString &logFile)
void errorMessageChanged(const QString &errorMessage)
void taggingCompleteChanged()
Model for displaying geotagging image status in QML.
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)
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)
QByteArray readFile(const QString &filePath, QString *errorString, qint64 maxBytes)
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.