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 class EditMapArea;
64 
65 class RTABMAPGUI_EXP DatabaseViewer : public QMainWindow
66 {
67  Q_OBJECT
68 
69 public:
70  DatabaseViewer(const QString & ini = QString(), QWidget * parent = 0);
71  virtual ~DatabaseViewer();
72  bool openDatabase(const QString & path);
73  bool isSavedMaximized() const {return savedMaximized_;}
74  void showCloseButton(bool visible = true);
75 
76 protected:
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);
83 
84 private Q_SLOTS:
85  void writeSettings();
86  void restoreDefaultSettings();
87  void configModified();
88  void openDatabase();
89  bool closeDatabase();
90  void recoverDatabase();
91  void updateInfo();
92  void updateStatistics();
93  void selectObstacleColor();
94  void selectGroundColor();
95  void selectEmptyColor();
96  void editDepthImage();
97  void generateGraph();
98  void editSaved2DMap();
99  void exportSaved2DMap();
100  void import2DMap();
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();
119  void view3DMap();
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);
131  void update3dView();
132  void sliderNeighborValueChanged(int);
133  void sliderLoopValueChanged(int);
134  void sliderIterationsValueChanged(int);
135  void editConstraint();
136  void updateGrid();
137  void updateOctomapView();
138  void updateGraphView();
139  void refineConstraint();
140  void addConstraint();
141  void resetConstraint();
142  void rejectConstraint();
143  void updateConstraintView();
144  void updateLoggerLevel();
145  void updateStereo();
146  void notifyParametersChanged(const QStringList &);
147  void setupMainLayout(bool vertical);
148  void updateConstraintButtons();
149 
150 private:
151  QString getIniFilePath() const;
152  void readSettings();
153 
154  void updateIds();
155  void update(int value,
156  QLabel * labelIndex,
157  QLabel * labelParents,
158  QLabel * labelChildren,
159  QLabel * weight,
160  QLabel * label,
161  QLabel * stamp,
162  rtabmap::ImageView * view,
163  QLabel * labelId,
164  QLabel * labelMapId,
165  QLabel * labelPose,
166  QLabel * labelVelocity,
167  QLabel * labelCalib,
168  QLabel * labelScan,
169  QLabel * labelGravity,
170  QLabel * labelGps,
171  QLabel * labelSensors,
172  bool updateConstraintView);
173  void updateStereo(const SensorData * data);
174  void updateWordsMatching(const std::vector<int> & inliers = std::vector<int>());
175  void updateConstraintView(
176  const rtabmap::Link & link,
177  bool updateImageSliders = true,
178  const Signature & signatureFrom = Signature(0),
179  const Signature & signatureTo = Signature(0));
180  Link findActiveLink(int from, int to);
181  bool containsLink(
182  std::multimap<int, Link> & links,
183  int from,
184  int to);
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);
192  void exportPoses(int format);
193  void exportGPS(int format);
194 
195 private:
196  Ui_DatabaseViewer * ui_;
201  QList<int> ids_;
202  std::set<int> lastWmIds_;
203  std::map<int, int> mapIds_;
204  std::map<int, int> weights_;
205  std::map<int, std::vector<int> > wmStates_;
206  QMap<int, int> idToIndex_;
207  QList<rtabmap::Link> neighborLinks_;
208  QList<rtabmap::Link> loopLinks_;
211  QString pathDatabase_;
212  std::string databaseFileName_;
213  std::list<std::map<int, rtabmap::Transform> > graphes_;
214  std::multimap<int, rtabmap::Link> graphLinks_;
215  std::map<int, rtabmap::Transform> odomPoses_;
216  std::map<int, rtabmap::Transform> groundTruthPoses_;
217  std::map<int, rtabmap::Transform> gpsPoses_;
218  std::map<int, GPS> gpsValues_;
219  std::multimap<int, rtabmap::Link> links_;
220  std::multimap<int, rtabmap::Link> linksRefined_;
221  std::multimap<int, rtabmap::Link> linksAdded_;
222  std::multimap<int, rtabmap::Link> linksRemoved_;
223  std::map<int, std::pair<std::pair<cv::Mat, cv::Mat>, cv::Mat> > localMaps_; // < <ground, obstacles>, empty>
224  std::map<int, std::pair<float, cv::Point3f> > localMapsInfo_; // <cell size, viewpoint>
225  std::map<int, std::pair<std::pair<cv::Mat, cv::Mat>, cv::Mat> > generatedLocalMaps_; // < <ground, obstacles>, empty>
226  std::map<int, std::pair<float, cv::Point3f> > generatedLocalMapsInfo_; // <cell size, viewpoint>
227  std::map<int, LaserScan> modifiedLaserScans_;
228  std::vector<double> odomMaxInf_;
231  QDialog * editDepthDialog_;
233  QDialog * editMapDialog_;
235 
238  QString iniFilePath_;
239 
244 };
245 
246 }
247 
248 #endif /* DATABASEVIEWER_H_ */
#define RTABMAPGUI_EXP
Definition: RtabmapGuiExp.h:38
std::vector< double > odomMaxInf_
std::map< int, std::pair< float, cv::Point3f > > generatedLocalMapsInfo_
Ui_DatabaseViewer * ui_
bool exportPoses
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:478
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_
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::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)
Definition: sqlite3.c:121404


rtabmap
Author(s): Mathieu Labbe
autogenerated on Mon Dec 14 2020 03:34:58