28 #ifndef RTABMAP_DATABASEVIEWER_H_ 29 #define RTABMAP_DATABASEVIEWER_H_ 33 #include <QMainWindow> 34 #include <QtCore/QByteArray> 35 #include <QtCore/QMap> 36 #include <QtCore/QSet> 37 #include <QtGui/QImage> 38 #include <opencv2/core/core.hpp> 39 #include <opencv2/features2d/features2d.hpp> 42 #include <pcl/point_cloud.h> 43 #include <pcl/point_types.h> 48 class Ui_DatabaseViewer;
61 class ExportCloudsDialog;
69 DatabaseViewer(
const QString & ini = QString(), QWidget * parent = 0);
73 void showCloseButton(
bool visible =
true);
76 virtual void showEvent(QShowEvent* anEvent);
77 virtual void moveEvent(QMoveEvent* anEvent);
78 virtual void resizeEvent(QResizeEvent* anEvent);
79 virtual void keyPressEvent(QKeyEvent *event);
80 virtual void closeEvent(QCloseEvent* event);
81 virtual bool eventFilter(QObject *obj, QEvent *event);
85 void restoreDefaultSettings();
86 void configModified();
89 void recoverDatabase();
90 void updateStatistics();
91 void selectObstacleColor();
92 void selectGroundColor();
93 void selectEmptyColor();
94 void editDepthImage();
96 void exportSaved2DMap();
98 void viewOptimizedMesh();
99 void exportOptimizedMesh();
100 void updateOptimizedMesh();
101 void exportDatabase();
102 void extractImages();
103 void exportPosesRaw();
104 void exportPosesRGBDSLAM();
105 void exportPosesKITTI();
106 void exportPosesTORO();
107 void exportPosesG2O();
108 void exportPosesKML();
109 void exportGPS_TXT();
110 void exportGPS_KML();
111 void generateLocalGraph();
112 void regenerateLocalMaps();
113 void regenerateCurrentLocalMaps();
115 void generate3DMap();
116 void detectMoreLoopClosures();
117 void refineAllNeighborLinks();
118 void refineAllLoopClosureLinks();
119 void resetAllChanges();
120 void sliderAValueChanged(
int);
121 void sliderBValueChanged(
int);
122 void sliderAMoved(
int);
123 void sliderBMoved(
int);
125 void sliderNeighborValueChanged(
int);
126 void sliderLoopValueChanged(
int);
127 void sliderIterationsValueChanged(
int);
129 void updateOctomapView();
130 void updateGraphView();
131 void refineConstraint();
132 void addConstraint();
133 void resetConstraint();
134 void rejectConstraint();
135 void updateConstraintView();
136 void updateLoggerLevel();
138 void notifyParametersChanged(
const QStringList &);
139 void setupMainLayout(
bool vertical);
142 QString getIniFilePath()
const;
146 void update(
int value,
148 QLabel * labelParents,
149 QLabel * labelChildren,
157 QLabel * labelVelocity,
160 bool updateConstraintView);
162 void updateWordsMatching();
163 void updateConstraintView(
165 bool updateImageSliders =
true,
168 void updateConstraintButtons();
169 Link findActiveLink(
int from,
int to);
171 std::multimap<int, Link> & links,
174 std::multimap<int, rtabmap::Link> updateLinksWithModifications(
175 const std::multimap<int, rtabmap::Link> & edgeConstraints);
176 void updateLoopClosuresSlider(
int from = 0,
int to = 0);
177 void refineConstraint(
int from,
int to,
bool silent);
178 bool addConstraint(
int from,
int to,
bool silent);
198 std::list<std::map<int, rtabmap::Transform> >
graphes_;
204 std::multimap<int, rtabmap::Link>
links_;
208 std::map<int, std::pair<std::pair<cv::Mat, cv::Mat>, cv::Mat> >
localMaps_;
std::map< int, std::pair< float, cv::Point3f > > generatedLocalMapsInfo_
bool RTABMAP_EXP exportPoses(const std::string &filePath, int format, const std::map< int, Transform > &poses, const std::multimap< int, Link > &constraints=std::multimap< int, Link >(), const std::map< int, double > &stamps=std::map< int, double >(), bool g2oRobust=false)
std::map< int, rtabmap::Transform > gpsPoses_
bool RTABMAP_EXP exportGPS(const std::string &filePath, const std::map< int, GPS > &gpsValues, unsigned int rgba=0xFFFFFFFF)
std::list< std::map< int, rtabmap::Transform > > graphes_
CloudViewer * constraintsViewer_
std::multimap< int, rtabmap::Link > linksAdded_
QList< rtabmap::Link > neighborLinks_
std::multimap< int, rtabmap::Link > links_
ExportCloudsDialog * exportDialog_
QMap< int, int > idToIndex_
QDialog * editDepthDialog_
std::map< int, Transform > lastOptimizedGraph_
std::string databaseFileName_
EditDepthArea * editDepthArea_
std::multimap< int, rtabmap::Link > linksRefined_
std::map< int, int > mapIds_
std::map< int, GPS > gpsValues_
std::multimap< int, rtabmap::Link > graphLinks_
QList< rtabmap::Link > loopLinks_
bool useLastOptimizedGraphAsGuess_
std::map< int, std::vector< int > > wmStates_
std::map< int, std::pair< float, cv::Point3f > > localMapsInfo_
std::map< int, int > weights_
std::multimap< int, rtabmap::Link > linksRemoved_
std::map< int, rtabmap::Transform > odomPoses_
std::map< int, rtabmap::Transform > groundTruthPoses_
CloudViewer * stereoViewer_
rtabmap::DBDriver * dbDriver_
bool isSavedMaximized() const
std::map< int, cv::Mat > modifiedDepthImages_
std::map< int, std::pair< std::pair< cv::Mat, cv::Mat >, cv::Mat > > localMaps_
CloudViewer * cloudViewer_
CloudViewer * occupancyGridViewer_
std::map< int, std::pair< std::pair< cv::Mat, cv::Mat >, cv::Mat > > generatedLocalMaps_
static int openDatabase(const char *zFilename, sqlite3 **ppDb, unsigned int flags, const char *zVfs)