QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
GeoTagController.h
Go to the documentation of this file.
1#pragma once
2
3#include "GeoTagData.h"
4
5#include <QtCore/QElapsedTimer>
6#include <QtCore/QFileInfo>
7#include <QtCore/QFileInfoList>
8#include <QtCore/QFutureWatcher>
9#include <QtCore/QHash>
10#include <QtCore/QMap>
11#include <QtCore/QMutex>
12#include <QtCore/QObject>
13#include <QtCore/QString>
14#include <QtPositioning/QGeoCoordinate>
15#include <QtQmlIntegration/QtQmlIntegration>
16
17#include <atomic>
18
20
23 QList<int> imageIndices;
24 QList<int> triggerIndices;
25 QList<int> unmatchedImages;
27};
28
30
37CalibrationResult calibrate(const QList<qint64> &imageTimestamps,
38 const QList<GeoTagData> &triggers,
39 qint64 timeOffsetSecs,
40 qint64 toleranceSecs);
41
42} // namespace GeoTagCalibrator
43
48class GeoTagController : public QObject
49{
50 Q_OBJECT
51 QML_ELEMENT
52 QML_SINGLETON
53 Q_MOC_INCLUDE("GeoTagImageModel.h")
54
55 Q_PROPERTY(QString logFile READ logFile WRITE setLogFile NOTIFY logFileChanged)
56 Q_PROPERTY(QString imageDirectory READ imageDirectory WRITE setImageDirectory NOTIFY imageDirectoryChanged)
57 Q_PROPERTY(QString saveDirectory READ saveDirectory WRITE setSaveDirectory NOTIFY saveDirectoryChanged)
58 Q_PROPERTY(QString errorMessage READ errorMessage NOTIFY errorMessageChanged)
59 Q_PROPERTY(double progress READ progress NOTIFY progressChanged)
60 Q_PROPERTY(bool inProgress READ inProgress NOTIFY inProgressChanged)
61 Q_PROPERTY(int taggedCount READ taggedCount NOTIFY taggingCompleteChanged)
62 Q_PROPERTY(int skippedCount READ skippedCount NOTIFY taggingCompleteChanged)
63 Q_PROPERTY(int failedCount READ failedCount NOTIFY taggingCompleteChanged)
64 Q_PROPERTY(double timeOffsetSecs READ timeOffsetSecs WRITE setTimeOffsetSecs NOTIFY timeOffsetSecsChanged)
65 Q_PROPERTY(double toleranceSecs READ toleranceSecs WRITE setToleranceSecs NOTIFY toleranceSecsChanged)
66 Q_PROPERTY(bool previewMode READ previewMode WRITE setPreviewMode NOTIFY previewModeChanged)
67 Q_PROPERTY(bool recursiveScan READ recursiveScan WRITE setRecursiveScan NOTIFY recursiveScanChanged)
68 Q_PROPERTY(GeoTagImageModel* imageModel READ imageModel CONSTANT)
69
70public:
71 explicit GeoTagController(QObject *parent = nullptr);
72 ~GeoTagController() override;
73
74 Q_INVOKABLE void startTagging();
75 Q_INVOKABLE void cancelTagging();
76
77 QString logFile() const { return _logFile; }
78 QString imageDirectory() const { return _imageDirectory; }
79 QString saveDirectory() const { return _saveDirectory; }
80 double progress() const { return _progress; }
81 bool inProgress() const { return _stage != Stage::Idle; }
82 QString errorMessage() const { return _errorMessage; }
83 int taggedCount() const { return _taggedCount; }
84 int skippedCount() const { return _skippedCount; }
85 int failedCount() const { return _failedCount; }
86 double timeOffsetSecs() const { return _timeOffsetSecs; }
87 double toleranceSecs() const { return _toleranceSecs; }
88 bool previewMode() const { return _previewMode; }
89 bool recursiveScan() const { return _recursiveScan; }
90 GeoTagImageModel* imageModel() const { return _imageModel; }
91
92 void setLogFile(const QString &file);
93 void setImageDirectory(const QString &dir);
94 void setSaveDirectory(const QString &dir);
95 void setTimeOffsetSecs(double offset);
96 void setToleranceSecs(double tolerance);
97 void setPreviewMode(bool preview);
98 void setRecursiveScan(bool recursive);
99
100signals:
101 void logFileChanged(const QString &logFile);
106 void errorMessageChanged(const QString &errorMessage);
112
113private:
114 // Processing stages for async state machine
115 enum class Stage {
116 Idle,
117 LoadingImages,
118 ParsingExif,
119 ParsingLogs,
120 Calibrating,
121 TaggingImages,
122 Finished
123 };
124
125 static const char* stageName(Stage stage);
126
127 struct ExifResult {
128 qint64 timestamp = 0;
129 QString errorMessage;
130 bool success = false;
131 };
132
133 struct TagResult {
134 int imageIndex = -1;
135 QString fileName;
136 QString errorMessage;
137 QGeoCoordinate coordinate;
138 bool success = false;
139 };
140
141 struct TagTask {
142 int imageIndex = -1;
143 QFileInfo imageInfo;
144 GeoTagData geoTag;
145 QString outputDir;
146 bool previewMode = false;
147 };
148
149 // State machine control
150 void _setErrorMessage(const QString &errorMsg);
151 void _setProgress(double progress);
152 void _transitionTo(Stage stage);
153 void _finishWithError(const QString &errorMsg);
154 void _finishSuccess();
155
156 // Stage implementations
157 void _startLoadImages();
158 void _startParseExif();
159 void _startParseLogs();
160 void _startCalibrate();
161 void _startTagImages();
162
163 // Async stage handlers (slots for QFutureWatcher signals)
164 void _onExifProgress(int value);
165 void _onExifFinished();
166 void _onTagProgress(int value);
167 void _onTagFinished();
168
169 // Synchronous helpers (called from stage implementations)
170 bool _loadImages(QString &errorMsg);
171 bool _parseLogs(QString &errorMsg);
172 bool _calibrate(QString &errorMsg);
173 bool _validateOutputDirectory(const QString &outputDir, QString &errorMsg);
174 QList<TagTask> _buildTagTasks(const QString &outputDir, bool preview, QString &errorMsg);
175 qint64 _estimateOutputSize() const;
176
177 ExifResult _parseExifForImage(const QFileInfo &imageInfo);
178 TagResult _tagImage(const TagTask &task);
179
180 // Image buffer cache (thread-safe)
181 QByteArray _readImageCached(const QString &path, QString *errorString = nullptr);
182 void _evictUnmatchedImages();
183 void _clearImageCache();
184
185 // QML properties
186 QString _logFile;
187 QString _imageDirectory;
188 QString _saveDirectory;
189 QString _errorMessage;
190 double _progress = 0.;
191 int _taggedCount = 0;
192 int _skippedCount = 0;
193 int _failedCount = 0;
194 double _timeOffsetSecs = 0.0;
195 double _toleranceSecs = 2.0;
196 bool _previewMode = false;
197 bool _recursiveScan = false;
198
199 // Processing state
200 struct ProcessingState {
201 QFileInfoList imageList;
202 QList<qint64> imageTimestamps;
203 QList<GeoTagData> triggerList;
204 QList<int> imageIndices;
205 QList<int> triggerIndices;
206 int skippedCount = 0;
207 int failedCount = 0;
208
209 void clear() {
210 imageList.clear();
211 imageTimestamps.clear();
212 triggerList.clear();
213 imageIndices.clear();
214 triggerIndices.clear();
215 skippedCount = 0;
216 failedCount = 0;
217 }
218 };
219
220 // Async state machine
221 Stage _stage = Stage::Idle;
222 std::atomic<bool> _cancel{false};
223 QElapsedTimer _totalTimer;
224 QElapsedTimer _stageTimer;
225
226 // Async watchers for parallel stages
227 QFutureWatcher<ExifResult> _exifWatcher;
228 QFutureWatcher<TagResult> _tagWatcher;
229
230 ProcessingState _state;
231
232 // Image model for QML display
233 GeoTagImageModel *_imageModel = nullptr;
234
235 // Image buffer cache to avoid reading files twice
236 mutable QMutex _bufferMutex;
237 QHash<QString, QByteArray> _imageBuffers;
238
239 // Progress calculation constants
240 static constexpr double kLoadImagesEnd = 20.0;
241 static constexpr double kParseExifEnd = 40.0;
242 static constexpr double kParseLogsEnd = 60.0;
243 static constexpr double kCalibrateEnd = 80.0;
244 static constexpr double kTagImagesEnd = 100.0;
245};
QString errorString
Controller for GeoTagPage.qml. Supports geotagging images based on logfile camera tags.
QString imageDirectory() const
void setPreviewMode(bool preview)
int taggedCount() const
double timeOffsetSecs() const
void setTimeOffsetSecs(double offset)
QString errorMessage() const
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)
int skippedCount() const
void setRecursiveScan(bool recursive)
int failedCount() const
QString logFile() const
bool recursiveScan() const
GeoTagImageModel * imageModel() const
Q_INVOKABLE void cancelTagging()
bool previewMode() const
void toleranceSecsChanged(double toleranceSecs)
void progressChanged(double progress)
~GeoTagController() override
void logFileChanged(const QString &logFile)
QString saveDirectory() const
void errorMessageChanged(const QString &errorMessage)
double toleranceSecs() const
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.
CalibrationResult calibrate(const QList< qint64 > &imageTimestamps, const QList< GeoTagData > &triggers, qint64 timeOffsetSecs, qint64 toleranceSecs)
QString errorMessage(const QNetworkReply *reply)
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.