Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Include gps metadata to extracted image #920

Open
wants to merge 3 commits into
base: master
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
3 changes: 3 additions & 0 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -224,6 +224,9 @@ set_property(CACHE RTABMAP_QT_VERSION PROPERTY STRINGS AUTO 4 5)

FIND_PACKAGE(OpenCV REQUIRED QUIET COMPONENTS core calib3d imgproc highgui stitching photo video OPTIONAL_COMPONENTS aruco xfeatures2d nonfree gpu cudafeatures2d)

FIND_PACKAGE(exiv2 REQUIRED CONFIG NAMES exiv2)
link_libraries(exiv2lib)

IF(WITH_QT)
FIND_PACKAGE(PCL 1.7 REQUIRED QUIET COMPONENTS common io kdtree search surface filters registration sample_consensus segmentation visualization)
ELSE()
Expand Down
42 changes: 42 additions & 0 deletions guilib/include/rtabmap/gui/DatabaseViewer.h
Original file line number Diff line number Diff line change
Expand Up @@ -45,6 +45,8 @@ SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
#include <rtabmap/core/Link.h>
#include <rtabmap/core/Signature.h>

#include <exiv2/exiv2.hpp>

class Ui_DatabaseViewer;
class QGraphicsScene;
class QGraphicsView;
Expand Down Expand Up @@ -104,6 +106,7 @@ private Q_SLOTS:
void updateOptimizedMesh();
void exportDatabase();
void extractImages();
std::string selectGraph();
void exportPosesRaw();
void exportPosesRGBDSLAMMotionCapture();
void exportPosesRGBDSLAM();
Expand Down Expand Up @@ -197,6 +200,45 @@ private Q_SLOTS:
void exportPoses(int format);
void exportGPS(int format);

std::map<int, GPS> graphToGPS(std::string graphSource);
void writeExiv2Data(Exiv2::ExifData &exifData, std::string keyStr, std::string str);

std::string toExifTimeStamp(std::string& t)
{
char result[200];
const char* arg = t.c_str();
int HH = 0;
int mm = 0;
int SS1 = 0;
if (strstr(arg, ":") || strstr(arg, "-")) {
int YY = 0, MM = 0, DD = 0;
char a = 0, b = 0, c = 0, d = 0, e = 0;
sscanf(arg, "%d%c%d%c%d%c%d%c%d%c%d", &YY, &a, &MM, &b, &DD, &c, &HH, &d, &mm, &e, &SS1);
}
snprintf(result, sizeof(result), "%d/1 %d/1 %d/1", HH, mm, SS1);
return result;
}

std::string toExifString(double d)
{
char result[200];
d *= 100;
snprintf(result, sizeof(result), "%d/100", abs(static_cast<int>(d)));
return result;
}

std::string toExifLatLonString(double l)
{
if(l < 0) l = -l;
int degrees = floor(l);
double minTmp = (l - degrees) * 60;
int min = floor(minTmp);
int secM = floor((minTmp - min) * 60 * 1000);
std::stringstream ss;
ss << degrees << "/1 " << min << "/1 " << secM << "/1000";
return ss.str();
}

private:
Ui_DatabaseViewer * ui_;
CloudViewer * constraintsViewer_;
Expand Down
Loading