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 exportPosesRGBDSLAMID();
111  void exportPosesKITTI();
112  void exportPosesTORO();
113  void exportPosesG2O();
114  void exportPosesKML();
115  void exportGPS_TXT();
116  void exportGPS_KML();
117  void generateLocalGraph();
118  void regenerateLocalMaps();
119  void regenerateCurrentLocalMaps();
120  void view3DMap();
121  void generate3DMap();
122  void detectMoreLoopClosures();
123  void updateAllNeighborCovariances();
124  void updateAllLoopClosureCovariances();
125  void updateAllLandmarkCovariances();
126  void refineAllNeighborLinks();
127  void refineAllLoopClosureLinks();
128  void resetAllChanges();
129  void sliderAValueChanged(int);
130  void sliderBValueChanged(int);
131  void sliderAMoved(int);
132  void sliderBMoved(int);
133  void update3dView();
134  void sliderNeighborValueChanged(int);
135  void sliderLoopValueChanged(int);
136  void sliderIterationsValueChanged(int);
137  void editConstraint();
138  void updateGrid();
139  void updateOctomapView();
140  void updateGraphView();
141  void refineConstraint();
142  void addConstraint();
143  void resetConstraint();
144  void rejectConstraint();
145  void updateConstraintView();
146  void updateLoggerLevel();
147  void updateStereo();
148  void notifyParametersChanged(const QStringList &);
149  void setupMainLayout(bool vertical);
150  void updateConstraintButtons();
151 
152 private:
153  QString getIniFilePath() const;
154  void readSettings();
155 
156  void updateIds();
157  void update(int value,
158  QLabel * labelIndex,
159  QLabel * labelParents,
160  QLabel * labelChildren,
161  QLabel * weight,
162  QLabel * label,
163  QLabel * stamp,
164  rtabmap::ImageView * view,
165  QLabel * labelId,
166  QLabel * labelMapId,
167  QLabel * labelPose,
168  QLabel * labelOptPose,
169  QLabel * labelVelocity,
170  QLabel * labelCalib,
171  QLabel * labelScan,
172  QLabel * labelGravity,
173  QLabel * labelPrior,
174  QLabel * labelGps,
175  QLabel * labelGt,
176  QLabel * labelSensors,
177  bool updateConstraintView);
178  void updateStereo(const SensorData * data);
179  void updateWordsMatching(const std::vector<int> & inliers = std::vector<int>());
180  void updateConstraintView(
181  const rtabmap::Link & link,
182  bool updateImageSliders = true,
183  const Signature & signatureFrom = Signature(0),
184  const Signature & signatureTo = Signature(0));
185  Link findActiveLink(int from, int to);
186  bool containsLink(
187  std::multimap<int, Link> & links,
188  int from,
189  int to);
190  std::multimap<int, rtabmap::Link> updateLinksWithModifications(
191  const std::multimap<int, rtabmap::Link> & edgeConstraints);
192  void updateLoopClosuresSlider(int from = 0, int to = 0);
193  void updateAllCovariances(const QList<Link> & links);
194  void refineAllLinks(const QList<Link> & links);
195  void refineConstraint(int from, int to, bool silent);
196  bool addConstraint(int from, int to, bool silent);
197  void exportPoses(int format);
198  void exportGPS(int format);
199 
200 private:
201  Ui_DatabaseViewer * ui_;
206  QList<int> ids_;
207  std::set<int> lastWmIds_;
208  std::map<int, int> mapIds_;
209  std::map<int, int> weights_;
210  std::map<int, std::vector<int> > wmStates_;
211  QMap<int, int> idToIndex_;
212  QList<rtabmap::Link> neighborLinks_;
213  QList<rtabmap::Link> loopLinks_;
216  QString pathDatabase_;
217  std::string databaseFileName_;
218  std::list<std::map<int, rtabmap::Transform> > graphes_;
219  std::multimap<int, rtabmap::Link> graphLinks_;
220  std::map<int, rtabmap::Transform> odomPoses_;
221  std::map<int, rtabmap::Transform> groundTruthPoses_;
222  std::map<int, rtabmap::Transform> gpsPoses_;
223  std::map<int, GPS> gpsValues_;
224  std::multimap<int, rtabmap::Link> links_;
225  std::multimap<int, rtabmap::Link> linksRefined_;
226  std::multimap<int, rtabmap::Link> linksAdded_;
227  std::multimap<int, rtabmap::Link> linksRemoved_;
228  std::map<int, std::pair<std::pair<cv::Mat, cv::Mat>, cv::Mat> > localMaps_; // < <ground, obstacles>, empty>
229  std::map<int, std::pair<float, cv::Point3f> > localMapsInfo_; // <cell size, viewpoint>
230  std::map<int, std::pair<std::pair<cv::Mat, cv::Mat>, cv::Mat> > generatedLocalMaps_; // < <ground, obstacles>, empty>
231  std::map<int, std::pair<float, cv::Point3f> > generatedLocalMapsInfo_; // <cell size, viewpoint>
232  std::map<int, LaserScan> modifiedLaserScans_;
233  std::vector<double> odomMaxInf_;
236  QDialog * editDepthDialog_;
238  QDialog * editMapDialog_;
240 
243  QString iniFilePath_;
244 
249 };
250 
251 }
252 
253 #endif /* DATABASEVIEWER_H_ */
bool isSavedMaximized() const
#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:497
std::list< std::map< int, rtabmap::Transform > > graphes_
CloudViewer * constraintsViewer_
data
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_
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 Jan 23 2023 03:37:28