Commit b36d59c0 authored by Andreas Bircher's avatar Andreas Bircher

updating the geotagging implementation

parent a82877ee
......@@ -508,7 +508,7 @@ SOURCES += \
src/QtLocationPlugin/QMLControl/QGCMapEngineManager.cc \
src/PositionManager/SimulatedPosition.cc \
src/PositionManager/PositionManager.cpp \
src/AnalyzeView/ExifParser.cpp
src/AnalyzeView/ExifParser.cc
DebugBuild {
SOURCES += \
......
#include "ExifParser.h"
#include <math.h>
#include <QtEndian>
#include <QDateTime>
......@@ -14,8 +15,8 @@ ExifParser::~ExifParser()
double ExifParser::readTime(QByteArray& buf)
{
char tiffHeader[] = {0x49,0x49,0x2A,0x00};
char createDateHeader[] = {0x04,0x90,0x02,0x00};
char tiffHeader[] = {static_cast<char>(0x49),static_cast<char>(0x49),static_cast<char>(0x2A),static_cast<char>(0x00)};
char createDateHeader[] = {static_cast<char>(0x04),static_cast<char>(0x90),static_cast<char>(0x02),static_cast<char>(0x00)};
// find header position
uint32_t tiffHeaderIndex = buf.indexOf(tiffHeader);
......@@ -57,7 +58,9 @@ double ExifParser::readTime(QByteArray& buf)
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);
uint16_t *conversionPointer = reinterpret_cast<uint16_t *>(buf.mid(app1HeaderInd + 2, 2).data());
uint16_t app1Size = *conversionPointer;
......@@ -122,7 +125,7 @@ bool ExifParser::write(QByteArray &buf, QGeoCoordinate coordinate)
gpsIFDInd.i = nextIfdOffset;
// 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
uint32_t gpsDataExtInd = gpsIFDInd.i + 2 + sizeof(fields_s);
......@@ -173,14 +176,14 @@ bool ExifParser::write(QByteArray &buf, QGeoCoordinate coordinate)
// 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[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[4] = 0;
gpsData.readable.extendedData.gpsLat[5] = 1;
gpsData.readable.extendedData.gpsLon[0] = abs(static_cast<int>(coordinate.longitude()));
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[4] = 0;
gpsData.readable.extendedData.gpsLon[5] = 1;
......
......@@ -8,9 +8,13 @@
****************************************************************************/
#include "GeoTagController.h"
#include "QGCFileDialog.h"
#include "ExifParser.h"
#include "QGCFileDialog.h"
#include "QGCLoggingCategory.h"
#include <math.h>
#include <QtEndian>
#include <QMessageBox>
#include <QDebug>
#include <cfloat>
GeoTagController::GeoTagController(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)
{
_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();
}
......@@ -67,6 +142,9 @@ void GeoTagController::_workerError(QString errorMessage)
GeoTagWorker::GeoTagWorker(void)
: _cancel(false)
, _logFile("")
, _imageDirectory("")
, _saveDirectory("")
{
}
......@@ -74,139 +152,148 @@ GeoTagWorker::GeoTagWorker(void)
void GeoTagWorker::run(void)
{
_cancel = false;
emit progressChanged(0);
//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();
emit progressChanged(1);
double nSteps = 5;
// Load Images
_imageList.clear();
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.setSorting(QDir::Name);
QStringList nameFilters;
nameFilters << "*.jpg" << "*.JPG";
imageDirectory.setNameFilters(nameFilters);
QFileInfoList imageList = imageDirectory.entryInfoList();
if(imageList.isEmpty()) {
_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));
_imageBuffers.clear();
for (int i = 0; i < imageList.size(); ++i) {
QFile file(imageList.at(i).absoluteFilePath());
// 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)) {
continue;
emit error(tr("Geotagging failed. Couldn't open an image."));
return;
}
_imageBuffers.append(QByteArray(file.readAll()));
QByteArray imageBuffer = file.readAll();
file.close();
}
qWarning() << "Image loading time elapsed: " << timerLoadImages.elapsed() << " milliseconds";
_tagTime.append(exifParser.readTime(imageBuffer));
////////// Parse exif data
timerParseExif.start();
emit progressChanged((100/nSteps) + ((100/nSteps) / _imageList.size())*i);
// Parse EXIF
ExifParser exifParser;
_tagTime.clear();
for (int i = 0; i < _imageBuffers.count(); i++) {
_tagTime.append(exifParser.readTime(_imageBuffers[i]));
if (_cancel) {
qCDebug(GeotaggingLog) << "Tagging cancelled";
emit error(tr("Tagging cancelled"));
return;
}
}
qWarning() << "Parse exif data time elapsed: " << timerParseExif.elapsed() << " milliseconds";
////////// Load PX4 log
timerLoadLogFile.start();
// Load PX4 log
_geoRef.clear();
_triggerTime.clear();
if (!parsePX4Log()) {
qWarning() << "Geotagging failed";
return;
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;
}
}
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
timerFilter.start();
if (_cancel) {
qCDebug(GeotaggingLog) << "Tagging cancelled";
emit error(tr("Tagging cancelled"));
return;
}
// Filter Trigger
if (!triggerFiltering()) {
qWarning() << "Geotagging failed";
qCDebug(GeotaggingLog) << "Geotagging failed in trigger filtering";
emit error(tr("Geotagging failed in trigger filtering"));
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
timerGeotag.start();
// 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();
for(int i = 0; i < _imageIndices.count() && i < _triggerIndices.count() && i < imageList.count(); i++) {
if (!exifParser.write(_imageBuffers[_imageIndices[i]], _geoRef[_triggerIndices[i]])) {
_cancel = true;
break;
if (!exifParser.write(imageBuffer, _geoRef[_triggerIndices[i]])) {
emit error(tr("Geotagging failed. Couldn't write to image."));
return;
} else {
QFile file(_imageDirectory + "/TAGGED/" + imageList[_imageIndices[i]].fileName());
if (file.open( QFile::WriteOnly)) {
file.write(_imageBuffers[_imageIndices[i]]);
file.close();
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);
qWarning() << "Tagging images time elapsed: " << timerGeotag.elapsed() << " milliseconds";
for (int i=0; i<10;i++) {
if (_cancel) {
qCDebug(GeotaggingLog) << "Tagging cancelled";
emit error(tr("Tagging cancelled"));
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 taggingComplete();
}
bool GeoTagWorker::parsePX4Log()
{
// general message header
// char header[] = {0xA3, 0x95, 0x00};
char header[] = {(char)0xA3, (char)0x95, (char)0x00};
// 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 gposLengths[3] = {4, 4, 4};
// 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 triggerLengths[2] = {8, 4};
// load log
QFile file(_logFile);
if (!file.open(QIODevice::ReadOnly)) {
qWarning() << "Could not open log file";
qCDebug(GeotaggingLog) << "Could not open log file " << _logFile;
return false;
}
QByteArray log = file.readAll();
......@@ -217,40 +304,55 @@ bool GeoTagWorker::parsePX4Log()
int sequence = -1;
QGeoCoordinate lastCoordinate;
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);
// 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;
} else if (gposIndex < 0) {
gposIndex = triggerIndex + 1;
} else if (triggerIndex < 0) {
triggerIndex = gposIndex + 1;
}
// extract next entry, gpos or trigger
if (gposIndex < triggerIndex) {
// TODO: somehow verify that the gposIndex is really the header of a gpos message
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));
uint64_t* time = reinterpret_cast<uint64_t*>(log.mid(triggerIndex + triggerOffsets[0], triggerLengths[0]).data());
double timeDouble = static_cast<double>(qFromLittleEndian(*time));
uint32_t* seq = reinterpret_cast<uint32_t*>(log.mid(triggerIndex + 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
_triggerTime.append(timeDouble/1000000.0);
sequence = seqInt;
}
index = triggerIndex; // extract next entry gpos
// 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;
} else {
uint64_t* time = reinterpret_cast<uint64_t*>(log.mid(triggerIndex + triggerOffsets[0], triggerLengths[0]).data());
double timeDouble = static_cast<double>(qFromLittleEndian(*time));
uint32_t* seq = reinterpret_cast<uint32_t*>(log.mid(triggerIndex + 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
_geoRef.append(lastCoordinate);
_triggerTime.append(timeDouble/1000000.0);
sequence = seqInt;
// verify that at an offset of 27 the next log message starts
if (gposIndex + 27 == 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;
}
index = triggerIndex;
}
}
return true;
......@@ -258,9 +360,12 @@ bool GeoTagWorker::parsePX4Log()
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);
_imagesIndices.append(i);
}
return true;
}
......@@ -10,9 +10,13 @@
#ifndef GeoTagController_H
#define GeoTagController_H
#include "QmlObjectListModel.h"
#include "Fact.h"
#include "FactMetaData.h"
#include <QObject>
#include <QString>
#include <QThread>
#include <QFileInfoList>
#include <QElapsedTimer>
#include <QDebug>
#include <QGeoCoordinate>
......@@ -24,36 +28,38 @@ class GeoTagWorker : public QThread
public:
GeoTagWorker(void);
QString logFile(void) const { return _logFile; }
QString imageDirectory(void) const { return _imageDirectory; }
void setLogFile (const QString& logFile) { _logFile = logFile; }
void setImageDirectory (const QString& imageDirectory) { _imageDirectory = imageDirectory; }
void setSaveDirectory (const QString& saveDirectory) { _saveDirectory = saveDirectory; }
void setLogFile(const QString& logFile) { _logFile = logFile; }
void setImageDirectory(const QString& imageDirectory) { _imageDirectory = imageDirectory; }
QString logFile (void) const { return _logFile; }
QString imageDirectory (void) const { return _imageDirectory; }
QString saveDirectory (void) const { return _saveDirectory; }
void cancelTagging(void) { _cancel = true; }
void cancelTagging (void) { _cancel = true; }
protected:
void run(void) final;
signals:
void error(QString errorMsg);
void taggingComplete(void);
void progressChanged(double progress);
void error (QString errorMsg);
void taggingComplete (void);
void progressChanged (double progress);
private:
bool parsePX4Log();
bool triggerFiltering();
bool _cancel;
QString _logFile;
QString _imageDirectory;
QList<QByteArray> _imageBuffers;
QList<double> _tagTime;
QList<QGeoCoordinate> _geoRef;
QList<double> _triggerTime;
QList<int> _imageIndices;
QList<int> _triggerIndices;
bool _cancel;
QString _logFile;
QString _imageDirectory;
QString _saveDirectory;
QFileInfoList _imageList;
QList<double> _tagTime;
QList<QGeoCoordinate> _geoRef;
QList<double> _triggerTime;
QList<int> _imageIndices;
QList<int> _triggerIndices;
};
/// Controller for GeoTagPage.qml. Supports geotagging images based on logfile camera tags.
......@@ -67,6 +73,7 @@ public:
Q_PROPERTY(QString logFile READ logFile NOTIFY logFileChanged)
Q_PROPERTY(QString imageDirectory READ imageDirectory NOTIFY imageDirectoryChanged)
Q_PROPERTY(QString saveDirectory READ saveDirectory NOTIFY saveDirectoryChanged)
/// Set to an error message is geotagging fails
Q_PROPERTY(QString errorMessage READ errorMessage NOTIFY errorMessageChanged)
......@@ -79,32 +86,35 @@ public:
Q_INVOKABLE void pickLogFile(void);
Q_INVOKABLE void pickImageDirectory(void);
Q_INVOKABLE void pickSaveDirectory(void);
Q_INVOKABLE void startTagging(void);
Q_INVOKABLE void cancelTagging(void) { _worker.cancelTagging(); }
QString logFile (void) const { return _worker.logFile(); }
QString imageDirectory (void) const { return _worker.imageDirectory(); }
double progress (void) const { return _progress; }
bool inProgress (void) const { return _worker.isRunning(); }
QString errorMessage (void) const { return _errorMessage; }
QString logFile (void) const { return _worker.logFile(); }
QString imageDirectory (void) const { return _worker.imageDirectory(); }
QString saveDirectory (void) const { return _worker.saveDirectory(); }
double progress (void) const { return _progress; }
bool inProgress (void) const { return _worker.isRunning(); }
QString errorMessage (void) const { return _errorMessage; }
signals:
void logFileChanged(QString logFile);
void imageDirectoryChanged(QString imageDirectory);
void progressChanged(double progress);
void inProgressChanged(void);
void errorMessageChanged(QString errorMessage);
void logFileChanged (QString logFile);
void imageDirectoryChanged (QString imageDirectory);
void saveDirectoryChanged (QString saveDirectory);
void progressChanged (double progress);
void inProgressChanged (void);
void errorMessageChanged (QString errorMessage);
private slots:
void _workerProgressChanged(double progress);
void _workerError(QString errorMsg);
private:
QString _errorMessage;
double _progress;
bool _inProgress;
QString _errorMessage;
double _progress;
bool _inProgress;
GeoTagWorker _worker;
GeoTagWorker _worker;
};
#endif
......@@ -11,7 +11,10 @@ import QtQuick 2.5
import QtQuick.Controls 1.4
import QtQuick.Dialogs 1.2
import QGroundControl 1.0
import QGroundControl.Palette 1.0
import QGroundControl.FactSystem 1.0
import QGroundControl.FactControls 1.0
import QGroundControl.Controls 1.0
import QGroundControl.ScreenTools 1.0
import QGroundControl.Controllers 1.0
......@@ -19,17 +22,17 @@ import QGroundControl.Controllers 1.0
AnalyzePage {
id: geoTagPage
pageComponent: pageComponent
pageName: qsTr("GeoTag Images (WIP)")
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.")
pageName: qsTr("GeoTag Images")
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 {
id: controller
}
Component {
id: pageComponent
id: pageComponent
Column {
id: mainColumn
......@@ -37,67 +40,104 @@ AnalyzePage {
spacing: _margin
Row {
spacing: _margin
spacing: ScreenTools.defaultFontPixelWidth * 2
QGCLabel {
text: "Log file:"
ProgressBar {
id: progressBar
width: qgcView.width -_margin * 5
maximumValue: 100
value: controller.progress
}
QGCLabel {
text: controller.logFile
BusyIndicator {
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 {
text: qsTr("Select log file")
width: ScreenTools.defaultFontPixelWidth * 30
onClicked: controller.pickLogFile()
anchors.verticalCenter: parent.verticalCenter
}
QGCLabel {
text: controller.logFile
anchors.verticalCenter: parent.verticalCenter
}
}
Row {
spacing: _margin
QGCLabel {
text: "Image directory:"
QGCButton {
text: qsTr("Select image directory")
width: ScreenTools.defaultFontPixelWidth * 30
onClicked: controller.pickImageDirectory()
anchors.verticalCenter: parent.verticalCenter
}
QGCLabel {
text: controller.imageDirectory
anchors.verticalCenter: parent.verticalCenter
}
}
Row {
spacing: _margin
QGCButton {
text: qsTr("Select image directory")
onClicked: controller.pickImageDirectory()
text: qsTr("(Optionally) Select save directory")
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 {
text: controller.inProgress ? qsTr("Cancel Tagging") : qsTr("Start Tagging")
width: ScreenTools.defaultFontPixelWidth * 30
onClicked: {
if (controller.inProgress) {
controller.cancelTagging()
} 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()
}
}
}
QGCLabel {
text: controller.errorMessage
}
ProgressBar {
anchors.left: parent.left
anchors.right: parent.right
maximumValue: 100
value: controller.progress
}
} // Column
} // Component
} // AnalyzePage
......@@ -20,7 +20,8 @@ QGC_LOGGING_CATEGORY(FirmwareUpgradeLog, "FirmwareUpgradeLog")
QGC_LOGGING_CATEGORY(FirmwareUpgradeVerboseLog, "FirmwareUpgradeVerboseLog")
QGC_LOGGING_CATEGORY(MissionCommandsLog, "MissionCommandsLog")
QGC_LOGGING_CATEGORY(MissionItemLog, "MissionItemLog")
QGC_LOGGING_CATEGORY(ParameterManagerLog, "ParameterManagerLog")
QGC_LOGGING_CATEGORY(ParameterManagerLog, "ParameterManagerLog")
QGC_LOGGING_CATEGORY(GeotaggingLog, "GeotaggingLog")
QGCLoggingCategoryRegister* _instance = NULL;
const char* QGCLoggingCategoryRegister::_filterRulesSettingsGroup = "LoggingFilters";
......
......@@ -23,6 +23,7 @@ Q_DECLARE_LOGGING_CATEGORY(FirmwareUpgradeVerboseLog)
Q_DECLARE_LOGGING_CATEGORY(MissionCommandsLog)
Q_DECLARE_LOGGING_CATEGORY(MissionItemLog)
Q_DECLARE_LOGGING_CATEGORY(ParameterManagerLog)
Q_DECLARE_LOGGING_CATEGORY(GeotaggingLog)
/// @def QGC_LOGGING_CATEGORY
/// 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