MainWindow.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_MAINWINDOW_H_
29 #define RTABMAP_MAINWINDOW_H_
30 
31 #include "rtabmap/gui/RtabmapGuiExp.h" // DLL export/import defines
32 
34 #include <QMainWindow>
35 #include <QtCore/QSet>
41 
42 #include <pcl/point_cloud.h>
43 #include <pcl/point_types.h>
44 #include <pcl/PolygonMesh.h>
45 #include <pcl/pcl_base.h>
46 #include <pcl/TextureMesh.h>
47 
48 namespace rtabmap {
49 class CameraThread;
50 class OdometryThread;
51 class IMUThread;
52 class CloudViewer;
53 class LoopClosureViewer;
54 class OccupancyGrid;
55 }
56 
57 class QGraphicsScene;
58 class Ui_mainWindow;
59 class QActionGroup;
60 
61 namespace rtabmap {
62 
63 class LikelihoodScene;
64 class AboutDialog;
65 class Plot;
66 class PdfPlotCurve;
67 class StatsToolBox;
68 class ProgressDialog;
69 class TwistGridWidget;
70 class ExportCloudsDialog;
71 class ExportBundlerDialog;
72 class PostProcessingDialog;
73 class DepthCalibrationDialog;
74 class DataRecorder;
75 class OctoMap;
76 
77 class RTABMAPGUI_EXP MainWindow : public QMainWindow, public UEventsHandler
78 {
79  Q_OBJECT
80 
81 public:
82  enum State {
92  kMonitoringPaused
93  };
94 
95 public:
100  MainWindow(PreferencesDialog * prefDialog = 0, QWidget * parent = 0, bool showSplashScreen = true);
101  virtual ~MainWindow();
102 
103  QString getWorkingDirectory() const;
104  void setMonitoringState(bool pauseChecked = false); // in monitoring state, only some actions are enabled
105  bool isSavedMaximized() const {return _savedMaximized;}
106 
107  bool isProcessingStatistics() const {return _processingStatistics;}
108  bool isProcessingOdometry() const {return _processingOdometry;}
109 
110  bool isDatabaseUpdated() const { return _databaseUpdated; }
111 
112 public Q_SLOTS:
113  virtual void processStats(const rtabmap::Statistics & stat);
114  void updateCacheFromDatabase(const QString & path);
115  void openDatabase(const QString & path, const rtabmap::ParametersMap & overridedParameters = rtabmap::ParametersMap());
116  void updateParameters(const rtabmap::ParametersMap & parameters);
117 
118 protected:
119  virtual void closeEvent(QCloseEvent* event);
120  virtual bool handleEvent(UEvent* anEvent);
121  virtual void showEvent(QShowEvent* anEvent);
122  virtual void moveEvent(QMoveEvent* anEvent);
123  virtual void resizeEvent(QResizeEvent* anEvent);
124  virtual void keyPressEvent(QKeyEvent *event);
125  virtual bool eventFilter(QObject *obj, QEvent *event);
126 
127 protected Q_SLOTS:
128  virtual void changeState(MainWindow::State state);
129  virtual void newDatabase();
130  virtual void openDatabase();
131  virtual bool closeDatabase();
132  virtual void startDetection();
133  virtual void pauseDetection();
134  virtual void stopDetection();
135  virtual void saveConfigGUI();
136  virtual void downloadAllClouds();
137  virtual void downloadPoseGraph();
138  virtual void clearTheCache();
139  virtual void openHelp();
140  virtual void openPreferences();
141  virtual void openPreferencesSource();
142  virtual void setDefaultViews();
143  virtual void resetOdometry();
144  virtual void triggerNewMap();
145  virtual void deleteMemory();
146 
147 protected Q_SLOTS:
148  void beep();
149  void cancelProgress();
150  void configGUIModified();
151  void editDatabase();
152  void notifyNoMoreImages();
153  void printLoopClosureIds();
154  void generateGraphDOT();
155  void exportPosesRaw();
156  void exportPosesRGBDSLAM();
157  void exportPosesKITTI();
158  void exportPosesTORO();
159  void exportPosesG2O();
160  void exportImages();
161  void exportOctomap();
162  void postProcessing();
163  void depthCalibration();
164  void openWorkingDirectory();
165  void updateEditMenu();
166  void selectStream();
167  void selectOpenni();
168  void selectFreenect();
169  void selectOpenniCv();
170  void selectOpenniCvAsus();
171  void selectOpenni2();
172  void selectFreenect2();
173  void selectK4W2();
174  void selectRealSense();
175  void selectRealSense2();
176  void selectStereoDC1394();
177  void selectStereoFlyCapture2();
178  void selectStereoZed();
179  void selectStereoUsb();
180  void dumpTheMemory();
181  void dumpThePrediction();
182  void sendGoal();
183  void sendWaypoints();
184  void postGoal(const QString & goal);
185  void cancelGoal();
186  void label();
187  void updateCacheFromDatabase();
188  void anchorCloudsToGroundTruth();
189  void selectScreenCaptureFormat(bool checked);
190  void takeScreenshot();
191  void updateElapsedTime();
192  void processCameraInfo(const rtabmap::CameraInfo & info);
193  void processOdometry(const rtabmap::OdometryEvent & odom, bool dataIgnored);
194  void applyPrefSettings(PreferencesDialog::PANEL_FLAGS flags);
195  void applyPrefSettings(const rtabmap::ParametersMap & parameters);
196  void processRtabmapEventInit(int status, const QString & info);
197  void processRtabmapEvent3DMap(const rtabmap::RtabmapEvent3DMap & event);
198  void processRtabmapGlobalPathEvent(const rtabmap::RtabmapGlobalPathEvent & event);
199  void processRtabmapLabelErrorEvent(int id, const QString & label);
200  void processRtabmapGoalStatusEvent(int status);
201  void changeImgRateSetting();
202  void changeDetectionRateSetting();
203  void changeTimeLimitSetting();
204  void changeMappingMode();
205  void setAspectRatio(int w, int h);
206  void setAspectRatio16_9();
207  void setAspectRatio16_10();
208  void setAspectRatio4_3();
209  void setAspectRatio240p();
210  void setAspectRatio360p();
211  void setAspectRatio480p();
212  void setAspectRatio720p();
213  void setAspectRatio1080p();
214  void setAspectRatioCustom();
215  void exportGridMap();
216  void exportClouds();
217  void exportBundlerFormat();
218  void viewClouds();
219  void dataRecorder();
220  void dataRecorderDestroyed();
221  void updateNodeVisibility(int, bool);
222  void updateGraphView();
223 
224 Q_SIGNALS:
225  void statsReceived(const rtabmap::Statistics &);
226  void statsProcessed();
227  void cameraInfoReceived(const rtabmap::CameraInfo &);
228  void cameraInfoProcessed();
229  void odometryReceived(const rtabmap::OdometryEvent &, bool);
230  void odometryProcessed();
231  void thresholdsChanged(int, int);
232  void stateChanged(MainWindow::State);
233  void rtabmapEventInitReceived(int status, const QString & info);
234  void rtabmapEvent3DMapReceived(const rtabmap::RtabmapEvent3DMap & event);
235  void rtabmapEvent3DMapProcessed();
236  void rtabmapGlobalPathEventReceived(const rtabmap::RtabmapGlobalPathEvent & event);
237  void rtabmapLabelErrorReceived(int id, const QString & label);
238  void rtabmapGoalStatusEventReceived(int status);
239  void imgRateChanged(double);
240  void detectionRateChanged(double);
241  void timeLimitChanged(float);
242  void mappingModeChanged(bool);
243  void noMoreImagesReceived();
244  void loopClosureThrChanged(float);
245  void twistReceived(float x, float y, float z, float roll, float pitch, float yaw, int row, int col);
246 
247 private:
248  void update3DMapVisibility(bool cloudsShown, bool scansShown);
249  void updateMapCloud(
250  const std::map<int, Transform> & poses,
251  const std::multimap<int, Link> & constraints,
252  const std::map<int, int> & mapIds,
253  const std::map<int, std::string> & labels,
254  const std::map<int, Transform> & groundTruths,
255  bool verboseProgress = false,
256  std::map<std::string, float> * stats = 0);
257  std::pair<pcl::PointCloud<pcl::PointXYZRGB>::Ptr, pcl::IndicesPtr> createAndAddCloudToMap(int nodeId, const Transform & pose, int mapId);
258  void createAndAddScanToMap(int nodeId, const Transform & pose, int mapId);
259  void createAndAddFeaturesToMap(int nodeId, const Transform & pose, int mapId);
260  Transform alignPosesToGroundTruth(const std::map<int, Transform> & poses, const std::map<int, Transform> & groundTruth);
261  void drawKeypoints(const std::multimap<int, cv::KeyPoint> & refWords, const std::multimap<int, cv::KeyPoint> & loopWords);
262  void setupMainLayout(bool vertical);
263  void updateSelectSourceMenu();
264  void applyPrefSettings(const rtabmap::ParametersMap & parameters, bool postParamEvent);
265  void saveFigures();
266  void loadFigures();
267  void exportPoses(int format);
268  QString captureScreen(bool cacheInRAM = false, bool png = true);
269 
270 protected:
271  Ui_mainWindow * ui() { return _ui; }
272  const State & state() const { return _state; }
273 
274  const QMap<int, Signature> & cachedSignatures() const { return _cachedSignatures;}
275  const std::map<int, Transform> & currentPosesMap() const { return _currentPosesMap; } // <nodeId, pose>
276  const std::map<int, Transform> & currentGTPosesMap() const { return _currentGTPosesMap; } // <nodeId, pose>
277  const std::multimap<int, Link> & currentLinksMap() const { return _currentLinksMap; } // <nodeFromId, link>
278  const std::map<int, int> & currentMapIds() const { return _currentMapIds; } // <nodeId, mapId>
279  const std::map<int, std::string> & currentLabels() const { return _currentLabels; } // <nodeId, label>
280  const std::map<int, std::pair<pcl::PointCloud<pcl::PointXYZRGB>::Ptr, pcl::IndicesPtr> > & cachedClouds() const { return _cachedClouds; }
281  const std::map<int, LaserScan> & createdScans() const { return _createdScans; }
282  const std::map<int, pcl::PointCloud<pcl::PointXYZRGB>::Ptr> & createdFeatures() const { return _createdFeatures; }
283 
284  const rtabmap::OccupancyGrid * occupancyGrid() const { return _occupancyGrid; }
285  const rtabmap::OctoMap * octomap() const { return _octomap; }
286 
287  rtabmap::ProgressDialog * progressDialog() { return _progressDialog; }
288  rtabmap::CloudViewer * cloudViewer() const { return _cloudViewer; }
289  rtabmap::LoopClosureViewer * loopClosureViewer() const { return _loopClosureViewer; }
290 
291  void setCloudViewer(rtabmap::CloudViewer * cloudViewer);
292  void setLoopClosureViewer(rtabmap::LoopClosureViewer * loopClosureViewer);
293 
294  void setNewDatabasePathOutput(const QString & newDatabasePathOutput) {_newDatabasePathOutput = newDatabasePathOutput;}
295  const QString & newDatabasePathOutput() const { return _newDatabasePathOutput; }
296 
297 private:
298  Ui_mainWindow * _ui;
299 
304 
305  //Dialogs
313 
314  QSet<int> _lastIds;
315  int _lastId;
316  double _firstStamp;
328  QStringList _waypoints;
330  std::vector<CameraModel> _rectCameraModels;
331 
332  QMap<int, Signature> _cachedSignatures;
334  std::map<int, Transform> _currentPosesMap; // <nodeId, pose>
335  std::map<int, Transform> _currentGTPosesMap; // <nodeId, pose>
336  std::multimap<int, Link> _currentLinksMap; // <nodeFromId, link>
337  std::map<int, int> _currentMapIds; // <nodeId, mapId>
338  std::map<int, std::string> _currentLabels; // <nodeId, label>
339  std::map<int, std::pair<pcl::PointCloud<pcl::PointXYZRGB>::Ptr, pcl::IndicesPtr> > _cachedClouds;
341  std::set<int> _cachedEmptyClouds;
342  std::pair<int, std::pair<std::pair<pcl::PointCloud<pcl::PointXYZRGB>::Ptr, pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr>, pcl::IndicesPtr> > _previousCloud; // used for subtraction
343  std::map<int, float> _cachedWordsCount;
344  std::map<int, float> _cachedLocalizationsCount;
345 
346  std::map<int, LaserScan> _createdScans;
347 
350 
351  std::map<int, pcl::PointCloud<pcl::PointXYZRGB>::Ptr> _createdFeatures;
352 
356 
357  QTimer * _oneSecondTimer;
358  QTime * _elapsedTime;
359  QTime * _logEventTime;
360 
364 
366 
369 
372  QMap<int, QString> _exportPosesFileName;
376  QMap<QString, QByteArray> _autoScreenCaptureCachedImages;
377 
378  QVector<int> _refIds;
379  QVector<int> _loopClosureIds;
380 
383 };
384 
385 }
386 
387 #endif /* RTABMAP_MainWindow_H_ */
#define RTABMAPGUI_EXP
Definition: RtabmapGuiExp.h:38
GLM_FUNC_DECL T roll(detail::tquat< T, P > const &x)
const std::map< int, pcl::PointCloud< pcl::PointXYZRGB >::Ptr > & createdFeatures() const
Definition: MainWindow.h:282
std::set< int > _cachedEmptyClouds
Definition: MainWindow.h:341
bool isProcessingOdometry() const
Definition: MainWindow.h:108
bool isDatabaseUpdated() const
Definition: MainWindow.h:110
DepthCalibrationDialog * _depthCalibrationDialog
Definition: MainWindow.h:311
QStringList _waypoints
Definition: MainWindow.h:328
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
void setNewDatabasePathOutput(const QString &newDatabasePathOutput)
Definition: MainWindow.h:294
Definition: UEvent.h:57
QString _newDatabasePathOutput
Definition: MainWindow.h:322
std::map< int, float > _cachedLocalizationsCount
Definition: MainWindow.h:344
PreferencesDialog * _preferencesDialog
Definition: MainWindow.h:306
const std::map< int, LaserScan > & createdScans() const
Definition: MainWindow.h:281
const std::map< int, std::pair< pcl::PointCloud< pcl::PointXYZRGB >::Ptr, pcl::IndicesPtr > > & cachedClouds() const
Definition: MainWindow.h:280
rtabmap::CameraThread * _camera
Definition: MainWindow.h:301
bool _autoScreenCaptureOdomSync
Definition: MainWindow.h:373
const rtabmap::OctoMap * octomap() const
Definition: MainWindow.h:285
const std::map< int, Transform > & currentGTPosesMap() const
Definition: MainWindow.h:276
std::multimap< int, Link > _currentLinksMap
Definition: MainWindow.h:336
QString _openedDatabasePath
Definition: MainWindow.h:323
rtabmap::OdometryThread * _odomThread
Definition: MainWindow.h:302
std::map< std::string, std::string > ParametersMap
Definition: Parameters.h:41
GLM_FUNC_DECL genType::row_type row(genType const &m, length_t const &index)
rtabmap::LoopClosureViewer * loopClosureViewer() const
Definition: MainWindow.h:289
GLM_FUNC_DECL T pitch(detail::tquat< T, P > const &x)
std::vector< CameraModel > _rectCameraModels
Definition: MainWindow.h:330
QString _newDatabasePath
Definition: MainWindow.h:321
QMap< int, QString > _exportPosesFileName
Definition: MainWindow.h:372
long _createdCloudsMemoryUsage
Definition: MainWindow.h:340
bool isProcessingStatistics() const
Definition: MainWindow.h:107
const State & state() const
Definition: MainWindow.h:272
std::map< int, Transform > _currentPosesMap
Definition: MainWindow.h:334
Transform _odometryCorrection
Definition: MainWindow.h:353
std::pair< int, std::pair< std::pair< pcl::PointCloud< pcl::PointXYZRGB >::Ptr, pcl::PointCloud< pcl::PointXYZRGBNormal >::Ptr >, pcl::IndicesPtr > > _previousCloud
Definition: MainWindow.h:342
const QMap< int, Signature > & cachedSignatures() const
Definition: MainWindow.h:274
std::map< int, LaserScan > _createdScans
Definition: MainWindow.h:346
const std::map< int, Transform > & currentPosesMap() const
Definition: MainWindow.h:275
QVector< int > _refIds
Definition: MainWindow.h:378
QSet< int > _lastIds
Definition: MainWindow.h:314
rtabmap::OctoMap * _octomap
Definition: MainWindow.h:349
const QString & newDatabasePathOutput() const
Definition: MainWindow.h:295
PdfPlotCurve * _likelihoodCurve
Definition: MainWindow.h:362
rtabmap::IMUThread * _imuThread
Definition: MainWindow.h:303
const std::map< int, std::string > & currentLabels() const
Definition: MainWindow.h:279
std::map< int, std::pair< pcl::PointCloud< pcl::PointXYZRGB >::Ptr, pcl::IndicesPtr > > _cachedClouds
Definition: MainWindow.h:339
const std::multimap< int, Link > & currentLinksMap() const
Definition: MainWindow.h:277
std::map< int, std::string > _currentLabels
Definition: MainWindow.h:338
rtabmap::ProgressDialog * progressDialog()
Definition: MainWindow.h:287
bool isSavedMaximized() const
Definition: MainWindow.h:105
CloudViewer * _cloudViewer
Definition: MainWindow.h:367
PdfPlotCurve * _posteriorCurve
Definition: MainWindow.h:361
RecoveryProgressState state
std::map< int, Transform > _currentGTPosesMap
Definition: MainWindow.h:335
std::map< int, pcl::PointCloud< pcl::PointXYZRGB >::Ptr > _createdFeatures
Definition: MainWindow.h:351
QMap< int, Signature > _cachedSignatures
Definition: MainWindow.h:332
QMap< QString, QByteArray > _autoScreenCaptureCachedImages
Definition: MainWindow.h:376
Ui_mainWindow * ui()
Definition: MainWindow.h:271
PdfPlotCurve * _rawLikelihoodCurve
Definition: MainWindow.h:363
rtabmap::OccupancyGrid * _occupancyGrid
Definition: MainWindow.h:348
std::map< int, float > _cachedWordsCount
Definition: MainWindow.h:343
std::map< int, int > _currentMapIds
Definition: MainWindow.h:337
ProgressDialog * _progressDialog
Definition: MainWindow.h:365
PostProcessingDialog * _postProcessingDialog
Definition: MainWindow.h:310
AboutDialog * _aboutDialog
Definition: MainWindow.h:307
ExportBundlerDialog * _exportBundlerDialog
Definition: MainWindow.h:309
GLM_FUNC_DECL T yaw(detail::tquat< T, P > const &x)
Ui_mainWindow * _ui
Definition: MainWindow.h:298
QString _graphSavingFileName
Definition: MainWindow.h:370
QTimer * _oneSecondTimer
Definition: MainWindow.h:357
QVector< int > _loopClosureIds
Definition: MainWindow.h:379
static int newDatabase(BtShared *pBt)
Definition: sqlite3.c:52932
ExportCloudsDialog * _exportCloudsDialog
Definition: MainWindow.h:308
const std::map< int, int > & currentMapIds() const
Definition: MainWindow.h:278
Transform _lastOdomPose
Definition: MainWindow.h:354
DataRecorder * _dataRecorder
Definition: MainWindow.h:312
LoopClosureViewer * _loopClosureViewer
Definition: MainWindow.h:368
rtabmap::CloudViewer * cloudViewer() const
Definition: MainWindow.h:288
const rtabmap::OccupancyGrid * occupancyGrid() const
Definition: MainWindow.h:284
bool _processingDownloadedMap
Definition: MainWindow.h:318
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