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