28 #ifndef RTABMAP_DATABASEVIEWER_H_
29 #define RTABMAP_DATABASEVIEWER_H_
31 #include "rtabmap/gui/rtabmap_gui_export.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>
49 class Ui_DatabaseViewer;
63 class ExportCloudsDialog;
66 class LinkRefiningDialog;
73 DatabaseViewer(
const QString & ini = QString(), QWidget * parent = 0);
77 void showCloseButton(
bool visible =
true);
80 virtual void showEvent(QShowEvent* anEvent);
81 virtual void moveEvent(QMoveEvent* anEvent);
82 virtual void resizeEvent(QResizeEvent* anEvent);
83 virtual void keyPressEvent(QKeyEvent *event);
84 virtual void closeEvent(QCloseEvent* event);
85 virtual bool eventFilter(QObject *obj, QEvent *event);
89 void restoreDefaultSettings();
90 void configModified();
93 void recoverDatabase();
95 void updateStatistics();
96 void selectObstacleColor();
97 void selectGroundColor();
98 void selectEmptyColor();
99 void selectFrontierColor();
100 void editDepthImage();
101 void generateGraph();
102 void editSaved2DMap();
103 void exportSaved2DMap();
105 void regenerateSavedMap();
106 void viewOptimizedMesh();
107 void exportOptimizedMesh();
108 void updateOptimizedMesh();
109 void exportDatabase();
110 void extractImages();
111 void exportPosesRaw();
112 void exportPosesRGBDSLAMMotionCapture();
113 void exportPosesRGBDSLAM();
114 void exportPosesRGBDSLAMID();
115 void exportPosesKITTI();
116 void exportPosesTORO();
117 void exportPosesG2O();
118 void exportPosesKML();
119 void exportGPS_TXT();
120 void exportGPS_KML();
121 void generateLocalGraph();
122 void regenerateLocalMaps();
123 void regenerateCurrentLocalMaps();
125 void generate3DMap();
126 void detectMoreLoopClosures();
127 void updateAllNeighborCovariances();
128 void updateAllLoopClosureCovariances();
129 void updateAllLandmarkCovariances();
131 void resetAllChanges();
132 void graphNodeSelected(
int);
133 void graphLinkSelected(
int,
int);
134 void sliderAValueChanged(
int);
135 void sliderBValueChanged(
int);
136 void sliderAMoved(
int);
137 void sliderBMoved(
int);
139 void sliderNeighborValueChanged(
int);
140 void sliderLoopValueChanged(
int);
141 void sliderIterationsValueChanged(
int);
142 void editConstraint();
144 void updateOctomapView();
145 void updateGraphRotation();
146 void updateGraphView();
147 void refineConstraint();
148 void addConstraint();
149 void resetConstraint();
150 void rejectConstraint();
151 void updateConstraintView();
152 void updateLoggerLevel();
154 void notifyParametersChanged(
const QStringList &);
155 void setupMainLayout(
bool vertical);
156 void updateConstraintButtons();
159 QString getIniFilePath()
const;
165 QLabel * labelParents,
166 QLabel * labelChildren,
174 QLabel * labelOptPose,
175 QLabel * labelVelocity,
178 QLabel * labelGravity,
180 QToolButton * editPriorButton,
181 QToolButton * removePriorButton,
184 QLabel * labelSensors,
185 bool updateConstraintView);
187 void updateWordsMatching(
const std::vector<int> & inliers = std::vector<int>());
188 void updateConstraintView(
190 bool updateImageSliders =
true,
193 Link findActiveLink(
int from,
int to);
195 std::multimap<int, Link> & links,
198 std::multimap<int, rtabmap::Link> updateLinksWithModifications(
199 const std::multimap<int, rtabmap::Link> & edgeConstraints);
200 void updateLoopClosuresSlider(
int from = 0,
int to = 0);
201 void updateCovariances(
const QList<Link> & links);
202 void refineLinks(
const QList<Link> & links);
203 void refineConstraint(
int from,
int to,
bool silent);
204 bool addConstraint(
int from,
int to,
bool silent,
bool silentlyUseOptimizedGraphAsGuess =
false);
226 std::list<std::map<int, rtabmap::Transform> >
graphes_;
232 std::multimap<int, rtabmap::Link>
links_;