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


rtabmap
Author(s): Mathieu Labbe
autogenerated on Mon Jan 23 2023 03:37:29