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;
64 class ExportCloudsDialog;
67 class LinkRefiningDialog;
74 DatabaseViewer(
const QString & ini = QString(), QWidget * parent = 0);
78 void showCloseButton(
bool visible =
true);
81 virtual void showEvent(QShowEvent* anEvent);
82 virtual void moveEvent(QMoveEvent* anEvent);
83 virtual void resizeEvent(QResizeEvent* anEvent);
84 virtual void keyPressEvent(QKeyEvent *event);
85 virtual void closeEvent(QCloseEvent* event);
86 virtual bool eventFilter(QObject *obj, QEvent *event);
90 void restoreDefaultSettings();
91 void configModified();
94 void recoverDatabase();
96 void updateStatistics();
97 void selectObstacleColor();
98 void selectGroundColor();
99 void selectEmptyColor();
100 void selectFrontierColor();
101 void editDepthImage();
102 void generateGraph();
103 void editSaved2DMap();
104 void exportSaved2DMap();
106 void regenerateSavedMap();
107 void viewOptimizedMesh();
108 void exportOptimizedMesh();
109 void updateOptimizedMesh();
110 void exportDatabase();
111 void extractImages();
112 void exportPosesRaw();
113 void exportPosesRGBDSLAMMotionCapture();
114 void exportPosesRGBDSLAM();
115 void exportPosesRGBDSLAMID();
116 void exportPosesKITTI();
117 void exportPosesTORO();
118 void exportPosesG2O();
119 void exportPosesKML();
120 void exportGPS_TXT();
121 void exportGPS_KML();
122 void generateLocalGraph();
123 void regenerateLocalMaps();
124 void regenerateCurrentLocalMaps();
126 void generate3DMap();
127 void detectMoreLoopClosures();
128 void updateAllNeighborCovariances();
129 void updateAllLoopClosureCovariances();
130 void updateAllLandmarkCovariances();
132 void resetAllChanges();
133 void graphNodeSelected(
int);
134 void graphLinkSelected(
int,
int);
135 void sliderAValueChanged(
int);
136 void sliderBValueChanged(
int);
137 void sliderAMoved(
int);
138 void sliderBMoved(
int);
140 void sliderNeighborValueChanged(
int);
141 void sliderLoopValueChanged(
int);
142 void sliderIterationsValueChanged(
int);
143 void editConstraint();
145 void updateOctomapView();
146 void updateGraphRotation();
147 void updateGraphView();
148 void refineConstraint();
149 void addConstraint();
150 void resetConstraint();
151 void rejectConstraint();
152 void updateConstraintView();
153 void updateLoggerLevel();
155 void notifyParametersChanged(
const QStringList &);
156 void setupMainLayout(
bool vertical);
157 void updateConstraintButtons();
160 QString getIniFilePath()
const;
165 QSpinBox * spinBoxIndex,
166 QLabel * labelParents,
167 QLabel * labelChildren,
175 QLabel * labelOptPose,
176 QLabel * labelVelocity,
179 QLabel * labelGravity,
181 QToolButton * editPriorButton,
182 QToolButton * removePriorButton,
185 QLabel * labelSensors,
186 bool updateConstraintView);
188 void updateWordsMatching(
const std::vector<int> & inliers = std::vector<int>());
189 void updateConstraintView(
191 bool updateImageSliders =
true,
194 Link findActiveLink(
int from,
int to);
196 std::multimap<int, Link> & links,
199 std::multimap<int, rtabmap::Link> updateLinksWithModifications(
200 const std::multimap<int, rtabmap::Link> & edgeConstraints);
201 void updateNeighborsSlider(
int from = 0,
int to = 0);
202 void updateLoopClosuresSlider(
int from = 0,
int to = 0);
203 void updateCovariances(
const QList<Link> & links);
204 void refineLinks(
const QList<Link> & links);
205 void refineConstraint(
int from,
int to,
bool silent);
206 bool addConstraint(
int from,
int to,
bool silent,
bool silentlyUseOptimizedGraphAsGuess =
false);
228 std::list<std::map<int, rtabmap::Transform> >
graphes_;
234 std::multimap<int, rtabmap::Link>
links_;