PreferencesDialog.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_PREFERENCESDIALOG_H_
29 #define RTABMAP_PREFERENCESDIALOG_H_
30 
31 #include "rtabmap/gui/rtabmap_gui_export.h" // DLL export/import defines
32 
33 #include <QDialog>
34 #include <QtCore/QModelIndex>
35 #include <QtCore/QVector>
36 #include <set>
37 
38 #include "rtabmap/core/Transform.h"
40 
41 class Ui_preferencesDialog;
42 class QAbstractItemModel;
43 class QAbstractButton;
44 class QStandardItemModel;
45 class QStandardItem;
46 class QFile;
47 class QGroupBox;
48 class QMainWindow;
49 class QLineEdit;
50 class QSlider;
51 class QProgressDialog;
52 class UPlotCurve;
53 class QStackedWidget;
54 class QCheckBox;
55 class QSpinBox;
56 class QDoubleSpinBox;
57 
58 namespace rtabmap {
59 
60 class Signature;
61 class LoopClosureViewer;
62 class Camera;
63 class SensorCapture;
64 class Lidar;
65 class CalibrationDialog;
66 class CreateSimpleCalibrationDialog;
67 
68 class RTABMAP_GUI_EXPORT PreferencesDialog : public QDialog
69 {
70  Q_OBJECT
71 
72 public:
73  enum PanelFlag {
74  kPanelDummy = 0,
75  kPanelGeneral = 1,
76  kPanelCloudRendering = 2,
77  kPanelLogging = 4,
78  kPanelSource = 8,
79  kPanelCalibration = 16,
80  kPanelAll = 31
81  };
82  // TODO, tried to change the name of PANEL_FLAGS to PanelFlags... but signals/slots errors appeared...
83  Q_DECLARE_FLAGS(PANEL_FLAGS, PanelFlag);
84 
85  enum Src {
86  kSrcUndef = -1,
87 
88  kSrcRGBD = 0,
89  kSrcOpenNI_PCL = 0,
90  kSrcFreenect = 1,
91  kSrcOpenNI_CV = 2,
92  kSrcOpenNI_CV_ASUS = 3,
93  kSrcOpenNI2 = 4,
94  kSrcFreenect2 = 5,
95  kSrcRealSense = 6,
96  kSrcRGBDImages = 7,
97  kSrcK4W2 = 8,
98  kSrcRealSense2 = 9,
99  kSrcK4A = 10,
100  kSrcSeerSense = 11,
101 
102  kSrcStereo = 100,
103  kSrcDC1394 = 100,
104  kSrcFlyCapture2 = 101,
105  kSrcStereoImages = 102,
106  kSrcStereoVideo = 103,
107  kSrcStereoZed = 104,
108  kSrcStereoUsb = 105,
109  kSrcStereoTara = 106,
110  kSrcStereoRealSense2 = 107,
111  kSrcStereoMyntEye = 108,
112  kSrcStereoZedOC = 109,
113  kSrcStereoDepthAI = 110,
114 
115  kSrcRGB = 200,
116  kSrcUsbDevice = 200,
117  kSrcImages = 201,
118  kSrcVideo = 202,
119 
120  kSrcDatabase = 300,
121 
122  kSrcLidar = 400,
123  kSrcLidarVLP16 = 400,
124  };
125 
126 public:
127  PreferencesDialog(QWidget * parent = 0);
128  virtual ~PreferencesDialog();
129 
130  virtual QString getIniFilePath() const;
131  virtual QString getTmpIniFilePath() const;
132  void init(const QString & iniFilePath = "");
133  void setCurrentPanelToSource();
134  virtual QString getDefaultWorkingDirectory() const;
135 
136  // save stuff
137  void saveSettings();
138  void saveWindowGeometry(const QWidget * window);
139  void loadWindowGeometry(QWidget * window);
140  void saveMainWindowState(const QMainWindow * mainWindow);
141  void loadMainWindowState(QMainWindow * mainWindow, bool & maximized, bool & statusBarShown);
142  void saveWidgetState(const QWidget * widget);
143  void loadWidgetState(QWidget * widget);
144 
145  void saveCustomConfig(const QString & section, const QString & key, const QString & value);
146  QString loadCustomConfig(const QString & section, const QString & key);
147 
148  rtabmap::ParametersMap getAllParameters() const;
149  std::string getParameter(const std::string & key) const;
150  void updateParameters(const ParametersMap & parameters, bool setOtherParametersToDefault = false);
151 
152  //General panel
153  int getGeneralLoggerLevel() const;
154  int getGeneralLoggerEventLevel() const;
155  int getGeneralLoggerPauseLevel() const;
156  int getGeneralLoggerType() const;
157  bool getGeneralLoggerPrintTime() const;
158  bool getGeneralLoggerPrintThreadId() const;
159  std::vector<std::string> getGeneralLoggerThreads() const;
160  bool isVerticalLayoutUsed() const;
161  bool imageRejectedShown() const;
162  bool imageHighestHypShown() const;
163  bool beepOnPause() const;
164  bool isTimeUsedInFigures() const;
165  bool isCacheSavedInFigures() const;
166  bool notifyWhenNewGlobalPathIsReceived() const;
167  int getOdomQualityWarnThr() const;
168  bool isOdomOnlyInliersShown() const;
169  bool isPosteriorGraphView() const;
170  bool isWordsCountGraphView() const;
171  bool isLocalizationsCountGraphView() const;
172  bool isRelocalizationColorOdomCacheGraphView() const;
173  int getOdomRegistrationApproach() const;
174  double getOdomF2MGravitySigma() const;
175  bool isOdomDisabled() const;
176  bool isOdomSensorAsGt() const;
177  bool isGroundTruthAligned() const;
178 
179  bool isGraphsShown() const;
180  bool isLabelsShown() const;
181  bool isFramesShown() const;
182  bool isLandmarksShown() const;
183  double landmarkVisSize() const;
184  bool isIMUGravityShown(int index) const;
185  double getIMUGravityLength(int index) const;
186  bool isIMUAccShown() const;
187  bool isMarkerDetection() const;
188  double getMarkerLength() const;
189  double getVoxel() const;
190  double getNoiseRadius() const;
191  int getNoiseMinNeighbors() const;
192  double getCeilingFilteringHeight() const;
193  double getFloorFilteringHeight() const;
194  int getNormalKSearch() const;
195  double getNormalRadiusSearch() const;
196  double getScanCeilingFilteringHeight() const;
197  double getScanFloorFilteringHeight() const;
198  int getScanNormalKSearch() const;
199  double getScanNormalRadiusSearch() const;
200  bool isCloudsShown(int index) const; // 0=map, 1=odom
201  bool isOctomapUpdated() const;
202  bool isOctomapShown() const;
203  int getOctomapRenderingType() const;
204  bool isOctomap2dGrid() const;
205  int getOctomapTreeDepth() const;
206  int getOctomapPointSize() const;
207  int getCloudDecimation(int index) const; // 0=map, 1=odom
208  double getCloudMaxDepth(int index) const; // 0=map, 1=odom
209  double getCloudMinDepth(int index) const; // 0=map, 1=odom
210  std::vector<float> getCloudRoiRatios(int index) const; // 0=map, 1=odom
211  int getCloudColorScheme(int index) const; // 0=map, 1=odom
212  double getCloudOpacity(int index) const; // 0=map, 1=odom
213  int getCloudPointSize(int index) const; // 0=map, 1=odom
214 
215  bool isScansShown(int index) const; // 0=map, 1=odom
216  int getDownsamplingStepScan(int index) const; // 0=map, 1=odom
217  double getScanMaxRange(int index) const; // 0=map, 1=odom
218  double getScanMinRange(int index) const; // 0=map, 1=odom
219  double getCloudVoxelSizeScan(int index) const; // 0=map, 1=odom
220  int getScanColorScheme(int index) const; // 0=map, 1=odom
221  double getScanOpacity(int index) const; // 0=map, 1=odom
222  int getScanPointSize(int index) const; // 0=map, 1=odom
223 
224  bool isFeaturesShown(int index) const; // 0=map, 1=odom
225  bool isFrustumsShown(int index) const; // 0=map, 1=odom
226  int getFeaturesPointSize(int index) const; // 0=map, 1=odom
227 
228  bool isCloudFiltering() const;
229  bool isSubtractFiltering() const;
230  double getCloudFilteringRadius() const;
231  double getCloudFilteringAngle() const;
232  int getSubtractFilteringMinPts() const;
233  double getSubtractFilteringRadius() const;
234  double getSubtractFilteringAngle() const;
235 
236  double getGridUIResolution() const;
237  bool getGridMapShown() const;
238  int getElevationMapShown() const;
239  int getGridMapSensor() const;
240  bool projMapFrame() const;
241  double projMaxGroundAngle() const;
242  double projMaxGroundHeight() const;
243  int projMinClusterSize() const;
244  double projMaxObstaclesHeight() const;
245  bool projFlatObstaclesDetected() const;
246  double getGridMapOpacity() const;
247 
248  bool isCloudMeshing() const;
249  double getCloudMeshingAngle() const;
250  bool isCloudMeshingQuad() const;
251  bool isCloudMeshingTexture() const;
252  int getCloudMeshingTriangleSize();
253 
254  QString getWorkingDirectory() const;
255 
256  // source panel
257  double getGeneralInputRate() const;
258  bool isSourceMirroring() const;
259  PreferencesDialog::Src getSourceType() const;
260  PreferencesDialog::Src getSourceDriver() const;
261  QString getSourceDriverStr() const;
262  QString getSourceDevice() const;
263  PreferencesDialog::Src getLidarSourceDriver() const;
264  PreferencesDialog::Src getOdomSourceDriver() const;
265 
266  bool isSourceDatabaseStampsUsed() const;
267  bool isSourceDatabaseStereoToDepth() const;
268  bool isSourceRGBDColorOnly() const;
269  int getIMUFilteringStrategy() const;
270  bool getIMUFilteringBaseFrameConversion() const;
271  bool isDepthFilteringAvailable() const;
272  QString getSourceDistortionModel() const;
273  bool isBilateralFiltering() const;
274  double getBilateralSigmaS() const;
275  double getBilateralSigmaR() const;
276  int getSourceImageDecimation() const;
277  int getSourceHistogramMethod() const;
278  bool isSourceFeatureDetection() const;
279  bool isSourceStereoDepthGenerated() const;
280  bool isSourceStereoExposureCompensation() const;
281  bool isRightGrayScale() const;
282  bool isSourceScanFromDepth() const;
283  bool isSourceScanDeskewing() const;
284  int getSourceScanDownsampleStep() const;
285  double getSourceScanRangeMin() const;
286  double getSourceScanRangeMax() const;
287  double getSourceScanVoxelSize() const;
288  int getSourceScanNormalsK() const;
289  double getSourceScanNormalsRadius() const;
290  double getSourceScanForceGroundNormalsUp() const;
291  Transform getSourceLocalTransform() const; //Openni group
292  Transform getLaserLocalTransform() const; // directory images
293  Transform getIMULocalTransform() const; // directory images
294  QString getIMUPath() const;
295  int getIMURate() const;
296  Camera * createCamera(bool useRawImages = false, bool useColor = true); // return camera should be deleted if not null
297  SensorCapture * createOdomSensor(Transform & extrinsics, double & timeOffset, float & scaleFactor, double & waitTime); // return odom sensor should be deleted if not null
298  Lidar * createLidar(); // return lidar should be deleted if not null
299 
300  int getIgnoredDCComponents() const;
301 
302  //
303  bool isImagesKept() const;
304  bool isMissingCacheRepublished() const;
305  bool isCloudsKept() const;
306  float getTimeLimit() const;
307  float getDetectionRate() const;
308  bool isSLAMMode() const;
309  bool isRGBDMode() const;
310  int getKpMaxFeatures() const;
311  bool isPriorIgnored() const;
312 
313  //specific
314  bool isStatisticsPublished() const;
315  double getLoopThr() const;
316  double getVpThr() const;
317  double getSimThr() const;
318  int getOdomStrategy() const;
319  int getOdomBufferSize() const;
320  QString getCameraInfoDir() const; // "workinfDir/camera_info"
321 
322  //
323  void setMonitoringState(bool monitoringState) {_monitoringState = monitoringState;}
324 
325 Q_SIGNALS:
326  void settingsChanged(PreferencesDialog::PANEL_FLAGS);
327  void settingsChanged(rtabmap::ParametersMap);
328 
329 public Q_SLOTS:
330  void setInputRate(double value);
331  void setDetectionRate(double value);
332  void setTimeLimit(float value);
333  void setSLAMMode(bool enabled);
334  void selectSourceDriver(Src src, int variant = 0);
335  void calibrate();
336  void calibrateSimple();
337  void calibrateOdomSensorExtrinsics();
338  void testLidar();
339 
340 private Q_SLOTS:
341  void closeDialog ( QAbstractButton * button );
342  void resetApply ( QAbstractButton * button );
343  void resetSettings(int panelNumber);
344  void loadConfigFrom();
345  bool saveConfigTo();
346  void resetConfig();
347  void loadPreset();
348  void makeObsoleteGeneralPanel();
349  void makeObsoleteCloudRenderingPanel();
350  void makeObsoleteLoggingPanel();
351  void makeObsoleteSourcePanel();
352  void makeObsoleteCalibrationPanel();
353  void clicked(const QModelIndex & current, const QModelIndex & previous);
354  void addParameter(int value);
355  void addParameter(bool value);
356  void addParameter(double value);
357  void addParameter(const QString & value);
358  void updatePredictionPlot();
359  void updateKpROI();
360  void updateStereoDisparityVisibility();
361  void updateFeatureMatchingVisibility();
362  void updateGlobalDescriptorVisibility();
363  void updateOdometryStackedIndex(int index);
364  void useOdomFeatures();
365  void changeWorkingDirectory();
366  void changeDictionaryPath();
367  void changeOdometryORBSLAMVocabulary();
368  void changeOdometryOKVISConfigPath();
369  void changeOdometryVINSConfigPath();
370  void changeOdometryOpenVINSLeftMask();
371  void changeOdometryOpenVINSRightMask();
372  void changeIcpPMConfigPath();
373  void changeSuperPointModelPath();
374  void changePyMatcherPath();
375  void changePyMatcherModel();
376  void changePyDescriptorPath();
377  void changePyDetectorPath();
378  void readSettingsEnd();
379  void setupTreeView();
380  void updateBasicParameter();
381  void openDatabaseViewer();
382  void visualizeDistortionModel();
383  void selectSourceDatabase();
384  void selectCalibrationPath();
385  void selectOdomSensorCalibrationPath();
386  void selectSourceImagesStamps();
387  void selectSourceRGBDImagesPathRGB();
388  void selectSourceRGBDImagesPathDepth();
389  void selectSourceImagesPathScans();
390  void selectSourceImagesPathIMU();
391  void selectSourceImagesPathOdom();
392  void selectSourceImagesPathGt();
393  void selectSourceStereoImagesPathLeft();
394  void selectSourceStereoImagesPathRight();
395  void selectSourceImagesPath();
396  void selectSourceVideoPath();
397  void selectSourceStereoVideoPath();
398  void selectSourceStereoVideoPath2();
399  void selectSourceDistortionModel();
400  void selectSourceOniPath();
401  void selectSourceOni2Path();
402  void selectSourceMKVPath();
403  void selectSourceSvoPath();
404  void selectSourceRealsense2JsonPath();
405  void selectSourceDepthaiBlobPath();
406  void selectVlp16PcapPath();
407  void updateSourceGrpVisibility();
408  void testOdometry();
409  void testCamera();
410 
411 protected:
412  virtual void showEvent ( QShowEvent * event );
413  virtual void closeEvent(QCloseEvent *event);
414 
415  virtual QString getParamMessage();
416 
417  virtual void readGuiSettings(const QString & filePath = QString());
418  virtual void readCameraSettings(const QString & filePath = QString());
419  virtual bool readCoreSettings(const QString & filePath = QString());
420 
421  virtual void writeGuiSettings(const QString & filePath = QString()) const;
422  virtual void writeCameraSettings(const QString & filePath = QString()) const;
423  virtual void writeCoreSettings(const QString & filePath = QString()) const;
424 
425  void setParameter(const std::string & key, const std::string & value);
426 
427 private:
428  void readSettings(const QString & filePath = QString());
429  void writeSettings(const QString & filePath = QString());
430  bool validateForm();
431  void setupSignals();
432  void setupKpRoiPanel();
433  bool parseModel(QList<QGroupBox*> & boxes, QStandardItem * parentItem, int currentLevel, int & absoluteIndex);
434  void resetSettings(QGroupBox * groupBox);
435  void loadPreset(const std::string & presetHexHeader);
436  void addParameter(const QObject * object, int value);
437  void addParameter(const QObject * object, bool value);
438  void addParameter(const QObject * object, double value);
439  void addParameter(const QObject * object, const QString & value);
440  void addParameters(const QObjectList & children);
441  void addParameters(const QStackedWidget * stackedWidget, int panel = -1);
442  void addParameters(const QGroupBox * box);
443  QList<QGroupBox*> getGroupBoxes();
444  void readSettingsBegin();
445  Camera * createCamera(Src driver, const QString & device, const QString & calibrationPath, bool useRawImages, bool useColor, bool odomOnly, bool odomSensorExtrinsicsCalib); // return camera should be deleted if not null
446 
447 protected:
448  PANEL_FLAGS _obsoletePanels;
449 
450 private:
453  Ui_preferencesDialog * _ui;
454  QStandardItemModel * _indexModel;
457 
458  QProgressDialog * _progressDialog;
459 
460  //calibration
463 
464  QVector<QCheckBox*> _3dRenderingShowClouds;
465  QVector<QSpinBox*> _3dRenderingDecimation;
466  QVector<QDoubleSpinBox*> _3dRenderingMaxDepth;
467  QVector<QDoubleSpinBox*> _3dRenderingMinDepth;
468  QVector<QLineEdit*> _3dRenderingRoiRatios;
469  QVector<QSpinBox*> _3dRenderingColorScheme;
470  QVector<QDoubleSpinBox*> _3dRenderingOpacity;
471  QVector<QSpinBox*> _3dRenderingPtSize;
472  QVector<QCheckBox*> _3dRenderingShowScans;
473  QVector<QSpinBox*> _3dRenderingDownsamplingScan;
474  QVector<QDoubleSpinBox*> _3dRenderingMaxRange;
475  QVector<QDoubleSpinBox*> _3dRenderingMinRange;
476  QVector<QDoubleSpinBox*> _3dRenderingVoxelSizeScan;
477  QVector<QSpinBox*> _3dRenderingColorSchemeScan;
478  QVector<QDoubleSpinBox*> _3dRenderingOpacityScan;
479  QVector<QSpinBox*> _3dRenderingPtSizeScan;
480  QVector<QCheckBox*> _3dRenderingShowFeatures;
481  QVector<QCheckBox*> _3dRenderingShowFrustums;
482  QVector<QSpinBox*> _3dRenderingPtSizeFeatures;
483  QVector<QCheckBox*> _3dRenderingGravity;
484  QVector<QDoubleSpinBox*> _3dRenderingGravityLength;
485 };
486 
487 Q_DECLARE_OPERATORS_FOR_FLAGS(PreferencesDialog::PANEL_FLAGS)
488 
489 }
490 
491 #endif /* PREFERENCESDIALOG_H_ */
rtabmap::PreferencesDialog::_parameters
rtabmap::ParametersMap _parameters
Definition: PreferencesDialog.h:452
rtabmap::PreferencesDialog::_3dRenderingGravityLength
QVector< QDoubleSpinBox * > _3dRenderingGravityLength
Definition: PreferencesDialog.h:484
rtabmap::CreateSimpleCalibrationDialog
Definition: CreateSimpleCalibrationDialog.h:40
rtabmap::PreferencesDialog::_calibrationDialog
CalibrationDialog * _calibrationDialog
Definition: PreferencesDialog.h:461
rtabmap::PreferencesDialog::_3dRenderingColorScheme
QVector< QSpinBox * > _3dRenderingColorScheme
Definition: PreferencesDialog.h:469
Camera
clams::calibrate
DiscreteDepthDistortionModel RTABMAP_CORE_EXPORT calibrate(const std::map< int, rtabmap::SensorData > &sequence, const std::map< int, rtabmap::Transform > &trajectory, const pcl::PointCloud< pcl::PointXYZ >::Ptr &map, double coneRadius=0.02, double coneStdevThresh=0.03)
rtabmap::PreferencesDialog::_3dRenderingDecimation
QVector< QSpinBox * > _3dRenderingDecimation
Definition: PreferencesDialog.h:465
rtabmap::PreferencesDialog::Src
Src
Definition: PreferencesDialog.h:85
rtabmap::PreferencesDialog::_3dRenderingPtSizeScan
QVector< QSpinBox * > _3dRenderingPtSizeScan
Definition: PreferencesDialog.h:479
Transform.h
rtabmap::PreferencesDialog::_indexModel
QStandardItemModel * _indexModel
Definition: PreferencesDialog.h:454
rtabmap::PreferencesDialog::_3dRenderingShowScans
QVector< QCheckBox * > _3dRenderingShowScans
Definition: PreferencesDialog.h:472
rtabmap::PreferencesDialog::_3dRenderingOpacity
QVector< QDoubleSpinBox * > _3dRenderingOpacity
Definition: PreferencesDialog.h:470
rtabmap::ParametersMap
std::map< std::string, std::string > ParametersMap
Definition: Parameters.h:43
rtabmap::PreferencesDialog::_initialized
bool _initialized
Definition: PreferencesDialog.h:455
Parameters.h
rtabmap::PreferencesDialog::_3dRenderingDownsamplingScan
QVector< QSpinBox * > _3dRenderingDownsamplingScan
Definition: PreferencesDialog.h:473
rtabmap::PreferencesDialog::_3dRenderingColorSchemeScan
QVector< QSpinBox * > _3dRenderingColorSchemeScan
Definition: PreferencesDialog.h:477
rtabmap::PreferencesDialog::_3dRenderingShowClouds
QVector< QCheckBox * > _3dRenderingShowClouds
Definition: PreferencesDialog.h:464
rtabmap::PreferencesDialog::_modifiedParameters
rtabmap::ParametersMap _modifiedParameters
Definition: PreferencesDialog.h:451
rtabmap_superglue.device
string device
Definition: rtabmap_superglue.py:21
rtabmap::PreferencesDialog::_ui
Ui_preferencesDialog * _ui
Definition: PreferencesDialog.h:453
rtabmap::PreferencesDialog::_3dRenderingGravity
QVector< QCheckBox * > _3dRenderingGravity
Definition: PreferencesDialog.h:483
rtabmap::PreferencesDialog::PanelFlag
PanelFlag
Definition: PreferencesDialog.h:73
rtabmap::Camera
Definition: Camera.h:43
rtabmap::PreferencesDialog::_progressDialog
QProgressDialog * _progressDialog
Definition: PreferencesDialog.h:458
rtabmap::PreferencesDialog::_monitoringState
bool _monitoringState
Definition: PreferencesDialog.h:456
rtabmap::SensorCapture
Definition: SensorCapture.h:49
rtabmap::PreferencesDialog
Definition: PreferencesDialog.h:68
rtabmap::PreferencesDialog::_3dRenderingMinRange
QVector< QDoubleSpinBox * > _3dRenderingMinRange
Definition: PreferencesDialog.h:475
rtabmap_netvlad.init
def init(descriptorDim)
Definition: rtabmap_netvlad.py:30
rtabmap::Transform
Definition: Transform.h:41
rtabmap::PreferencesDialog::_3dRenderingOpacityScan
QVector< QDoubleSpinBox * > _3dRenderingOpacityScan
Definition: PreferencesDialog.h:478
rtabmap::PreferencesDialog::_3dRenderingPtSizeFeatures
QVector< QSpinBox * > _3dRenderingPtSizeFeatures
Definition: PreferencesDialog.h:482
UPlotCurve
Definition: UPlot.h:93
rtabmap::PreferencesDialog::_3dRenderingShowFeatures
QVector< QCheckBox * > _3dRenderingShowFeatures
Definition: PreferencesDialog.h:480
rtabmap::PreferencesDialog::_3dRenderingPtSize
QVector< QSpinBox * > _3dRenderingPtSize
Definition: PreferencesDialog.h:471
rtabmap::PreferencesDialog::_3dRenderingVoxelSizeScan
QVector< QDoubleSpinBox * > _3dRenderingVoxelSizeScan
Definition: PreferencesDialog.h:476
rtabmap::PreferencesDialog::_3dRenderingShowFrustums
QVector< QCheckBox * > _3dRenderingShowFrustums
Definition: PreferencesDialog.h:481
rtabmap::PreferencesDialog::_3dRenderingRoiRatios
QVector< QLineEdit * > _3dRenderingRoiRatios
Definition: PreferencesDialog.h:468
rtabmap::PreferencesDialog::_createCalibrationDialog
CreateSimpleCalibrationDialog * _createCalibrationDialog
Definition: PreferencesDialog.h:462
rtabmap::CalibrationDialog
Definition: CalibrationDialog.h:55
rtabmap::PreferencesDialog::setMonitoringState
void setMonitoringState(bool monitoringState)
Definition: PreferencesDialog.h:323
rtabmap::PreferencesDialog::_3dRenderingMinDepth
QVector< QDoubleSpinBox * > _3dRenderingMinDepth
Definition: PreferencesDialog.h:467
rtabmap::PreferencesDialog::_3dRenderingMaxDepth
QVector< QDoubleSpinBox * > _3dRenderingMaxDepth
Definition: PreferencesDialog.h:466
rtabmap::PreferencesDialog::_3dRenderingMaxRange
QVector< QDoubleSpinBox * > _3dRenderingMaxRange
Definition: PreferencesDialog.h:474
rtabmap::Lidar
Definition: Lidar.h:40
rtabmap
Definition: CameraARCore.cpp:35
rtabmap::PreferencesDialog::_obsoletePanels
PANEL_FLAGS _obsoletePanels
Definition: PreferencesDialog.h:448


rtabmap
Author(s): Mathieu Labbe
autogenerated on Mon Apr 28 2025 02:45:58