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


rtabmap
Author(s): Mathieu Labbe
autogenerated on Thu Jul 25 2024 02:50:12