Commit b36d59c0 authored by Andreas Bircher's avatar Andreas Bircher

updating the geotagging implementation

parent a82877ee
...@@ -508,7 +508,7 @@ SOURCES += \ ...@@ -508,7 +508,7 @@ SOURCES += \
src/QtLocationPlugin/QMLControl/QGCMapEngineManager.cc \ src/QtLocationPlugin/QMLControl/QGCMapEngineManager.cc \
src/PositionManager/SimulatedPosition.cc \ src/PositionManager/SimulatedPosition.cc \
src/PositionManager/PositionManager.cpp \ src/PositionManager/PositionManager.cpp \
src/AnalyzeView/ExifParser.cpp src/AnalyzeView/ExifParser.cc
DebugBuild { DebugBuild {
SOURCES += \ SOURCES += \
......
#include "ExifParser.h" #include "ExifParser.h"
#include <math.h>
#include <QtEndian> #include <QtEndian>
#include <QDateTime> #include <QDateTime>
...@@ -14,8 +15,8 @@ ExifParser::~ExifParser() ...@@ -14,8 +15,8 @@ ExifParser::~ExifParser()
double ExifParser::readTime(QByteArray& buf) double ExifParser::readTime(QByteArray& buf)
{ {
char tiffHeader[] = {0x49,0x49,0x2A,0x00}; char tiffHeader[] = {static_cast<char>(0x49),static_cast<char>(0x49),static_cast<char>(0x2A),static_cast<char>(0x00)};
char createDateHeader[] = {0x04,0x90,0x02,0x00}; char createDateHeader[] = {static_cast<char>(0x04),static_cast<char>(0x90),static_cast<char>(0x02),static_cast<char>(0x00)};
// find header position // find header position
uint32_t tiffHeaderIndex = buf.indexOf(tiffHeader); uint32_t tiffHeaderIndex = buf.indexOf(tiffHeader);
...@@ -57,7 +58,9 @@ double ExifParser::readTime(QByteArray& buf) ...@@ -57,7 +58,9 @@ double ExifParser::readTime(QByteArray& buf)
bool ExifParser::write(QByteArray &buf, QGeoCoordinate coordinate) bool ExifParser::write(QByteArray &buf, QGeoCoordinate coordinate)
{ {
char app1Header[2] = {0xff, 0xe1}; QByteArray app1Header;
app1Header.append(0xff);
app1Header.append(0xe1);
uint32_t app1HeaderInd = buf.indexOf(app1Header); uint32_t app1HeaderInd = buf.indexOf(app1Header);
uint16_t *conversionPointer = reinterpret_cast<uint16_t *>(buf.mid(app1HeaderInd + 2, 2).data()); uint16_t *conversionPointer = reinterpret_cast<uint16_t *>(buf.mid(app1HeaderInd + 2, 2).data());
uint16_t app1Size = *conversionPointer; uint16_t app1Size = *conversionPointer;
...@@ -122,7 +125,7 @@ bool ExifParser::write(QByteArray &buf, QGeoCoordinate coordinate) ...@@ -122,7 +125,7 @@ bool ExifParser::write(QByteArray &buf, QGeoCoordinate coordinate)
gpsIFDInd.i = nextIfdOffset; gpsIFDInd.i = nextIfdOffset;
// this will stay constant // this will stay constant
char gpsInfo[12] = {0x25, 0x88, 0x04, 0x00, 0x01, 0x00, 0x00, 0x00, gpsIFDInd.c[0], gpsIFDInd.c[1], gpsIFDInd.c[2], gpsIFDInd.c[3]}; char gpsInfo[12] = {static_cast<char>(0x25), static_cast<char>(0x88), static_cast<char>(0x04), static_cast<char>(0x00), static_cast<char>(0x01), static_cast<char>(0x00), static_cast<char>(0x00), static_cast<char>(0x00), static_cast<char>(gpsIFDInd.c[0]), static_cast<char>(gpsIFDInd.c[1]), static_cast<char>(gpsIFDInd.c[2]), static_cast<char>(gpsIFDInd.c[3])};
// filling values to gpsData // filling values to gpsData
uint32_t gpsDataExtInd = gpsIFDInd.i + 2 + sizeof(fields_s); uint32_t gpsDataExtInd = gpsIFDInd.i + 2 + sizeof(fields_s);
...@@ -173,14 +176,14 @@ bool ExifParser::write(QByteArray &buf, QGeoCoordinate coordinate) ...@@ -173,14 +176,14 @@ bool ExifParser::write(QByteArray &buf, QGeoCoordinate coordinate)
// Filling up the additional information that does not fit into the fields // Filling up the additional information that does not fit into the fields
gpsData.readable.extendedData.gpsLat[0] = abs(static_cast<int>(coordinate.latitude())); gpsData.readable.extendedData.gpsLat[0] = abs(static_cast<int>(coordinate.latitude()));
gpsData.readable.extendedData.gpsLat[1] = 1; gpsData.readable.extendedData.gpsLat[1] = 1;
gpsData.readable.extendedData.gpsLat[2] = static_cast<int>((fabs(coordinate.latitude()) - std::floor(fabs(coordinate.latitude()))) * 60000.0); gpsData.readable.extendedData.gpsLat[2] = static_cast<int>((fabs(coordinate.latitude()) - floor(fabs(coordinate.latitude()))) * 60000.0);
gpsData.readable.extendedData.gpsLat[3] = 1000; gpsData.readable.extendedData.gpsLat[3] = 1000;
gpsData.readable.extendedData.gpsLat[4] = 0; gpsData.readable.extendedData.gpsLat[4] = 0;
gpsData.readable.extendedData.gpsLat[5] = 1; gpsData.readable.extendedData.gpsLat[5] = 1;
gpsData.readable.extendedData.gpsLon[0] = abs(static_cast<int>(coordinate.longitude())); gpsData.readable.extendedData.gpsLon[0] = abs(static_cast<int>(coordinate.longitude()));
gpsData.readable.extendedData.gpsLon[1] = 1; gpsData.readable.extendedData.gpsLon[1] = 1;
gpsData.readable.extendedData.gpsLon[2] = static_cast<int>((fabs(coordinate.longitude()) - std::floor(fabs(coordinate.longitude()))) * 60000.0); gpsData.readable.extendedData.gpsLon[2] = static_cast<int>((fabs(coordinate.longitude()) - floor(fabs(coordinate.longitude()))) * 60000.0);
gpsData.readable.extendedData.gpsLon[3] = 1000; gpsData.readable.extendedData.gpsLon[3] = 1000;
gpsData.readable.extendedData.gpsLon[4] = 0; gpsData.readable.extendedData.gpsLon[4] = 0;
gpsData.readable.extendedData.gpsLon[5] = 1; gpsData.readable.extendedData.gpsLon[5] = 1;
......
...@@ -8,9 +8,13 @@ ...@@ -8,9 +8,13 @@
****************************************************************************/ ****************************************************************************/
#include "GeoTagController.h" #include "GeoTagController.h"
#include "QGCFileDialog.h"
#include "ExifParser.h" #include "ExifParser.h"
#include "QGCFileDialog.h"
#include "QGCLoggingCategory.h"
#include <math.h>
#include <QtEndian> #include <QtEndian>
#include <QMessageBox>
#include <QDebug>
#include <cfloat> #include <cfloat>
GeoTagController::GeoTagController(void) GeoTagController::GeoTagController(void)
...@@ -46,10 +50,81 @@ void GeoTagController::pickImageDirectory(void) ...@@ -46,10 +50,81 @@ void GeoTagController::pickImageDirectory(void)
} }
} }
void GeoTagController::pickSaveDirectory(void)
{
QString dir = QGCFileDialog::getExistingDirectory(NULL, "Select save directory");
if (!dir.isEmpty()) {
_worker.setSaveDirectory(dir);
emit saveDirectoryChanged(dir);
}
}
void GeoTagController::startTagging(void) void GeoTagController::startTagging(void)
{ {
_errorMessage.clear(); _errorMessage.clear();
emit errorMessageChanged(_errorMessage); 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(); _worker.start();
} }
...@@ -67,6 +142,9 @@ void GeoTagController::_workerError(QString errorMessage) ...@@ -67,6 +142,9 @@ void GeoTagController::_workerError(QString errorMessage)
GeoTagWorker::GeoTagWorker(void) GeoTagWorker::GeoTagWorker(void)
: _cancel(false) : _cancel(false)
, _logFile("")
, _imageDirectory("")
, _saveDirectory("")
{ {
} }
...@@ -74,139 +152,148 @@ GeoTagWorker::GeoTagWorker(void) ...@@ -74,139 +152,148 @@ GeoTagWorker::GeoTagWorker(void)
void GeoTagWorker::run(void) void GeoTagWorker::run(void)
{ {
_cancel = false; _cancel = false;
emit progressChanged(0); emit progressChanged(1);
double nSteps = 5;
//used to time operations to get a feel for how much to progress the progressBar
QElapsedTimer timerTotal;
QElapsedTimer timerLoadImages;
QElapsedTimer timerParseExif;
QElapsedTimer timerFilter;
QElapsedTimer timerLoadLogFile;
QElapsedTimer timerGeotag;
timerTotal.start();
//////////// Load Images
timerLoadImages.start();
// Load Images
_imageList.clear();
QDir imageDirectory = QDir(_imageDirectory); QDir imageDirectory = QDir(_imageDirectory);
if(!imageDirectory.exists()) {
emit error(tr("Cannot find the image directory"));
return;
}
if(!imageDirectory.mkdir(_imageDirectory + "/TAGGED")) {
emit error(tr("Images have already been tagged"));
return;
}
imageDirectory.setFilter(QDir::Files | QDir::Readable | QDir::NoSymLinks | QDir::Writable); imageDirectory.setFilter(QDir::Files | QDir::Readable | QDir::NoSymLinks | QDir::Writable);
imageDirectory.setSorting(QDir::Name); imageDirectory.setSorting(QDir::Name);
QStringList nameFilters; QStringList nameFilters;
nameFilters << "*.jpg" << "*.JPG"; nameFilters << "*.jpg" << "*.JPG";
imageDirectory.setNameFilters(nameFilters); imageDirectory.setNameFilters(nameFilters);
_imageList = imageDirectory.entryInfoList();
QFileInfoList imageList = imageDirectory.entryInfoList(); if(_imageList.isEmpty()) {
if(imageList.isEmpty()) {
emit error(tr("The image directory doesn't contain images, make sure your images are of the JPG format")); emit error(tr("The image directory doesn't contain images, make sure your images are of the JPG format"));
return; return;
} }
emit progressChanged((100/nSteps));
_imageBuffers.clear(); // Parse EXIF
for (int i = 0; i < imageList.size(); ++i) { ExifParser exifParser;
QFile file(imageList.at(i).absoluteFilePath()); _tagTime.clear();
for (int i = 0; i < _imageList.size(); ++i) {
QFile file(_imageList.at(i).absoluteFilePath());
if (!file.open(QIODevice::ReadOnly)) { if (!file.open(QIODevice::ReadOnly)) {
continue; emit error(tr("Geotagging failed. Couldn't open an image."));
return;
} }
_imageBuffers.append(QByteArray(file.readAll())); QByteArray imageBuffer = file.readAll();
file.close(); file.close();
}
qWarning() << "Image loading time elapsed: " << timerLoadImages.elapsed() << " milliseconds"; _tagTime.append(exifParser.readTime(imageBuffer));
////////// Parse exif data emit progressChanged((100/nSteps) + ((100/nSteps) / _imageList.size())*i);
timerParseExif.start();
// Parse EXIF if (_cancel) {
ExifParser exifParser; qCDebug(GeotaggingLog) << "Tagging cancelled";
_tagTime.clear(); emit error(tr("Tagging cancelled"));
for (int i = 0; i < _imageBuffers.count(); i++) { return;
_tagTime.append(exifParser.readTime(_imageBuffers[i])); }
} }
qWarning() << "Parse exif data time elapsed: " << timerParseExif.elapsed() << " milliseconds"; // Load PX4 log
////////// Load PX4 log
timerLoadLogFile.start();
_geoRef.clear(); _geoRef.clear();
_triggerTime.clear(); _triggerTime.clear();
if (!parsePX4Log()) { if (!parsePX4Log()) {
qWarning() << "Geotagging failed"; if (_cancel) {
return; 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;
}
} }
qWarning() << "Found " << _geoRef.count() << " trigger logs."; emit progressChanged(3*(100/nSteps));
qWarning() << "Log loading time elapsed: " << timerLoadLogFile.elapsed() << " milliseconds"; qCDebug(GeotaggingLog) << "Found " << _geoRef.count() << " trigger logs.";
////////// Filter Trigger if (_cancel) {
timerFilter.start(); qCDebug(GeotaggingLog) << "Tagging cancelled";
emit error(tr("Tagging cancelled"));
return;
}
// Filter Trigger
if (!triggerFiltering()) { if (!triggerFiltering()) {
qWarning() << "Geotagging failed"; qCDebug(GeotaggingLog) << "Geotagging failed in trigger filtering";
emit error(tr("Geotagging failed in trigger filtering"));
return; return;
} }
emit progressChanged(4*(100/nSteps));
qWarning() << "Filter time elapsed: " << timerFilter.elapsed() << " milliseconds"; if (_cancel) {
qCDebug(GeotaggingLog) << "Tagging cancelled";
emit error(tr("Tagging cancelled"));
return;
}
//////////// Tag images // Tag images
timerGeotag.start(); 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();
for(int i = 0; i < _imageIndices.count() && i < _triggerIndices.count() && i < imageList.count(); i++) { if (!exifParser.write(imageBuffer, _geoRef[_triggerIndices[i]])) {
if (!exifParser.write(_imageBuffers[_imageIndices[i]], _geoRef[_triggerIndices[i]])) { emit error(tr("Geotagging failed. Couldn't write to image."));
_cancel = true; return;
break;
} else { } else {
QFile file(_imageDirectory + "/TAGGED/" + imageList[_imageIndices[i]].fileName()); QFile fileWrite;
if (file.open( QFile::WriteOnly)) { if(_saveDirectory == "") {
file.write(_imageBuffers[_imageIndices[i]]); fileWrite.setFileName(_imageDirectory + "/TAGGED/" + _imageList.at(_imageIndices[i]).fileName());
file.close(); } 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);
qWarning() << "Tagging images time elapsed: " << timerGeotag.elapsed() << " milliseconds";
for (int i=0; i<10;i++) {
if (_cancel) { if (_cancel) {
qCDebug(GeotaggingLog) << "Tagging cancelled";
emit error(tr("Tagging cancelled")); emit error(tr("Tagging cancelled"));
return; return;
} }
emit progressChanged(i*10);
//sleep(1);
} }
qWarning() << "Total time elapsed: " << timerTotal.elapsed() << " milliseconds"; if (_cancel) {
qCDebug(GeotaggingLog) << "Tagging cancelled";
emit error(tr("Tagging cancelled"));
return;
}
emit progressChanged(100); emit progressChanged(100);
emit taggingComplete();
} }
bool GeoTagWorker::parsePX4Log() bool GeoTagWorker::parsePX4Log()
{ {
// general message header // general message header
// char header[] = {0xA3, 0x95, 0x00}; char header[] = {(char)0xA3, (char)0x95, (char)0x00};
// header for GPOS message // header for GPOS message
char gposHeader[] = {0xA3, 0x95, 0x10, 0x00}; char gposHeader[] = {(char)0xA3, (char)0x95, (char)0x10, (char)0x00};
int gposOffsets[3] = {3, 7, 11}; int gposOffsets[3] = {3, 7, 11};
int gposLengths[3] = {4, 4, 4}; int gposLengths[3] = {4, 4, 4};
// header for trigger message // header for trigger message
char triggerHeader[] = {0xA3, 0x95, 0x37, 0x00}; char triggerHeader[] = {(char)0xA3, (char)0x95, (char)0x37, (char)0x00};
int triggerOffsets[2] = {3, 11}; int triggerOffsets[2] = {3, 11};
int triggerLengths[2] = {8, 4}; int triggerLengths[2] = {8, 4};
// load log // load log
QFile file(_logFile); QFile file(_logFile);
if (!file.open(QIODevice::ReadOnly)) { if (!file.open(QIODevice::ReadOnly)) {
qWarning() << "Could not open log file"; qCDebug(GeotaggingLog) << "Could not open log file " << _logFile;
return false; return false;
} }
QByteArray log = file.readAll(); QByteArray log = file.readAll();
...@@ -217,40 +304,55 @@ bool GeoTagWorker::parsePX4Log() ...@@ -217,40 +304,55 @@ bool GeoTagWorker::parsePX4Log()
int sequence = -1; int sequence = -1;
QGeoCoordinate lastCoordinate; QGeoCoordinate lastCoordinate;
while(index < log.count() - 1) { while(index < log.count() - 1) {
int gposIndex = log.indexOf(gposHeader, index + 1);
if (_cancel) {
return false;
}
// first extract trigger
int triggerIndex = log.indexOf(triggerHeader, index + 1); int triggerIndex = log.indexOf(triggerHeader, index + 1);
// check for whether last entry has been passed // check for whether last entry has been passed
if ((gposIndex < 0 && triggerIndex < 0) || (gposIndex >= log.count() - 1 && triggerIndex >= log.count() - 1)) { if (triggerIndex < 0) {
break; break;
} else if (gposIndex < 0) {
gposIndex = triggerIndex + 1;
} else if (triggerIndex < 0) {
triggerIndex = gposIndex + 1;
} }
// extract next entry, gpos or trigger uint64_t* time = reinterpret_cast<uint64_t*>(log.mid(triggerIndex + triggerOffsets[0], triggerLengths[0]).data());
if (gposIndex < triggerIndex) { double timeDouble = static_cast<double>(qFromLittleEndian(*time));
// TODO: somehow verify that the gposIndex is really the header of a gpos message uint32_t* seq = reinterpret_cast<uint32_t*>(log.mid(triggerIndex + triggerOffsets[1], triggerLengths[1]).data());
int32_t* lat = reinterpret_cast<int32_t*>(log.mid(gposIndex + gposOffsets[0], gposLengths[0]).data()); int seqInt = static_cast<int>(qFromLittleEndian(*seq));
double latitude = static_cast<double>(qFromLittleEndian(*lat))/1.0e7; if (sequence < seqInt && sequence + 20 > seqInt) { // assume that logging has not skipped more than 20 triggers. this prevents wrong header detection
lastCoordinate.setLatitude(latitude); _triggerTime.append(timeDouble/1000000.0);
int32_t* lon = reinterpret_cast<int32_t*>(log.mid(gposIndex + gposOffsets[1], gposLengths[1]).data()); sequence = seqInt;
double longitude = static_cast<double>(qFromLittleEndian(*lon))/1.0e7; }
longitude = fmod(180.0 + longitude, 360.0) - 180.0; index = triggerIndex; // extract next entry gpos
lastCoordinate.setLongitude(longitude);
float* alt = reinterpret_cast<float*>(log.mid(gposIndex + gposOffsets[2], gposLengths[2]).data()); // second extract position
lastCoordinate.setAltitude(qFromLittleEndian(*alt)); 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; index = gposIndex;
} else { // verify that at an offset of 27 the next log message starts
uint64_t* time = reinterpret_cast<uint64_t*>(log.mid(triggerIndex + triggerOffsets[0], triggerLengths[0]).data()); if (gposIndex + 27 == log.indexOf(header, gposIndex + 1)) {
double timeDouble = static_cast<double>(qFromLittleEndian(*time)); int32_t* lat = reinterpret_cast<int32_t*>(log.mid(gposIndex + gposOffsets[0], gposLengths[0]).data());
uint32_t* seq = reinterpret_cast<uint32_t*>(log.mid(triggerIndex + triggerOffsets[1], triggerLengths[1]).data()); double latitude = static_cast<double>(qFromLittleEndian(*lat))/1.0e7;
int seqInt = static_cast<int>(qFromLittleEndian(*seq)); lastCoordinate.setLatitude(latitude);
if (sequence < seqInt && sequence + 20 > seqInt) { // assume that logging has not skipped more than 20 triggers. this prevents wrong header detection int32_t* lon = reinterpret_cast<int32_t*>(log.mid(gposIndex + gposOffsets[1], gposLengths[1]).data());
_geoRef.append(lastCoordinate); double longitude = static_cast<double>(qFromLittleEndian(*lon))/1.0e7;
_triggerTime.append(timeDouble/1000000.0); longitude = fmod(180.0 + longitude, 360.0) - 180.0;
sequence = seqInt; lastCoordinate.setLongitude(longitude);
float* alt = reinterpret_cast<float*>(log.mid(gposIndex + gposOffsets[2], gposLengths[2]).data());
lastCoordinate.setAltitude(qFromLittleEndian(*alt));
_geoRef.append(lastCoordinate);
break;
} }
index = triggerIndex;
} }
} }
return true; return true;
...@@ -258,9 +360,12 @@ bool GeoTagWorker::parsePX4Log() ...@@ -258,9 +360,12 @@ bool GeoTagWorker::parsePX4Log()
bool GeoTagWorker::triggerFiltering() bool GeoTagWorker::triggerFiltering()
{ {
for (int i = 0; i < _triggerTime.count() && i < _tagTime.count(); i++) { _imageIndices.clear();
_triggerIndices.clear();
for(int i = 0; i < _tagTime.count() && i < _triggerTime.count(); i++) {
_imageIndices.append(i);
_triggerIndices.append(i); _triggerIndices.append(i);
_imagesIndices.append(i);
} }
return true; return true;
} }
...@@ -10,9 +10,13 @@ ...@@ -10,9 +10,13 @@
#ifndef GeoTagController_H #ifndef GeoTagController_H
#define GeoTagController_H #define GeoTagController_H
#include "QmlObjectListModel.h"
#include "Fact.h"
#include "FactMetaData.h"
#include <QObject> #include <QObject>
#include <QString> #include <QString>
#include <QThread> #include <QThread>
#include <QFileInfoList>
#include <QElapsedTimer> #include <QElapsedTimer>
#include <QDebug> #include <QDebug>
#include <QGeoCoordinate> #include <QGeoCoordinate>
...@@ -24,36 +28,38 @@ class GeoTagWorker : public QThread ...@@ -24,36 +28,38 @@ class GeoTagWorker : public QThread
public: public:
GeoTagWorker(void); GeoTagWorker(void);
QString logFile(void) const { return _logFile; } void setLogFile (const QString& logFile) { _logFile = logFile; }
QString imageDirectory(void) const { return _imageDirectory; } void setImageDirectory (const QString& imageDirectory) { _imageDirectory = imageDirectory; }
void setSaveDirectory (const QString& saveDirectory) { _saveDirectory = saveDirectory; }
void setLogFile(const QString& logFile) { _logFile = logFile; } QString logFile (void) const { return _logFile; }
void setImageDirectory(const QString& imageDirectory) { _imageDirectory = imageDirectory; } QString imageDirectory (void) const { return _imageDirectory; }
QString saveDirectory (void) const { return _saveDirectory; }
void cancelTagging(void) { _cancel = true; } void cancelTagging (void) { _cancel = true; }
protected: protected:
void run(void) final; void run(void) final;
signals: signals:
void error(QString errorMsg); void error (QString errorMsg);
void taggingComplete(void); void taggingComplete (void);
void progressChanged(double progress); void progressChanged (double progress);
private: private:
bool parsePX4Log(); bool parsePX4Log();
bool triggerFiltering(); bool triggerFiltering();
bool _cancel;
bool _cancel; QString _logFile;
QString _logFile; QString _imageDirectory;
QString _imageDirectory; QString _saveDirectory;
QList<QByteArray> _imageBuffers; QFileInfoList _imageList;
QList<double> _tagTime; QList<double> _tagTime;
QList<QGeoCoordinate> _geoRef; QList<QGeoCoordinate> _geoRef;
QList<double> _triggerTime; QList<double> _triggerTime;
QList<int> _imageIndices; QList<int> _imageIndices;
QList<int> _triggerIndices; QList<int> _triggerIndices;
}; };
/// Controller for GeoTagPage.qml. Supports geotagging images based on logfile camera tags. /// Controller for GeoTagPage.qml. Supports geotagging images based on logfile camera tags.
...@@ -67,6 +73,7 @@ public: ...@@ -67,6 +73,7 @@ public:
Q_PROPERTY(QString logFile READ logFile NOTIFY logFileChanged) Q_PROPERTY(QString logFile READ logFile NOTIFY logFileChanged)
Q_PROPERTY(QString imageDirectory READ imageDirectory NOTIFY imageDirectoryChanged) Q_PROPERTY(QString imageDirectory READ imageDirectory NOTIFY imageDirectoryChanged)
Q_PROPERTY(QString saveDirectory READ saveDirectory NOTIFY saveDirectoryChanged)
/// Set to an error message is geotagging fails /// Set to an error message is geotagging fails
Q_PROPERTY(QString errorMessage READ errorMessage NOTIFY errorMessageChanged) Q_PROPERTY(QString errorMessage READ errorMessage NOTIFY errorMessageChanged)
...@@ -79,32 +86,35 @@ public: ...@@ -79,32 +86,35 @@ public:
Q_INVOKABLE void pickLogFile(void); Q_INVOKABLE void pickLogFile(void);
Q_INVOKABLE void pickImageDirectory(void); Q_INVOKABLE void pickImageDirectory(void);
Q_INVOKABLE void pickSaveDirectory(void);
Q_INVOKABLE void startTagging(void); Q_INVOKABLE void startTagging(void);
Q_INVOKABLE void cancelTagging(void) { _worker.cancelTagging(); } Q_INVOKABLE void cancelTagging(void) { _worker.cancelTagging(); }
QString logFile (void) const { return _worker.logFile(); } QString logFile (void) const { return _worker.logFile(); }
QString imageDirectory (void) const { return _worker.imageDirectory(); } QString imageDirectory (void) const { return _worker.imageDirectory(); }
double progress (void) const { return _progress; } QString saveDirectory (void) const { return _worker.saveDirectory(); }
bool inProgress (void) const { return _worker.isRunning(); } double progress (void) const { return _progress; }
QString errorMessage (void) const { return _errorMessage; } bool inProgress (void) const { return _worker.isRunning(); }
QString errorMessage (void) const { return _errorMessage; }
signals: signals:
void logFileChanged(QString logFile); void logFileChanged (QString logFile);
void imageDirectoryChanged(QString imageDirectory); void imageDirectoryChanged (QString imageDirectory);
void progressChanged(double progress); void saveDirectoryChanged (QString saveDirectory);
void inProgressChanged(void); void progressChanged (double progress);
void errorMessageChanged(QString errorMessage); void inProgressChanged (void);
void errorMessageChanged (QString errorMessage);
private slots: private slots:
void _workerProgressChanged(double progress); void _workerProgressChanged(double progress);
void _workerError(QString errorMsg); void _workerError(QString errorMsg);
private: private:
QString _errorMessage; QString _errorMessage;
double _progress; double _progress;
bool _inProgress; bool _inProgress;
GeoTagWorker _worker; GeoTagWorker _worker;
}; };
#endif #endif
...@@ -11,7 +11,10 @@ import QtQuick 2.5 ...@@ -11,7 +11,10 @@ import QtQuick 2.5
import QtQuick.Controls 1.4 import QtQuick.Controls 1.4
import QtQuick.Dialogs 1.2 import QtQuick.Dialogs 1.2
import QGroundControl 1.0
import QGroundControl.Palette 1.0 import QGroundControl.Palette 1.0
import QGroundControl.FactSystem 1.0
import QGroundControl.FactControls 1.0
import QGroundControl.Controls 1.0 import QGroundControl.Controls 1.0
import QGroundControl.ScreenTools 1.0 import QGroundControl.ScreenTools 1.0
import QGroundControl.Controllers 1.0 import QGroundControl.Controllers 1.0
...@@ -19,17 +22,17 @@ import QGroundControl.Controllers 1.0 ...@@ -19,17 +22,17 @@ import QGroundControl.Controllers 1.0
AnalyzePage { AnalyzePage {
id: geoTagPage id: geoTagPage
pageComponent: pageComponent pageComponent: pageComponent
pageName: qsTr("GeoTag Images (WIP)") pageName: qsTr("GeoTag Images")
pageDescription: qsTr("GetTag Images is used to tag a set of images from a survey mission with gps coordinates. You must provide the binary log from the flight as well as the directory which contains the images to tag.") pageDescription: qsTr("GeoTag Images is used to tag a set of images from a survey mission with gps coordinates. You must provide the binary log from the flight as well as the directory which contains the images to tag.")
property real _margin: ScreenTools.defaultFontPixelWidth property real _margin: ScreenTools.defaultFontPixelWidth * 2
GeoTagController { GeoTagController {
id: controller id: controller
} }
Component { Component {
id: pageComponent id: pageComponent
Column { Column {
id: mainColumn id: mainColumn
...@@ -37,67 +40,104 @@ AnalyzePage { ...@@ -37,67 +40,104 @@ AnalyzePage {
spacing: _margin spacing: _margin
Row { Row {
spacing: _margin spacing: ScreenTools.defaultFontPixelWidth * 2
QGCLabel { ProgressBar {
text: "Log file:" id: progressBar
width: qgcView.width -_margin * 5
maximumValue: 100
value: controller.progress
} }
QGCLabel { BusyIndicator {
text: controller.logFile running: controller.progress > 0 && controller.progress < 100 && controller.errorMessage === ""
width: progressBar.height
height: progressBar.height
} }
}
QGCLabel {
text: controller.errorMessage
font.bold: true
font.pointSize: ScreenTools.largeFontPointSize
color: "red"
}
// Horizontal spacer line
Rectangle {
height: 1
width: qgcView.width * 1.0
color: qgcPal.windowShadeDark
anchors.horizontalCenter: parent.horizontalCenter
}
Row {
spacing: _margin
QGCButton { QGCButton {
text: qsTr("Select log file") text: qsTr("Select log file")
width: ScreenTools.defaultFontPixelWidth * 30
onClicked: controller.pickLogFile() onClicked: controller.pickLogFile()
anchors.verticalCenter: parent.verticalCenter
}
QGCLabel {
text: controller.logFile
anchors.verticalCenter: parent.verticalCenter
} }
} }
Row { Row {
spacing: _margin spacing: _margin
QGCLabel { QGCButton {
text: "Image directory:" text: qsTr("Select image directory")
width: ScreenTools.defaultFontPixelWidth * 30
onClicked: controller.pickImageDirectory()
anchors.verticalCenter: parent.verticalCenter
} }
QGCLabel { QGCLabel {
text: controller.imageDirectory text: controller.imageDirectory
anchors.verticalCenter: parent.verticalCenter
} }
}
Row {
spacing: _margin
QGCButton { QGCButton {
text: qsTr("Select image directory") text: qsTr("(Optionally) Select save directory")
onClicked: controller.pickImageDirectory() width: ScreenTools.defaultFontPixelWidth * 30
onClicked: controller.pickSaveDirectory()
anchors.verticalCenter: parent.verticalCenter
}
QGCLabel {
text: controller.saveDirectory != "" ? controller.saveDirectory : "/TAGGED folder in your image folder"
anchors.verticalCenter: parent.verticalCenter
} }
} }
QGCLabel { text: "NYI - Simulated only" } // Horizontal spacer line
Rectangle {
height: 1
width: qgcView.width * 1.0
color: qgcPal.windowShadeDark
anchors.horizontalCenter: parent.horizontalCenter
}
QGCButton { QGCButton {
text: controller.inProgress ? qsTr("Cancel Tagging") : qsTr("Start Tagging") text: controller.inProgress ? qsTr("Cancel Tagging") : qsTr("Start Tagging")
width: ScreenTools.defaultFontPixelWidth * 30
onClicked: { onClicked: {
if (controller.inProgress) { if (controller.inProgress) {
controller.cancelTagging() controller.cancelTagging()
} else { } else {
if (controller.logFile == "" || controller.imageDirectory == "") {
geoTagPage.showMessage(qsTr("Error"), qsTr("You must select a log file and image directory before you can start tagging."), StandardButton.Ok)
return
}
controller.startTagging() controller.startTagging()
} }
} }
} }
QGCLabel {
text: controller.errorMessage
}
ProgressBar {
anchors.left: parent.left
anchors.right: parent.right
maximumValue: 100
value: controller.progress
}
} // Column } // Column
} // Component } // Component
} // AnalyzePage } // AnalyzePage
...@@ -20,7 +20,8 @@ QGC_LOGGING_CATEGORY(FirmwareUpgradeLog, "FirmwareUpgradeLog") ...@@ -20,7 +20,8 @@ QGC_LOGGING_CATEGORY(FirmwareUpgradeLog, "FirmwareUpgradeLog")
QGC_LOGGING_CATEGORY(FirmwareUpgradeVerboseLog, "FirmwareUpgradeVerboseLog") QGC_LOGGING_CATEGORY(FirmwareUpgradeVerboseLog, "FirmwareUpgradeVerboseLog")
QGC_LOGGING_CATEGORY(MissionCommandsLog, "MissionCommandsLog") QGC_LOGGING_CATEGORY(MissionCommandsLog, "MissionCommandsLog")
QGC_LOGGING_CATEGORY(MissionItemLog, "MissionItemLog") QGC_LOGGING_CATEGORY(MissionItemLog, "MissionItemLog")
QGC_LOGGING_CATEGORY(ParameterManagerLog, "ParameterManagerLog") QGC_LOGGING_CATEGORY(ParameterManagerLog, "ParameterManagerLog")
QGC_LOGGING_CATEGORY(GeotaggingLog, "GeotaggingLog")
QGCLoggingCategoryRegister* _instance = NULL; QGCLoggingCategoryRegister* _instance = NULL;
const char* QGCLoggingCategoryRegister::_filterRulesSettingsGroup = "LoggingFilters"; const char* QGCLoggingCategoryRegister::_filterRulesSettingsGroup = "LoggingFilters";
......
...@@ -23,6 +23,7 @@ Q_DECLARE_LOGGING_CATEGORY(FirmwareUpgradeVerboseLog) ...@@ -23,6 +23,7 @@ Q_DECLARE_LOGGING_CATEGORY(FirmwareUpgradeVerboseLog)
Q_DECLARE_LOGGING_CATEGORY(MissionCommandsLog) Q_DECLARE_LOGGING_CATEGORY(MissionCommandsLog)
Q_DECLARE_LOGGING_CATEGORY(MissionItemLog) Q_DECLARE_LOGGING_CATEGORY(MissionItemLog)
Q_DECLARE_LOGGING_CATEGORY(ParameterManagerLog) Q_DECLARE_LOGGING_CATEGORY(ParameterManagerLog)
Q_DECLARE_LOGGING_CATEGORY(GeotaggingLog)
/// @def QGC_LOGGING_CATEGORY /// @def QGC_LOGGING_CATEGORY
/// This is a QGC specific replacement for Q_LOGGING_CATEGORY. It will register the category name into a /// This is a QGC specific replacement for Q_LOGGING_CATEGORY. It will register the category name into a
......
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment