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 isSourceScanFromDepth() const;
282  bool isSourceScanDeskewing() const;
283  int getSourceScanDownsampleStep() const;
284  double getSourceScanRangeMin() const;
285  double getSourceScanRangeMax() const;
286  double getSourceScanVoxelSize() const;
287  int getSourceScanNormalsK() const;
288  double getSourceScanNormalsRadius() const;
289  double getSourceScanForceGroundNormalsUp() const;
290  Transform getSourceLocalTransform() const; //Openni group
291  Transform getLaserLocalTransform() const; // directory images
292  Transform getIMULocalTransform() const; // directory images
293  QString getIMUPath() const;
294  int getIMURate() const;
295  Camera * createCamera(bool useRawImages = false, bool useColor = true); // return camera should be deleted if not null
296  SensorCapture * createOdomSensor(Transform & extrinsics, double & timeOffset, float & scaleFactor, double & waitTime); // return odom sensor should be deleted if not null
297  Lidar * createLidar(); // return lidar should be deleted if not null
298 
299  int getIgnoredDCComponents() const;
300 
301  //
302  bool isImagesKept() const;
303  bool isMissingCacheRepublished() const;
304  bool isCloudsKept() const;
305  float getTimeLimit() const;
306  float getDetectionRate() const;
307  bool isSLAMMode() const;
308  bool isRGBDMode() const;
309  int getKpMaxFeatures() const;
310  bool isPriorIgnored() const;
311 
312  //specific
313  bool isStatisticsPublished() const;
314  double getLoopThr() const;
315  double getVpThr() const;
316  double getSimThr() const;
317  int getOdomStrategy() const;
318  int getOdomBufferSize() const;
319  QString getCameraInfoDir() const; // "workinfDir/camera_info"
320 
321  //
322  void setMonitoringState(bool monitoringState) {_monitoringState = monitoringState;}
323 
324 Q_SIGNALS:
325  void settingsChanged(PreferencesDialog::PANEL_FLAGS);
326  void settingsChanged(rtabmap::ParametersMap);
327 
328 public Q_SLOTS:
329  void setInputRate(double value);
330  void setDetectionRate(double value);
331  void setTimeLimit(float value);
332  void setSLAMMode(bool enabled);
333  void selectSourceDriver(Src src, int variant = 0);
334  void calibrate();
335  void calibrateSimple();
336  void calibrateOdomSensorExtrinsics();
337  void testLidar();
338 
339 private Q_SLOTS:
340  void closeDialog ( QAbstractButton * button );
341  void resetApply ( QAbstractButton * button );
342  void resetSettings(int panelNumber);
343  void loadConfigFrom();
344  bool saveConfigTo();
345  void resetConfig();
346  void loadPreset();
347  void makeObsoleteGeneralPanel();
348  void makeObsoleteCloudRenderingPanel();
349  void makeObsoleteLoggingPanel();
350  void makeObsoleteSourcePanel();
351  void makeObsoleteCalibrationPanel();
352  void clicked(const QModelIndex & current, const QModelIndex & previous);
353  void addParameter(int value);
354  void addParameter(bool value);
355  void addParameter(double value);
356  void addParameter(const QString & value);
357  void updatePredictionPlot();
358  void updateKpROI();
359  void updateStereoDisparityVisibility();
360  void updateFeatureMatchingVisibility();
361  void updateGlobalDescriptorVisibility();
362  void updateOdometryStackedIndex(int index);
363  void useOdomFeatures();
364  void changeWorkingDirectory();
365  void changeDictionaryPath();
366  void changeOdometryORBSLAMVocabulary();
367  void changeOdometryOKVISConfigPath();
368  void changeOdometryVINSConfigPath();
369  void changeOdometryOpenVINSLeftMask();
370  void changeOdometryOpenVINSRightMask();
371  void changeIcpPMConfigPath();
372  void changeSuperPointModelPath();
373  void changePyMatcherPath();
374  void changePyMatcherModel();
375  void changePyDescriptorPath();
376  void changePyDetectorPath();
377  void readSettingsEnd();
378  void setupTreeView();
379  void updateBasicParameter();
380  void openDatabaseViewer();
381  void visualizeDistortionModel();
382  void selectSourceDatabase();
383  void selectCalibrationPath();
384  void selectOdomSensorCalibrationPath();
385  void selectSourceImagesStamps();
386  void selectSourceRGBDImagesPathRGB();
387  void selectSourceRGBDImagesPathDepth();
388  void selectSourceImagesPathScans();
389  void selectSourceImagesPathIMU();
390  void selectSourceImagesPathOdom();
391  void selectSourceImagesPathGt();
392  void selectSourceStereoImagesPathLeft();
393  void selectSourceStereoImagesPathRight();
394  void selectSourceImagesPath();
395  void selectSourceVideoPath();
396  void selectSourceStereoVideoPath();
397  void selectSourceStereoVideoPath2();
398  void selectSourceDistortionModel();
399  void selectSourceOniPath();
400  void selectSourceOni2Path();
401  void selectSourceMKVPath();
402  void selectSourceSvoPath();
403  void selectSourceRealsense2JsonPath();
404  void selectSourceDepthaiBlobPath();
405  void selectVlp16PcapPath();
406  void updateSourceGrpVisibility();
407  void testOdometry();
408  void testCamera();
409 
410 protected:
411  virtual void showEvent ( QShowEvent * event );
412  virtual void closeEvent(QCloseEvent *event);
413 
414  virtual QString getParamMessage();
415 
416  virtual void readGuiSettings(const QString & filePath = QString());
417  virtual void readCameraSettings(const QString & filePath = QString());
418  virtual bool readCoreSettings(const QString & filePath = QString());
419 
420  virtual void writeGuiSettings(const QString & filePath = QString()) const;
421  virtual void writeCameraSettings(const QString & filePath = QString()) const;
422  virtual void writeCoreSettings(const QString & filePath = QString()) const;
423 
424  void setParameter(const std::string & key, const std::string & value);
425 
426 private:
427  void readSettings(const QString & filePath = QString());
428  void writeSettings(const QString & filePath = QString());
429  bool validateForm();
430  void setupSignals();
431  void setupKpRoiPanel();
432  bool parseModel(QList<QGroupBox*> & boxes, QStandardItem * parentItem, int currentLevel, int & absoluteIndex);
433  void resetSettings(QGroupBox * groupBox);
434  void loadPreset(const std::string & presetHexHeader);
435  void addParameter(const QObject * object, int value);
436  void addParameter(const QObject * object, bool value);
437  void addParameter(const QObject * object, double value);
438  void addParameter(const QObject * object, const QString & value);
439  void addParameters(const QObjectList & children);
440  void addParameters(const QStackedWidget * stackedWidget, int panel = -1);
441  void addParameters(const QGroupBox * box);
442  QList<QGroupBox*> getGroupBoxes();
443  void readSettingsBegin();
444  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
445 
446 protected:
447  PANEL_FLAGS _obsoletePanels;
448 
449 private:
452  Ui_preferencesDialog * _ui;
453  QStandardItemModel * _indexModel;
456 
457  QProgressDialog * _progressDialog;
458 
459  //calibration
462 
463  QVector<QCheckBox*> _3dRenderingShowClouds;
464  QVector<QSpinBox*> _3dRenderingDecimation;
465  QVector<QDoubleSpinBox*> _3dRenderingMaxDepth;
466  QVector<QDoubleSpinBox*> _3dRenderingMinDepth;
467  QVector<QLineEdit*> _3dRenderingRoiRatios;
468  QVector<QSpinBox*> _3dRenderingColorScheme;
469  QVector<QDoubleSpinBox*> _3dRenderingOpacity;
470  QVector<QSpinBox*> _3dRenderingPtSize;
471  QVector<QCheckBox*> _3dRenderingShowScans;
472  QVector<QSpinBox*> _3dRenderingDownsamplingScan;
473  QVector<QDoubleSpinBox*> _3dRenderingMaxRange;
474  QVector<QDoubleSpinBox*> _3dRenderingMinRange;
475  QVector<QDoubleSpinBox*> _3dRenderingVoxelSizeScan;
476  QVector<QSpinBox*> _3dRenderingColorSchemeScan;
477  QVector<QDoubleSpinBox*> _3dRenderingOpacityScan;
478  QVector<QSpinBox*> _3dRenderingPtSizeScan;
479  QVector<QCheckBox*> _3dRenderingShowFeatures;
480  QVector<QCheckBox*> _3dRenderingShowFrustums;
481  QVector<QSpinBox*> _3dRenderingPtSizeFeatures;
482  QVector<QCheckBox*> _3dRenderingGravity;
483  QVector<QDoubleSpinBox*> _3dRenderingGravityLength;
484 };
485 
486 Q_DECLARE_OPERATORS_FOR_FLAGS(PreferencesDialog::PANEL_FLAGS)
487 
488 }
489 
490 #endif /* PREFERENCESDIALOG_H_ */
rtabmap::PreferencesDialog::_parameters
rtabmap::ParametersMap _parameters
Definition: PreferencesDialog.h:451
rtabmap::PreferencesDialog::_3dRenderingGravityLength
QVector< QDoubleSpinBox * > _3dRenderingGravityLength
Definition: PreferencesDialog.h:483
rtabmap::CreateSimpleCalibrationDialog
Definition: CreateSimpleCalibrationDialog.h:40
rtabmap::PreferencesDialog::_calibrationDialog
CalibrationDialog * _calibrationDialog
Definition: PreferencesDialog.h:460
rtabmap::PreferencesDialog::_3dRenderingColorScheme
QVector< QSpinBox * > _3dRenderingColorScheme
Definition: PreferencesDialog.h:468
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:464
rtabmap::PreferencesDialog::Src
Src
Definition: PreferencesDialog.h:85
rtabmap::PreferencesDialog::_3dRenderingPtSizeScan
QVector< QSpinBox * > _3dRenderingPtSizeScan
Definition: PreferencesDialog.h:478
Transform.h
rtabmap::PreferencesDialog::_indexModel
QStandardItemModel * _indexModel
Definition: PreferencesDialog.h:453
rtabmap::PreferencesDialog::_3dRenderingShowScans
QVector< QCheckBox * > _3dRenderingShowScans
Definition: PreferencesDialog.h:471
rtabmap::PreferencesDialog::_3dRenderingOpacity
QVector< QDoubleSpinBox * > _3dRenderingOpacity
Definition: PreferencesDialog.h:469
rtabmap::ParametersMap
std::map< std::string, std::string > ParametersMap
Definition: Parameters.h:43
rtabmap::PreferencesDialog::_initialized
bool _initialized
Definition: PreferencesDialog.h:454
Parameters.h
rtabmap::PreferencesDialog::_3dRenderingDownsamplingScan
QVector< QSpinBox * > _3dRenderingDownsamplingScan
Definition: PreferencesDialog.h:472
rtabmap::PreferencesDialog::_3dRenderingColorSchemeScan
QVector< QSpinBox * > _3dRenderingColorSchemeScan
Definition: PreferencesDialog.h:476
rtabmap::PreferencesDialog::_3dRenderingShowClouds
QVector< QCheckBox * > _3dRenderingShowClouds
Definition: PreferencesDialog.h:463
rtabmap::PreferencesDialog::_modifiedParameters
rtabmap::ParametersMap _modifiedParameters
Definition: PreferencesDialog.h:450
rtabmap_superglue.device
string device
Definition: rtabmap_superglue.py:21
rtabmap::PreferencesDialog::_ui
Ui_preferencesDialog * _ui
Definition: PreferencesDialog.h:452
rtabmap::PreferencesDialog::_3dRenderingGravity
QVector< QCheckBox * > _3dRenderingGravity
Definition: PreferencesDialog.h:482
rtabmap::PreferencesDialog::PanelFlag
PanelFlag
Definition: PreferencesDialog.h:73
rtabmap::Camera
Definition: Camera.h:43
rtabmap::PreferencesDialog::_progressDialog
QProgressDialog * _progressDialog
Definition: PreferencesDialog.h:457
rtabmap::PreferencesDialog::_monitoringState
bool _monitoringState
Definition: PreferencesDialog.h:455
rtabmap::SensorCapture
Definition: SensorCapture.h:49
rtabmap::PreferencesDialog
Definition: PreferencesDialog.h:68
rtabmap::PreferencesDialog::_3dRenderingMinRange
QVector< QDoubleSpinBox * > _3dRenderingMinRange
Definition: PreferencesDialog.h:474
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:477
rtabmap::PreferencesDialog::_3dRenderingPtSizeFeatures
QVector< QSpinBox * > _3dRenderingPtSizeFeatures
Definition: PreferencesDialog.h:481
UPlotCurve
Definition: UPlot.h:93
rtabmap::PreferencesDialog::_3dRenderingShowFeatures
QVector< QCheckBox * > _3dRenderingShowFeatures
Definition: PreferencesDialog.h:479
rtabmap::PreferencesDialog::_3dRenderingPtSize
QVector< QSpinBox * > _3dRenderingPtSize
Definition: PreferencesDialog.h:470
rtabmap::PreferencesDialog::_3dRenderingVoxelSizeScan
QVector< QDoubleSpinBox * > _3dRenderingVoxelSizeScan
Definition: PreferencesDialog.h:475
rtabmap::PreferencesDialog::_3dRenderingShowFrustums
QVector< QCheckBox * > _3dRenderingShowFrustums
Definition: PreferencesDialog.h:480
rtabmap::PreferencesDialog::_3dRenderingRoiRatios
QVector< QLineEdit * > _3dRenderingRoiRatios
Definition: PreferencesDialog.h:467
rtabmap::PreferencesDialog::_createCalibrationDialog
CreateSimpleCalibrationDialog * _createCalibrationDialog
Definition: PreferencesDialog.h:461
rtabmap::CalibrationDialog
Definition: CalibrationDialog.h:52
rtabmap::PreferencesDialog::setMonitoringState
void setMonitoringState(bool monitoringState)
Definition: PreferencesDialog.h:322
rtabmap::PreferencesDialog::_3dRenderingMinDepth
QVector< QDoubleSpinBox * > _3dRenderingMinDepth
Definition: PreferencesDialog.h:466
rtabmap::PreferencesDialog::_3dRenderingMaxDepth
QVector< QDoubleSpinBox * > _3dRenderingMaxDepth
Definition: PreferencesDialog.h:465
rtabmap::PreferencesDialog::_3dRenderingMaxRange
QVector< QDoubleSpinBox * > _3dRenderingMaxRange
Definition: PreferencesDialog.h:473
rtabmap::Lidar
Definition: Lidar.h:40
rtabmap
Definition: CameraARCore.cpp:35
rtabmap::PreferencesDialog::_obsoletePanels
PANEL_FLAGS _obsoletePanels
Definition: PreferencesDialog.h:447


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