Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028 #ifndef PREFERENCESDIALOG_H_
00029 #define PREFERENCESDIALOG_H_
00030
00031 #include "rtabmap/gui/RtabmapGuiExp.h"
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 CameraRGBD;
00063 class CalibrationDialog;
00064
00065 class RTABMAPGUI_EXP PreferencesDialog : public QDialog
00066 {
00067 Q_OBJECT
00068
00069 public:
00070 enum PanelFlag {
00071 kPanelDummy = 0,
00072 kPanelGeneral = 1,
00073 kPanelCloudRendering = 2,
00074 kPanelLogging = 4,
00075 kPanelSource = 8,
00076 kPanelAll = 15
00077 };
00078
00079 Q_DECLARE_FLAGS(PANEL_FLAGS, PanelFlag);
00080
00081 enum Src {
00082 kSrcUndef,
00083 kSrcUsbDevice,
00084 kSrcImages,
00085 kSrcVideo,
00086 kSrcOpenNI_PCL,
00087 kSrcFreenect,
00088 kSrcOpenNI_CV,
00089 kSrcOpenNI_CV_ASUS,
00090 kSrcOpenNI2,
00091 kSrcFreenect2,
00092 kSrcStereoDC1394,
00093 kSrcStereoFlyCapture2
00094 };
00095
00096 public:
00097 PreferencesDialog(QWidget * parent = 0);
00098 virtual ~PreferencesDialog();
00099
00100 virtual QString getIniFilePath() const;
00101 void init();
00102
00103
00104 void saveSettings();
00105 void saveWindowGeometry(const QWidget * window);
00106 void loadWindowGeometry(QWidget * window);
00107 void saveMainWindowState(const QMainWindow * mainWindow);
00108 void loadMainWindowState(QMainWindow * mainWindow, bool & maximized);
00109 void saveWidgetState(const QWidget * widget);
00110 void loadWidgetState(QWidget * widget);
00111
00112 void saveCustomConfig(const QString & section, const QString & key, const QString & value);
00113 QString loadCustomConfig(const QString & section, const QString & key);
00114
00115 rtabmap::ParametersMap getAllParameters();
00116
00117
00118 int getGeneralLoggerLevel() const;
00119 int getGeneralLoggerEventLevel() const;
00120 int getGeneralLoggerPauseLevel() const;
00121 int getGeneralLoggerType() const;
00122 bool getGeneralLoggerPrintTime() const;
00123 bool isVerticalLayoutUsed() const;
00124 bool imageRejectedShown() const;
00125 bool imageHighestHypShown() const;
00126 bool beepOnPause() const;
00127 bool notifyWhenNewGlobalPathIsReceived() const;
00128 int getOdomQualityWarnThr() const;
00129 bool isPosteriorGraphView() const;
00130
00131 bool isGraphsShown() const;
00132 bool isCloudMeshing() const;
00133 bool isCloudsShown(int index) const;
00134 double getCloudVoxelSize(int index) const;
00135 int getCloudDecimation(int index) const;
00136 double getCloudMaxDepth(int index) const;
00137 double getCloudOpacity(int index) const;
00138 int getCloudPointSize(int index) const;
00139
00140 bool isScansShown(int index) const;
00141 double getScanOpacity(int index) const;
00142 int getScanPointSize(int index) const;
00143
00144 int getMeshNormalKSearch() const;
00145 double getMeshGP3Radius() const;
00146 bool getMeshSmoothing() const;
00147 double getMeshSmoothingRadius() const;
00148
00149 bool isCloudFiltering() const;
00150 double getCloudFilteringRadius() const;
00151 double getCloudFilteringAngle() const;
00152
00153 bool getGridMapShown() const;
00154 double getGridMapResolution() const;
00155 bool isGridMapFrom3DCloud() const;
00156 bool isGridMapEroded() const;
00157 double getGridMapOpacity() const;
00158
00159 QString getWorkingDirectory() const;
00160
00161
00162 double getGeneralInputRate() const;
00163 bool isSourceMirroring() const;
00164 bool isSourceImageUsed() const;
00165 bool isSourceDatabaseUsed() const;
00166 bool isSourceRGBDUsed() const;
00167 PreferencesDialog::Src getSourceImageType() const;
00168 QString getSourceImageTypeStr() const;
00169 int getSourceWidth() const;
00170 int getSourceHeight() const;
00171 QString getSourceImagesPath() const;
00172 QString getSourceImagesSuffix() const;
00173 int getSourceImagesSuffixIndex() const;
00174 int getSourceImagesStartPos() const;
00175 bool getSourceImagesRefreshDir() const;
00176 QString getSourceVideoPath() const;
00177 int getSourceUsbDeviceId() const;
00178 QString getSourceDatabasePath() const;
00179 bool getSourceDatabaseOdometryIgnored() const;
00180 bool getSourceDatabaseGoalDelayIgnored() const;
00181 int getSourceDatabaseStartPos() const;
00182 bool getSourceDatabaseStampsUsed() const;
00183 Src getSourceRGBD() const;
00184 bool getSourceOpenni2AutoWhiteBalance() const;
00185 bool getSourceOpenni2AutoExposure() const;
00186 int getSourceOpenni2Exposure() const;
00187 int getSourceOpenni2Gain() const;
00188 bool getSourceOpenni2Mirroring() const;
00189 int getSourceFreenect2Format() const;
00190 bool isSourceRGBDColorOnly() const;
00191 QString getSourceOpenniDevice() const;
00192 Transform getSourceOpenniLocalTransform() const;
00193 CameraRGBD * createCameraRGBD(bool forCalibration = false);
00194
00195 int getIgnoredDCComponents() const;
00196
00197
00198 bool isImagesKept() const;
00199 float getTimeLimit() const;
00200 float getDetectionRate() const;
00201 bool isSLAMMode() const;
00202
00203
00204 bool isStatisticsPublished() const;
00205 double getLoopThr() const;
00206 double getVpThr() const;
00207 int getOdomStrategy() const;
00208 QString getCameraInfoDir() const;
00209
00210
00211 void setMonitoringState(bool monitoringState) {_monitoringState = monitoringState;}
00212
00213 signals:
00214 void settingsChanged(PreferencesDialog::PANEL_FLAGS);
00215 void settingsChanged(rtabmap::ParametersMap);
00216
00217 public slots:
00218 void setInputRate(double value);
00219 void setDetectionRate(double value);
00220 void setTimeLimit(float value);
00221 void setSLAMMode(bool enabled);
00222 void selectSourceImage(Src src = kSrcUndef);
00223 void selectSourceDatabase(bool user = false);
00224 void selectSourceRGBD(Src src = kSrcUndef);
00225 void calibrate();
00226
00227 private slots:
00228 void closeDialog ( QAbstractButton * button );
00229 void resetApply ( QAbstractButton * button );
00230 void resetSettings(int panelNumber);
00231 void loadConfigFrom();
00232 bool saveConfigTo();
00233 void resetConfig();
00234 void makeObsoleteGeneralPanel();
00235 void makeObsoleteCloudRenderingPanel();
00236 void makeObsoleteLoggingPanel();
00237 void makeObsoleteSourcePanel();
00238 void clicked(const QModelIndex &index);
00239 void addParameter(int value);
00240 void addParameter(bool value);
00241 void addParameter(double value);
00242 void addParameter(const QString & value);
00243 void updatePredictionPlot();
00244 void updateKpROI();
00245 void changeWorkingDirectory();
00246 void changeDictionaryPath();
00247 void readSettingsEnd();
00248 void setupTreeView();
00249 void updateBasicParameter();
00250 void openDatabaseViewer();
00251 void updateRGBDCameraGroupBoxVisibility();
00252 void testOdometry();
00253 void testRGBDCamera();
00254
00255 protected:
00256 virtual void showEvent ( QShowEvent * event );
00257 virtual void closeEvent(QCloseEvent *event);
00258
00259 void setParameter(const std::string & key, const std::string & value);
00260
00261 virtual QString getParamMessage();
00262
00263 virtual void readSettings(const QString & filePath = QString());
00264 virtual void readGuiSettings(const QString & filePath = QString());
00265 virtual void readCameraSettings(const QString & filePath = QString());
00266 virtual bool readCoreSettings(const QString & filePath = QString());
00267
00268 virtual void writeSettings(const QString & filePath = QString());
00269 virtual void writeGuiSettings(const QString & filePath = QString()) const;
00270 virtual void writeCameraSettings(const QString & filePath = QString()) const;
00271 virtual void writeCoreSettings(const QString & filePath = QString()) const;
00272
00273 virtual QString getTmpIniFilePath() const;
00274
00275 private:
00276 bool validateForm();
00277 void setupSignals();
00278 void setupKpRoiPanel();
00279 bool parseModel(QList<QGroupBox*> & boxes, QStandardItem * parentItem, int currentLevel, int & absoluteIndex);
00280 void resetSettings(QGroupBox * groupBox);
00281 void addParameter(const QObject * object, int value);
00282 void addParameter(const QObject * object, bool value);
00283 void addParameter(const QObject * object, double value);
00284 void addParameter(const QObject * object, const QString & value);
00285 void addParameters(const QObjectList & children);
00286 void addParameters(const QStackedWidget * stackedWidget);
00287 void addParameters(const QGroupBox * box);
00288 QList<QGroupBox*> getGroupBoxes();
00289 void readSettingsBegin();
00290 void testOdometry(int type);
00291
00292 protected:
00293 rtabmap::ParametersMap _parameters;
00294 PANEL_FLAGS _obsoletePanels;
00295
00296 private:
00297 Ui_preferencesDialog * _ui;
00298 QStandardItemModel * _indexModel;
00299 bool _initialized;
00300 bool _monitoringState;
00301
00302 QProgressDialog * _progressDialog;
00303
00304
00305 CalibrationDialog * _calibrationDialog;
00306
00307 QVector<QCheckBox*> _3dRenderingShowClouds;
00308 QVector<QDoubleSpinBox*> _3dRenderingVoxelSize;
00309 QVector<QSpinBox*> _3dRenderingDecimation;
00310 QVector<QDoubleSpinBox*> _3dRenderingMaxDepth;
00311 QVector<QDoubleSpinBox*> _3dRenderingOpacity;
00312 QVector<QSpinBox*> _3dRenderingPtSize;
00313 QVector<QCheckBox*> _3dRenderingShowScans;
00314 QVector<QDoubleSpinBox*> _3dRenderingOpacityScan;
00315 QVector<QSpinBox*> _3dRenderingPtSizeScan;
00316 };
00317
00318 Q_DECLARE_OPERATORS_FOR_FLAGS(PreferencesDialog::PANEL_FLAGS)
00319
00320 }
00321
00322 #endif