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;
70 DatabaseViewer(
const QString & ini = QString(), QWidget * parent = 0);
74 void showCloseButton(
bool visible =
true);
77 virtual void showEvent(QShowEvent* anEvent);
78 virtual void moveEvent(QMoveEvent* anEvent);
79 virtual void resizeEvent(QResizeEvent* anEvent);
80 virtual void keyPressEvent(QKeyEvent *event);
81 virtual void closeEvent(QCloseEvent* event);
82 virtual bool eventFilter(QObject *obj, QEvent *event);
86 void restoreDefaultSettings();
87 void configModified();
90 void recoverDatabase();
92 void updateStatistics();
93 void selectObstacleColor();
94 void selectGroundColor();
95 void selectEmptyColor();
96 void editDepthImage();
98 void editSaved2DMap();
99 void exportSaved2DMap();
101 void regenerateSavedMap();
102 void viewOptimizedMesh();
103 void exportOptimizedMesh();
104 void updateOptimizedMesh();
105 void exportDatabase();
106 void extractImages();
107 void exportPosesRaw();
108 void exportPosesRGBDSLAMMotionCapture();
109 void exportPosesRGBDSLAM();
110 void exportPosesKITTI();
111 void exportPosesTORO();
112 void exportPosesG2O();
113 void exportPosesKML();
114 void exportGPS_TXT();
115 void exportGPS_KML();
116 void generateLocalGraph();
117 void regenerateLocalMaps();
118 void regenerateCurrentLocalMaps();
120 void generate3DMap();
121 void detectMoreLoopClosures();
122 void updateAllNeighborCovariances();
123 void updateAllLoopClosureCovariances();
124 void refineAllNeighborLinks();
125 void refineAllLoopClosureLinks();
126 void resetAllChanges();
127 void sliderAValueChanged(
int);
128 void sliderBValueChanged(
int);
129 void sliderAMoved(
int);
130 void sliderBMoved(
int);
132 void sliderNeighborValueChanged(
int);
133 void sliderLoopValueChanged(
int);
134 void sliderIterationsValueChanged(
int);
135 void editConstraint();
137 void updateOctomapView();
138 void updateGraphView();
139 void refineConstraint();
140 void addConstraint();
141 void resetConstraint();
142 void rejectConstraint();
143 void updateConstraintView();
144 void updateLoggerLevel();
146 void notifyParametersChanged(
const QStringList &);
147 void setupMainLayout(
bool vertical);
148 void updateConstraintButtons();
151 QString getIniFilePath()
const;
155 void update(
int value,
157 QLabel * labelParents,
158 QLabel * labelChildren,
166 QLabel * labelVelocity,
169 QLabel * labelGravity,
171 QLabel * labelSensors,
172 bool updateConstraintView);
174 void updateWordsMatching(
const std::vector<int> & inliers = std::vector<int>());
175 void updateConstraintView(
177 bool updateImageSliders =
true,
180 Link findActiveLink(
int from,
int to);
182 std::multimap<int, Link> & links,
185 std::multimap<int, rtabmap::Link> updateLinksWithModifications(
186 const std::multimap<int, rtabmap::Link> & edgeConstraints);
187 void updateLoopClosuresSlider(
int from = 0,
int to = 0);
188 void updateAllCovariances(
const QList<Link> & links);
189 void refineAllLinks(
const QList<Link> & links);
190 void refineConstraint(
int from,
int to,
bool silent);
191 bool addConstraint(
int from,
int to,
bool silent);
213 std::list<std::map<int, rtabmap::Transform> >
graphes_;
219 std::multimap<int, rtabmap::Link>
links_;
223 std::map<int, std::pair<std::pair<cv::Mat, cv::Mat>, cv::Mat> >
localMaps_;
std::vector< double > odomMaxInf_
std::map< int, std::pair< float, cv::Point3f > > generatedLocalMapsInfo_
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_
std::map< int, LaserScan > modifiedLaserScans_
QDialog * editDepthDialog_
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_
int lastSliderIndexBrowsed_
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::set< int > lastWmIds_
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_
EditMapArea * editMapArea_
static int openDatabase(const char *zFilename, sqlite3 **ppDb, unsigned int flags, const char *zVfs)