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