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