forked from mavlink/qgroundcontrol
-
Notifications
You must be signed in to change notification settings - Fork 0
/
GeoTagController.cc
389 lines (348 loc) · 13.6 KB
/
GeoTagController.cc
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
/****************************************************************************
*
* (c) 2009-2016 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
*
* QGroundControl is licensed according to the terms in the file
* COPYING.md in the root of the source code directory.
*
****************************************************************************/
#include "GeoTagController.h"
#include "ExifParser.h"
#include "QGCQFileDialog.h"
#include "QGCLoggingCategory.h"
#include "MainWindow.h"
#include <math.h>
#include <QtEndian>
#include <QMessageBox>
#include <QDebug>
#include <cfloat>
GeoTagController::GeoTagController(void)
: _progress(0)
, _inProgress(false)
{
connect(&_worker, &GeoTagWorker::progressChanged, this, &GeoTagController::_workerProgressChanged);
connect(&_worker, &GeoTagWorker::error, this, &GeoTagController::_workerError);
connect(&_worker, &GeoTagWorker::started, this, &GeoTagController::inProgressChanged);
connect(&_worker, &GeoTagWorker::finished, this, &GeoTagController::inProgressChanged);
}
GeoTagController::~GeoTagController()
{
}
void GeoTagController::pickLogFile(void)
{
QString filename = QGCQFileDialog::getOpenFileName(MainWindow::instance(), "Select log file load", QString(), "PX4 log file (*.px4log);;All Files (*.*)");
if (!filename.isEmpty()) {
_worker.setLogFile(filename);
emit logFileChanged(filename);
}
}
void GeoTagController::pickImageDirectory(void)
{
QString dir = QGCQFileDialog::getExistingDirectory(MainWindow::instance(), "Select image directory");
if (!dir.isEmpty()) {
_worker.setImageDirectory(dir);
emit imageDirectoryChanged(dir);
}
}
void GeoTagController::pickSaveDirectory(void)
{
QString dir = QGCQFileDialog::getExistingDirectory(MainWindow::instance(), "Select save directory");
if (!dir.isEmpty()) {
_worker.setSaveDirectory(dir);
emit saveDirectoryChanged(dir);
}
}
void GeoTagController::startTagging(void)
{
_errorMessage.clear();
emit errorMessageChanged(_errorMessage);
QDir imageDirectory = QDir(_worker.imageDirectory());
if(!imageDirectory.exists()) {
_errorMessage = tr("Cannot find the image directory");
emit errorMessageChanged(_errorMessage);
return;
}
if(_worker.saveDirectory() == "") {
if(!imageDirectory.mkdir(_worker.imageDirectory() + "/TAGGED")) {
QMessageBox msgBox(QMessageBox::Question,
tr("Images have alreay been tagged."),
tr("The images have already been tagged. Do you want to replace the previously tagged images?"),
QMessageBox::Cancel);
msgBox.setWindowModality(Qt::ApplicationModal);
msgBox.addButton(tr("Replace"), QMessageBox::ActionRole);
if (msgBox.exec() == QMessageBox::Cancel) {
_errorMessage = tr("Images have already been tagged");
emit errorMessageChanged(_errorMessage);
return;
}
QDir oldTaggedFolder = QDir(_worker.imageDirectory() + "/TAGGED");
oldTaggedFolder.removeRecursively();
if(!imageDirectory.mkdir(_worker.imageDirectory() + "/TAGGED")) {
_errorMessage = tr("Couldn't replace the previously tagged images");
emit errorMessageChanged(_errorMessage);
return;
}
}
} else {
QDir saveDirectory = QDir(_worker.saveDirectory());
if(!saveDirectory.exists()) {
_errorMessage = tr("Cannot find the save directory");
emit errorMessageChanged(_errorMessage);
return;
}
saveDirectory.setFilter(QDir::Files | QDir::Readable | QDir::NoSymLinks | QDir::Writable);
QStringList nameFilters;
nameFilters << "*.jpg" << "*.JPG";
saveDirectory.setNameFilters(nameFilters);
QStringList imageList = saveDirectory.entryList();
if(!imageList.isEmpty()) {
QMessageBox msgBox(QMessageBox::Question,
tr("Save folder not empty."),
tr("The save folder already contains images. Do you want to replace them?"),
QMessageBox::Cancel);
msgBox.setWindowModality(Qt::ApplicationModal);
msgBox.addButton(tr("Replace"), QMessageBox::ActionRole);
if (msgBox.exec() == QMessageBox::Cancel) {
_errorMessage = tr("Save folder not empty");
emit errorMessageChanged(_errorMessage);
return;
}
foreach(QString dirFile, imageList)
{
if(!saveDirectory.remove(dirFile)) {
_errorMessage = tr("Couldn't replace the existing images");
emit errorMessageChanged(_errorMessage);
return;
}
}
}
}
_worker.start();
}
void GeoTagController::_workerProgressChanged(double progress)
{
_progress = progress;
emit progressChanged(progress);
}
void GeoTagController::_workerError(QString errorMessage)
{
_errorMessage = errorMessage;
emit errorMessageChanged(errorMessage);
}
GeoTagWorker::GeoTagWorker(void)
: _cancel(false)
, _logFile("")
, _imageDirectory("")
, _saveDirectory("")
{
}
void GeoTagWorker::run(void)
{
_cancel = false;
emit progressChanged(1);
double nSteps = 5;
// Load Images
_imageList.clear();
QDir imageDirectory = QDir(_imageDirectory);
imageDirectory.setFilter(QDir::Files | QDir::Readable | QDir::NoSymLinks | QDir::Writable);
imageDirectory.setSorting(QDir::Name);
QStringList nameFilters;
nameFilters << "*.jpg" << "*.JPG";
imageDirectory.setNameFilters(nameFilters);
_imageList = imageDirectory.entryInfoList();
if(_imageList.isEmpty()) {
emit error(tr("The image directory doesn't contain images, make sure your images are of the JPG format"));
return;
}
emit progressChanged((100/nSteps));
// Parse EXIF
ExifParser exifParser;
_tagTime.clear();
for (int i = 0; i < _imageList.size(); ++i) {
QFile file(_imageList.at(i).absoluteFilePath());
if (!file.open(QIODevice::ReadOnly)) {
emit error(tr("Geotagging failed. Couldn't open an image."));
return;
}
QByteArray imageBuffer = file.readAll();
file.close();
_tagTime.append(exifParser.readTime(imageBuffer));
emit progressChanged((100/nSteps) + ((100/nSteps) / _imageList.size())*i);
if (_cancel) {
qCDebug(GeotaggingLog) << "Tagging cancelled";
emit error(tr("Tagging cancelled"));
return;
}
}
// Load PX4 log
_geoRef.clear();
_triggerTime.clear();
if (!parsePX4Log()) {
if (_cancel) {
qCDebug(GeotaggingLog) << "Tagging cancelled";
emit error(tr("Tagging cancelled"));
return;
} else {
qCDebug(GeotaggingLog) << "Log parsing failed";
emit error(tr("Log parsing failed - tagging cancelled"));
return;
}
}
emit progressChanged(3*(100/nSteps));
qCDebug(GeotaggingLog) << "Found " << _geoRef.count() << " trigger logs.";
if (_cancel) {
qCDebug(GeotaggingLog) << "Tagging cancelled";
emit error(tr("Tagging cancelled"));
return;
}
// Filter Trigger
if (!triggerFiltering()) {
qCDebug(GeotaggingLog) << "Geotagging failed in trigger filtering";
emit error(tr("Geotagging failed in trigger filtering"));
return;
}
emit progressChanged(4*(100/nSteps));
if (_cancel) {
qCDebug(GeotaggingLog) << "Tagging cancelled";
emit error(tr("Tagging cancelled"));
return;
}
// Tag images
int maxIndex = std::min(_imageIndices.count(), _triggerIndices.count());
maxIndex = std::min(maxIndex, _imageList.count());
for(int i = 0; i < maxIndex; i++) {
QFile fileRead(_imageList.at(_imageIndices[i]).absoluteFilePath());
if (!fileRead.open(QIODevice::ReadOnly)) {
emit error(tr("Geotagging failed. Couldn't open an image."));
return;
}
QByteArray imageBuffer = fileRead.readAll();
fileRead.close();
if (!exifParser.write(imageBuffer, _geoRef[_triggerIndices[i]])) {
emit error(tr("Geotagging failed. Couldn't write to image."));
return;
} else {
QFile fileWrite;
if(_saveDirectory == "") {
fileWrite.setFileName(_imageDirectory + "/TAGGED/" + _imageList.at(_imageIndices[i]).fileName());
} else {
fileWrite.setFileName(_saveDirectory + "/" + _imageList.at(_imageIndices[i]).fileName());
}
if (!fileWrite.open(QFile::WriteOnly)) {
emit error(tr("Geotagging failed. Couldn't write to an image."));
return;
}
fileWrite.write(imageBuffer);
fileWrite.close();
}
emit progressChanged(4*(100/nSteps) + ((100/nSteps) / maxIndex)*i);
if (_cancel) {
qCDebug(GeotaggingLog) << "Tagging cancelled";
emit error(tr("Tagging cancelled"));
return;
}
}
if (_cancel) {
qCDebug(GeotaggingLog) << "Tagging cancelled";
emit error(tr("Tagging cancelled"));
return;
}
emit progressChanged(100);
}
bool GeoTagWorker::parsePX4Log()
{
// general message header
char header[] = {(char)0xA3, (char)0x95, (char)0x00};
// header for GPOS message header
char gposHeaderHeader[] = {(char)0xA3, (char)0x95, (char)0x80, (char)0x10, (char)0x00};
int gposHeaderOffset;
// header for GPOS message
char gposHeader[] = {(char)0xA3, (char)0x95, (char)0x10, (char)0x00};
int gposOffsets[3] = {3, 7, 11};
int gposLengths[3] = {4, 4, 4};
// header for trigger message header
char triggerHeaderHeader[] = {(char)0xA3, (char)0x95, (char)0x80, (char)0x37, (char)0x00};
int triggerHeaderOffset;
// header for trigger message
char triggerHeader[] = {(char)0xA3, (char)0x95, (char)0x37, (char)0x00};
int triggerOffsets[2] = {3, 11};
int triggerLengths[2] = {8, 4};
// load log
QFile file(_logFile);
if (!file.open(QIODevice::ReadOnly)) {
qCDebug(GeotaggingLog) << "Could not open log file " << _logFile;
return false;
}
QByteArray log = file.readAll();
file.close();
// extract header information: message lengths
uint8_t* iptr = reinterpret_cast<uint8_t*>(log.mid(log.indexOf(gposHeaderHeader) + 4, 1).data());
gposHeaderOffset = static_cast<int>(qFromLittleEndian(*iptr));
iptr = reinterpret_cast<uint8_t*>(log.mid(log.indexOf(triggerHeaderHeader) + 4, 1).data());
triggerHeaderOffset = static_cast<int>(qFromLittleEndian(*iptr));
// extract trigger data
int index = 1;
int sequence = -1;
QGeoCoordinate lastCoordinate;
while(index < log.count() - 1) {
if (_cancel) {
return false;
}
// first extract trigger
index = log.indexOf(triggerHeader, index + 1);
// check for whether last entry has been passed
if (index < 0) {
break;
}
if (log.indexOf(header, index + 1) != index + triggerHeaderOffset) {
continue;
}
uint64_t* time = reinterpret_cast<uint64_t*>(log.mid(index + triggerOffsets[0], triggerLengths[0]).data());
double timeDouble = static_cast<double>(qFromLittleEndian(*time)) / 1.0e6;
uint32_t* seq = reinterpret_cast<uint32_t*>(log.mid(index + triggerOffsets[1], triggerLengths[1]).data());
int seqInt = static_cast<int>(qFromLittleEndian(*seq));
if (sequence >= seqInt || sequence + 20 < seqInt) { // assume that logging has not skipped more than 20 triggers. this prevents wrong header detection
continue;
}
_triggerTime.append(timeDouble);
sequence = seqInt;
// second extract position
bool lookForGpos = true;
while (lookForGpos) {
if (_cancel) {
return false;
}
int gposIndex = log.indexOf(gposHeader, index + 1);
if (gposIndex < 0) {
_geoRef.append(lastCoordinate);
break;
}
index = gposIndex;
// verify that at an offset of gposHeaderOffset the next log message starts
if (gposIndex + gposHeaderOffset == log.indexOf(header, gposIndex + 1)) {
int32_t* lat = reinterpret_cast<int32_t*>(log.mid(gposIndex + gposOffsets[0], gposLengths[0]).data());
double latitude = static_cast<double>(qFromLittleEndian(*lat))/1.0e7;
lastCoordinate.setLatitude(latitude);
int32_t* lon = reinterpret_cast<int32_t*>(log.mid(gposIndex + gposOffsets[1], gposLengths[1]).data());
double longitude = static_cast<double>(qFromLittleEndian(*lon))/1.0e7;
longitude = fmod(180.0 + longitude, 360.0) - 180.0;
lastCoordinate.setLongitude(longitude);
float* alt = reinterpret_cast<float*>(log.mid(gposIndex + gposOffsets[2], gposLengths[2]).data());
lastCoordinate.setAltitude(qFromLittleEndian(*alt));
_geoRef.append(lastCoordinate);
break;
}
}
}
return true;
}
bool GeoTagWorker::triggerFiltering()
{
_imageIndices.clear();
_triggerIndices.clear();
for(int i = 0; i < _tagTime.count() && i < _triggerTime.count(); i++) {
_imageIndices.append(i);
_triggerIndices.append(i);
}
return true;
}