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