QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
GeoTagController.cc
Go to the documentation of this file.
1#include "GeoTagController.h"
2#include "DataFlashParser.h"
3#include "ExifParser.h"
4#include "GeoTagImageModel.h"
5#include "QGCCompression.h"
6#include "QGCFileHelper.h"
8#include "ULogParser.h"
9
10#include <QtConcurrent/QtConcurrent>
11#include <QtCore/QDir>
12#include <QtCore/QDirIterator>
13#include <QtCore/QFile>
14#include <QtCore/QFileInfo>
15#include <QtCore/QMimeDatabase>
16#include <QtCore/QMultiMap>
17#include <QtCore/QMutexLocker>
18#include <QtCore/QSet>
19
20QGC_LOGGING_CATEGORY(GeoTagControllerLog, "AnalyzeView.GeoTagController")
21
22namespace {
23
24// Supported image extensions for geotagging (case variations for QDir filtering)
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")
31};
32
33// Supported MIME types for verification
34const QSet<QString> kSupportedMimeTypes = {
35 QStringLiteral("image/jpeg"),
36 QStringLiteral("image/tiff"),
37 QStringLiteral("image/x-adobe-dng"),
38 QStringLiteral("image/x-dcraw")
39};
40
42bool isSupportedImageMimeType(const QMimeType &mimeType)
43{
44 if (kSupportedMimeTypes.contains(mimeType.name())) {
45 return true;
46 }
47
48 // Check parent MIME types (e.g., image/x-adobe-dng inherits from image/tiff)
49 for (const QString &parent : mimeType.parentMimeTypes()) {
50 if (kSupportedMimeTypes.contains(parent)) {
51 return true;
52 }
53 }
54
55 // Accept files if MIME detection returns generic type (extension already matched)
56 if (mimeType.name() == QStringLiteral("application/octet-stream") ||
57 mimeType.name().startsWith(QStringLiteral("application/"))) {
58 return true;
59 }
60
61 return false;
62}
63
65double calculateStageProgress(double stageStart, double stageEnd, int completed, int total)
66{
67 if (total <= 0) {
68 return stageStart;
69 }
70 return stageStart + (stageEnd - stageStart) * completed / total;
71}
72
73} // namespace
74
75// ============================================================================
76// Stage name helper for debug logging
77// ============================================================================
78
79const char* GeoTagController::stageName(Stage stage)
80{
81 switch (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";
89 }
90 return "Unknown";
91}
92
93// ============================================================================
94// GeoTagCalibrator implementation
95// ============================================================================
96
97CalibrationResult GeoTagCalibrator::calibrate(const QList<qint64> &imageTimestamps,
98 const QList<GeoTagData> &triggers,
99 qint64 timeOffsetSecs,
100 qint64 toleranceSecs)
101{
102 CalibrationResult result;
103
104 if (triggers.isEmpty() || imageTimestamps.isEmpty()) {
105 return result;
106 }
107
108 // Use offset-from-end approach to handle different time bases (EXIF vs GPS/boot time).
109 // Both sequences are normalized to "seconds before end of sequence", making them comparable.
110 const qint64 lastImageTimestamp = imageTimestamps.last() + timeOffsetSecs;
111 const qint64 lastTriggerTimestamp = triggers.last().timestamp;
112
113 // Build image offset map for efficient searching (QMultiMap is sorted by key)
114 // Key: offset from end (lastImageTimestamp - adjustedTimestamp), Value: image index
115 // Skip images with timestamp 0 (failed EXIF parsing)
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);
121 continue;
122 }
123 const qint64 adjustedTimestamp = imageTimestamps[i] + timeOffsetSecs;
124 const qint64 offset = lastImageTimestamp - adjustedTimestamp;
125 imageOffsets.insert(offset, i);
126 }
127
128 // Track which images have been matched to avoid duplicates
129 QSet<int> usedImageIndices;
130
131 for (int triggerIdx = 0; triggerIdx < triggers.size(); ++triggerIdx) {
132 const GeoTagData &trigger = triggers[triggerIdx];
133 if (!trigger.isValid() || !trigger.coordinate.isValid()) {
134 ++result.skippedTriggers;
135 continue;
136 }
137
138 const qint64 triggerOffset = lastTriggerTimestamp - trigger.timestamp;
139
140 // Find closest image within tolerance using binary search
141 int bestImageIdx = -1;
142 qint64 bestDiff = toleranceSecs + 1;
143
144 // Search range: [triggerOffset - tolerance, triggerOffset + tolerance]
145 auto it = imageOffsets.lowerBound(triggerOffset - toleranceSecs);
146
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())) {
150 bestDiff = diff;
151 bestImageIdx = it.value();
152 }
153 ++it;
154 }
155
156 if (bestImageIdx >= 0) {
157 result.imageIndices.append(bestImageIdx);
158 result.triggerIndices.append(triggerIdx);
159 usedImageIndices.insert(bestImageIdx);
160 }
161 }
162
163 // Collect unmatched image indices
164 for (int i = 0; i < imageTimestamps.size(); ++i) {
165 if (!usedImageIndices.contains(i)) {
166 result.unmatchedImages.append(i);
167 }
168 }
169
170 return result;
171}
172
173// ============================================================================
174// GeoTagController implementation
175// ============================================================================
176
178 : QObject(parent)
179 , _imageModel(new GeoTagImageModel(this))
180{
181 qCDebug(GeoTagControllerLog) << this;
182
183 // Connect EXIF parsing watcher signals
184 (void) connect(&_exifWatcher, &QFutureWatcher<ExifResult>::progressValueChanged,
185 this, &GeoTagController::_onExifProgress);
186 (void) connect(&_exifWatcher, &QFutureWatcher<ExifResult>::finished,
187 this, &GeoTagController::_onExifFinished);
188
189 // Connect tagging watcher signals
190 (void) connect(&_tagWatcher, &QFutureWatcher<TagResult>::progressValueChanged,
191 this, &GeoTagController::_onTagProgress);
192 (void) connect(&_tagWatcher, &QFutureWatcher<TagResult>::finished,
193 this, &GeoTagController::_onTagFinished);
194}
195
197{
198 qCDebug(GeoTagControllerLog) << this;
199
200 // Cancel and wait for any running operations
201 _cancel = true;
202 _exifWatcher.waitForFinished();
203 _tagWatcher.waitForFinished();
204}
205
206void GeoTagController::setLogFile(const QString &file)
207{
208 const QString path = QGCFileHelper::toLocalPath(file);
209
210 if (path.isEmpty()) {
211 _setErrorMessage(tr("Empty Filename."));
212 return;
213 }
214
215 const QFileInfo logFileInfo(path);
216 if (!logFileInfo.exists() || !logFileInfo.isFile()) {
217 _setErrorMessage(tr("Invalid Filename."));
218 return;
219 }
220
221 if (_logFile != path) {
222 _logFile = path;
223 emit logFileChanged(_logFile);
224 }
225
226 _setErrorMessage(QString());
227}
228
230{
231 const QString path = QGCFileHelper::toLocalPath(dir);
232
233 if (path.isEmpty()) {
234 _setErrorMessage(tr("Invalid Directory."));
235 return;
236 }
237
238 const QFileInfo imageDirectoryInfo(path);
239 if (!imageDirectoryInfo.exists() || !imageDirectoryInfo.isDir()) {
240 _setErrorMessage(tr("Invalid Directory."));
241 return;
242 }
243
244 if (_imageDirectory != path) {
245 _imageDirectory = path;
246 emit imageDirectoryChanged(_imageDirectory);
247 }
248
249 if (_saveDirectory.isEmpty()) {
250 const QString taggedPath = QGCFileHelper::joinPath(_imageDirectory, QStringLiteral("TAGGED"));
251 if (QGCFileHelper::exists(taggedPath)) {
252 _setErrorMessage(tr("Images have already been tagged. Existing images will be removed."));
253 return;
254 }
255 }
256
257 _setErrorMessage(QString());
258}
259
261{
262 const QString path = QGCFileHelper::toLocalPath(dir);
263
264 if (path.isEmpty()) {
265 _setErrorMessage(tr("Invalid Directory."));
266 return;
267 }
268
269 const QFileInfo saveDirectoryInfo(path);
270 if (!saveDirectoryInfo.exists() || !saveDirectoryInfo.isDir()) {
271 _setErrorMessage(tr("Invalid Directory."));
272 return;
273 }
274
275 if (_saveDirectory != path) {
276 _saveDirectory = path;
277 emit saveDirectoryChanged(_saveDirectory);
278 }
279
280 QDir saveDir(path);
281 saveDir.setFilter(QDir::Files | QDir::Readable | QDir::NoSymLinks | QDir::Writable);
282 saveDir.setNameFilters(kImageExtensionFilters);
283
284 if (!saveDir.entryList().isEmpty()) {
285 _setErrorMessage(tr("The save folder already contains images."));
286 return;
287 }
288
289 _setErrorMessage(QString());
290}
291
293{
294 if (!qFuzzyCompare(_timeOffsetSecs, offset)) {
295 _timeOffsetSecs = offset;
296 emit timeOffsetSecsChanged(_timeOffsetSecs);
297 }
298}
299
301{
302 // Clamp to reasonable range: 0.1 to 60 seconds
303 tolerance = qBound(0.1, tolerance, 60.0);
304 if (!qFuzzyCompare(_toleranceSecs, tolerance)) {
305 _toleranceSecs = tolerance;
306 emit toleranceSecsChanged(_toleranceSecs);
307 }
308}
309
311{
312 if (_previewMode != preview) {
313 _previewMode = preview;
314 emit previewModeChanged(_previewMode);
315 }
316}
317
319{
320 if (_recursiveScan != recursive) {
321 _recursiveScan = recursive;
322 emit recursiveScanChanged(_recursiveScan);
323 }
324}
325
326void GeoTagController::_setErrorMessage(const QString &errorMsg)
327{
328 if (errorMsg != _errorMessage) {
329 _errorMessage = errorMsg;
330 emit errorMessageChanged(_errorMessage);
331 }
332}
333
334void GeoTagController::_setProgress(double progress)
335{
336 if (progress != _progress) {
337 _progress = progress;
338 emit progressChanged(_progress);
339 }
340}
341
342// ============================================================================
343// State machine control
344// ============================================================================
345
347{
348 if (inProgress()) {
349 qCWarning(GeoTagControllerLog) << "Tagging already in progress";
350 return;
351 }
352
353 _setErrorMessage(QString());
354 _setProgress(0.);
355 _taggedCount = 0;
356 _skippedCount = 0;
357 _failedCount = 0;
359
360 if (_imageDirectory.isEmpty()) {
361 _setErrorMessage(tr("Please select an image directory."));
362 return;
363 }
364
365 if (_logFile.isEmpty()) {
366 _setErrorMessage(tr("Please select a log file."));
367 return;
368 }
369
370 if (!QGCFileHelper::exists(_imageDirectory)) {
371 _setErrorMessage(tr("Cannot find the image directory."));
372 return;
373 }
374
375 if (!_saveDirectory.isEmpty() && !QGCFileHelper::exists(_saveDirectory)) {
376 _setErrorMessage(tr("Cannot find the save directory."));
377 return;
378 }
379
380 // Clear previous state
381 _state.clear();
382 _clearImageCache();
383 _cancel = false;
384
385 // Start timing and begin processing
386 _totalTimer.start();
387 _transitionTo(Stage::LoadingImages);
388}
389
391{
392 if (!inProgress()) {
393 return;
394 }
395
396 _cancel = true;
397
398 // Cancel any running futures
399 if (_exifWatcher.isRunning()) {
400 _exifWatcher.cancel();
401 }
402 if (_tagWatcher.isRunning()) {
403 _tagWatcher.cancel();
404 }
405
406 _finishWithError(tr("Tagging cancelled"));
407}
408
409void GeoTagController::_transitionTo(Stage stage)
410{
411 if (_cancel && stage != Stage::Idle && stage != Stage::Finished) {
412 _finishWithError(tr("Tagging cancelled"));
413 return;
414 }
415
416 _stage = stage;
417 _stageTimer.start();
418
419 qCDebug(GeoTagControllerLog) << "Transitioning to stage:" << stageName(stage);
420
421 switch (stage) {
422 case Stage::Idle:
423 break;
424 case Stage::LoadingImages:
425 emit inProgressChanged();
426 _startLoadImages();
427 break;
428 case Stage::ParsingExif:
429 _startParseExif();
430 break;
431 case Stage::ParsingLogs:
432 _startParseLogs();
433 break;
434 case Stage::Calibrating:
435 _startCalibrate();
436 break;
437 case Stage::TaggingImages:
438 _startTagImages();
439 break;
440 case Stage::Finished:
441 _finishSuccess();
442 break;
443 }
444}
445
446void GeoTagController::_finishWithError(const QString &errorMsg)
447{
448 qCDebug(GeoTagControllerLog) << "Finishing with error:" << errorMsg;
449 qCDebug(GeoTagControllerLog) << "Total processing time:" << _totalTimer.elapsed() << "ms";
450
451 _clearImageCache();
452 _stage = Stage::Idle;
453 _setErrorMessage(errorMsg);
454 emit inProgressChanged();
455}
456
457void GeoTagController::_finishSuccess()
458{
459 qCDebug(GeoTagControllerLog) << "Finishing successfully";
460 qCDebug(GeoTagControllerLog) << "Total processing time:" << _totalTimer.elapsed() << "ms";
461
462 _clearImageCache();
463 _stage = Stage::Idle;
464
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;
469
470 _setProgress(100.0);
472 emit inProgressChanged();
473
474 if (_state.failedCount > 0) {
475 _setErrorMessage(tr("%1 image(s) failed to tag").arg(_state.failedCount));
476 }
477}
478
479// ============================================================================
480// Stage implementations
481// ============================================================================
482
483void GeoTagController::_startLoadImages()
484{
485 QString errorMsg;
486 if (!_loadImages(errorMsg)) {
487 _finishWithError(errorMsg);
488 return;
489 }
490
491 qCDebug(GeoTagControllerLog) << "Stage: loadImages took" << _stageTimer.elapsed() << "ms";
492 _setProgress(kLoadImagesEnd);
493 _transitionTo(Stage::ParsingExif);
494}
495
496void GeoTagController::_startParseExif()
497{
498 // Launch parallel EXIF parsing
499 QFuture<ExifResult> future = QtConcurrent::mapped(_state.imageList,
500 [this](const QFileInfo &info) { return _parseExifForImage(info); });
501
502 _exifWatcher.setFuture(future);
503 // Progress and completion handled by _onExifProgress and _onExifFinished
504}
505
506void GeoTagController::_onExifProgress(int value)
507{
508 const int total = _state.imageList.size();
509 const double progress = calculateStageProgress(kLoadImagesEnd, kParseExifEnd, value, total);
510 _setProgress(progress);
511}
512
513void GeoTagController::_onExifFinished()
514{
515 qCDebug(GeoTagControllerLog) << "Stage: parseExif took" << _stageTimer.elapsed() << "ms";
516
517 if (_cancel) {
518 _finishWithError(tr("Tagging cancelled"));
519 return;
520 }
521
522 // Process results - skip images that fail EXIF parsing instead of failing entirely
523 _state.imageTimestamps.clear();
524 _state.imageTimestamps.reserve(_state.imageList.size());
525
526 const QList<ExifResult> results = _exifWatcher.future().results();
527 QList<int> failedIndices;
528
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);
533 } else {
534 // Mark as skipped and use placeholder timestamp
535 failedIndices.append(i);
536 _state.imageTimestamps.append(0);
537 qCWarning(GeoTagControllerLog) << "Skipping image with EXIF error:" << result.errorMessage;
538 }
539 }
540
541 // Mark failed images in the model
542 for (int idx : failedIndices) {
543 if (idx < _state.imageList.size()) {
544 _imageModel->setStatus(idx, GeoTagImageModel::Skipped,
545 tr("Could not read EXIF timestamp"));
546 }
547 ++_state.skippedCount;
548 }
549
550 if (failedIndices.size() == results.size()) {
551 _finishWithError(tr("Could not read EXIF data from any images"));
552 return;
553 }
554
555 if (!failedIndices.isEmpty()) {
556 qCDebug(GeoTagControllerLog) << "Skipped" << failedIndices.size() << "images with EXIF errors";
557 }
558
559 _setProgress(kParseExifEnd);
560 _transitionTo(Stage::ParsingLogs);
561}
562
563void GeoTagController::_startParseLogs()
564{
565 QString errorMsg;
566 if (!_parseLogs(errorMsg)) {
567 _finishWithError(errorMsg);
568 return;
569 }
570
571 qCDebug(GeoTagControllerLog) << "Stage: parseLogs took" << _stageTimer.elapsed() << "ms";
572 _setProgress(kParseLogsEnd);
573 _transitionTo(Stage::Calibrating);
574}
575
576void GeoTagController::_startCalibrate()
577{
578 QString errorMsg;
579 if (!_calibrate(errorMsg)) {
580 _finishWithError(errorMsg);
581 return;
582 }
583
584 // Evict unmatched images from cache to save memory
585 _evictUnmatchedImages();
586
587 qCDebug(GeoTagControllerLog) << "Stage: calibrate took" << _stageTimer.elapsed() << "ms";
588 _setProgress(kCalibrateEnd);
589 _transitionTo(Stage::TaggingImages);
590}
591
592void GeoTagController::_startTagImages()
593{
594 const bool preview = _previewMode;
595 const QString outputDir = _saveDirectory.isEmpty()
596 ? QGCFileHelper::joinPath(_imageDirectory, QStringLiteral("TAGGED"))
597 : _saveDirectory;
598
599 QString errorMsg;
600
601 // Validate output directory (skip in preview mode)
602 if (!preview && !_validateOutputDirectory(outputDir, errorMsg)) {
603 _finishWithError(errorMsg);
604 return;
605 }
606
607 // Build task list (local - copied into future)
608 QList<TagTask> tagTasks = _buildTagTasks(outputDir, preview, errorMsg);
609 if (tagTasks.isEmpty()) {
610 if (!errorMsg.isEmpty()) {
611 _finishWithError(errorMsg);
612 } else {
613 _transitionTo(Stage::Finished); // No tasks is valid (no matches)
614 }
615 return;
616 }
617
618 // Mark images being processed
619 for (const TagTask &task : tagTasks) {
620 _imageModel->setStatus(task.imageIndex, GeoTagImageModel::Processing);
621 }
622
623 // Launch parallel tagging (tagTasks copied into future)
624 QFuture<TagResult> future = QtConcurrent::mapped(tagTasks,
625 [this](const TagTask &task) { return _tagImage(task); });
626
627 _tagWatcher.setFuture(future);
628 // Progress and completion handled by _onTagProgress and _onTagFinished
629}
630
631void GeoTagController::_onTagProgress(int value)
632{
633 const int total = _tagWatcher.progressMaximum();
634 const double progress = calculateStageProgress(kCalibrateEnd, kTagImagesEnd, value, total);
635 _setProgress(progress);
636}
637
638void GeoTagController::_onTagFinished()
639{
640 qCDebug(GeoTagControllerLog) << "Stage: tagImages took" << _stageTimer.elapsed() << "ms";
641
642 if (_cancel) {
643 _finishWithError(tr("Tagging cancelled"));
644 return;
645 }
646
647 // Process results
648 const QList<TagResult> results = _tagWatcher.future().results();
649
650 for (const TagResult &result : results) {
651 if (result.success) {
652 _imageModel->setStatus(result.imageIndex, GeoTagImageModel::Tagged);
653 _imageModel->setCoordinate(result.imageIndex, result.coordinate);
654 } else {
655 _imageModel->setStatus(result.imageIndex, GeoTagImageModel::Failed, result.errorMessage);
656 ++_state.failedCount;
657 qCWarning(GeoTagControllerLog) << "Failed to tag image:" << result.fileName << "-" << result.errorMessage;
658 }
659 }
660
661 // Only fail completely if ALL images failed
662 if (_state.failedCount > 0 && _state.failedCount == results.count()) {
663 _finishWithError(tr("All images failed to tag"));
664 return;
665 }
666
667 _transitionTo(Stage::Finished);
668}
669
670// ============================================================================
671// Synchronous helper methods
672// ============================================================================
673
674bool GeoTagController::_loadImages(QString &errorMsg)
675{
676 _state.imageList.clear();
677
678 // Collect candidate files (optionally recursive)
679 QFileInfoList candidateFiles;
680 QDirIterator::IteratorFlags flags = QDirIterator::NoIteratorFlags;
681 if (_recursiveScan) {
682 flags = QDirIterator::Subdirectories;
683 }
684
685 QDirIterator it(_imageDirectory, kImageExtensionFilters,
686 QDir::Files | QDir::Readable | QDir::NoSymLinks, flags);
687 while (it.hasNext()) {
688 it.next();
689 candidateFiles.append(it.fileInfo());
690 }
691
692 // Sort by name for consistent ordering
693 std::sort(candidateFiles.begin(), candidateFiles.end(),
694 [](const QFileInfo &a, const QFileInfo &b) { return a.fileName() < b.fileName(); });
695
696 if (candidateFiles.isEmpty()) {
697 errorMsg = tr("The image directory doesn't contain supported images. Supported formats: JPEG, TIFF, DNG");
698 return false;
699 }
700
701 // Verify MIME types to filter out misnamed files
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);
707 } else {
708 qCDebug(GeoTagControllerLog) << "Skipping misnamed file:" << fileInfo.fileName()
709 << "MIME:" << mimeType.name();
710 }
711 }
712
713 if (_state.imageList.isEmpty()) {
714 errorMsg = tr("The image directory doesn't contain supported images. Supported formats: JPEG, TIFF, DNG");
715 return false;
716 }
717
718 // Populate image model
719 _imageModel->clear();
720 for (const QFileInfo &info : _state.imageList) {
721 _imageModel->addImage(info.absoluteFilePath());
722 }
723
724 qCDebug(GeoTagControllerLog) << "Found" << _state.imageList.count() << "images"
725 << (_recursiveScan ? "(recursive)" : "");
726
727 return true;
728}
729
730GeoTagController::ExifResult GeoTagController::_parseExifForImage(const QFileInfo &imageInfo)
731{
732 ExifResult result;
733 result.success = false;
734
735 if (_cancel) {
736 result.errorMessage = tr("Tagging cancelled");
737 return result;
738 }
739
740 QString errorString;
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());
744 return result;
745 }
746
747 const QDateTime imageTime = ExifParser::readTime(imageBuffer);
748 if (!imageTime.isValid()) {
749 result.errorMessage = tr("Geotagging failed. Couldn't extract time from image: %1").arg(imageInfo.fileName());
750 return result;
751 }
752
753 result.timestamp = imageTime.toSecsSinceEpoch();
754 result.success = true;
755 return result;
756}
757
758bool GeoTagController::_parseLogs(QString &errorMsg)
759{
760 _state.triggerList.clear();
761
762 QFile logFile(_logFile);
763 if (!logFile.open(QIODevice::ReadOnly)) {
764 errorMsg = tr("Geotagging failed. Couldn't open log file.");
765 return false;
766 }
767
768 const qint64 fileSize = logFile.size();
769 if (fileSize == 0) {
770 errorMsg = tr("Geotagging failed. Log file is empty.");
771 return false;
772 }
773
774 // Memory-map the file for efficient parsing of large logs
775 const uchar *mappedData = logFile.map(0, fileSize);
776 const char *data = nullptr;
777 qint64 dataSize = fileSize;
778 QByteArray fallbackBuffer;
779
780 if (mappedData) {
781 data = reinterpret_cast<const char*>(mappedData);
782 qCDebug(GeoTagControllerLog) << "Memory-mapped log file:" << fileSize << "bytes";
783 } else {
784 // Fallback to reading into memory if mapping fails
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.");
789 return false;
790 }
791 data = fallbackBuffer.constData();
792 dataSize = fallbackBuffer.size();
793 }
794
795 // Auto-detect log format based on file extension
796 const QString logFileLower = _logFile.toLower();
797 bool parseSuccess = false;
798 QString errorString;
799
800 if (logFileLower.endsWith(QStringLiteral(".bin"))) {
801 qCDebug(GeoTagControllerLog) << "Parsing DataFlash log:" << _logFile;
802 parseSuccess = DataFlashParser::getTagsFromLog(data, dataSize, _state.triggerList, errorString);
803 } else if (logFileLower.endsWith(QStringLiteral(".ulg"))) {
804 qCDebug(GeoTagControllerLog) << "Parsing ULog:" << _logFile;
805 parseSuccess = ULogParser::getTagsFromLog(data, dataSize, _state.triggerList, errorString);
806 } else {
807 // Try ULog first (PX4), then DataFlash (ArduPilot) as fallback
808 qCDebug(GeoTagControllerLog) << "Unknown extension, trying ULog parser first";
809 parseSuccess = ULogParser::getTagsFromLog(data, dataSize, _state.triggerList, errorString);
810 if (!parseSuccess) {
811 qCDebug(GeoTagControllerLog) << "ULog failed, trying DataFlash parser";
812 errorString.clear();
813 parseSuccess = DataFlashParser::getTagsFromLog(data, dataSize, _state.triggerList, errorString);
814 }
815 }
816
817 // Unmap the file (if mapped)
818 if (mappedData) {
819 logFile.unmap(const_cast<uchar*>(mappedData));
820 }
821
822 if (!parseSuccess) {
823 errorMsg = errorString.isEmpty() ? tr("Log parsing failed") : errorString;
824 return false;
825 }
826
827 qCDebug(GeoTagControllerLog) << "Found" << _state.triggerList.count() << "camera capture events";
828
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";
835 }
836
837 return true;
838}
839
840bool GeoTagController::_calibrate(QString &errorMsg)
841{
842 _state.imageIndices.clear();
843 _state.triggerIndices.clear();
844 _state.skippedCount = 0;
845
846 if (_state.triggerList.isEmpty() || _state.imageTimestamps.isEmpty()) {
847 errorMsg = tr("Calibration failed: No triggers or images available.");
848 return false;
849 }
850
851 // Run the matching algorithm
852 const qint64 timeOffsetSec = static_cast<qint64>(_timeOffsetSecs);
853 const qint64 toleranceSec = static_cast<qint64>(_toleranceSecs);
855 _state.imageTimestamps, _state.triggerList, timeOffsetSec, toleranceSec);
856
857 // Store results in processing state
858 _state.imageIndices = calibration.imageIndices;
859 _state.triggerIndices = calibration.triggerIndices;
860 _state.skippedCount = calibration.skippedTriggers;
861
862 qCDebug(GeoTagControllerLog) << "Calibration complete:"
863 << _state.imageIndices.count() << "matched,"
864 << _state.skippedCount << "skipped (invalid),"
865 << calibration.unmatchedImages.count() << "unmatched";
866
867 // Mark unmatched images as Skipped in the model
868 if (!calibration.unmatchedImages.isEmpty()) {
869 for (int idx : calibration.unmatchedImages) {
870 _imageModel->setStatus(idx, GeoTagImageModel::Skipped, tr("No matching trigger"));
871 }
872 _state.skippedCount += calibration.unmatchedImages.count();
873 }
874
875 if (_state.imageIndices.isEmpty()) {
876 errorMsg = tr("Calibration failed: No matching triggers found for images.");
877 return false;
878 }
879
880 return true;
881}
882
883bool GeoTagController::_validateOutputDirectory(const QString &outputDir, QString &errorMsg)
884{
885 const qint64 requiredSpace = _estimateOutputSize();
886 if (!QGCFileHelper::hasSufficientDiskSpace(outputDir, requiredSpace)) {
887 errorMsg = tr("Geotagging failed. Insufficient disk space. Need approximately %1 MB.")
888 .arg(requiredSpace / (1024 * 1024));
889 return false;
890 }
891
892 if (!QGCFileHelper::ensureDirectoryExists(outputDir)) {
893 errorMsg = tr("Geotagging failed. Couldn't create output directory: %1").arg(outputDir);
894 return false;
895 }
896
897 return true;
898}
899
900QList<GeoTagController::TagTask> GeoTagController::_buildTagTasks(const QString &outputDir, bool preview, QString &errorMsg)
901{
902 const qsizetype maxIndex = std::min(_state.imageIndices.count(), _state.triggerIndices.count());
903
904 QList<TagTask> tasks;
905 tasks.reserve(maxIndex);
906
907 for (qsizetype i = 0; i < maxIndex; ++i) {
908 const int imageIndex = _state.imageIndices[i];
909 const int triggerIndex = _state.triggerIndices[i];
910
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());
914 return {};
915 }
916
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());
920 return {};
921 }
922
923 TagTask task;
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;
929 tasks.append(task);
930 }
931
932 return tasks;
933}
934
935qint64 GeoTagController::_estimateOutputSize() const
936{
937 qint64 totalSize = 0;
938 const qsizetype maxIndex = std::min(_state.imageIndices.count(), _state.triggerIndices.count());
939
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();
944 }
945 }
946
947 // Add 10% margin for EXIF data additions
948 return static_cast<qint64>(totalSize * 1.1);
949}
950
951GeoTagController::TagResult GeoTagController::_tagImage(const TagTask &task)
952{
953 TagResult result;
954 result.imageIndex = task.imageIndex;
955 result.fileName = task.imageInfo.fileName();
956 result.success = false;
957
958 if (_cancel) {
959 result.errorMessage = tr("Tagging cancelled");
960 return result;
961 }
962
963 QString errorString;
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);
967 return result;
968 }
969
970 // In preview mode, skip actual EXIF modification and file writing
971 if (!task.previewMode) {
972 // Detach from cache before modifying (copy-on-write)
973 imageBuffer.detach();
974
975 if (!ExifParser::write(imageBuffer, task.geoTag)) {
976 result.errorMessage = tr("Geotagging failed. Couldn't write EXIF to image: %1").arg(result.fileName);
977 return result;
978 }
979
980 const QString outputPath = QGCFileHelper::joinPath(task.outputDir, result.fileName);
981 if (!QGCFileHelper::atomicWrite(outputPath, imageBuffer)) {
982 result.errorMessage = tr("Geotagging failed. Couldn't save image: %1").arg(outputPath);
983 return result;
984 }
985 }
986
987 result.coordinate = task.geoTag.coordinate;
988 result.success = true;
989 return result;
990}
991
992// ============================================================================
993// Image cache methods
994// ============================================================================
995
996QByteArray GeoTagController::_readImageCached(const QString &path, QString *errorString)
997{
998 {
999 QMutexLocker locker(&_bufferMutex);
1000 auto it = _imageBuffers.constFind(path);
1001 if (it != _imageBuffers.constEnd()) {
1002 return it.value();
1003 }
1004 }
1005
1006 // Read from disk (outside lock to allow parallel reads)
1007 QString error;
1008 QByteArray data = QGCCompression::readFile(path, &error);
1009
1010 if (data.isEmpty()) {
1011 if (errorString) {
1012 *errorString = error;
1013 }
1014 return {};
1015 }
1016
1017 // Cache the data
1018 {
1019 QMutexLocker locker(&_bufferMutex);
1020 _imageBuffers.insert(path, data);
1021 }
1022
1023 return data;
1024}
1025
1026void GeoTagController::_evictUnmatchedImages()
1027{
1028 QSet<QString> matchedPaths;
1029 for (int idx : _state.imageIndices) {
1030 if (idx < _state.imageList.count()) {
1031 matchedPaths.insert(_state.imageList[idx].absoluteFilePath());
1032 }
1033 }
1034
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);
1040 } else {
1041 ++it;
1042 }
1043 }
1044
1045 qCDebug(GeoTagControllerLog) << "Evicted unmatched images, cache size:" << _imageBuffers.count();
1046}
1047
1048void GeoTagController::_clearImageCache()
1049{
1050 QMutexLocker locker(&_bufferMutex);
1051 _imageBuffers.clear();
1052}
QString errorString
Error error
#define QGC_LOGGING_CATEGORY(name, categoryStr)
void setPreviewMode(bool preview)
void setTimeOffsetSecs(double offset)
bool inProgress() const
void setLogFile(const QString &file)
void recursiveScanChanged(bool recursiveScan)
void timeOffsetSecsChanged(double timeOffsetSecs)
void previewModeChanged(bool previewMode)
double progress() const
void saveDirectoryChanged(const QString &saveDirectory)
void imageDirectoryChanged(const QString &imageDirectory)
void setRecursiveScan(bool recursive)
QString logFile() const
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)
void inProgressChanged()
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)
Definition ExifParser.cc:13
bool write(QByteArray &buffer, const GeoTagData &geotag)
Definition ExifParser.cc:32
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)
Definition ULogParser.cc:57
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.
bool isValid() const
Definition GeoTagData.h:22
QGeoCoordinate coordinate
Definition GeoTagData.h:17
qint64 timestamp
Seconds since epoch.
Definition GeoTagData.h:14