PreferencesDialog.h
Go to the documentation of this file.
00001 /*
00002 Copyright (c) 2010-2016, Mathieu Labbe - IntRoLab - Universite de Sherbrooke
00003 All rights reserved.
00004 
00005 Redistribution and use in source and binary forms, with or without
00006 modification, are permitted provided that the following conditions are met:
00007     * Redistributions of source code must retain the above copyright
00008       notice, this list of conditions and the following disclaimer.
00009     * Redistributions in binary form must reproduce the above copyright
00010       notice, this list of conditions and the following disclaimer in the
00011       documentation and/or other materials provided with the distribution.
00012     * Neither the name of the Universite de Sherbrooke nor the
00013       names of its contributors may be used to endorse or promote products
00014       derived from this software without specific prior written permission.
00015 
00016 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
00017 ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
00018 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
00019 DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY
00020 DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
00021 (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00022 LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
00023 ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
00024 (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
00025 SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
00026 */
00027 
00028 #ifndef PREFERENCESDIALOG_H_
00029 #define PREFERENCESDIALOG_H_
00030 
00031 #include "rtabmap/gui/RtabmapGuiExp.h" // DLL export/import defines
00032 
00033 #include <QDialog>
00034 #include <QtCore/QModelIndex>
00035 #include <QtCore/QVector>
00036 #include <set>
00037 
00038 #include "rtabmap/core/Transform.h"
00039 #include "rtabmap/core/Parameters.h"
00040 
00041 class Ui_preferencesDialog;
00042 class QAbstractItemModel;
00043 class QAbstractButton;
00044 class QStandardItemModel;
00045 class QStandardItem;
00046 class QFile;
00047 class QGroupBox;
00048 class QMainWindow;
00049 class QLineEdit;
00050 class QSlider;
00051 class QProgressDialog;
00052 class UPlotCurve;
00053 class QStackedWidget;
00054 class QCheckBox;
00055 class QSpinBox;
00056 class QDoubleSpinBox;
00057 
00058 namespace rtabmap {
00059 
00060 class Signature;
00061 class LoopClosureViewer;
00062 class Camera;
00063 class CalibrationDialog;
00064 class CreateSimpleCalibrationDialog;
00065 
00066 class RTABMAPGUI_EXP PreferencesDialog : public QDialog
00067 {
00068         Q_OBJECT
00069 
00070 public:
00071         enum PanelFlag {
00072                 kPanelDummy = 0,
00073                 kPanelGeneral = 1,
00074                 kPanelCloudRendering = 2,
00075                 kPanelLogging = 4,
00076                 kPanelSource = 8,
00077                 kPanelAll = 15
00078         };
00079         // TODO, tried to change the name of PANEL_FLAGS to PanelFlags... but signals/slots errors appeared...
00080         Q_DECLARE_FLAGS(PANEL_FLAGS, PanelFlag);
00081 
00082         enum Src {
00083                 kSrcUndef = -1,
00084 
00085                 kSrcRGBD           = 0,
00086                 kSrcOpenNI_PCL     = 0,
00087                 kSrcFreenect       = 1,
00088                 kSrcOpenNI_CV      = 2,
00089                 kSrcOpenNI_CV_ASUS = 3,
00090                 kSrcOpenNI2        = 4,
00091                 kSrcFreenect2      = 5,
00092                 kSrcRGBDImages     = 6,
00093 
00094                 kSrcStereo         = 100,
00095                 kSrcDC1394         = 100,
00096                 kSrcFlyCapture2    = 101,
00097                 kSrcStereoImages   = 102,
00098                 kSrcStereoVideo    = 103,
00099                 kSrcStereoZed      = 104,
00100                 kSrcStereoUsb      = 105,
00101 
00102                 kSrcRGB            = 200,
00103                 kSrcUsbDevice      = 200,
00104                 kSrcImages         = 201,
00105                 kSrcVideo          = 202,
00106 
00107                 kSrcDatabase       = 300
00108         };
00109 
00110 public:
00111         PreferencesDialog(QWidget * parent = 0);
00112         virtual ~PreferencesDialog();
00113 
00114         virtual QString getIniFilePath() const;
00115         virtual QString getTmpIniFilePath() const;
00116         void init();
00117         void setCurrentPanelToSource();
00118 
00119         // save stuff
00120         void saveSettings();
00121         void saveWindowGeometry(const QWidget * window);
00122         void loadWindowGeometry(QWidget * window);
00123         void saveMainWindowState(const QMainWindow * mainWindow);
00124         void loadMainWindowState(QMainWindow * mainWindow, bool & maximized, bool & statusBarShown);
00125         void saveWidgetState(const QWidget * widget);
00126         void loadWidgetState(QWidget * widget);
00127 
00128         void saveCustomConfig(const QString & section, const QString & key, const QString & value);
00129         QString loadCustomConfig(const QString & section, const QString & key);
00130 
00131         rtabmap::ParametersMap getAllParameters() const;
00132         void updateParameters(const ParametersMap & parameters);
00133 
00134         //General panel
00135         int getGeneralLoggerLevel() const;
00136         int getGeneralLoggerEventLevel() const;
00137         int getGeneralLoggerPauseLevel() const;
00138         int getGeneralLoggerType() const;
00139         bool getGeneralLoggerPrintTime() const;
00140         bool getGeneralLoggerPrintThreadId() const;
00141         bool isVerticalLayoutUsed() const;
00142         bool imageRejectedShown() const;
00143         bool imageHighestHypShown() const;
00144         bool beepOnPause() const;
00145         bool isTimeUsedInFigures() const;
00146         bool notifyWhenNewGlobalPathIsReceived() const;
00147         int getOdomQualityWarnThr() const;
00148         bool isPosteriorGraphView() const;
00149 
00150         bool isGraphsShown() const;
00151         bool isLabelsShown() const;
00152         double getMapVoxel() const;
00153         double getMapNoiseRadius() const;
00154         int getMapNoiseMinNeighbors() const;
00155         bool isCloudsShown(int index) const;      // 0=map, 1=odom
00156         bool isOctomapShown() const;
00157         int getOctomapTreeDepth() const;
00158         bool isOctomapGroundAnObstacle() const;
00159         int getCloudDecimation(int index) const;   // 0=map, 1=odom
00160         double getCloudMaxDepth(int index) const;  // 0=map, 1=odom
00161         double getCloudMinDepth(int index) const;  // 0=map, 1=odom
00162         double getCloudOpacity(int index) const;   // 0=map, 1=odom
00163         int getCloudPointSize(int index) const;    // 0=map, 1=odom
00164 
00165         bool isScansShown(int index) const;       // 0=map, 1=odom
00166         int getDownsamplingStepScan(int index) const; // 0=map, 1=odom
00167         double getCloudVoxelSizeScan(int index) const; // 0=map, 1=odom
00168         double getScanOpacity(int index) const;    // 0=map, 1=odom
00169         int getScanPointSize(int index) const;     // 0=map, 1=odom
00170 
00171         bool isFeaturesShown(int index) const;     // 0=map, 1=odom
00172         int getFeaturesPointSize(int index) const; // 0=map, 1=odom
00173 
00174         bool isCloudFiltering() const;
00175         bool isSubtractFiltering() const;
00176         double getCloudFilteringRadius() const;
00177         double getCloudFilteringAngle() const;
00178         int getSubtractFilteringMinPts() const;
00179         double getSubtractFilteringRadius() const;
00180         double getSubtractFilteringAngle() const;
00181         int getNormalKSearch() const;
00182 
00183         bool getGridMapShown() const;
00184         double getGridMapResolution() const;;
00185         bool isGridMapEroded() const;
00186         bool isGridMapFrom3DCloud() const;
00187         bool projMapFrame() const;
00188         double projMaxGroundAngle() const;
00189         double projMaxGroundHeight() const;
00190         int projMinClusterSize() const;
00191         double projMaxObstaclesHeight() const;
00192         bool projFlatObstaclesDetected() const;
00193         double getGridMapOpacity() const;
00194 
00195         bool isCloudMeshing() const;
00196         double getCloudMeshingAngle() const;
00197         bool isCloudMeshingQuad() const;
00198         int getCloudMeshingTriangleSize();
00199 
00200         QString getWorkingDirectory() const;
00201 
00202         // source panel
00203         double getGeneralInputRate() const;
00204         bool isSourceMirroring() const;
00205         PreferencesDialog::Src getSourceType() const;
00206         PreferencesDialog::Src getSourceDriver() const;
00207         QString getSourceDriverStr() const;
00208         QString getSourceDevice() const;
00209 
00210         bool getSourceDatabaseStampsUsed() const;
00211         bool isSourceRGBDColorOnly() const;
00212         int getSourceImageDecimation() const;
00213         bool isSourceStereoDepthGenerated() const;
00214         bool isSourceScanFromDepth() const;
00215         int getSourceScanFromDepthDecimation() const;
00216         double getSourceScanFromDepthMaxDepth() const;
00217         double getSourceScanVoxelSize() const;
00218         int getSourceScanNormalsK() const;
00219         Transform getSourceLocalTransform() const;    //Openni group
00220         Transform getLaserLocalTransform() const; // directory images
00221         Camera * createCamera(bool useRawImages = false); // return camera should be deleted if not null
00222 
00223         int getIgnoredDCComponents() const;
00224 
00225         //
00226         bool isImagesKept() const;
00227         bool isCloudsKept() const;
00228         float getTimeLimit() const;
00229         float getDetectionRate() const;
00230         bool isSLAMMode() const;
00231         bool isRGBDMode() const;
00232 
00233         //specific
00234         bool isStatisticsPublished() const;
00235         double getLoopThr() const;
00236         double getVpThr() const;
00237         double getSimThr() const;
00238         int getOdomStrategy() const;
00239         int getOdomBufferSize() const;
00240         bool getRegVarianceFromInliersCount() const;
00241         QString getCameraInfoDir() const; // "workinfDir/camera_info"
00242 
00243         //
00244         void setMonitoringState(bool monitoringState) {_monitoringState = monitoringState;}
00245 
00246 signals:
00247         void settingsChanged(PreferencesDialog::PANEL_FLAGS);
00248         void settingsChanged(rtabmap::ParametersMap);
00249 
00250 public slots:
00251         void setInputRate(double value);
00252         void setDetectionRate(double value);
00253         void setTimeLimit(float value);
00254         void setSLAMMode(bool enabled);
00255         void selectSourceDriver(Src src);
00256         void calibrate();
00257         void calibrateSimple();
00258 
00259 private slots:
00260         void closeDialog ( QAbstractButton * button );
00261         void resetApply ( QAbstractButton * button );
00262         void resetSettings(int panelNumber);
00263         void loadConfigFrom();
00264         bool saveConfigTo();
00265         void resetConfig();
00266         void makeObsoleteGeneralPanel();
00267         void makeObsoleteCloudRenderingPanel();
00268         void makeObsoleteLoggingPanel();
00269         void makeObsoleteSourcePanel();
00270         void clicked(const QModelIndex & current, const QModelIndex & previous);
00271         void addParameter(int value);
00272         void addParameter(bool value);
00273         void addParameter(double value);
00274         void addParameter(const QString & value);
00275         void updatePredictionPlot();
00276         void updateKpROI();
00277         void updateG2oVisibility();
00278         void updateStereoDisparityVisibility();
00279         void useOdomFeatures();
00280         void changeWorkingDirectory();
00281         void changeDictionaryPath();
00282         void changeOdomBowFixedLocalMapPath();
00283         void readSettingsEnd();
00284         void setupTreeView();
00285         void updateBasicParameter();
00286         void openDatabaseViewer();
00287         void selectSourceDatabase();
00288         void selectCalibrationPath();
00289         void selectSourceImagesStamps();
00290         void selectSourceRGBDImagesPathRGB();
00291         void selectSourceRGBDImagesPathDepth();
00292         void selectSourceImagesPathScans();
00293         void selectSourceImagesPathGt();
00294         void selectSourceStereoImagesPathLeft();
00295         void selectSourceStereoImagesPathRight();
00296         void selectSourceImagesPath();
00297         void selectSourceVideoPath();
00298         void selectSourceStereoVideoPath();
00299         void selectSourceOniPath();
00300         void selectSourceOni2Path();
00301         void selectSourceSvoPath();
00302         void updateSourceGrpVisibility();
00303         void testOdometry();
00304         void testCamera();
00305 
00306 protected:
00307         virtual void showEvent ( QShowEvent * event );
00308         virtual void closeEvent(QCloseEvent *event);
00309 
00310         virtual QString getParamMessage();
00311 
00312         virtual void readGuiSettings(const QString & filePath = QString());
00313         virtual void readCameraSettings(const QString & filePath = QString());
00314         virtual bool readCoreSettings(const QString & filePath = QString());
00315 
00316         virtual void writeGuiSettings(const QString & filePath = QString()) const;
00317         virtual void writeCameraSettings(const QString & filePath = QString()) const;
00318         virtual void writeCoreSettings(const QString & filePath = QString()) const;
00319 
00320         void setParameter(const std::string & key, const std::string & value);
00321 
00322 private:
00323         void readSettings(const QString & filePath = QString());
00324         void writeSettings(const QString & filePath = QString());
00325         bool validateForm();
00326         void setupSignals();
00327         void setupKpRoiPanel();
00328         bool parseModel(QList<QGroupBox*> & boxes, QStandardItem * parentItem, int currentLevel, int & absoluteIndex);
00329         void resetSettings(QGroupBox * groupBox);
00330         void addParameter(const QObject * object, int value);
00331         void addParameter(const QObject * object, bool value);
00332         void addParameter(const QObject * object, double value);
00333         void addParameter(const QObject * object, const QString & value);
00334         void addParameters(const QObjectList & children);
00335         void addParameters(const QStackedWidget * stackedWidget, int panel = -1);
00336         void addParameters(const QGroupBox * box);
00337         QList<QGroupBox*> getGroupBoxes();
00338         void readSettingsBegin();
00339 
00340 protected:
00341         PANEL_FLAGS _obsoletePanels;
00342 
00343 private:
00344         rtabmap::ParametersMap _modifiedParameters;
00345         rtabmap::ParametersMap _parameters;
00346         Ui_preferencesDialog * _ui;
00347         QStandardItemModel * _indexModel;
00348         bool _initialized;
00349         bool _monitoringState;
00350 
00351         QProgressDialog * _progressDialog;
00352 
00353         //calibration
00354         CalibrationDialog * _calibrationDialog;
00355         CreateSimpleCalibrationDialog * _createCalibrationDialog;
00356 
00357         QVector<QCheckBox*> _3dRenderingShowClouds;
00358         QVector<QSpinBox*> _3dRenderingDecimation;
00359         QVector<QDoubleSpinBox*> _3dRenderingMaxDepth;
00360         QVector<QDoubleSpinBox*> _3dRenderingMinDepth;
00361         QVector<QDoubleSpinBox*> _3dRenderingOpacity;
00362         QVector<QSpinBox*> _3dRenderingPtSize;
00363         QVector<QCheckBox*> _3dRenderingShowScans;
00364         QVector<QSpinBox*> _3dRenderingDownsamplingScan;
00365         QVector<QDoubleSpinBox*> _3dRenderingVoxelSizeScan;
00366         QVector<QDoubleSpinBox*> _3dRenderingOpacityScan;
00367         QVector<QSpinBox*> _3dRenderingPtSizeScan;
00368         QVector<QCheckBox*> _3dRenderingShowFeatures;
00369         QVector<QSpinBox*> _3dRenderingPtSizeFeatures;
00370 };
00371 
00372 Q_DECLARE_OPERATORS_FOR_FLAGS(PreferencesDialog::PANEL_FLAGS)
00373 
00374 }
00375 
00376 #endif /* PREFERENCESDIALOG_H_ */


rtabmap
Author(s): Mathieu Labbe
autogenerated on Sat Jul 23 2016 11:44:17