DatabaseViewer.h
Go to the documentation of this file.
1 /*
2 Copyright (c) 2010-2016, Mathieu Labbe - IntRoLab - Universite de Sherbrooke
3 All rights reserved.
4 
5 Redistribution and use in source and binary forms, with or without
6 modification, are permitted provided that the following conditions are met:
7  * Redistributions of source code must retain the above copyright
8  notice, this list of conditions and the following disclaimer.
9  * Redistributions in binary form must reproduce the above copyright
10  notice, this list of conditions and the following disclaimer in the
11  documentation and/or other materials provided with the distribution.
12  * Neither the name of the Universite de Sherbrooke nor the
13  names of its contributors may be used to endorse or promote products
14  derived from this software without specific prior written permission.
15 
16 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
17 ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
18 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
19 DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY
20 DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
21 (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
22 LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
23 ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
24 (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
25 SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
26 */
27 
28 #ifndef RTABMAP_DATABASEVIEWER_H_
29 #define RTABMAP_DATABASEVIEWER_H_
30 
31 #include "rtabmap/gui/RtabmapGuiExp.h" // DLL export/import defines
32 
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>
40 #include <set>
41 #include <vector>
42 #include <pcl/point_cloud.h>
43 #include <pcl/point_types.h>
44 
45 #include <rtabmap/core/Link.h>
46 #include <rtabmap/core/Signature.h>
47 
48 class Ui_DatabaseViewer;
49 class QGraphicsScene;
50 class QGraphicsView;
51 class QLabel;
52 class QDialog;
53 
54 namespace rtabmap
55 {
56 class DBDriver;
57 class ImageView;
58 class SensorData;
59 class CloudViewer;
60 class OctoMap;
61 class ExportCloudsDialog;
62 class EditDepthArea;
63 
64 class RTABMAPGUI_EXP DatabaseViewer : public QMainWindow
65 {
66  Q_OBJECT
67 
68 public:
69  DatabaseViewer(const QString & ini = QString(), QWidget * parent = 0);
70  virtual ~DatabaseViewer();
71  bool openDatabase(const QString & path);
72  bool isSavedMaximized() const {return savedMaximized_;}
73  void showCloseButton(bool visible = true);
74 
75 protected:
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);
82 
83 private Q_SLOTS:
84  void writeSettings();
85  void restoreDefaultSettings();
86  void configModified();
87  void openDatabase();
88  bool closeDatabase();
89  void recoverDatabase();
90  void updateStatistics();
91  void selectObstacleColor();
92  void selectGroundColor();
93  void selectEmptyColor();
94  void editDepthImage();
95  void generateGraph();
96  void exportSaved2DMap();
97  void import2DMap();
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();
114  void view3DMap();
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);
124  void update3dView();
125  void sliderNeighborValueChanged(int);
126  void sliderLoopValueChanged(int);
127  void sliderIterationsValueChanged(int);
128  void updateGrid();
129  void updateOctomapView();
130  void updateGraphView();
131  void refineConstraint();
132  void addConstraint();
133  void resetConstraint();
134  void rejectConstraint();
135  void updateConstraintView();
136  void updateLoggerLevel();
137  void updateStereo();
138  void notifyParametersChanged(const QStringList &);
139  void setupMainLayout(bool vertical);
140 
141 private:
142  QString getIniFilePath() const;
143  void readSettings();
144 
145  void updateIds();
146  void update(int value,
147  QLabel * labelIndex,
148  QLabel * labelParents,
149  QLabel * labelChildren,
150  QLabel * weight,
151  QLabel * label,
152  QLabel * stamp,
153  rtabmap::ImageView * view,
154  QLabel * labelId,
155  QLabel * labelMapId,
156  QLabel * labelPose,
157  QLabel * labelVelocity,
158  QLabel * labeCalib,
159  QLabel * labelGps,
160  bool updateConstraintView);
161  void updateStereo(const SensorData * data);
162  void updateWordsMatching();
163  void updateConstraintView(
164  const rtabmap::Link & link,
165  bool updateImageSliders = true,
166  const Signature & signatureFrom = Signature(0),
167  const Signature & signatureTo = Signature(0));
168  void updateConstraintButtons();
169  Link findActiveLink(int from, int to);
170  bool containsLink(
171  std::multimap<int, Link> & links,
172  int from,
173  int to);
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);
179  void exportPoses(int format);
180  void exportGPS(int format);
181 
182 private:
183  Ui_DatabaseViewer * ui_;
188  QList<int> ids_;
189  std::map<int, int> mapIds_;
190  std::map<int, int> weights_;
191  std::map<int, std::vector<int> > wmStates_;
192  QMap<int, int> idToIndex_;
193  QList<rtabmap::Link> neighborLinks_;
194  QList<rtabmap::Link> loopLinks_;
196  QString pathDatabase_;
197  std::string databaseFileName_;
198  std::list<std::map<int, rtabmap::Transform> > graphes_;
199  std::multimap<int, rtabmap::Link> graphLinks_;
200  std::map<int, rtabmap::Transform> odomPoses_;
201  std::map<int, rtabmap::Transform> groundTruthPoses_;
202  std::map<int, rtabmap::Transform> gpsPoses_;
203  std::map<int, GPS> gpsValues_;
204  std::multimap<int, rtabmap::Link> links_;
205  std::multimap<int, rtabmap::Link> linksRefined_;
206  std::multimap<int, rtabmap::Link> linksAdded_;
207  std::multimap<int, rtabmap::Link> linksRemoved_;
208  std::map<int, std::pair<std::pair<cv::Mat, cv::Mat>, cv::Mat> > localMaps_; // < <ground, obstacles>, empty>
209  std::map<int, std::pair<float, cv::Point3f> > localMapsInfo_; // <cell size, viewpoint>
210  std::map<int, std::pair<std::pair<cv::Mat, cv::Mat>, cv::Mat> > generatedLocalMaps_; // < <ground, obstacles>, empty>
211  std::map<int, std::pair<float, cv::Point3f> > generatedLocalMapsInfo_; // <cell size, viewpoint>
212  std::map<int, cv::Mat> modifiedDepthImages_;
215  QDialog * editDepthDialog_;
217 
220  QString iniFilePath_;
221 
223  std::map<int, Transform> lastOptimizedGraph_;
224 };
225 
226 }
227 
228 #endif /* DATABASEVIEWER_H_ */
#define RTABMAPGUI_EXP
Definition: RtabmapGuiExp.h:38
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)
Definition: Graph.cpp:53
Ui_DatabaseViewer * ui_
std::map< int, rtabmap::Transform > gpsPoses_
bool RTABMAP_EXP exportGPS(const std::string &filePath, const std::map< int, GPS > &gpsValues, unsigned int rgba=0xFFFFFFFF)
Definition: Graph.cpp:467
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, Transform > lastOptimizedGraph_
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_
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)
Definition: sqlite3.c:121404


rtabmap
Author(s): Mathieu Labbe
autogenerated on Wed Jun 5 2019 22:41:31