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 RTABMAP_PREFERENCESDIALOG_H_
00029 #define RTABMAP_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 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
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 kSrcRealSense = 6,
00093 kSrcRGBDImages = 7,
00094 kSrcK4W2 = 8,
00095 kSrcRealSense2 = 9,
00096
00097 kSrcStereo = 100,
00098 kSrcDC1394 = 100,
00099 kSrcFlyCapture2 = 101,
00100 kSrcStereoImages = 102,
00101 kSrcStereoVideo = 103,
00102 kSrcStereoZed = 104,
00103 kSrcStereoUsb = 105,
00104
00105 kSrcRGB = 200,
00106 kSrcUsbDevice = 200,
00107 kSrcImages = 201,
00108 kSrcVideo = 202,
00109
00110 kSrcDatabase = 300
00111 };
00112
00113 public:
00114 PreferencesDialog(QWidget * parent = 0);
00115 virtual ~PreferencesDialog();
00116
00117 virtual QString getIniFilePath() const;
00118 virtual QString getTmpIniFilePath() const;
00119 void init();
00120 void setCurrentPanelToSource();
00121 virtual QString getDefaultWorkingDirectory() const;
00122
00123
00124 void saveSettings();
00125 void saveWindowGeometry(const QWidget * window);
00126 void loadWindowGeometry(QWidget * window);
00127 void saveMainWindowState(const QMainWindow * mainWindow);
00128 void loadMainWindowState(QMainWindow * mainWindow, bool & maximized, bool & statusBarShown);
00129 void saveWidgetState(const QWidget * widget);
00130 void loadWidgetState(QWidget * widget);
00131
00132 void saveCustomConfig(const QString & section, const QString & key, const QString & value);
00133 QString loadCustomConfig(const QString & section, const QString & key);
00134
00135 rtabmap::ParametersMap getAllParameters() const;
00136 std::string getParameter(const std::string & key) const;
00137 void updateParameters(const ParametersMap & parameters, bool setOtherParametersToDefault = false);
00138
00139
00140 int getGeneralLoggerLevel() const;
00141 int getGeneralLoggerEventLevel() const;
00142 int getGeneralLoggerPauseLevel() const;
00143 int getGeneralLoggerType() const;
00144 bool getGeneralLoggerPrintTime() const;
00145 bool getGeneralLoggerPrintThreadId() const;
00146 std::vector<std::string> getGeneralLoggerThreads() const;
00147 bool isVerticalLayoutUsed() const;
00148 bool imageRejectedShown() const;
00149 bool imageHighestHypShown() const;
00150 bool beepOnPause() const;
00151 bool isTimeUsedInFigures() const;
00152 bool isCacheSavedInFigures() const;
00153 bool notifyWhenNewGlobalPathIsReceived() const;
00154 int getOdomQualityWarnThr() const;
00155 bool isOdomOnlyInliersShown() const;
00156 bool isPosteriorGraphView() const;
00157 bool isWordsCountGraphView() const;
00158 bool isLocalizationsCountGraphView() const;
00159 int getOdomRegistrationApproach() const;
00160 bool isOdomDisabled() const;
00161 bool isGroundTruthAligned() const;
00162
00163 bool isGraphsShown() const;
00164 bool isLabelsShown() const;
00165 double getVoxel() const;
00166 double getNoiseRadius() const;
00167 int getNoiseMinNeighbors() const;
00168 double getCeilingFilteringHeight() const;
00169 double getFloorFilteringHeight() const;
00170 int getNormalKSearch() const;
00171 double getNormalRadiusSearch() const;
00172 double getScanCeilingFilteringHeight() const;
00173 double getScanFloorFilteringHeight() const;
00174 int getScanNormalKSearch() const;
00175 double getScanNormalRadiusSearch() const;
00176 bool isCloudsShown(int index) const;
00177 bool isOctomapUpdated() const;
00178 bool isOctomapShown() const;
00179 int getOctomapRenderingType() const;
00180 bool isOctomap2dGrid() const;
00181 int getOctomapTreeDepth() const;
00182 int getOctomapPointSize() const;
00183 int getCloudDecimation(int index) const;
00184 double getCloudMaxDepth(int index) const;
00185 double getCloudMinDepth(int index) const;
00186 std::vector<float> getCloudRoiRatios(int index) const;
00187 int getCloudColorScheme(int index) const;
00188 double getCloudOpacity(int index) const;
00189 int getCloudPointSize(int index) const;
00190
00191 bool isScansShown(int index) const;
00192 int getDownsamplingStepScan(int index) const;
00193 double getScanMaxRange(int index) const;
00194 double getScanMinRange(int index) const;
00195 double getCloudVoxelSizeScan(int index) const;
00196 int getScanColorScheme(int index) const;
00197 double getScanOpacity(int index) const;
00198 int getScanPointSize(int index) const;
00199
00200 bool isFeaturesShown(int index) const;
00201 bool isFrustumsShown(int index) const;
00202 int getFeaturesPointSize(int index) const;
00203
00204 bool isCloudFiltering() const;
00205 bool isSubtractFiltering() const;
00206 double getCloudFilteringRadius() const;
00207 double getCloudFilteringAngle() const;
00208 int getSubtractFilteringMinPts() const;
00209 double getSubtractFilteringRadius() const;
00210 double getSubtractFilteringAngle() const;
00211
00212 bool getGridMapShown() const;
00213 bool isGridMapFrom3DCloud() const;
00214 bool projMapFrame() const;
00215 double projMaxGroundAngle() const;
00216 double projMaxGroundHeight() const;
00217 int projMinClusterSize() const;
00218 double projMaxObstaclesHeight() const;
00219 bool projFlatObstaclesDetected() const;
00220 double getGridMapOpacity() const;
00221
00222 bool isCloudMeshing() const;
00223 double getCloudMeshingAngle() const;
00224 bool isCloudMeshingQuad() const;
00225 bool isCloudMeshingTexture() const;
00226 int getCloudMeshingTriangleSize();
00227
00228 QString getWorkingDirectory() const;
00229
00230
00231 double getGeneralInputRate() const;
00232 bool isSourceMirroring() const;
00233 PreferencesDialog::Src getSourceType() const;
00234 PreferencesDialog::Src getSourceDriver() const;
00235 QString getSourceDriverStr() const;
00236 QString getSourceDevice() const;
00237
00238 bool isSourceDatabaseStampsUsed() const;
00239 bool isSourceRGBDColorOnly() const;
00240 bool isDepthFilteringAvailable() const;
00241 QString getSourceDistortionModel() const;
00242 bool isBilateralFiltering() const;
00243 double getBilateralSigmaS() const;
00244 double getBilateralSigmaR() const;
00245 int getSourceImageDecimation() const;
00246 bool isSourceStereoDepthGenerated() const;
00247 bool isSourceStereoExposureCompensation() const;
00248 bool isSourceScanFromDepth() const;
00249 int getSourceScanFromDepthDecimation() const;
00250 double getSourceScanFromDepthMaxDepth() const;
00251 double getSourceScanVoxelSize() const;
00252 int getSourceScanNormalsK() const;
00253 double getSourceScanNormalsRadius() const;
00254 Transform getSourceLocalTransform() const;
00255 Transform getLaserLocalTransform() const;
00256 Transform getIMULocalTransform() const;
00257 QString getIMUPath() const;
00258 int getIMURate() const;
00259 Camera * createCamera(bool useRawImages = false, bool useColor = true);
00260
00261 int getIgnoredDCComponents() const;
00262
00263
00264 bool isImagesKept() const;
00265 bool isCloudsKept() const;
00266 float getTimeLimit() const;
00267 float getDetectionRate() const;
00268 bool isSLAMMode() const;
00269 bool isRGBDMode() const;
00270 int getKpMaxFeatures() const;
00271
00272
00273 bool isStatisticsPublished() const;
00274 double getLoopThr() const;
00275 double getVpThr() const;
00276 double getSimThr() const;
00277 int getOdomStrategy() const;
00278 int getOdomBufferSize() const;
00279 QString getCameraInfoDir() const;
00280
00281
00282 void setMonitoringState(bool monitoringState) {_monitoringState = monitoringState;}
00283
00284 Q_SIGNALS:
00285 void settingsChanged(PreferencesDialog::PANEL_FLAGS);
00286 void settingsChanged(rtabmap::ParametersMap);
00287
00288 public Q_SLOTS:
00289 void setInputRate(double value);
00290 void setDetectionRate(double value);
00291 void setTimeLimit(float value);
00292 void setSLAMMode(bool enabled);
00293 void selectSourceDriver(Src src);
00294 void calibrate();
00295 void calibrateSimple();
00296
00297 private Q_SLOTS:
00298 void closeDialog ( QAbstractButton * button );
00299 void resetApply ( QAbstractButton * button );
00300 void resetSettings(int panelNumber);
00301 void loadConfigFrom();
00302 bool saveConfigTo();
00303 void resetConfig();
00304 void makeObsoleteGeneralPanel();
00305 void makeObsoleteCloudRenderingPanel();
00306 void makeObsoleteLoggingPanel();
00307 void makeObsoleteSourcePanel();
00308 void clicked(const QModelIndex & current, const QModelIndex & previous);
00309 void addParameter(int value);
00310 void addParameter(bool value);
00311 void addParameter(double value);
00312 void addParameter(const QString & value);
00313 void updatePredictionPlot();
00314 void updateKpROI();
00315 void updateStereoDisparityVisibility();
00316 void useOdomFeatures();
00317 void changeWorkingDirectory();
00318 void changeDictionaryPath();
00319 void changeOdometryORBSLAM2Vocabulary();
00320 void changeOdometryOKVISConfigPath();
00321 void changeIcpPMConfigPath();
00322 void readSettingsEnd();
00323 void setupTreeView();
00324 void updateBasicParameter();
00325 void openDatabaseViewer();
00326 void visualizeDistortionModel();
00327 void selectSourceDatabase();
00328 void selectCalibrationPath();
00329 void selectSourceImagesStamps();
00330 void selectSourceRGBDImagesPathRGB();
00331 void selectSourceRGBDImagesPathDepth();
00332 void selectSourceImagesPathScans();
00333 void selectSourceImagesPathIMU();
00334 void selectSourceImagesPathOdom();
00335 void selectSourceImagesPathGt();
00336 void selectSourceStereoImagesPathLeft();
00337 void selectSourceStereoImagesPathRight();
00338 void selectSourceImagesPath();
00339 void selectSourceVideoPath();
00340 void selectSourceStereoVideoPath();
00341 void selectSourceStereoVideoPath2();
00342 void selectSourceDistortionModel();
00343 void selectSourceOniPath();
00344 void selectSourceOni2Path();
00345 void selectSourceSvoPath();
00346 void updateSourceGrpVisibility();
00347 void testOdometry();
00348 void testCamera();
00349
00350 protected:
00351 virtual void showEvent ( QShowEvent * event );
00352 virtual void closeEvent(QCloseEvent *event);
00353
00354 virtual QString getParamMessage();
00355
00356 virtual void readGuiSettings(const QString & filePath = QString());
00357 virtual void readCameraSettings(const QString & filePath = QString());
00358 virtual bool readCoreSettings(const QString & filePath = QString());
00359
00360 virtual void writeGuiSettings(const QString & filePath = QString()) const;
00361 virtual void writeCameraSettings(const QString & filePath = QString()) const;
00362 virtual void writeCoreSettings(const QString & filePath = QString()) const;
00363
00364 void setParameter(const std::string & key, const std::string & value);
00365
00366 private:
00367 void readSettings(const QString & filePath = QString());
00368 void writeSettings(const QString & filePath = QString());
00369 bool validateForm();
00370 void setupSignals();
00371 void setupKpRoiPanel();
00372 bool parseModel(QList<QGroupBox*> & boxes, QStandardItem * parentItem, int currentLevel, int & absoluteIndex);
00373 void resetSettings(QGroupBox * groupBox);
00374 void addParameter(const QObject * object, int value);
00375 void addParameter(const QObject * object, bool value);
00376 void addParameter(const QObject * object, double value);
00377 void addParameter(const QObject * object, const QString & value);
00378 void addParameters(const QObjectList & children);
00379 void addParameters(const QStackedWidget * stackedWidget, int panel = -1);
00380 void addParameters(const QGroupBox * box);
00381 QList<QGroupBox*> getGroupBoxes();
00382 void readSettingsBegin();
00383
00384 protected:
00385 PANEL_FLAGS _obsoletePanels;
00386
00387 private:
00388 rtabmap::ParametersMap _modifiedParameters;
00389 rtabmap::ParametersMap _parameters;
00390 Ui_preferencesDialog * _ui;
00391 QStandardItemModel * _indexModel;
00392 bool _initialized;
00393 bool _monitoringState;
00394
00395 QProgressDialog * _progressDialog;
00396
00397
00398 CalibrationDialog * _calibrationDialog;
00399 CreateSimpleCalibrationDialog * _createCalibrationDialog;
00400
00401 QVector<QCheckBox*> _3dRenderingShowClouds;
00402 QVector<QSpinBox*> _3dRenderingDecimation;
00403 QVector<QDoubleSpinBox*> _3dRenderingMaxDepth;
00404 QVector<QDoubleSpinBox*> _3dRenderingMinDepth;
00405 QVector<QLineEdit*> _3dRenderingRoiRatios;
00406 QVector<QSpinBox*> _3dRenderingColorScheme;
00407 QVector<QDoubleSpinBox*> _3dRenderingOpacity;
00408 QVector<QSpinBox*> _3dRenderingPtSize;
00409 QVector<QCheckBox*> _3dRenderingShowScans;
00410 QVector<QSpinBox*> _3dRenderingDownsamplingScan;
00411 QVector<QDoubleSpinBox*> _3dRenderingMaxRange;
00412 QVector<QDoubleSpinBox*> _3dRenderingMinRange;
00413 QVector<QDoubleSpinBox*> _3dRenderingVoxelSizeScan;
00414 QVector<QSpinBox*> _3dRenderingColorSchemeScan;
00415 QVector<QDoubleSpinBox*> _3dRenderingOpacityScan;
00416 QVector<QSpinBox*> _3dRenderingPtSizeScan;
00417 QVector<QCheckBox*> _3dRenderingShowFeatures;
00418 QVector<QCheckBox*> _3dRenderingShowFrustums;
00419 QVector<QSpinBox*> _3dRenderingPtSizeFeatures;
00420 };
00421
00422 Q_DECLARE_OPERATORS_FOR_FLAGS(PreferencesDialog::PANEL_FLAGS)
00423
00424 }
00425
00426 #endif