PreferencesDialog.cpp
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 #include "rtabmap/gui/PreferencesDialog.h"
00029 #include "rtabmap/gui/DatabaseViewer.h"
00030 #include "rtabmap/gui/OdometryViewer.h"
00031 #include "rtabmap/gui/CalibrationDialog.h"
00032 
00033 #include <QtCore/QSettings>
00034 #include <QtCore/QDir>
00035 #include <QtCore/QTimer>
00036 #include <QUrl>
00037 
00038 #include <QButtonGroup>
00039 #include <QFileDialog>
00040 #include <QInputDialog>
00041 #include <QMessageBox>
00042 #include <QtGui/QStandardItemModel>
00043 #include <QMainWindow>
00044 #include <QProgressDialog>
00045 #include <QScrollBar>
00046 #include <QStatusBar>
00047 #include <QDesktopServices>
00048 #include <QtGui/QCloseEvent>
00049 
00050 #include "ui_preferencesDialog.h"
00051 
00052 #include "rtabmap/core/Version.h"
00053 #include "rtabmap/core/Parameters.h"
00054 #include "rtabmap/core/Odometry.h"
00055 #include "rtabmap/core/OdometryThread.h"
00056 #include "rtabmap/core/CameraRGBD.h"
00057 #include "rtabmap/core/CameraThread.h"
00058 #include "rtabmap/core/CameraRGB.h"
00059 #include "rtabmap/core/CameraStereo.h"
00060 #include "rtabmap/core/IMUThread.h"
00061 #include "rtabmap/core/Memory.h"
00062 #include "rtabmap/core/VWDictionary.h"
00063 #include "rtabmap/core/Optimizer.h"
00064 #include "rtabmap/core/OptimizerG2O.h"
00065 #include "rtabmap/core/DBReader.h"
00066 #include "rtabmap/core/clams/discrete_depth_distortion_model.h"
00067 
00068 #include "rtabmap/gui/LoopClosureViewer.h"
00069 #include "rtabmap/gui/CameraViewer.h"
00070 #include "rtabmap/gui/CloudViewer.h"
00071 #include "rtabmap/gui/ImageView.h"
00072 #include "rtabmap/gui/GraphViewer.h"
00073 #include "rtabmap/gui/ExportCloudsDialog.h"
00074 #include "rtabmap/gui/ExportBundlerDialog.h"
00075 #include "rtabmap/gui/PostProcessingDialog.h"
00076 #include "rtabmap/gui/CreateSimpleCalibrationDialog.h"
00077 #include "rtabmap/gui/DepthCalibrationDialog.h"
00078 
00079 #include <rtabmap/utilite/ULogger.h>
00080 #include <rtabmap/utilite/UConversion.h>
00081 #include <rtabmap/utilite/UStl.h>
00082 #include <rtabmap/utilite/UEventsManager.h>
00083 #include "rtabmap/utilite/UPlot.h"
00084 
00085 #include <opencv2/opencv_modules.hpp>
00086 #if CV_MAJOR_VERSION < 3
00087 #ifdef HAVE_OPENCV_GPU
00088   #include <opencv2/gpu/gpu.hpp>
00089 #endif
00090 #else
00091 #ifdef HAVE_OPENCV_CUDAFEATURES2D
00092   #include <opencv2/core/cuda.hpp>
00093 #endif
00094 #endif
00095 
00096 using namespace rtabmap;
00097 
00098 namespace rtabmap {
00099 
00100 PreferencesDialog::PreferencesDialog(QWidget * parent) :
00101         QDialog(parent),
00102         _obsoletePanels(kPanelDummy),
00103         _ui(0),
00104         _indexModel(0),
00105         _initialized(false),
00106         _progressDialog(new QProgressDialog(this)),
00107         _calibrationDialog(new CalibrationDialog(false, ".", false, this)),
00108         _createCalibrationDialog(new CreateSimpleCalibrationDialog(".", "", this))
00109 {
00110         ULOGGER_DEBUG("");
00111         _calibrationDialog->setWindowFlags(Qt::Window);
00112         _calibrationDialog->setWindowTitle(tr("Calibration"));
00113 
00114         _progressDialog->setWindowTitle(tr("Read parameters..."));
00115         _progressDialog->setMaximum(2);
00116         _progressDialog->setValue(2);
00117 
00118         _ui = new Ui_preferencesDialog();
00119         _ui->setupUi(this);
00120 
00121         bool haveCuda = false;
00122 #if CV_MAJOR_VERSION < 3
00123 #ifdef HAVE_OPENCV_GPU
00124         haveCuda = cv::gpu::getCudaEnabledDeviceCount() != 0;
00125 #endif
00126 #else
00127 #ifdef HAVE_OPENCV_CUDAFEATURES2D
00128         haveCuda = cv::cuda::getCudaEnabledDeviceCount() != 0;
00129 #endif
00130 #endif
00131         if(!haveCuda)
00132         {
00133                 _ui->surf_checkBox_gpuVersion->setChecked(false);
00134                 _ui->surf_checkBox_gpuVersion->setEnabled(false);
00135                 _ui->label_surf_checkBox_gpuVersion->setEnabled(false);
00136                 _ui->surf_doubleSpinBox_gpuKeypointsRatio->setEnabled(false);
00137                 _ui->label_surf_checkBox_gpuKeypointsRatio->setEnabled(false);
00138 
00139                 _ui->fastGpu->setChecked(false);
00140                 _ui->fastGpu->setEnabled(false);
00141                 _ui->label_fastGPU->setEnabled(false);
00142                 _ui->fastKeypointRatio->setEnabled(false);
00143                 _ui->label_fastGPUKptRatio->setEnabled(false);
00144 
00145                 _ui->checkBox_ORBGpu->setChecked(false);
00146                 _ui->checkBox_ORBGpu->setEnabled(false);
00147                 _ui->label_orbGpu->setEnabled(false);
00148 
00149                 // remove BruteForceGPU option
00150                 _ui->comboBox_dictionary_strategy->removeItem(4);
00151                 _ui->reextract_nn->removeItem(4);
00152         }
00153 
00154 #ifndef RTABMAP_OCTOMAP
00155         _ui->groupBox_octomap->setChecked(false);
00156         _ui->groupBox_octomap->setEnabled(false);
00157 #endif
00158 
00159 #ifndef RTABMAP_REALSENSE_SLAM
00160         _ui->checkbox_realsenseOdom->setChecked(false);
00161         _ui->checkbox_realsenseOdom->setEnabled(false);
00162         _ui->label_realsenseOdom->setEnabled(false);
00163 #endif
00164 
00165 #ifndef RTABMAP_FOVIS
00166         _ui->odom_strategy->setItemData(2, 0, Qt::UserRole - 1);
00167 #endif
00168 #ifndef RTABMAP_VISO2
00169         _ui->odom_strategy->setItemData(3, 0, Qt::UserRole - 1);
00170 #endif
00171 #ifndef RTABMAP_DVO
00172         _ui->odom_strategy->setItemData(4, 0, Qt::UserRole - 1);
00173 #endif
00174 #ifndef RTABMAP_ORB_SLAM2
00175         _ui->odom_strategy->setItemData(5, 0, Qt::UserRole - 1);
00176 #endif
00177 #ifndef RTABMAP_OKVIS
00178         _ui->odom_strategy->setItemData(6, 0, Qt::UserRole - 1);
00179 #endif
00180 #ifndef RTABMAP_LOAM
00181         _ui->odom_strategy->setItemData(7, 0, Qt::UserRole - 1);
00182 #endif
00183 #ifndef RTABMAP_MSCKF_VIO
00184         _ui->odom_strategy->setItemData(8, 0, Qt::UserRole - 1);
00185 #endif
00186 
00187 #ifndef RTABMAP_NONFREE
00188                 _ui->comboBox_detector_strategy->setItemData(0, 0, Qt::UserRole - 1);
00189                 _ui->comboBox_detector_strategy->setItemData(1, 0, Qt::UserRole - 1);
00190                 _ui->reextract_type->setItemData(0, 0, Qt::UserRole - 1);
00191                 _ui->reextract_type->setItemData(1, 0, Qt::UserRole - 1);
00192 
00193 #if CV_MAJOR_VERSION >= 3
00194                 _ui->comboBox_detector_strategy->setItemData(0, 0, Qt::UserRole - 1);
00195                 _ui->comboBox_detector_strategy->setItemData(1, 0, Qt::UserRole - 1);
00196                 _ui->comboBox_detector_strategy->setItemData(3, 0, Qt::UserRole - 1);
00197                 _ui->comboBox_detector_strategy->setItemData(4, 0, Qt::UserRole - 1);
00198                 _ui->comboBox_detector_strategy->setItemData(5, 0, Qt::UserRole - 1);
00199                 _ui->comboBox_detector_strategy->setItemData(6, 0, Qt::UserRole - 1);
00200                 _ui->reextract_type->setItemData(0, 0, Qt::UserRole - 1);
00201                 _ui->reextract_type->setItemData(1, 0, Qt::UserRole - 1);
00202                 _ui->reextract_type->setItemData(3, 0, Qt::UserRole - 1);
00203                 _ui->reextract_type->setItemData(4, 0, Qt::UserRole - 1);
00204                 _ui->reextract_type->setItemData(5, 0, Qt::UserRole - 1);
00205                 _ui->reextract_type->setItemData(6, 0, Qt::UserRole - 1);
00206 #endif
00207 #endif
00208 
00209 #if CV_MAJOR_VERSION >= 3
00210         _ui->groupBox_fast_opencv2->setEnabled(false);
00211 #else
00212         _ui->comboBox_detector_strategy->setItemData(9, 0, Qt::UserRole - 1); // No KAZE
00213         _ui->reextract_type->setItemData(9, 0, Qt::UserRole - 1); // No KAZE
00214 #endif
00215 
00216         _ui->comboBox_cameraImages_odomFormat->setItemData(4, 0, Qt::UserRole - 1);
00217         _ui->comboBox_cameraImages_gtFormat->setItemData(4, 0, Qt::UserRole - 1);
00218         if(!Optimizer::isAvailable(Optimizer::kTypeG2O))
00219         {
00220                 _ui->graphOptimization_type->setItemData(1, 0, Qt::UserRole - 1);
00221                 _ui->odom_f2m_bundleStrategy->setItemData(1, 0, Qt::UserRole - 1);
00222                 _ui->loopClosure_bundle->setItemData(1, 0, Qt::UserRole - 1);
00223                 _ui->groupBoxx_g2o->setEnabled(false);
00224         }
00225 #ifdef RTABMAP_ORB_SLAM2
00226         else
00227         {
00228                 // only graph optimization is disabled, g2o (from ORB_SLAM2) is valid only for SBA
00229                 _ui->graphOptimization_type->setItemData(1, 0, Qt::UserRole - 1);
00230         }
00231 #endif
00232         if(!OptimizerG2O::isCSparseAvailable())
00233         {
00234                 _ui->comboBox_g2o_solver->setItemData(0, 0, Qt::UserRole - 1);
00235         }
00236         if(!OptimizerG2O::isCholmodAvailable())
00237         {
00238                 _ui->comboBox_g2o_solver->setItemData(2, 0, Qt::UserRole - 1);
00239         }
00240         if(!Optimizer::isAvailable(Optimizer::kTypeTORO))
00241         {
00242                 _ui->graphOptimization_type->setItemData(0, 0, Qt::UserRole - 1);
00243         }
00244         if(!Optimizer::isAvailable(Optimizer::kTypeGTSAM))
00245         {
00246                 _ui->graphOptimization_type->setItemData(2, 0, Qt::UserRole - 1);
00247         }
00248         if(!Optimizer::isAvailable(Optimizer::kTypeCVSBA))
00249         {
00250                 _ui->odom_f2m_bundleStrategy->setItemData(2, 0, Qt::UserRole - 1);
00251                 _ui->loopClosure_bundle->setItemData(2, 0, Qt::UserRole - 1);
00252         }
00253 #ifdef RTABMAP_VERTIGO
00254         if(!Optimizer::isAvailable(Optimizer::kTypeG2O) && !Optimizer::isAvailable(Optimizer::kTypeGTSAM))
00255 #endif
00256         {
00257                 _ui->graphOptimization_robust->setEnabled(false);
00258         }
00259 #ifndef RTABMAP_POINTMATCHER
00260         _ui->groupBox_libpointmatcher->setEnabled(false);
00261 #endif
00262         if(!CameraOpenni::available())
00263         {
00264                 _ui->comboBox_cameraRGBD->setItemData(kSrcOpenNI_PCL - kSrcRGBD, 0, Qt::UserRole - 1);
00265         }
00266         if(!CameraFreenect::available())
00267         {
00268                 _ui->comboBox_cameraRGBD->setItemData(kSrcFreenect - kSrcRGBD, 0, Qt::UserRole - 1);
00269         }
00270         if(!CameraOpenNICV::available())
00271         {
00272                 _ui->comboBox_cameraRGBD->setItemData(kSrcOpenNI_CV - kSrcRGBD, 0, Qt::UserRole - 1);
00273                 _ui->comboBox_cameraRGBD->setItemData(kSrcOpenNI_CV_ASUS - kSrcRGBD, 0, Qt::UserRole - 1);
00274         }
00275         if(!CameraOpenNI2::available())
00276         {
00277                 _ui->comboBox_cameraRGBD->setItemData(kSrcOpenNI2 - kSrcRGBD, 0, Qt::UserRole - 1);
00278         }
00279         if(!CameraFreenect2::available())
00280         {
00281                 _ui->comboBox_cameraRGBD->setItemData(kSrcFreenect2 - kSrcRGBD, 0, Qt::UserRole - 1);
00282         }
00283         if (!CameraK4W2::available())
00284         {
00285                 _ui->comboBox_cameraRGBD->setItemData(kSrcK4W2 - kSrcRGBD, 0, Qt::UserRole - 1);
00286         }
00287         if (!CameraRealSense::available())
00288         {
00289                 _ui->comboBox_cameraRGBD->setItemData(kSrcRealSense - kSrcRGBD, 0, Qt::UserRole - 1);
00290         }
00291         if (!CameraRealSense2::available())
00292         {
00293                 _ui->comboBox_cameraRGBD->setItemData(kSrcRealSense2 - kSrcRGBD, 0, Qt::UserRole - 1);
00294         }
00295         if(!CameraStereoDC1394::available())
00296         {
00297                 _ui->comboBox_cameraStereo->setItemData(kSrcDC1394 - kSrcStereo, 0, Qt::UserRole - 1);
00298         }
00299         if(!CameraStereoFlyCapture2::available())
00300         {
00301                 _ui->comboBox_cameraStereo->setItemData(kSrcFlyCapture2 - kSrcStereo, 0, Qt::UserRole - 1);
00302         }
00303         if (!CameraStereoZed::available())
00304         {
00305                 _ui->comboBox_cameraStereo->setItemData(kSrcStereoZed - kSrcStereo, 0, Qt::UserRole - 1);
00306         }
00307         _ui->openni2_exposure->setEnabled(CameraOpenNI2::exposureGainAvailable());
00308         _ui->openni2_gain->setEnabled(CameraOpenNI2::exposureGainAvailable());
00309 
00310 #if PCL_VERSION_COMPARE(<, 1, 7, 2)
00311         _ui->checkBox_showFrustums->setEnabled(false);
00312         _ui->checkBox_showFrustums->setChecked(false);
00313         _ui->checkBox_showOdomFrustums->setEnabled(false);
00314         _ui->checkBox_showOdomFrustums->setChecked(false);
00315 #endif
00316 
00317         // in case we change the ui, we should not forget to change stuff related to this parameter
00318         UASSERT(_ui->odom_registration->count() == 4);
00319 
00320         // Default Driver
00321         connect(_ui->comboBox_sourceType, SIGNAL(currentIndexChanged(int)), this, SLOT(updateSourceGrpVisibility()));
00322         connect(_ui->comboBox_cameraRGBD, SIGNAL(currentIndexChanged(int)), this, SLOT(updateSourceGrpVisibility()));
00323         connect(_ui->source_comboBox_image_type, SIGNAL(currentIndexChanged(int)), this, SLOT(updateSourceGrpVisibility()));
00324         connect(_ui->comboBox_cameraStereo, SIGNAL(currentIndexChanged(int)), this, SLOT(updateSourceGrpVisibility()));
00325         this->resetSettings(_ui->groupBox_source0);
00326 
00327         _ui->predictionPlot->showLegend(false);
00328 
00329         QButtonGroup * buttonGroup = new QButtonGroup(this);
00330         buttonGroup->addButton(_ui->radioButton_basic);
00331         buttonGroup->addButton(_ui->radioButton_advanced);
00332 
00333         // Connect
00334         connect(_ui->buttonBox_global, SIGNAL(clicked(QAbstractButton *)), this, SLOT(closeDialog(QAbstractButton *)));
00335         connect(_ui->buttonBox_local, SIGNAL(clicked(QAbstractButton *)), this, SLOT(resetApply(QAbstractButton *)));
00336         connect(_ui->pushButton_loadConfig, SIGNAL(clicked()), this, SLOT(loadConfigFrom()));
00337         connect(_ui->pushButton_saveConfig, SIGNAL(clicked()), this, SLOT(saveConfigTo()));
00338         connect(_ui->pushButton_resetConfig, SIGNAL(clicked()), this, SLOT(resetConfig()));
00339         connect(_ui->radioButton_basic, SIGNAL(toggled(bool)), this, SLOT(setupTreeView()));
00340         connect(_ui->pushButton_testOdometry, SIGNAL(clicked()), this, SLOT(testOdometry()));
00341         connect(_ui->pushButton_test_camera, SIGNAL(clicked()), this, SLOT(testCamera()));
00342 
00343         // General panel
00344         connect(_ui->general_checkBox_imagesKept, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteGeneralPanel()));
00345         connect(_ui->general_checkBox_cloudsKept, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteGeneralPanel()));
00346         connect(_ui->checkBox_verticalLayoutUsed, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteGeneralPanel()));
00347         connect(_ui->checkBox_imageRejectedShown, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteGeneralPanel()));
00348         connect(_ui->checkBox_imageHighestHypShown, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteGeneralPanel()));
00349         connect(_ui->checkBox_beep, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteGeneralPanel()));
00350         connect(_ui->checkBox_stamps, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteGeneralPanel()));
00351         connect(_ui->checkBox_cacheStatistics, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteGeneralPanel()));
00352         connect(_ui->checkBox_notifyWhenNewGlobalPathIsReceived, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteGeneralPanel()));
00353         connect(_ui->spinBox_odomQualityWarnThr, SIGNAL(valueChanged(int)), this, SLOT(makeObsoleteGeneralPanel()));
00354         connect(_ui->checkBox_odom_onlyInliersShown, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteGeneralPanel()));
00355         connect(_ui->radioButton_posteriorGraphView, SIGNAL(toggled(bool)), this, SLOT(makeObsoleteGeneralPanel()));
00356         connect(_ui->radioButton_wordsGraphView, SIGNAL(toggled(bool)), this, SLOT(makeObsoleteGeneralPanel()));
00357         connect(_ui->radioButton_localizationsGraphView, SIGNAL(toggled(bool)), this, SLOT(makeObsoleteGeneralPanel()));
00358         connect(_ui->radioButton_nochangeGraphView, SIGNAL(toggled(bool)), this, SLOT(makeObsoleteGeneralPanel()));
00359         connect(_ui->checkbox_odomDisabled, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteGeneralPanel()));
00360         connect(_ui->odom_registration, SIGNAL(currentIndexChanged(int)), this, SLOT(makeObsoleteGeneralPanel()));
00361         connect(_ui->checkbox_groundTruthAlign, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteGeneralPanel()));
00362 
00363         // Cloud rendering panel
00364         _3dRenderingShowClouds.resize(2);
00365         _3dRenderingShowClouds[0] = _ui->checkBox_showClouds;
00366         _3dRenderingShowClouds[1] = _ui->checkBox_showOdomClouds;
00367 
00368         _3dRenderingDecimation.resize(2);
00369         _3dRenderingDecimation[0] = _ui->spinBox_decimation;
00370         _3dRenderingDecimation[1] = _ui->spinBox_decimation_odom;
00371 
00372         _3dRenderingMaxDepth.resize(2);
00373         _3dRenderingMaxDepth[0] = _ui->doubleSpinBox_maxDepth;
00374         _3dRenderingMaxDepth[1] = _ui->doubleSpinBox_maxDepth_odom;
00375 
00376         _3dRenderingMinDepth.resize(2);
00377         _3dRenderingMinDepth[0] = _ui->doubleSpinBox_minDepth;
00378         _3dRenderingMinDepth[1] = _ui->doubleSpinBox_minDepth_odom;
00379 
00380         _3dRenderingRoiRatios.resize(2);
00381         _3dRenderingRoiRatios[0] = _ui->lineEdit_roiRatios;
00382         _3dRenderingRoiRatios[1] = _ui->lineEdit_roiRatios_odom;
00383 
00384         _3dRenderingColorScheme.resize(2);
00385         _3dRenderingColorScheme[0] = _ui->spinBox_colorScheme;
00386         _3dRenderingColorScheme[1] = _ui->spinBox_colorScheme_odom;
00387 
00388         _3dRenderingOpacity.resize(2);
00389         _3dRenderingOpacity[0] = _ui->doubleSpinBox_opacity;
00390         _3dRenderingOpacity[1] = _ui->doubleSpinBox_opacity_odom;
00391 
00392         _3dRenderingPtSize.resize(2);
00393         _3dRenderingPtSize[0] = _ui->spinBox_ptsize;
00394         _3dRenderingPtSize[1] = _ui->spinBox_ptsize_odom;
00395 
00396         _3dRenderingShowScans.resize(2);
00397         _3dRenderingShowScans[0] = _ui->checkBox_showScans;
00398         _3dRenderingShowScans[1] = _ui->checkBox_showOdomScans;
00399 
00400         _3dRenderingDownsamplingScan.resize(2);
00401         _3dRenderingDownsamplingScan[0] = _ui->spinBox_downsamplingScan;
00402         _3dRenderingDownsamplingScan[1] = _ui->spinBox_downsamplingScan_odom;
00403 
00404         _3dRenderingMaxRange.resize(2);
00405         _3dRenderingMaxRange[0] = _ui->doubleSpinBox_maxRange;
00406         _3dRenderingMaxRange[1] = _ui->doubleSpinBox_maxRange_odom;
00407 
00408         _3dRenderingMinRange.resize(2);
00409         _3dRenderingMinRange[0] = _ui->doubleSpinBox_minRange;
00410         _3dRenderingMinRange[1] = _ui->doubleSpinBox_minRange_odom;
00411 
00412         _3dRenderingVoxelSizeScan.resize(2);
00413         _3dRenderingVoxelSizeScan[0] = _ui->doubleSpinBox_voxelSizeScan;
00414         _3dRenderingVoxelSizeScan[1] = _ui->doubleSpinBox_voxelSizeScan_odom;
00415 
00416         _3dRenderingColorSchemeScan.resize(2);
00417         _3dRenderingColorSchemeScan[0] = _ui->spinBox_colorSchemeScan;
00418         _3dRenderingColorSchemeScan[1] = _ui->spinBox_colorSchemeScan_odom;
00419 
00420         _3dRenderingOpacityScan.resize(2);
00421         _3dRenderingOpacityScan[0] = _ui->doubleSpinBox_opacity_scan;
00422         _3dRenderingOpacityScan[1] = _ui->doubleSpinBox_opacity_odom_scan;
00423 
00424         _3dRenderingPtSizeScan.resize(2);
00425         _3dRenderingPtSizeScan[0] = _ui->spinBox_ptsize_scan;
00426         _3dRenderingPtSizeScan[1] = _ui->spinBox_ptsize_odom_scan;
00427 
00428         _3dRenderingShowFeatures.resize(2);
00429         _3dRenderingShowFeatures[0] = _ui->checkBox_showFeatures;
00430         _3dRenderingShowFeatures[1] = _ui->checkBox_showOdomFeatures;
00431 
00432         _3dRenderingShowFrustums.resize(2);
00433         _3dRenderingShowFrustums[0] = _ui->checkBox_showFrustums;
00434         _3dRenderingShowFrustums[1] = _ui->checkBox_showOdomFrustums;
00435 
00436         _3dRenderingPtSizeFeatures.resize(2);
00437         _3dRenderingPtSizeFeatures[0] = _ui->spinBox_ptsize_features;
00438         _3dRenderingPtSizeFeatures[1] = _ui->spinBox_ptsize_odom_features;
00439 
00440         for(int i=0; i<2; ++i)
00441         {
00442                 connect(_3dRenderingShowClouds[i], SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteCloudRenderingPanel()));
00443                 connect(_3dRenderingDecimation[i], SIGNAL(valueChanged(int)), this, SLOT(makeObsoleteCloudRenderingPanel()));
00444                 connect(_3dRenderingMaxDepth[i], SIGNAL(valueChanged(double)), this, SLOT(makeObsoleteCloudRenderingPanel()));
00445                 connect(_3dRenderingMinDepth[i], SIGNAL(valueChanged(double)), this, SLOT(makeObsoleteCloudRenderingPanel()));
00446                 connect(_3dRenderingRoiRatios[i], SIGNAL(textChanged(const QString &)), this, SLOT(makeObsoleteCloudRenderingPanel()));
00447                 connect(_3dRenderingShowScans[i], SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteCloudRenderingPanel()));
00448                 connect(_3dRenderingShowFeatures[i], SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteCloudRenderingPanel()));
00449                 connect(_3dRenderingShowFrustums[i], SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteCloudRenderingPanel()));
00450 
00451                 connect(_3dRenderingDownsamplingScan[i], SIGNAL(valueChanged(int)), this, SLOT(makeObsoleteCloudRenderingPanel()));
00452                 connect(_3dRenderingMaxRange[i], SIGNAL(valueChanged(double)), this, SLOT(makeObsoleteCloudRenderingPanel()));
00453                 connect(_3dRenderingMinRange[i], SIGNAL(valueChanged(double)), this, SLOT(makeObsoleteCloudRenderingPanel()));
00454                 connect(_3dRenderingVoxelSizeScan[i], SIGNAL(valueChanged(double)), this, SLOT(makeObsoleteCloudRenderingPanel()));
00455                 connect(_3dRenderingColorScheme[i], SIGNAL(valueChanged(int)), this, SLOT(makeObsoleteCloudRenderingPanel()));
00456                 connect(_3dRenderingOpacity[i], SIGNAL(valueChanged(double)), this, SLOT(makeObsoleteCloudRenderingPanel()));
00457                 connect(_3dRenderingPtSize[i], SIGNAL(valueChanged(int)), this, SLOT(makeObsoleteCloudRenderingPanel()));
00458                 connect(_3dRenderingColorSchemeScan[i], SIGNAL(valueChanged(int)), this, SLOT(makeObsoleteCloudRenderingPanel()));
00459                 connect(_3dRenderingOpacityScan[i], SIGNAL(valueChanged(double)), this, SLOT(makeObsoleteCloudRenderingPanel()));
00460                 connect(_3dRenderingPtSizeScan[i], SIGNAL(valueChanged(int)), this, SLOT(makeObsoleteCloudRenderingPanel()));
00461                 connect(_3dRenderingPtSizeFeatures[i], SIGNAL(valueChanged(int)), this, SLOT(makeObsoleteCloudRenderingPanel()));
00462         }
00463         connect(_ui->doubleSpinBox_voxel, SIGNAL(valueChanged(double)), this, SLOT(makeObsoleteCloudRenderingPanel()));
00464         connect(_ui->doubleSpinBox_noiseRadius, SIGNAL(valueChanged(double)), this, SLOT(makeObsoleteCloudRenderingPanel()));
00465         connect(_ui->spinBox_noiseMinNeighbors, SIGNAL(valueChanged(int)), this, SLOT(makeObsoleteCloudRenderingPanel()));
00466         connect(_ui->doubleSpinBox_ceilingFilterHeight, SIGNAL(valueChanged(double)), this, SLOT(makeObsoleteCloudRenderingPanel()));
00467         connect(_ui->doubleSpinBox_floorFilterHeight, SIGNAL(valueChanged(double)), this, SLOT(makeObsoleteCloudRenderingPanel()));
00468         connect(_ui->spinBox_normalKSearch, SIGNAL(valueChanged(int)), this, SLOT(makeObsoleteCloudRenderingPanel()));
00469         connect(_ui->doubleSpinBox_normalRadiusSearch, SIGNAL(valueChanged(double)), this, SLOT(makeObsoleteCloudRenderingPanel()));
00470         connect(_ui->doubleSpinBox_ceilingFilterHeight_scan, SIGNAL(valueChanged(double)), this, SLOT(makeObsoleteCloudRenderingPanel()));
00471         connect(_ui->doubleSpinBox_floorFilterHeight_scan, SIGNAL(valueChanged(double)), this, SLOT(makeObsoleteCloudRenderingPanel()));
00472         connect(_ui->spinBox_normalKSearch_scan, SIGNAL(valueChanged(int)), this, SLOT(makeObsoleteCloudRenderingPanel()));
00473         connect(_ui->doubleSpinBox_normalRadiusSearch_scan, SIGNAL(valueChanged(double)), this, SLOT(makeObsoleteCloudRenderingPanel()));
00474 
00475         connect(_ui->checkBox_showGraphs, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteCloudRenderingPanel()));
00476         connect(_ui->checkBox_showLabels, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteCloudRenderingPanel()));
00477 
00478         connect(_ui->radioButton_noFiltering, SIGNAL(toggled(bool)), this, SLOT(makeObsoleteCloudRenderingPanel()));
00479         connect(_ui->radioButton_nodeFiltering, SIGNAL(toggled(bool)), this, SLOT(makeObsoleteCloudRenderingPanel()));
00480         connect(_ui->radioButton_subtractFiltering, SIGNAL(toggled(bool)), this, SLOT(makeObsoleteCloudRenderingPanel()));
00481         connect(_ui->doubleSpinBox_cloudFilterRadius, SIGNAL(valueChanged(double)), this, SLOT(makeObsoleteCloudRenderingPanel()));
00482         connect(_ui->doubleSpinBox_cloudFilterAngle, SIGNAL(valueChanged(double)), this, SLOT(makeObsoleteCloudRenderingPanel()));
00483         connect(_ui->spinBox_subtractFilteringMinPts, SIGNAL(valueChanged(int)), this, SLOT(makeObsoleteCloudRenderingPanel()));
00484         connect(_ui->doubleSpinBox_subtractFilteringRadius, SIGNAL(valueChanged(double)), this, SLOT(makeObsoleteCloudRenderingPanel()));
00485         connect(_ui->doubleSpinBox_subtractFilteringAngle, SIGNAL(valueChanged(double)), this, SLOT(makeObsoleteCloudRenderingPanel()));
00486 
00487         connect(_ui->checkBox_map_shown, SIGNAL(clicked(bool)), this, SLOT(makeObsoleteCloudRenderingPanel()));
00488         connect(_ui->doubleSpinBox_map_opacity, SIGNAL(valueChanged(double)), this, SLOT(makeObsoleteCloudRenderingPanel()));
00489 
00490         connect(_ui->groupBox_octomap, SIGNAL(toggled(bool)), this, SLOT(makeObsoleteCloudRenderingPanel()));
00491         connect(_ui->spinBox_octomap_treeDepth, SIGNAL(valueChanged(int)), this, SLOT(makeObsoleteCloudRenderingPanel()));
00492         connect(_ui->checkBox_octomap_2dgrid, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteCloudRenderingPanel()));
00493         connect(_ui->checkBox_octomap_show3dMap, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteCloudRenderingPanel()));
00494         connect(_ui->comboBox_octomap_renderingType, SIGNAL(currentIndexChanged(int)), this, SLOT(makeObsoleteCloudRenderingPanel()));
00495         connect(_ui->spinBox_octomap_pointSize, SIGNAL(valueChanged(int)), this, SLOT(makeObsoleteCloudRenderingPanel()));
00496 
00497         connect(_ui->groupBox_organized, SIGNAL(toggled(bool)), this, SLOT(makeObsoleteCloudRenderingPanel()));
00498         connect(_ui->doubleSpinBox_mesh_angleTolerance, SIGNAL(valueChanged(double)), this, SLOT(makeObsoleteCloudRenderingPanel()));
00499         connect(_ui->checkBox_mesh_quad, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteCloudRenderingPanel()));
00500         connect(_ui->checkBox_mesh_texture, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteCloudRenderingPanel()));
00501         connect(_ui->spinBox_mesh_triangleSize, SIGNAL(valueChanged(int)), this, SLOT(makeObsoleteCloudRenderingPanel()));
00502 
00503         //Logging panel
00504         connect(_ui->comboBox_loggerLevel, SIGNAL(currentIndexChanged(int)), this, SLOT(makeObsoleteLoggingPanel()));
00505         connect(_ui->comboBox_loggerEventLevel, SIGNAL(currentIndexChanged(int)), this, SLOT(makeObsoleteLoggingPanel()));
00506         connect(_ui->comboBox_loggerPauseLevel, SIGNAL(currentIndexChanged(int)), this, SLOT(makeObsoleteLoggingPanel()));
00507         connect(_ui->checkBox_logger_printTime, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteLoggingPanel()));
00508         connect(_ui->checkBox_logger_printThreadId, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteLoggingPanel()));
00509         connect(_ui->comboBox_loggerType, SIGNAL(currentIndexChanged(int)), this, SLOT(makeObsoleteLoggingPanel()));
00510         _ui->comboBox_loggerFilter->SetDisplayText("Select:");
00511         connect(_ui->comboBox_loggerFilter, SIGNAL(itemChanged()), this, SLOT(makeObsoleteLoggingPanel()));
00512 
00513         //Source panel
00514         connect(_ui->general_doubleSpinBox_imgRate, SIGNAL(valueChanged(double)), this, SLOT(makeObsoleteSourcePanel()));
00515         connect(_ui->general_doubleSpinBox_imgRate, SIGNAL(valueChanged(double)), _ui->doubleSpinBox_OdomORBSLAM2Fps, SLOT(setValue(double)));
00516         connect(_ui->source_mirroring, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
00517         connect(_ui->toolButton_source_path_calibration, SIGNAL(clicked()), this, SLOT(selectCalibrationPath()));
00518         connect(_ui->lineEdit_calibrationFile, SIGNAL(textChanged(const QString &)), this, SLOT(makeObsoleteSourcePanel()));
00519         _ui->stackedWidget_src->setCurrentIndex(_ui->comboBox_sourceType->currentIndex());
00520         connect(_ui->comboBox_sourceType, SIGNAL(currentIndexChanged(int)), _ui->stackedWidget_src, SLOT(setCurrentIndex(int)));
00521         connect(_ui->comboBox_sourceType, SIGNAL(currentIndexChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
00522         connect(_ui->lineEdit_sourceDevice, SIGNAL(textChanged(const QString &)), this, SLOT(makeObsoleteSourcePanel()));
00523         connect(_ui->lineEdit_sourceLocalTransform, SIGNAL(textChanged(const QString &)), this, SLOT(makeObsoleteSourcePanel()));
00524 
00525         //RGB source
00526         _ui->stackedWidget_image->setCurrentIndex(_ui->source_comboBox_image_type->currentIndex());
00527         connect(_ui->source_comboBox_image_type, SIGNAL(currentIndexChanged(int)), _ui->stackedWidget_image, SLOT(setCurrentIndex(int)));
00528         connect(_ui->source_comboBox_image_type, SIGNAL(currentIndexChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
00529         connect(_ui->checkBox_rgb_rectify, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
00530         //images group
00531         connect(_ui->source_images_toolButton_selectSource, SIGNAL(clicked()), this, SLOT(selectSourceImagesPath()));
00532         connect(_ui->source_images_lineEdit_path, SIGNAL(textChanged(const QString &)), this, SLOT(makeObsoleteSourcePanel()));
00533         connect(_ui->source_images_spinBox_startPos, SIGNAL(valueChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
00534         connect(_ui->comboBox_cameraImages_bayerMode, SIGNAL(currentIndexChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
00535         //video group
00536         connect(_ui->source_video_toolButton_selectSource, SIGNAL(clicked()), this, SLOT(selectSourceVideoPath()));
00537         connect(_ui->source_video_lineEdit_path, SIGNAL(textChanged(const QString &)), this, SLOT(makeObsoleteSourcePanel()));
00538         //database group
00539         connect(_ui->source_database_toolButton_selectSource, SIGNAL(clicked()), this, SLOT(selectSourceDatabase()));
00540         connect(_ui->toolButton_dbViewer, SIGNAL(clicked()), this, SLOT(openDatabaseViewer()));
00541         connect(_ui->groupBox_sourceDatabase, SIGNAL(toggled(bool)), this, SLOT(makeObsoleteSourcePanel()));
00542         connect(_ui->source_database_lineEdit_path, SIGNAL(textChanged(const QString &)), this, SLOT(makeObsoleteSourcePanel()));
00543         connect(_ui->source_checkBox_ignoreOdometry, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
00544         connect(_ui->source_checkBox_ignoreGoalDelay, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
00545         connect(_ui->source_checkBox_ignoreGoals, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
00546         connect(_ui->source_spinBox_databaseStartPos, SIGNAL(valueChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
00547         connect(_ui->source_checkBox_useDbStamps, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
00548         connect(_ui->source_spinBox_database_cameraIndex, SIGNAL(valueChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
00549 
00550         //openni group
00551         _ui->stackedWidget_rgbd->setCurrentIndex(_ui->comboBox_cameraRGBD->currentIndex());
00552         connect(_ui->comboBox_cameraRGBD, SIGNAL(currentIndexChanged(int)), _ui->stackedWidget_rgbd, SLOT(setCurrentIndex(int)));
00553         connect(_ui->comboBox_cameraRGBD, SIGNAL(currentIndexChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
00554         _ui->stackedWidget_stereo->setCurrentIndex(_ui->comboBox_cameraStereo->currentIndex());
00555         connect(_ui->comboBox_cameraStereo, SIGNAL(currentIndexChanged(int)), _ui->stackedWidget_stereo, SLOT(setCurrentIndex(int)));
00556         connect(_ui->comboBox_cameraStereo, SIGNAL(currentIndexChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
00557         connect(_ui->openni2_autoWhiteBalance, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
00558         connect(_ui->openni2_autoExposure, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
00559         connect(_ui->openni2_exposure, SIGNAL(valueChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
00560         connect(_ui->openni2_gain, SIGNAL(valueChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
00561         connect(_ui->openni2_mirroring, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
00562         connect(_ui->openni2_stampsIdsUsed, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
00563         connect(_ui->openni2_hshift, SIGNAL(valueChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
00564         connect(_ui->openni2_vshift, SIGNAL(valueChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
00565         connect(_ui->comboBox_freenect2Format, SIGNAL(currentIndexChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
00566         connect(_ui->doubleSpinBox_freenect2MinDepth, SIGNAL(valueChanged(double)), this, SLOT(makeObsoleteSourcePanel()));
00567         connect(_ui->doubleSpinBox_freenect2MaxDepth, SIGNAL(valueChanged(double)), this, SLOT(makeObsoleteSourcePanel()));
00568         connect(_ui->checkBox_freenect2BilateralFiltering, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
00569         connect(_ui->checkBox_freenect2EdgeAwareFiltering, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
00570         connect(_ui->checkBox_freenect2NoiseFiltering, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
00571         connect(_ui->lineEdit_freenect2Pipeline, SIGNAL(textChanged(const QString &)), this, SLOT(makeObsoleteSourcePanel()));
00572         connect(_ui->comboBox_k4w2Format, SIGNAL(currentIndexChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
00573         connect(_ui->comboBox_realsensePresetRGB, SIGNAL(currentIndexChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
00574         connect(_ui->comboBox_realsensePresetDepth, SIGNAL(currentIndexChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
00575         connect(_ui->checkbox_realsenseOdom, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
00576         connect(_ui->checkbox_realsenseDepthScaledToRGBSize, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
00577         connect(_ui->comboBox_realsenseRGBSource, SIGNAL(currentIndexChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
00578         connect(_ui->checkbox_rs2_emitter, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
00579         connect(_ui->checkbox_rs2_irDepth, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
00580 
00581         connect(_ui->toolButton_cameraImages_timestamps, SIGNAL(clicked()), this, SLOT(selectSourceImagesStamps()));
00582         connect(_ui->lineEdit_cameraImages_timestamps, SIGNAL(textChanged(const QString &)), this, SLOT(makeObsoleteSourcePanel()));
00583         connect(_ui->toolButton_cameraRGBDImages_path_rgb, SIGNAL(clicked()), this, SLOT(selectSourceRGBDImagesPathRGB()));
00584         connect(_ui->toolButton_cameraRGBDImages_path_depth, SIGNAL(clicked()), this, SLOT(selectSourceRGBDImagesPathDepth()));
00585         connect(_ui->toolButton_cameraImages_path_scans, SIGNAL(clicked()), this, SLOT(selectSourceImagesPathScans()));
00586         connect(_ui->toolButton_cameraImages_path_imu, SIGNAL(clicked()), this, SLOT(selectSourceImagesPathIMU()));
00587         connect(_ui->toolButton_cameraImages_odom, SIGNAL(clicked()), this, SLOT(selectSourceImagesPathOdom()));
00588         connect(_ui->toolButton_cameraImages_gt, SIGNAL(clicked()), this, SLOT(selectSourceImagesPathGt()));
00589         connect(_ui->lineEdit_cameraRGBDImages_path_rgb, SIGNAL(textChanged(const QString &)), this, SLOT(makeObsoleteSourcePanel()));
00590         connect(_ui->lineEdit_cameraRGBDImages_path_depth, SIGNAL(textChanged(const QString &)), this, SLOT(makeObsoleteSourcePanel()));
00591         connect(_ui->checkBox_cameraImages_timestamps, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
00592         connect(_ui->checkBox_cameraImages_syncTimeStamps, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
00593         connect(_ui->doubleSpinBox_cameraRGBDImages_scale, SIGNAL(valueChanged(double)), this, SLOT(makeObsoleteSourcePanel()));
00594         connect(_ui->spinBox_cameraRGBDImages_startIndex, SIGNAL(valueChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
00595         connect(_ui->lineEdit_cameraImages_path_scans, SIGNAL(textChanged(const QString &)), this, SLOT(makeObsoleteSourcePanel()));
00596         connect(_ui->lineEdit_cameraImages_laser_transform, SIGNAL(textChanged(const QString &)), this, SLOT(makeObsoleteSourcePanel()));
00597         connect(_ui->spinBox_cameraImages_max_scan_pts, SIGNAL(valueChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
00598         connect(_ui->spinBox_cameraImages_scanDownsampleStep, SIGNAL(valueChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
00599         connect(_ui->doubleSpinBox_cameraImages_scanVoxelSize, SIGNAL(valueChanged(double)), this, SLOT(makeObsoleteSourcePanel()));
00600         connect(_ui->lineEdit_cameraImages_odom, SIGNAL(textChanged(const QString &)), this, SLOT(makeObsoleteSourcePanel()));
00601         connect(_ui->comboBox_cameraImages_odomFormat, SIGNAL(currentIndexChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
00602         connect(_ui->lineEdit_cameraImages_gt, SIGNAL(textChanged(const QString &)), this, SLOT(makeObsoleteSourcePanel()));
00603         connect(_ui->comboBox_cameraImages_gtFormat, SIGNAL(currentIndexChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
00604         connect(_ui->doubleSpinBox_maxPoseTimeDiff, SIGNAL(valueChanged(double)), this, SLOT(makeObsoleteSourcePanel()));
00605         connect(_ui->lineEdit_cameraImages_path_imu, SIGNAL(textChanged(const QString &)), this, SLOT(makeObsoleteSourcePanel()));
00606         connect(_ui->lineEdit_cameraImages_imu_transform, SIGNAL(textChanged(const QString &)), this, SLOT(makeObsoleteSourcePanel()));
00607         connect(_ui->spinBox_cameraImages_max_imu_rate, SIGNAL(valueChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
00608         connect(_ui->groupBox_depthFromScan, SIGNAL(toggled(bool)), this, SLOT(makeObsoleteSourcePanel()));
00609         connect(_ui->groupBox_depthFromScan_fillHoles, SIGNAL(toggled(bool)), this, SLOT(makeObsoleteSourcePanel()));
00610         connect(_ui->radioButton_depthFromScan_vertical, SIGNAL(toggled(bool)), this, SLOT(makeObsoleteSourcePanel()));
00611         connect(_ui->radioButton_depthFromScan_horizontal, SIGNAL(toggled(bool)), this, SLOT(makeObsoleteSourcePanel()));
00612         connect(_ui->checkBox_depthFromScan_fillBorders, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
00613 
00614         connect(_ui->toolButton_cameraStereoImages_path_left, SIGNAL(clicked()), this, SLOT(selectSourceStereoImagesPathLeft()));
00615         connect(_ui->toolButton_cameraStereoImages_path_right, SIGNAL(clicked()), this, SLOT(selectSourceStereoImagesPathRight()));
00616         connect(_ui->lineEdit_cameraStereoImages_path_left, SIGNAL(textChanged(const QString &)), this, SLOT(makeObsoleteSourcePanel()));
00617         connect(_ui->lineEdit_cameraStereoImages_path_right, SIGNAL(textChanged(const QString &)), this, SLOT(makeObsoleteSourcePanel()));
00618         connect(_ui->checkBox_stereo_rectify, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
00619         connect(_ui->spinBox_cameraStereoImages_startIndex, SIGNAL(valueChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
00620 
00621         connect(_ui->toolButton_cameraStereoVideo_path, SIGNAL(clicked()), this, SLOT(selectSourceStereoVideoPath()));
00622         connect(_ui->toolButton_cameraStereoVideo_path_2, SIGNAL(clicked()), this, SLOT(selectSourceStereoVideoPath2()));
00623         connect(_ui->lineEdit_cameraStereoVideo_path, SIGNAL(textChanged(const QString &)), this, SLOT(makeObsoleteSourcePanel()));
00624         connect(_ui->lineEdit_cameraStereoVideo_path_2, SIGNAL(textChanged(const QString &)), this, SLOT(makeObsoleteSourcePanel()));
00625 
00626         connect(_ui->spinBox_stereo_right_device, SIGNAL(valueChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
00627 
00628         connect(_ui->comboBox_stereoZed_resolution, SIGNAL(currentIndexChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
00629         connect(_ui->comboBox_stereoZed_quality, SIGNAL(currentIndexChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
00630         connect(_ui->comboBox_stereoZed_quality, SIGNAL(currentIndexChanged(int)), this, SLOT(updateStereoDisparityVisibility()));
00631         connect(_ui->checkbox_stereoZed_selfCalibration, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
00632         connect(_ui->comboBox_cameraStereo, SIGNAL(currentIndexChanged(int)), this, SLOT(updateStereoDisparityVisibility()));
00633         connect(_ui->comboBox_stereoZed_sensingMode, SIGNAL(currentIndexChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
00634         connect(_ui->spinBox_stereoZed_confidenceThr, SIGNAL(valueChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
00635         connect(_ui->checkbox_stereoZed_odom, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
00636         connect(_ui->toolButton_zedSvoPath, SIGNAL(clicked()), this, SLOT(selectSourceSvoPath()));
00637         connect(_ui->lineEdit_zedSvoPath, SIGNAL(textChanged(const QString &)), this, SLOT(makeObsoleteSourcePanel()));
00638 
00639         connect(_ui->checkbox_rgbd_colorOnly, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
00640         connect(_ui->spinBox_source_imageDecimation, SIGNAL(valueChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
00641         connect(_ui->checkbox_stereo_depthGenerated, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
00642         connect(_ui->checkBox_stereo_exposureCompensation, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
00643         connect(_ui->pushButton_calibrate, SIGNAL(clicked()), this, SLOT(calibrate()));
00644         connect(_ui->pushButton_calibrate_simple, SIGNAL(clicked()), this, SLOT(calibrateSimple()));
00645         connect(_ui->toolButton_openniOniPath, SIGNAL(clicked()), this, SLOT(selectSourceOniPath()));
00646         connect(_ui->toolButton_openni2OniPath, SIGNAL(clicked()), this, SLOT(selectSourceOni2Path()));
00647         connect(_ui->toolButton_source_distortionModel, SIGNAL(clicked()), this, SLOT(selectSourceDistortionModel()));
00648         connect(_ui->toolButton_distortionModel, SIGNAL(clicked()), this, SLOT(visualizeDistortionModel()));
00649         connect(_ui->lineEdit_openniOniPath, SIGNAL(textChanged(const QString &)), this, SLOT(makeObsoleteSourcePanel()));
00650         connect(_ui->lineEdit_openni2OniPath, SIGNAL(textChanged(const QString &)), this, SLOT(makeObsoleteSourcePanel()));
00651         connect(_ui->lineEdit_source_distortionModel, SIGNAL(textChanged(const QString &)), this, SLOT(makeObsoleteSourcePanel()));
00652         connect(_ui->groupBox_bilateral, SIGNAL(toggled(bool)), this, SLOT(makeObsoleteSourcePanel()));
00653         connect(_ui->doubleSpinBox_bilateral_sigmaS, SIGNAL(valueChanged(double)), this, SLOT(makeObsoleteSourcePanel()));
00654         connect(_ui->doubleSpinBox_bilateral_sigmaR, SIGNAL(valueChanged(double)), this, SLOT(makeObsoleteSourcePanel()));
00655 
00656         connect(_ui->groupBox_scanFromDepth, SIGNAL(toggled(bool)), this, SLOT(makeObsoleteSourcePanel()));
00657         connect(_ui->spinBox_cameraScanFromDepth_decimation, SIGNAL(valueChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
00658         connect(_ui->doubleSpinBox_cameraSCanFromDepth_maxDepth, SIGNAL(valueChanged(double)), this, SLOT(makeObsoleteSourcePanel()));
00659         connect(_ui->doubleSpinBox_cameraImages_scanVoxelSize, SIGNAL(valueChanged(double)), this, SLOT(makeObsoleteSourcePanel()));
00660         connect(_ui->spinBox_cameraImages_scanNormalsK, SIGNAL(valueChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
00661         connect(_ui->doubleSpinBox_cameraImages_scanNormalsRadius, SIGNAL(valueChanged(double)), this, SLOT(makeObsoleteSourcePanel()));
00662         connect(_ui->checkBox_cameraImages_scanForceGroundNormalsUp, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
00663 
00664 
00665         //Rtabmap basic
00666         connect(_ui->general_doubleSpinBox_timeThr, SIGNAL(valueChanged(double)), _ui->general_doubleSpinBox_timeThr_2, SLOT(setValue(double)));
00667         connect(_ui->general_doubleSpinBox_hardThr, SIGNAL(valueChanged(double)), _ui->general_doubleSpinBox_hardThr_2, SLOT(setValue(double)));
00668         connect(_ui->doubleSpinBox_similarityThreshold, SIGNAL(valueChanged(double)), _ui->doubleSpinBox_similarityThreshold_2, SLOT(setValue(double)));
00669         connect(_ui->general_doubleSpinBox_detectionRate, SIGNAL(valueChanged(double)), _ui->general_doubleSpinBox_detectionRate_2, SLOT(setValue(double)));
00670         connect(_ui->general_spinBox_imagesBufferSize, SIGNAL(valueChanged(int)), _ui->general_spinBox_imagesBufferSize_2, SLOT(setValue(int)));
00671         connect(_ui->general_spinBox_maxStMemSize, SIGNAL(valueChanged(int)), _ui->general_spinBox_maxStMemSize_2, SLOT(setValue(int)));
00672 
00673         connect(_ui->general_doubleSpinBox_timeThr_2, SIGNAL(editingFinished()), this, SLOT(updateBasicParameter()));
00674         connect(_ui->general_doubleSpinBox_hardThr_2, SIGNAL(editingFinished()), this, SLOT(updateBasicParameter()));
00675         connect(_ui->doubleSpinBox_similarityThreshold_2, SIGNAL(editingFinished()), this, SLOT(updateBasicParameter()));
00676         connect(_ui->general_doubleSpinBox_detectionRate_2, SIGNAL(editingFinished()), this, SLOT(updateBasicParameter()));
00677         connect(_ui->general_spinBox_imagesBufferSize_2, SIGNAL(editingFinished()), this, SLOT(updateBasicParameter()));
00678         connect(_ui->general_spinBox_maxStMemSize_2, SIGNAL(editingFinished()), this, SLOT(updateBasicParameter()));
00679         connect(_ui->groupBox_publishing, SIGNAL(toggled(bool)), this, SLOT(updateBasicParameter()));
00680         connect(_ui->general_checkBox_publishStats_2, SIGNAL(stateChanged(int)), this, SLOT(updateBasicParameter()));
00681         connect(_ui->general_checkBox_activateRGBD, SIGNAL(stateChanged(int)), this, SLOT(updateBasicParameter()));
00682         connect(_ui->general_checkBox_activateRGBD_2, SIGNAL(stateChanged(int)), this, SLOT(updateBasicParameter()));
00683         connect(_ui->general_checkBox_SLAM_mode, SIGNAL(stateChanged(int)), this, SLOT(updateBasicParameter()));
00684         connect(_ui->general_checkBox_SLAM_mode_2, SIGNAL(stateChanged(int)), this, SLOT(updateBasicParameter()));
00685 
00686         // Map objects name with the corresponding parameter key, needed for the addParameter() slots
00687         //Rtabmap
00688         _ui->groupBox_publishing->setObjectName(Parameters::kRtabmapPublishStats().c_str());
00689         _ui->general_checkBox_publishRawData->setObjectName(Parameters::kRtabmapPublishLastSignature().c_str());
00690         _ui->general_checkBox_publishPdf->setObjectName(Parameters::kRtabmapPublishPdf().c_str());
00691         _ui->general_checkBox_publishLikelihood->setObjectName(Parameters::kRtabmapPublishLikelihood().c_str());
00692         _ui->general_checkBox_publishRMSE->setObjectName(Parameters::kRtabmapComputeRMSE().c_str());
00693         _ui->general_checkBox_saveWMState->setObjectName(Parameters::kRtabmapSaveWMState().c_str());
00694         _ui->general_checkBox_publishRAM->setObjectName(Parameters::kRtabmapPublishRAMUsage().c_str());
00695         _ui->general_checkBox_statisticLogsBufferedInRAM->setObjectName(Parameters::kRtabmapStatisticLogsBufferedInRAM().c_str());
00696         _ui->groupBox_statistics->setObjectName(Parameters::kRtabmapStatisticLogged().c_str());
00697         _ui->general_checkBox_statisticLoggedHeaders->setObjectName(Parameters::kRtabmapStatisticLoggedHeaders().c_str());
00698         _ui->general_doubleSpinBox_timeThr->setObjectName(Parameters::kRtabmapTimeThr().c_str());
00699         _ui->general_spinBox_memoryThr->setObjectName(Parameters::kRtabmapMemoryThr().c_str());
00700         _ui->general_doubleSpinBox_detectionRate->setObjectName(Parameters::kRtabmapDetectionRate().c_str());
00701         _ui->general_spinBox_imagesBufferSize->setObjectName(Parameters::kRtabmapImageBufferSize().c_str());
00702         _ui->general_checkBox_createIntermediateNodes->setObjectName(Parameters::kRtabmapCreateIntermediateNodes().c_str());
00703         _ui->general_spinBox_maxRetrieved->setObjectName(Parameters::kRtabmapMaxRetrieved().c_str());
00704         _ui->general_checkBox_startNewMapOnLoopClosure->setObjectName(Parameters::kRtabmapStartNewMapOnLoopClosure().c_str());
00705         _ui->general_checkBox_startNewMapOnGoodSignature->setObjectName(Parameters::kRtabmapStartNewMapOnGoodSignature().c_str());
00706         _ui->general_checkBox_imagesAlreadyRectified->setObjectName(Parameters::kRtabmapImagesAlreadyRectified().c_str());
00707         _ui->general_checkBox_rectifyOnlyFeatures->setObjectName(Parameters::kRtabmapRectifyOnlyFeatures().c_str());
00708         _ui->lineEdit_workingDirectory->setObjectName(Parameters::kRtabmapWorkingDirectory().c_str());
00709         connect(_ui->toolButton_workingDirectory, SIGNAL(clicked()), this, SLOT(changeWorkingDirectory()));
00710 
00711         // Memory
00712         _ui->general_checkBox_keepRawData->setObjectName(Parameters::kMemImageKept().c_str());
00713         _ui->general_checkBox_keepBinaryData->setObjectName(Parameters::kMemBinDataKept().c_str());
00714         _ui->general_checkBox_saveIntermediateNodeData->setObjectName(Parameters::kMemIntermediateNodeDataKept().c_str());
00715         _ui->general_checkBox_keepDescriptors->setObjectName(Parameters::kMemRawDescriptorsKept().c_str());
00716         _ui->general_checkBox_saveDepth16bits->setObjectName(Parameters::kMemSaveDepth16Format().c_str());
00717         _ui->general_checkBox_compressionParallelized->setObjectName(Parameters::kMemCompressionParallelized().c_str());
00718         _ui->general_checkBox_reduceGraph->setObjectName(Parameters::kMemReduceGraph().c_str());
00719         _ui->general_checkBox_keepNotLinkedNodes->setObjectName(Parameters::kMemNotLinkedNodesKept().c_str());
00720         _ui->general_spinBox_maxStMemSize->setObjectName(Parameters::kMemSTMSize().c_str());
00721         _ui->doubleSpinBox_similarityThreshold->setObjectName(Parameters::kMemRehearsalSimilarity().c_str());
00722         _ui->general_checkBox_SLAM_mode->setObjectName(Parameters::kMemIncrementalMemory().c_str());
00723         _ui->general_doubleSpinBox_recentWmRatio->setObjectName(Parameters::kMemRecentWmRatio().c_str());
00724         _ui->general_checkBox_transferSortingByWeightId->setObjectName(Parameters::kMemTransferSortingByWeightId().c_str());
00725         _ui->general_checkBox_RehearsalIdUpdatedToNewOne->setObjectName(Parameters::kMemRehearsalIdUpdatedToNewOne().c_str());
00726         _ui->general_checkBox_generateIds->setObjectName(Parameters::kMemGenerateIds().c_str());
00727         _ui->general_checkBox_badSignaturesIgnored->setObjectName(Parameters::kMemBadSignaturesIgnored().c_str());
00728         _ui->general_checkBox_createMapLabels->setObjectName(Parameters::kMemMapLabelsAdded().c_str());
00729         _ui->general_checkBox_initWMWithAllNodes->setObjectName(Parameters::kMemInitWMWithAllNodes().c_str());
00730         _ui->checkBox_localSpaceScanMatchingIDsSaved->setObjectName(Parameters::kRGBDScanMatchingIdsSavedInLinks().c_str());
00731         _ui->spinBox_imagePreDecimation->setObjectName(Parameters::kMemImagePreDecimation().c_str());
00732         _ui->spinBox_imagePostDecimation->setObjectName(Parameters::kMemImagePostDecimation().c_str());
00733         _ui->general_spinBox_laserScanDownsample->setObjectName(Parameters::kMemLaserScanDownsampleStepSize().c_str());
00734         _ui->general_doubleSpinBox_laserScanVoxelSize->setObjectName(Parameters::kMemLaserScanVoxelSize().c_str());
00735         _ui->general_spinBox_laserScanNormalK->setObjectName(Parameters::kMemLaserScanNormalK().c_str());
00736         _ui->general_doubleSpinBox_laserScanNormalRadius->setObjectName(Parameters::kMemLaserScanNormalRadius().c_str());
00737         _ui->checkBox_useOdomFeatures->setObjectName(Parameters::kMemUseOdomFeatures().c_str());
00738         _ui->memCovOffDiagIgnored->setObjectName(Parameters::kMemCovOffDiagIgnored().c_str());
00739 
00740         // Database
00741         _ui->checkBox_dbInMemory->setObjectName(Parameters::kDbSqlite3InMemory().c_str());
00742         _ui->spinBox_dbCacheSize->setObjectName(Parameters::kDbSqlite3CacheSize().c_str());
00743         _ui->comboBox_dbJournalMode->setObjectName(Parameters::kDbSqlite3JournalMode().c_str());
00744         _ui->comboBox_dbSynchronous->setObjectName(Parameters::kDbSqlite3Synchronous().c_str());
00745         _ui->comboBox_dbTempStore->setObjectName(Parameters::kDbSqlite3TempStore().c_str());
00746 
00747         // Create hypotheses
00748         _ui->general_doubleSpinBox_hardThr->setObjectName(Parameters::kRtabmapLoopThr().c_str());
00749         _ui->general_doubleSpinBox_loopRatio->setObjectName(Parameters::kRtabmapLoopRatio().c_str());
00750 
00751         //Bayes
00752         _ui->general_doubleSpinBox_vp->setObjectName(Parameters::kBayesVirtualPlacePriorThr().c_str());
00753         _ui->lineEdit_bayes_predictionLC->setObjectName(Parameters::kBayesPredictionLC().c_str());
00754         _ui->checkBox_bayes_fullPredictionUpdate->setObjectName(Parameters::kBayesFullPredictionUpdate().c_str());
00755         connect(_ui->lineEdit_bayes_predictionLC, SIGNAL(textChanged(const QString &)), this, SLOT(updatePredictionPlot()));
00756 
00757         //Keypoint-based
00758         _ui->comboBox_dictionary_strategy->setObjectName(Parameters::kKpNNStrategy().c_str());
00759         _ui->checkBox_dictionary_incremental->setObjectName(Parameters::kKpIncrementalDictionary().c_str());
00760         _ui->checkBox_kp_incrementalFlann->setObjectName(Parameters::kKpIncrementalFlann().c_str());
00761         _ui->surf_doubleSpinBox_rebalancingFactor->setObjectName(Parameters::kKpFlannRebalancingFactor().c_str());
00762         _ui->comboBox_detector_strategy->setObjectName(Parameters::kKpDetectorStrategy().c_str());
00763         _ui->surf_doubleSpinBox_nndrRatio->setObjectName(Parameters::kKpNndrRatio().c_str());
00764         _ui->surf_doubleSpinBox_maxDepth->setObjectName(Parameters::kKpMaxDepth().c_str());
00765         _ui->surf_doubleSpinBox_minDepth->setObjectName(Parameters::kKpMinDepth().c_str());
00766         _ui->checkBox_memDepthAsMask->setObjectName(Parameters::kMemDepthAsMask().c_str());
00767         _ui->surf_spinBox_wordsPerImageTarget->setObjectName(Parameters::kKpMaxFeatures().c_str());
00768         _ui->spinBox_KPGridRows->setObjectName(Parameters::kKpGridRows().c_str());
00769         _ui->spinBox_KPGridCols->setObjectName(Parameters::kKpGridCols().c_str());
00770         _ui->surf_doubleSpinBox_ratioBadSign->setObjectName(Parameters::kKpBadSignRatio().c_str());
00771         _ui->checkBox_kp_tfIdfLikelihoodUsed->setObjectName(Parameters::kKpTfIdfLikelihoodUsed().c_str());
00772         _ui->checkBox_kp_parallelized->setObjectName(Parameters::kKpParallelized().c_str());
00773         _ui->lineEdit_kp_roi->setObjectName(Parameters::kKpRoiRatios().c_str());
00774         _ui->lineEdit_dictionaryPath->setObjectName(Parameters::kKpDictionaryPath().c_str());
00775         connect(_ui->toolButton_dictionaryPath, SIGNAL(clicked()), this, SLOT(changeDictionaryPath()));
00776         _ui->checkBox_kp_newWordsComparedTogether->setObjectName(Parameters::kKpNewWordsComparedTogether().c_str());
00777         _ui->subpix_winSize_kp->setObjectName(Parameters::kKpSubPixWinSize().c_str());
00778         _ui->subpix_iterations_kp->setObjectName(Parameters::kKpSubPixIterations().c_str());
00779         _ui->subpix_eps_kp->setObjectName(Parameters::kKpSubPixEps().c_str());
00780 
00781         _ui->subpix_winSize->setObjectName(Parameters::kKpSubPixWinSize().c_str());
00782         _ui->subpix_iterations->setObjectName(Parameters::kKpSubPixIterations().c_str());
00783         _ui->subpix_eps->setObjectName(Parameters::kKpSubPixEps().c_str());
00784 
00785         //SURF detector
00786         _ui->surf_doubleSpinBox_hessianThr->setObjectName(Parameters::kSURFHessianThreshold().c_str());
00787         _ui->surf_spinBox_octaves->setObjectName(Parameters::kSURFOctaves().c_str());
00788         _ui->surf_spinBox_octaveLayers->setObjectName(Parameters::kSURFOctaveLayers().c_str());
00789         _ui->checkBox_surfExtended->setObjectName(Parameters::kSURFExtended().c_str());
00790         _ui->surf_checkBox_upright->setObjectName(Parameters::kSURFUpright().c_str());
00791         _ui->surf_checkBox_gpuVersion->setObjectName(Parameters::kSURFGpuVersion().c_str());
00792         _ui->surf_doubleSpinBox_gpuKeypointsRatio->setObjectName(Parameters::kSURFGpuKeypointsRatio().c_str());
00793 
00794         //SIFT detector
00795         _ui->sift_spinBox_nFeatures->setObjectName(Parameters::kSIFTNFeatures().c_str());
00796         _ui->sift_spinBox_nOctaveLayers->setObjectName(Parameters::kSIFTNOctaveLayers().c_str());
00797         _ui->sift_doubleSpinBox_contrastThr->setObjectName(Parameters::kSIFTContrastThreshold().c_str());
00798         _ui->sift_doubleSpinBox_edgeThr->setObjectName(Parameters::kSIFTEdgeThreshold().c_str());
00799         _ui->sift_doubleSpinBox_sigma->setObjectName(Parameters::kSIFTSigma().c_str());
00800 
00801         //BRIEF descriptor
00802         _ui->briefBytes->setObjectName(Parameters::kBRIEFBytes().c_str());
00803 
00804         //FAST detector
00805         _ui->fastSuppressNonMax->setObjectName(Parameters::kFASTNonmaxSuppression().c_str());
00806         _ui->fastThreshold->setObjectName(Parameters::kFASTThreshold().c_str());
00807         _ui->fastThresholdMin->setObjectName(Parameters::kFASTMinThreshold().c_str());
00808         _ui->fastThresholdMax->setObjectName(Parameters::kFASTMaxThreshold().c_str());
00809         _ui->fastGridRows->setObjectName(Parameters::kFASTGridRows().c_str());
00810         _ui->fastGridCols->setObjectName(Parameters::kFASTGridCols().c_str());
00811         _ui->fastGpu->setObjectName(Parameters::kFASTGpu().c_str());
00812         _ui->fastKeypointRatio->setObjectName(Parameters::kFASTGpuKeypointsRatio().c_str());
00813 
00814         //ORB detector
00815         _ui->doubleSpinBox_ORBScaleFactor->setObjectName(Parameters::kORBScaleFactor().c_str());
00816         _ui->spinBox_ORBNLevels->setObjectName(Parameters::kORBNLevels().c_str());
00817         _ui->spinBox_ORBEdgeThreshold->setObjectName(Parameters::kORBEdgeThreshold().c_str());
00818         _ui->spinBox_ORBFirstLevel->setObjectName(Parameters::kORBFirstLevel().c_str());
00819         _ui->spinBox_ORBWTA_K->setObjectName(Parameters::kORBWTA_K().c_str());
00820         _ui->spinBox_ORBScoreType->setObjectName(Parameters::kORBScoreType().c_str());
00821         _ui->spinBox_ORBPatchSize->setObjectName(Parameters::kORBPatchSize().c_str());
00822         _ui->checkBox_ORBGpu->setObjectName(Parameters::kORBGpu().c_str());
00823 
00824         //FREAK descriptor
00825         _ui->checkBox_FREAKOrientationNormalized->setObjectName(Parameters::kFREAKOrientationNormalized().c_str());
00826         _ui->checkBox_FREAKScaleNormalized->setObjectName(Parameters::kFREAKScaleNormalized().c_str());
00827         _ui->doubleSpinBox_FREAKPatternScale->setObjectName(Parameters::kFREAKPatternScale().c_str());
00828         _ui->spinBox_FREAKNOctaves->setObjectName(Parameters::kFREAKNOctaves().c_str());
00829 
00830         //GFTT detector
00831         _ui->doubleSpinBox_GFTT_qualityLevel->setObjectName(Parameters::kGFTTQualityLevel().c_str());
00832         _ui->doubleSpinBox_GFTT_minDistance->setObjectName(Parameters::kGFTTMinDistance().c_str());
00833         _ui->spinBox_GFTT_blockSize->setObjectName(Parameters::kGFTTBlockSize().c_str());
00834         _ui->checkBox_GFTT_useHarrisDetector->setObjectName(Parameters::kGFTTUseHarrisDetector().c_str());
00835         _ui->doubleSpinBox_GFTT_k->setObjectName(Parameters::kGFTTK().c_str());
00836 
00837         //BRISK
00838         _ui->spinBox_BRISK_thresh->setObjectName(Parameters::kBRISKThresh().c_str());
00839         _ui->spinBox_BRISK_octaves->setObjectName(Parameters::kBRISKOctaves().c_str());
00840         _ui->doubleSpinBox_BRISK_patterScale->setObjectName(Parameters::kBRISKPatternScale().c_str());
00841 
00842         //KAZE
00843         _ui->checkBox_kaze_extended->setObjectName(Parameters::kKAZEExtended().c_str());
00844         _ui->checkBox_kaze_upright->setObjectName(Parameters::kKAZEUpright().c_str());
00845         _ui->doubleSpinBox_kaze_threshold->setObjectName(Parameters::kKAZEThreshold().c_str());
00846         _ui->spinBox_kaze_octaves->setObjectName(Parameters::kKAZENOctaves().c_str());
00847         _ui->spinBox_kaze_octavelayers->setObjectName(Parameters::kKAZENOctaveLayers().c_str());
00848         _ui->spinBox_kaze_diffusivity->setObjectName(Parameters::kKAZEDiffusivity().c_str());
00849 
00850         // verifyHypotheses
00851         _ui->groupBox_vh_epipolar2->setObjectName(Parameters::kVhEpEnabled().c_str());
00852         _ui->surf_spinBox_matchCountMinAccepted->setObjectName(Parameters::kVhEpMatchCountMin().c_str());
00853         _ui->surf_doubleSpinBox_ransacParam1->setObjectName(Parameters::kVhEpRansacParam1().c_str());
00854         _ui->surf_doubleSpinBox_ransacParam2->setObjectName(Parameters::kVhEpRansacParam2().c_str());
00855 
00856         // RGB-D SLAM
00857         _ui->general_checkBox_activateRGBD->setObjectName(Parameters::kRGBDEnabled().c_str());
00858         _ui->rgdb_linearUpdate->setObjectName(Parameters::kRGBDLinearUpdate().c_str());
00859         _ui->rgdb_angularUpdate->setObjectName(Parameters::kRGBDAngularUpdate().c_str());
00860         _ui->rgdb_linearSpeedUpdate->setObjectName(Parameters::kRGBDLinearSpeedUpdate().c_str());
00861         _ui->rgdb_angularSpeedUpdate->setObjectName(Parameters::kRGBDAngularSpeedUpdate().c_str());
00862         _ui->rgbd_savedLocalizationIgnored->setObjectName(Parameters::kRGBDSavedLocalizationIgnored().c_str());
00863         _ui->rgdb_rehearsalWeightIgnoredWhileMoving->setObjectName(Parameters::kMemRehearsalWeightIgnoredWhileMoving().c_str());
00864         _ui->rgdb_newMapOdomChange->setObjectName(Parameters::kRGBDNewMapOdomChangeDistance().c_str());
00865         _ui->odomScanHistory->setObjectName(Parameters::kRGBDNeighborLinkRefining().c_str());
00866         _ui->spinBox_maxLocalLocationsRetrieved->setObjectName(Parameters::kRGBDMaxLocalRetrieved().c_str());
00867 
00868         _ui->graphOptimization_type->setObjectName(Parameters::kOptimizerStrategy().c_str());
00869         _ui->graphOptimization_iterations->setObjectName(Parameters::kOptimizerIterations().c_str());
00870         _ui->graphOptimization_covarianceIgnored->setObjectName(Parameters::kOptimizerVarianceIgnored().c_str());
00871         _ui->graphOptimization_fromGraphEnd->setObjectName(Parameters::kRGBDOptimizeFromGraphEnd().c_str());
00872         _ui->graphOptimization_maxError->setObjectName(Parameters::kRGBDOptimizeMaxError().c_str());
00873         _ui->graphOptimization_stopEpsilon->setObjectName(Parameters::kOptimizerEpsilon().c_str());
00874         _ui->graphOptimization_robust->setObjectName(Parameters::kOptimizerRobust().c_str());
00875         _ui->graphOptimization_priorsIgnored->setObjectName(Parameters::kOptimizerPriorsIgnored().c_str());
00876 
00877         _ui->comboBox_g2o_solver->setObjectName(Parameters::kg2oSolver().c_str());
00878         _ui->comboBox_g2o_optimizer->setObjectName(Parameters::kg2oOptimizer().c_str());
00879         _ui->doubleSpinBox_g2o_pixelVariance->setObjectName(Parameters::kg2oPixelVariance().c_str());
00880         _ui->doubleSpinBox_g2o_robustKernelDelta->setObjectName(Parameters::kg2oRobustKernelDelta().c_str());
00881         _ui->doubleSpinBox_g2o_baseline->setObjectName(Parameters::kg2oBaseline().c_str());
00882 
00883         _ui->comboBox_gtsam_optimizer->setObjectName(Parameters::kGTSAMOptimizer().c_str());
00884 
00885         _ui->graphPlan_goalReachedRadius->setObjectName(Parameters::kRGBDGoalReachedRadius().c_str());
00886         _ui->graphPlan_goalsSavedInUserData->setObjectName(Parameters::kRGBDGoalsSavedInUserData().c_str());
00887         _ui->graphPlan_stuckIterations->setObjectName(Parameters::kRGBDPlanStuckIterations().c_str());
00888         _ui->graphPlan_linearVelocity->setObjectName(Parameters::kRGBDPlanLinearVelocity().c_str());
00889         _ui->graphPlan_angularVelocity->setObjectName(Parameters::kRGBDPlanAngularVelocity().c_str());
00890 
00891         _ui->groupBox_localDetection_time->setObjectName(Parameters::kRGBDProximityByTime().c_str());
00892         _ui->groupBox_localDetection_space->setObjectName(Parameters::kRGBDProximityBySpace().c_str());
00893         _ui->localDetection_radius->setObjectName(Parameters::kRGBDLocalRadius().c_str());
00894         _ui->localDetection_maxDiffID->setObjectName(Parameters::kRGBDProximityMaxGraphDepth().c_str());
00895         _ui->localDetection_maxNeighbors->setObjectName(Parameters::kRGBDProximityPathMaxNeighbors().c_str());
00896         _ui->localDetection_maxPaths->setObjectName(Parameters::kRGBDProximityMaxPaths().c_str());
00897         _ui->localDetection_pathFilteringRadius->setObjectName(Parameters::kRGBDProximityPathFilteringRadius().c_str());
00898         _ui->localDetection_angle->setObjectName(Parameters::kRGBDProximityAngle().c_str());
00899         _ui->checkBox_localSpacePathOdomPosesUsed->setObjectName(Parameters::kRGBDProximityPathRawPosesUsed().c_str());
00900         _ui->rgdb_localImmunizationRatio->setObjectName(Parameters::kRGBDLocalImmunizationRatio().c_str());
00901         _ui->loopClosure_reextract->setObjectName(Parameters::kRGBDLoopClosureReextractFeatures().c_str());
00902         _ui->loopClosure_bunlde->setObjectName(Parameters::kRGBDLocalBundleOnLoopClosure().c_str());
00903         _ui->checkbox_rgbd_createOccupancyGrid->setObjectName(Parameters::kRGBDCreateOccupancyGrid().c_str());
00904 
00905         // Registration
00906         _ui->reg_repeatOnce->setObjectName(Parameters::kRegRepeatOnce().c_str());
00907         _ui->comboBox_registrationStrategy->setObjectName(Parameters::kRegStrategy().c_str());
00908         _ui->loopClosure_bowForce2D->setObjectName(Parameters::kRegForce3DoF().c_str());
00909 
00910         //RegistrationVis
00911         _ui->loopClosure_bowMinInliers->setObjectName(Parameters::kVisMinInliers().c_str());
00912         _ui->loopClosure_bowInlierDistance->setObjectName(Parameters::kVisInlierDistance().c_str());
00913         _ui->loopClosure_bowIterations->setObjectName(Parameters::kVisIterations().c_str());
00914         _ui->loopClosure_bowRefineIterations->setObjectName(Parameters::kVisRefineIterations().c_str());
00915         _ui->loopClosure_estimationType->setObjectName(Parameters::kVisEstimationType().c_str());
00916         connect(_ui->loopClosure_estimationType, SIGNAL(currentIndexChanged(int)), _ui->stackedWidget_loopClosureEstimation, SLOT(setCurrentIndex(int)));
00917         _ui->stackedWidget_loopClosureEstimation->setCurrentIndex(Parameters::defaultVisEstimationType());
00918         _ui->loopClosure_forwardEst->setObjectName(Parameters::kVisForwardEstOnly().c_str());
00919         _ui->loopClosure_bowEpipolarGeometryVar->setObjectName(Parameters::kVisEpipolarGeometryVar().c_str());
00920         _ui->loopClosure_pnpReprojError->setObjectName(Parameters::kVisPnPReprojError().c_str());
00921         _ui->loopClosure_pnpFlags->setObjectName(Parameters::kVisPnPFlags().c_str());
00922         _ui->loopClosure_pnpRefineIterations->setObjectName(Parameters::kVisPnPRefineIterations().c_str());
00923         _ui->reextract_nn->setObjectName(Parameters::kVisCorNNType().c_str());
00924         _ui->reextract_nndrRatio->setObjectName(Parameters::kVisCorNNDR().c_str());
00925         _ui->spinBox_visCorGuessWinSize->setObjectName(Parameters::kVisCorGuessWinSize().c_str());
00926         _ui->checkBox__visCorGuessMatchToProjection->setObjectName(Parameters::kVisCorGuessMatchToProjection().c_str());
00927         _ui->reextract_type->setObjectName(Parameters::kVisFeatureType().c_str());
00928         _ui->reextract_maxFeatures->setObjectName(Parameters::kVisMaxFeatures().c_str());
00929         _ui->reextract_gridrows->setObjectName(Parameters::kVisGridRows().c_str());
00930         _ui->reextract_gridcols->setObjectName(Parameters::kVisGridCols().c_str());
00931         _ui->loopClosure_bowMaxDepth->setObjectName(Parameters::kVisMaxDepth().c_str());
00932         _ui->loopClosure_bowMinDepth->setObjectName(Parameters::kVisMinDepth().c_str());
00933         _ui->checkBox_visDepthAsMask->setObjectName(Parameters::kVisDepthAsMask().c_str());
00934         _ui->loopClosure_roi->setObjectName(Parameters::kVisRoiRatios().c_str());
00935         _ui->subpix_winSize->setObjectName(Parameters::kVisSubPixWinSize().c_str());
00936         _ui->subpix_iterations->setObjectName(Parameters::kVisSubPixIterations().c_str());
00937         _ui->subpix_eps->setObjectName(Parameters::kVisSubPixEps().c_str());
00938         _ui->odom_flow_winSize_2->setObjectName(Parameters::kVisCorFlowWinSize().c_str());
00939         _ui->odom_flow_maxLevel_2->setObjectName(Parameters::kVisCorFlowMaxLevel().c_str());
00940         _ui->odom_flow_iterations_2->setObjectName(Parameters::kVisCorFlowIterations().c_str());
00941         _ui->odom_flow_eps_2->setObjectName(Parameters::kVisCorFlowEps().c_str());
00942         _ui->loopClosure_bundle->setObjectName(Parameters::kVisBundleAdjustment().c_str());
00943 
00944         //RegistrationIcp
00945         _ui->globalDetection_icpMaxTranslation->setObjectName(Parameters::kIcpMaxTranslation().c_str());
00946         _ui->globalDetection_icpMaxRotation->setObjectName(Parameters::kIcpMaxRotation().c_str());
00947         _ui->loopClosure_icpVoxelSize->setObjectName(Parameters::kIcpVoxelSize().c_str());
00948         _ui->loopClosure_icpDownsamplingStep->setObjectName(Parameters::kIcpDownsamplingStep().c_str());
00949         _ui->loopClosure_icpMaxCorrespondenceDistance->setObjectName(Parameters::kIcpMaxCorrespondenceDistance().c_str());
00950         _ui->loopClosure_icpIterations->setObjectName(Parameters::kIcpIterations().c_str());
00951         _ui->loopClosure_icpEpsilon->setObjectName(Parameters::kIcpEpsilon().c_str());
00952         _ui->loopClosure_icpRatio->setObjectName(Parameters::kIcpCorrespondenceRatio().c_str());
00953         _ui->loopClosure_icpPointToPlane->setObjectName(Parameters::kIcpPointToPlane().c_str());
00954         _ui->loopClosure_icpPointToPlaneNormals->setObjectName(Parameters::kIcpPointToPlaneK().c_str());
00955         _ui->loopClosure_icpPointToPlaneNormalsRadius->setObjectName(Parameters::kIcpPointToPlaneRadius().c_str());
00956         _ui->loopClosure_icpPointToPlaneNormalsMinComplexity->setObjectName(Parameters::kIcpPointToPlaneMinComplexity().c_str());
00957 
00958         _ui->groupBox_libpointmatcher->setObjectName(Parameters::kIcpPM().c_str());
00959         _ui->lineEdit_IcpPMConfigPath->setObjectName(Parameters::kIcpPMConfig().c_str());
00960         connect(_ui->toolButton_IcpConfigPath, SIGNAL(clicked()), this, SLOT(changeIcpPMConfigPath()));
00961         _ui->doubleSpinBox_icpPMOutlierRatio->setObjectName(Parameters::kIcpPMOutlierRatio().c_str());
00962         _ui->spinBox_icpPMMatcherKnn->setObjectName(Parameters::kIcpPMMatcherKnn().c_str());
00963         _ui->doubleSpinBox_icpPMMatcherEpsilon->setObjectName(Parameters::kIcpPMMatcherEpsilon().c_str());
00964 
00965         // Occupancy grid
00966         _ui->groupBox_grid_3d->setObjectName(Parameters::kGrid3D().c_str());
00967         _ui->checkBox_grid_groundObstacle->setObjectName(Parameters::kGridGroundIsObstacle().c_str());
00968         _ui->doubleSpinBox_grid_resolution->setObjectName(Parameters::kGridCellSize().c_str());
00969         _ui->checkBox_grid_preVoxelFiltering->setObjectName(Parameters::kGridPreVoxelFiltering().c_str());
00970         _ui->spinBox_grid_decimation->setObjectName(Parameters::kGridDepthDecimation().c_str());
00971         _ui->doubleSpinBox_grid_maxDepth->setObjectName(Parameters::kGridRangeMax().c_str());
00972         _ui->doubleSpinBox_grid_minDepth->setObjectName(Parameters::kGridRangeMin().c_str());
00973         _ui->lineEdit_grid_roi->setObjectName(Parameters::kGridDepthRoiRatios().c_str());
00974         _ui->checkBox_grid_projRayTracing->setObjectName(Parameters::kGridRayTracing().c_str());
00975         _ui->doubleSpinBox_grid_footprintLength->setObjectName(Parameters::kGridFootprintLength().c_str());
00976         _ui->doubleSpinBox_grid_footprintWidth->setObjectName(Parameters::kGridFootprintWidth().c_str());
00977         _ui->doubleSpinBox_grid_footprintHeight->setObjectName(Parameters::kGridFootprintHeight().c_str());
00978         _ui->checkBox_grid_flatObstaclesDetected->setObjectName(Parameters::kGridFlatObstacleDetected().c_str());
00979         _ui->groupBox_grid_fromDepthImage->setObjectName(Parameters::kGridFromDepth().c_str());
00980         _ui->checkBox_grid_projMapFrame->setObjectName(Parameters::kGridMapFrameProjection().c_str());
00981         _ui->doubleSpinBox_grid_maxGroundAngle->setObjectName(Parameters::kGridMaxGroundAngle().c_str());
00982         _ui->spinBox_grid_normalK->setObjectName(Parameters::kGridNormalK().c_str());
00983         _ui->doubleSpinBox_grid_maxGroundHeight->setObjectName(Parameters::kGridMaxGroundHeight().c_str());
00984         _ui->doubleSpinBox_grid_maxObstacleHeight->setObjectName(Parameters::kGridMaxObstacleHeight().c_str());
00985         _ui->doubleSpinBox_grid_clusterRadius->setObjectName(Parameters::kGridClusterRadius().c_str());
00986         _ui->spinBox_grid_minClusterSize->setObjectName(Parameters::kGridMinClusterSize().c_str());
00987         _ui->doubleSpinBox_grid_minGroundHeight->setObjectName(Parameters::kGridMinGroundHeight().c_str());
00988         _ui->spinBox_grid_noiseMinNeighbors->setObjectName(Parameters::kGridNoiseFilteringMinNeighbors().c_str());
00989         _ui->doubleSpinBox_grid_noiseRadius->setObjectName(Parameters::kGridNoiseFilteringRadius().c_str());
00990         _ui->groupBox_grid_normalsSegmentation->setObjectName(Parameters::kGridNormalsSegmentation().c_str());
00991         _ui->checkBox_grid_unknownSpaceFilled->setObjectName(Parameters::kGridScan2dUnknownSpaceFilled().c_str());
00992         _ui->spinBox_grid_scanDecimation->setObjectName(Parameters::kGridScanDecimation().c_str());
00993 
00994         _ui->checkBox_grid_fullUpdate->setObjectName(Parameters::kGridGlobalFullUpdate().c_str());
00995         _ui->doubleSpinBox_grid_updateError->setObjectName(Parameters::kGridGlobalUpdateError().c_str());
00996         _ui->doubleSpinBox_grid_minMapSize->setObjectName(Parameters::kGridGlobalMinSize().c_str());
00997         _ui->spinBox_grid_maxNodes->setObjectName(Parameters::kGridGlobalMaxNodes().c_str());
00998         _ui->doubleSpinBox_grid_footprintRadius->setObjectName(Parameters::kGridGlobalFootprintRadius().c_str());
00999         _ui->doubleSpinBox_grid_occThr->setObjectName(Parameters::kGridGlobalOccupancyThr().c_str());
01000         _ui->doubleSpinBox_grid_probHit->setObjectName(Parameters::kGridGlobalProbHit().c_str());
01001         _ui->doubleSpinBox_grid_probMiss->setObjectName(Parameters::kGridGlobalProbMiss().c_str());
01002         _ui->doubleSpinBox_grid_clampingMin->setObjectName(Parameters::kGridGlobalProbClampingMin().c_str());
01003         _ui->doubleSpinBox_grid_clampingMax->setObjectName(Parameters::kGridGlobalProbClampingMax().c_str());
01004         _ui->checkBox_grid_erode->setObjectName(Parameters::kGridGlobalEroded().c_str());
01005 
01006         //Odometry
01007         _ui->odom_strategy->setObjectName(Parameters::kOdomStrategy().c_str());
01008         connect(_ui->odom_strategy, SIGNAL(currentIndexChanged(int)), _ui->stackedWidget_odometryType, SLOT(setCurrentIndex(int)));
01009         _ui->odom_strategy->setCurrentIndex(Parameters::defaultOdomStrategy());
01010         _ui->stackedWidget_odometryType->setCurrentIndex(Parameters::defaultOdomStrategy());
01011         _ui->odom_countdown->setObjectName(Parameters::kOdomResetCountdown().c_str());
01012         _ui->odom_holonomic->setObjectName(Parameters::kOdomHolonomic().c_str());
01013         _ui->odom_fillInfoData->setObjectName(Parameters::kOdomFillInfoData().c_str());
01014         _ui->odom_dataBufferSize->setObjectName(Parameters::kOdomImageBufferSize().c_str());
01015         _ui->odom_flow_keyframeThr->setObjectName(Parameters::kOdomKeyFrameThr().c_str());
01016         _ui->odom_VisKeyFrameThr->setObjectName(Parameters::kOdomVisKeyFrameThr().c_str());
01017         _ui->odom_flow_scanKeyframeThr->setObjectName(Parameters::kOdomScanKeyFrameThr().c_str());
01018         _ui->odom_flow_guessMotion->setObjectName(Parameters::kOdomGuessMotion().c_str());
01019         _ui->odom_imageDecimation->setObjectName(Parameters::kOdomImageDecimation().c_str());
01020         _ui->odom_alignWithGround->setObjectName(Parameters::kOdomAlignWithGround().c_str());
01021 
01022         //Odometry Frame to Map
01023         _ui->odom_localHistory->setObjectName(Parameters::kOdomF2MMaxSize().c_str());
01024         _ui->spinBox_odom_f2m_maxNewFeatures->setObjectName(Parameters::kOdomF2MMaxNewFeatures().c_str());
01025         _ui->spinBox_odom_f2m_scanMaxSize->setObjectName(Parameters::kOdomF2MScanMaxSize().c_str());
01026         _ui->doubleSpinBox_odom_f2m_scanRadius->setObjectName(Parameters::kOdomF2MScanSubtractRadius().c_str());
01027         _ui->doubleSpinBox_odom_f2m_scanAngle->setObjectName(Parameters::kOdomF2MScanSubtractAngle().c_str());
01028         _ui->odom_f2m_bundleStrategy->setObjectName(Parameters::kOdomF2MBundleAdjustment().c_str());
01029         _ui->odom_f2m_bundleMaxFrames->setObjectName(Parameters::kOdomF2MBundleAdjustmentMaxFrames().c_str());
01030 
01031         //Odometry Frame To Frame
01032         _ui->comboBox_odomf2f_corType->setObjectName(Parameters::kVisCorType().c_str());
01033 
01034         //Odometry Mono
01035         _ui->doubleSpinBox_minFlow->setObjectName(Parameters::kOdomMonoInitMinFlow().c_str());
01036         _ui->doubleSpinBox_minInitTranslation->setObjectName(Parameters::kOdomMonoInitMinTranslation().c_str());
01037         _ui->doubleSpinBox_minTranslation->setObjectName(Parameters::kOdomMonoMinTranslation().c_str());
01038         _ui->doubleSpinBox_maxVariance->setObjectName(Parameters::kOdomMonoMaxVariance().c_str());
01039 
01040         //Odometry particle filter
01041         _ui->odom_filteringStrategy->setObjectName(Parameters::kOdomFilteringStrategy().c_str());
01042         _ui->stackedWidget_odometryFiltering->setCurrentIndex(_ui->odom_filteringStrategy->currentIndex());
01043         connect(_ui->odom_filteringStrategy, SIGNAL(currentIndexChanged(int)), _ui->stackedWidget_odometryFiltering, SLOT(setCurrentIndex(int)));
01044         _ui->spinBox_particleSize->setObjectName(Parameters::kOdomParticleSize().c_str());
01045         _ui->doubleSpinBox_particleNoiseT->setObjectName(Parameters::kOdomParticleNoiseT().c_str());
01046         _ui->doubleSpinBox_particleLambdaT->setObjectName(Parameters::kOdomParticleLambdaT().c_str());
01047         _ui->doubleSpinBox_particleNoiseR->setObjectName(Parameters::kOdomParticleNoiseR().c_str());
01048         _ui->doubleSpinBox_particleLambdaR->setObjectName(Parameters::kOdomParticleLambdaR().c_str());
01049 
01050         //Odometry Kalman filter
01051         _ui->doubleSpinBox_kalmanProcessNoise->setObjectName(Parameters::kOdomKalmanProcessNoise().c_str());
01052         _ui->doubleSpinBox_kalmanMeasurementNoise->setObjectName(Parameters::kOdomKalmanMeasurementNoise().c_str());
01053 
01054         //Odometry Fovis
01055         _ui->spinBox_OdomFovisFeatureWindowSize->setObjectName(Parameters::kOdomFovisFeatureWindowSize().c_str());
01056         _ui->spinBox_OdomFovisMaxPyramidLevel->setObjectName(Parameters::kOdomFovisMaxPyramidLevel().c_str());
01057         _ui->spinBox_OdomFovisMinPyramidLevel->setObjectName(Parameters::kOdomFovisMinPyramidLevel().c_str());
01058         _ui->spinBox_OdomFovisTargetPixelsPerFeature->setObjectName(Parameters::kOdomFovisTargetPixelsPerFeature().c_str());
01059         _ui->spinBox_OdomFovisFastThreshold->setObjectName(Parameters::kOdomFovisFastThreshold().c_str());
01060         _ui->checkBox_OdomFovisUseAdaptiveThreshold->setObjectName(Parameters::kOdomFovisUseAdaptiveThreshold().c_str());
01061         _ui->doubleSpinBox_OdomFovisFastThresholdAdaptiveGain->setObjectName(Parameters::kOdomFovisFastThresholdAdaptiveGain().c_str());
01062         _ui->checkBox_OdomFovisUseHomographyInitialization->setObjectName(Parameters::kOdomFovisUseHomographyInitialization().c_str());
01063 
01064         _ui->checkBox_OdomFovisUseBucketing->setObjectName(Parameters::kOdomFovisUseBucketing().c_str());
01065         _ui->spinBox_OdomFovisBucketWidth->setObjectName(Parameters::kOdomFovisBucketWidth().c_str());
01066         _ui->spinBox_OdomFovisBucketHeight->setObjectName(Parameters::kOdomFovisBucketHeight().c_str());
01067         _ui->spinBox_OdomFovisMaxKeypointsPerBucket->setObjectName(Parameters::kOdomFovisMaxKeypointsPerBucket().c_str());
01068         _ui->checkBox_OdomFovisUseImageNormalization->setObjectName(Parameters::kOdomFovisUseImageNormalization().c_str());
01069 
01070         _ui->doubleSpinBox_OdomFovisInlierMaxReprojectionError->setObjectName(Parameters::kOdomFovisInlierMaxReprojectionError().c_str());
01071         _ui->doubleSpinBox_OdomFovisCliqueInlierThreshold->setObjectName(Parameters::kOdomFovisCliqueInlierThreshold().c_str());
01072         _ui->spinBox_OdomFovisMinFeaturesForEstimate->setObjectName(Parameters::kOdomFovisMinFeaturesForEstimate().c_str());
01073         _ui->doubleSpinBox_OdomFovisMaxMeanReprojectionError->setObjectName(Parameters::kOdomFovisMaxMeanReprojectionError().c_str());
01074         _ui->checkBox_OdomFovisUseSubpixelRefinement->setObjectName(Parameters::kOdomFovisUseSubpixelRefinement().c_str());
01075         _ui->spinBox_OdomFovisFeatureSearchWindow->setObjectName(Parameters::kOdomFovisFeatureSearchWindow().c_str());
01076         _ui->checkBox_OdomFovisUpdateTargetFeaturesWithRefined->setObjectName(Parameters::kOdomFovisUpdateTargetFeaturesWithRefined().c_str());
01077 
01078         _ui->checkBox_OdomFovisStereoRequireMutualMatch->setObjectName(Parameters::kOdomFovisStereoRequireMutualMatch().c_str());
01079         _ui->doubleSpinBox_OdomFovisStereoMaxDistEpipolarLine->setObjectName(Parameters::kOdomFovisStereoMaxDistEpipolarLine().c_str());
01080         _ui->doubleSpinBox_OdomFovisStereoMaxRefinementDisplacement->setObjectName(Parameters::kOdomFovisStereoMaxRefinementDisplacement().c_str());
01081         _ui->spinBox_OdomFovisStereoMaxDisparity->setObjectName(Parameters::kOdomFovisStereoMaxDisparity().c_str());
01082 
01083         // Odometry viso2
01084         _ui->spinBox_OdomViso2RansacIters->setObjectName(Parameters::kOdomViso2RansacIters().c_str());
01085         _ui->doubleSpinBox_OdomViso2InlierThreshold->setObjectName(Parameters::kOdomViso2InlierThreshold().c_str());
01086         _ui->checkBox_OdomViso2Reweighting->setObjectName(Parameters::kOdomViso2Reweighting().c_str());
01087 
01088         _ui->spinBox_OdomViso2MatchNmsN->setObjectName(Parameters::kOdomViso2MatchNmsN().c_str());
01089         _ui->spinBox_OdomViso2MatchNmsTau->setObjectName(Parameters::kOdomViso2MatchNmsTau().c_str());
01090         _ui->spinBox_OdomViso2MatchBinsize->setObjectName(Parameters::kOdomViso2MatchBinsize().c_str());
01091         _ui->spinBox_OdomViso2MatchRadius->setObjectName(Parameters::kOdomViso2MatchRadius().c_str());
01092         _ui->spinBox_OdomViso2MatchDispTolerance->setObjectName(Parameters::kOdomViso2MatchDispTolerance().c_str());
01093         _ui->spinBox_OdomViso2MatchOutlierDispTolerance->setObjectName(Parameters::kOdomViso2MatchOutlierDispTolerance().c_str());
01094         _ui->spinBox_OdomViso2MatchOutlierFlowTolerance->setObjectName(Parameters::kOdomViso2MatchOutlierFlowTolerance().c_str());
01095         _ui->checkBox_OdomViso2MatchMultiStage->setObjectName(Parameters::kOdomViso2MatchMultiStage().c_str());
01096         _ui->checkBox_OdomViso2MatchHalfResolution->setObjectName(Parameters::kOdomViso2MatchHalfResolution().c_str());
01097         _ui->spinBox_OdomViso2MatchRefinement->setObjectName(Parameters::kOdomViso2MatchRefinement().c_str());
01098 
01099         _ui->spinBox_OdomViso2BucketMaxFeatures->setObjectName(Parameters::kOdomViso2BucketMaxFeatures().c_str());
01100         _ui->doubleSpinBox_OdomViso2BucketWidth->setObjectName(Parameters::kOdomViso2BucketWidth().c_str());
01101         _ui->doubleSpinBox_OdomViso2BucketHeight->setObjectName(Parameters::kOdomViso2BucketHeight().c_str());
01102 
01103         // Odometry ORBSLAM2
01104         _ui->lineEdit_OdomORBSLAM2VocPath->setObjectName(Parameters::kOdomORBSLAM2VocPath().c_str());
01105         connect(_ui->toolButton_OdomORBSLAM2VocPath, SIGNAL(clicked()), this, SLOT(changeOdometryORBSLAM2Vocabulary()));
01106         _ui->doubleSpinBox_OdomORBSLAM2Bf->setObjectName(Parameters::kOdomORBSLAM2Bf().c_str());
01107         _ui->doubleSpinBox_OdomORBSLAM2ThDepth->setObjectName(Parameters::kOdomORBSLAM2ThDepth().c_str());
01108         _ui->doubleSpinBox_OdomORBSLAM2Fps->setObjectName(Parameters::kOdomORBSLAM2Fps().c_str());
01109         _ui->spinBox_OdomORBSLAM2MaxFeatures->setObjectName(Parameters::kOdomORBSLAM2MaxFeatures().c_str());
01110         _ui->spinBox_OdomORBSLAM2MapSize->setObjectName(Parameters::kOdomORBSLAM2MapSize().c_str());
01111 
01112         // Odometry Okvis
01113         _ui->lineEdit_OdomOkvisPath->setObjectName(Parameters::kOdomOKVISConfigPath().c_str());
01114         connect(_ui->toolButton_OdomOkvisPath, SIGNAL(clicked()), this, SLOT(changeOdometryOKVISConfigPath()));
01115 
01116         // Odometry LOAM
01117         _ui->odom_loam_sensor->setObjectName(Parameters::kOdomLOAMSensor().c_str());
01118         _ui->odom_loam_scan_period->setObjectName(Parameters::kOdomLOAMScanPeriod().c_str());
01119         _ui->odom_loam_linvar->setObjectName(Parameters::kOdomLOAMLinVar().c_str());
01120         _ui->odom_loam_angvar->setObjectName(Parameters::kOdomLOAMAngVar().c_str());
01121         _ui->odom_loam_localMapping->setObjectName(Parameters::kOdomLOAMLocalMapping().c_str());
01122 
01123         // Odometry MSCKF_VIO
01124         _ui->OdomMSCKFGridRow->setObjectName(Parameters::kOdomMSCKFGridRow().c_str());
01125         _ui->OdomMSCKFGridCol->setObjectName(Parameters::kOdomMSCKFGridCol().c_str());
01126         _ui->OdomMSCKFGridMinFeatureNum->setObjectName(Parameters::kOdomMSCKFGridMinFeatureNum().c_str());
01127         _ui->OdomMSCKFGridMaxFeatureNum->setObjectName(Parameters::kOdomMSCKFGridMaxFeatureNum().c_str());
01128         _ui->OdomMSCKFPyramidLevels->setObjectName(Parameters::kOdomMSCKFPyramidLevels().c_str());
01129         _ui->OdomMSCKFPatchSize->setObjectName(Parameters::kOdomMSCKFPatchSize().c_str());
01130         _ui->OdomMSCKFFastThreshold->setObjectName(Parameters::kOdomMSCKFFastThreshold().c_str());
01131         _ui->OdomMSCKFMaxIteration->setObjectName(Parameters::kOdomMSCKFMaxIteration().c_str());
01132         _ui->OdomMSCKFMaxCamStateSize->setObjectName(Parameters::kOdomMSCKFMaxCamStateSize().c_str());
01133         _ui->OdomMSCKFTrackPrecision->setObjectName(Parameters::kOdomMSCKFTrackPrecision().c_str());
01134         _ui->OdomMSCKFRansacThreshold->setObjectName(Parameters::kOdomMSCKFRansacThreshold().c_str());
01135         _ui->OdomMSCKFStereoThreshold->setObjectName(Parameters::kOdomMSCKFStereoThreshold().c_str());
01136         _ui->OdomMSCKFPositionStdThreshold->setObjectName(Parameters::kOdomMSCKFPositionStdThreshold().c_str());
01137         _ui->OdomMSCKFRotationThreshold->setObjectName(Parameters::kOdomMSCKFRotationThreshold().c_str());
01138         _ui->OdomMSCKFTranslationThreshold->setObjectName(Parameters::kOdomMSCKFTranslationThreshold().c_str());
01139         _ui->OdomMSCKFTrackingRateThreshold->setObjectName(Parameters::kOdomMSCKFTrackingRateThreshold().c_str());
01140         _ui->OdomMSCKFOptTranslationThreshold->setObjectName(Parameters::kOdomMSCKFOptTranslationThreshold().c_str());
01141         _ui->OdomMSCKFNoiseGyro->setObjectName(Parameters::kOdomMSCKFNoiseGyro().c_str());
01142         _ui->OdomMSCKFNoiseAcc->setObjectName(Parameters::kOdomMSCKFNoiseAcc().c_str());
01143         _ui->OdomMSCKFNoiseGyroBias->setObjectName(Parameters::kOdomMSCKFNoiseGyroBias().c_str());
01144         _ui->OdomMSCKFNoiseAccBias->setObjectName(Parameters::kOdomMSCKFNoiseAccBias().c_str());
01145         _ui->OdomMSCKFNoiseFeature->setObjectName(Parameters::kOdomMSCKFNoiseFeature().c_str());
01146         _ui->OdomMSCKFInitCovVel->setObjectName(Parameters::kOdomMSCKFInitCovVel().c_str());
01147         _ui->OdomMSCKFInitCovGyroBias->setObjectName(Parameters::kOdomMSCKFInitCovGyroBias().c_str());
01148         _ui->OdomMSCKFInitCovAccBias->setObjectName(Parameters::kOdomMSCKFInitCovAccBias().c_str());
01149         _ui->OdomMSCKFInitCovExRot->setObjectName(Parameters::kOdomMSCKFInitCovExRot().c_str());
01150         _ui->OdomMSCKFInitCovExTrans->setObjectName(Parameters::kOdomMSCKFInitCovExTrans().c_str());
01151 
01152         //Stereo
01153         _ui->stereo_winWidth->setObjectName(Parameters::kStereoWinWidth().c_str());
01154         _ui->stereo_winHeight->setObjectName(Parameters::kStereoWinHeight().c_str());
01155         _ui->stereo_maxLevel->setObjectName(Parameters::kStereoMaxLevel().c_str());
01156         _ui->stereo_iterations->setObjectName(Parameters::kStereoIterations().c_str());
01157         _ui->stereo_minDisparity->setObjectName(Parameters::kStereoMinDisparity().c_str());
01158         _ui->stereo_maxDisparity->setObjectName(Parameters::kStereoMaxDisparity().c_str());
01159         _ui->stereo_ssd->setObjectName(Parameters::kStereoSSD().c_str());
01160         _ui->stereo_flow_eps->setObjectName(Parameters::kStereoEps().c_str());
01161         _ui->stereo_opticalFlow->setObjectName(Parameters::kStereoOpticalFlow().c_str());
01162 
01163         //StereoBM
01164         _ui->stereobm_blockSize->setObjectName(Parameters::kStereoBMBlockSize().c_str());
01165         _ui->stereobm_minDisparity->setObjectName(Parameters::kStereoBMMinDisparity().c_str());
01166         _ui->stereobm_numDisparities->setObjectName(Parameters::kStereoBMNumDisparities().c_str());
01167         _ui->stereobm_preFilterCap->setObjectName(Parameters::kStereoBMPreFilterCap().c_str());
01168         _ui->stereobm_preFilterSize->setObjectName(Parameters::kStereoBMPreFilterSize().c_str());
01169         _ui->stereobm_speckleRange->setObjectName(Parameters::kStereoBMSpeckleRange().c_str());
01170         _ui->stereobm_speckleWinSize->setObjectName(Parameters::kStereoBMSpeckleWindowSize().c_str());
01171         _ui->stereobm_tetureThreshold->setObjectName(Parameters::kStereoBMTextureThreshold().c_str());
01172         _ui->stereobm_uniquessRatio->setObjectName(Parameters::kStereoBMUniquenessRatio().c_str());
01173 
01174         // reset default settings for the gui
01175         resetSettings(_ui->groupBox_generalSettingsGui0);
01176         resetSettings(_ui->groupBox_cloudRendering1);
01177         resetSettings(_ui->groupBox_filtering2);
01178         resetSettings(_ui->groupBox_gridMap2);
01179         resetSettings(_ui->groupBox_logging1);
01180         resetSettings(_ui->groupBox_source0);
01181 
01182         setupSignals();
01183         // custom signals
01184         connect(_ui->doubleSpinBox_kp_roi0, SIGNAL(valueChanged(double)), this, SLOT(updateKpROI()));
01185         connect(_ui->doubleSpinBox_kp_roi1, SIGNAL(valueChanged(double)), this, SLOT(updateKpROI()));
01186         connect(_ui->doubleSpinBox_kp_roi2, SIGNAL(valueChanged(double)), this, SLOT(updateKpROI()));
01187         connect(_ui->doubleSpinBox_kp_roi3, SIGNAL(valueChanged(double)), this, SLOT(updateKpROI()));
01188         connect(_ui->checkBox_useOdomFeatures, SIGNAL(toggled(bool)), this, SLOT(useOdomFeatures()));
01189 
01190         //Create a model from the stacked widgets
01191         // This will add all parameters to the parameters Map
01192         _ui->stackedWidget->setCurrentIndex(0);
01193         this->setupTreeView();
01194 
01195         _obsoletePanels = kPanelAll;
01196 }
01197 
01198 PreferencesDialog::~PreferencesDialog() {
01199         // remove tmp ini file
01200         QFile::remove(getTmpIniFilePath());
01201         delete _ui;
01202 }
01203 
01204 void PreferencesDialog::init()
01205 {
01206         UDEBUG("");
01207         //First set all default values
01208         const ParametersMap & defaults = Parameters::getDefaultParameters();
01209         for(ParametersMap::const_iterator iter=defaults.begin(); iter!=defaults.end(); ++iter)
01210         {
01211                 this->setParameter(iter->first, iter->second);
01212         }
01213 
01214         this->readSettings();
01215         this->writeSettings(getTmpIniFilePath());
01216 
01217         _initialized = true;
01218 }
01219 
01220 void PreferencesDialog::setCurrentPanelToSource()
01221 {
01222         QList<QGroupBox*> boxes = this->getGroupBoxes();
01223         for(int i =0;i<boxes.size();++i)
01224         {
01225                 if(boxes[i] == _ui->groupBox_source0)
01226                 {
01227                         _ui->stackedWidget->setCurrentIndex(i);
01228                         _ui->treeView->setCurrentIndex(_indexModel->index(i-2, 0));
01229                         break;
01230                 }
01231         }
01232 }
01233 
01234 void PreferencesDialog::saveSettings()
01235 {
01236         writeSettings();
01237 }
01238 
01239 void PreferencesDialog::setupTreeView()
01240 {
01241         if(_indexModel)
01242         {
01243                 _ui->treeView->setModel(0);
01244                 delete _indexModel;
01245         }
01246         _indexModel = new QStandardItemModel(this);
01247         // Parse the model
01248         QList<QGroupBox*> boxes = this->getGroupBoxes();
01249         if(_ui->radioButton_basic->isChecked())
01250         {
01251                 boxes = boxes.mid(0,7);
01252         }
01253         else // Advanced
01254         {
01255                 boxes.removeAt(6);
01256         }
01257 
01258         QStandardItem * parentItem = _indexModel->invisibleRootItem();
01259         int index = 0;
01260         this->parseModel(boxes, parentItem, 0, index); // recursive method
01261         if(_ui->radioButton_advanced->isChecked() && index != _ui->stackedWidget->count()-1)
01262         {
01263                 ULOGGER_ERROR("The tree model is not the same size of the stacked widgets...%d vs %d advanced stacks", index, _ui->stackedWidget->count()-1);
01264         }
01265         int currentIndex = _ui->stackedWidget->currentIndex();
01266         if(_ui->radioButton_basic->isChecked())
01267         {
01268                 if(currentIndex >= 6)
01269                 {
01270                         _ui->stackedWidget->setCurrentIndex(6);
01271                         currentIndex = 6;
01272                 }
01273         }
01274         else // Advanced
01275         {
01276                 if(currentIndex == 6)
01277                 {
01278                         _ui->stackedWidget->setCurrentIndex(7);
01279                 }
01280         }
01281         _ui->treeView->setModel(_indexModel);
01282         _ui->treeView->expandToDepth(1);
01283 
01284         // should be after setModel()
01285         connect(_ui->treeView->selectionModel(), SIGNAL(currentChanged(const QModelIndex &, const QModelIndex &)), this, SLOT(clicked(const QModelIndex &, const QModelIndex &)));
01286 }
01287 
01288 // recursive...
01289 bool PreferencesDialog::parseModel(QList<QGroupBox*> & boxes, QStandardItem * parentItem, int currentLevel, int & absoluteIndex)
01290 {
01291         if(parentItem == 0)
01292         {
01293                 ULOGGER_ERROR("Parent item is null !");
01294                 return false;
01295         }
01296 
01297         QStandardItem * currentItem = 0;
01298         while(absoluteIndex < boxes.size())
01299         {
01300                 QString objectName = boxes.at(absoluteIndex)->objectName();
01301                 QString title = boxes.at(absoluteIndex)->title();
01302                 bool ok = false;
01303                 int lvl = QString(objectName.at(objectName.size()-1)).toInt(&ok);
01304                 if(!ok)
01305                 {
01306                         ULOGGER_ERROR("Error while parsing the first number of the QGroupBox title (%s), the first character must be the number in the hierarchy", title.toStdString().c_str());
01307                         return false;
01308                 }
01309 
01310 
01311                 if(lvl == currentLevel)
01312                 {
01313                         QStandardItem * item = new QStandardItem(title);
01314                         item->setData(absoluteIndex);
01315                         currentItem = item;
01316                         //ULOGGER_DEBUG("PreferencesDialog::parseModel() lvl(%d) Added %s", currentLevel, title.toStdString().c_str());
01317                         parentItem->appendRow(item);
01318                         ++absoluteIndex;
01319                 }
01320                 else if(lvl > currentLevel)
01321                 {
01322                         if(lvl>currentLevel+1)
01323                         {
01324                                 ULOGGER_ERROR("Intermediary lvl doesn't exist, lvl %d to %d, indexes %d and %d", currentLevel, lvl, absoluteIndex-1, absoluteIndex);
01325                                 return false;
01326                         }
01327                         else
01328                         {
01329                                 parseModel(boxes, currentItem, currentLevel+1, absoluteIndex); // recursive
01330                         }
01331                 }
01332                 else
01333                 {
01334                         return false;
01335                 }
01336         }
01337         return true;
01338 }
01339 
01340 void PreferencesDialog::setupSignals()
01341 {
01342         const rtabmap::ParametersMap & parameters = Parameters::getDefaultParameters();
01343         for(rtabmap::ParametersMap::const_iterator iter=parameters.begin(); iter!=parameters.end(); ++iter)
01344         {
01345                 QWidget * obj = _ui->stackedWidget->findChild<QWidget*>((*iter).first.c_str());
01346                 if(obj)
01347                 {
01348                         // set tooltip as the parameter name
01349                         obj->setToolTip(tr("%1 (Default=\"%2\")").arg(iter->first.c_str()).arg(iter->second.c_str()));
01350 
01351                         QSpinBox * spin = qobject_cast<QSpinBox *>(obj);
01352                         QDoubleSpinBox * doubleSpin = qobject_cast<QDoubleSpinBox *>(obj);
01353                         QComboBox * combo = qobject_cast<QComboBox *>(obj);
01354                         QCheckBox * check = qobject_cast<QCheckBox *>(obj);
01355                         QRadioButton * radio = qobject_cast<QRadioButton *>(obj);
01356                         QLineEdit * lineEdit = qobject_cast<QLineEdit *>(obj);
01357                         QGroupBox * groupBox = qobject_cast<QGroupBox *>(obj);
01358                         if(spin)
01359                         {
01360                                 connect(spin, SIGNAL(valueChanged(int)), this, SLOT(addParameter(int)));
01361                         }
01362                         else if(doubleSpin)
01363                         {
01364                                 connect(doubleSpin, SIGNAL(valueChanged(double)), this, SLOT(addParameter(double)));
01365                         }
01366                         else if(combo)
01367                         {
01368                                 connect(combo, SIGNAL(currentIndexChanged(int)), this, SLOT(addParameter(int)));
01369                         }
01370                         else if(check)
01371                         {
01372                                 connect(check, SIGNAL(toggled(bool)), this, SLOT(addParameter(bool)));
01373                         }
01374                         else if(radio)
01375                         {
01376                                 connect(radio, SIGNAL(toggled(bool)), this, SLOT(addParameter(bool)));
01377                         }
01378                         else if(lineEdit)
01379                         {
01380                                 connect(lineEdit, SIGNAL(textChanged(const QString &)), this, SLOT(addParameter(const QString &)));
01381                         }
01382                         else if(groupBox)
01383                         {
01384                                 connect(groupBox, SIGNAL(toggled(bool)), this, SLOT(addParameter(bool)));
01385                         }
01386                         else
01387                         {
01388                                 ULOGGER_WARN("QWidget called %s can't be cast to a supported widget", (*iter).first.c_str());
01389                         }
01390                 }
01391                 else
01392                 {
01393                         ULOGGER_WARN("Can't find the related QWidget for parameter %s", (*iter).first.c_str());
01394                 }
01395         }
01396 }
01397 
01398 void PreferencesDialog::clicked(const QModelIndex & current, const QModelIndex & previous)
01399  {
01400         QStandardItem * item = _indexModel->itemFromIndex(current);
01401         if(item && item->isEnabled())
01402         {
01403                 int index = item->data().toInt();
01404                 if(_ui->radioButton_advanced->isChecked() && index >= 6)
01405                 {
01406                         ++index;
01407                 }
01408                 _ui->stackedWidget->setCurrentIndex(index);
01409                 _ui->scrollArea->horizontalScrollBar()->setValue(0);
01410                 _ui->scrollArea->verticalScrollBar()->setValue(0);
01411         }
01412  }
01413 
01414 void PreferencesDialog::closeEvent(QCloseEvent *event)
01415 {
01416         UDEBUG("");
01417         _modifiedParameters.clear();
01418         _obsoletePanels = kPanelDummy;
01419         this->readGuiSettings(getTmpIniFilePath());
01420         this->readCameraSettings(getTmpIniFilePath());
01421         event->accept();
01422 }
01423 
01424 void PreferencesDialog::closeDialog ( QAbstractButton * button )
01425 {
01426         UDEBUG("");
01427 
01428         QDialogButtonBox::ButtonRole role = _ui->buttonBox_global->buttonRole(button);
01429         switch(role)
01430         {
01431         case QDialogButtonBox::RejectRole:
01432                 _modifiedParameters.clear();
01433                 _obsoletePanels = kPanelDummy;
01434                 this->readGuiSettings(getTmpIniFilePath());
01435                 this->readCameraSettings(getTmpIniFilePath());
01436                 this->reject();
01437                 break;
01438 
01439         case QDialogButtonBox::AcceptRole:
01440                 updateBasicParameter();// make that changes without editing finished signal are updated.
01441                 if((_obsoletePanels & kPanelAll) || _modifiedParameters.size())
01442                 {
01443                         if(validateForm())
01444                         {
01445                                 writeSettings(getTmpIniFilePath());
01446                                 this->accept();
01447                         }
01448                 }
01449                 else
01450                 {
01451                         this->accept();
01452                 }
01453                 break;
01454 
01455         default:
01456                 break;
01457         }
01458 }
01459 
01460 void PreferencesDialog::resetApply ( QAbstractButton * button )
01461 {
01462         QDialogButtonBox::ButtonRole role = _ui->buttonBox_local->buttonRole(button);
01463         switch(role)
01464         {
01465         case QDialogButtonBox::ApplyRole:
01466                 updateBasicParameter();// make that changes without editing finished signal are updated.
01467                 if(validateForm())
01468                 {
01469                         writeSettings(getTmpIniFilePath());
01470                 }
01471                 break;
01472 
01473         case QDialogButtonBox::ResetRole:
01474                 resetSettings(_ui->stackedWidget->currentIndex());
01475                 break;
01476 
01477         default:
01478                 break;
01479         }
01480 }
01481 
01482 void PreferencesDialog::resetSettings(QGroupBox * groupBox)
01483 {
01484         if(groupBox->objectName() == _ui->groupBox_generalSettingsGui0->objectName())
01485         {
01486                 _ui->general_checkBox_imagesKept->setChecked(true);
01487                 _ui->general_checkBox_cloudsKept->setChecked(true);
01488                 _ui->checkBox_beep->setChecked(false);
01489                 _ui->checkBox_stamps->setChecked(true);
01490                 _ui->checkBox_cacheStatistics->setChecked(true);
01491                 _ui->checkBox_notifyWhenNewGlobalPathIsReceived->setChecked(false);
01492                 _ui->checkBox_verticalLayoutUsed->setChecked(true);
01493                 _ui->checkBox_imageRejectedShown->setChecked(true);
01494                 _ui->checkBox_imageHighestHypShown->setChecked(false);
01495                 _ui->spinBox_odomQualityWarnThr->setValue(50);
01496                 _ui->checkBox_odom_onlyInliersShown->setChecked(false);
01497                 _ui->radioButton_posteriorGraphView->setChecked(true);
01498                 _ui->radioButton_wordsGraphView->setChecked(false);
01499                 _ui->radioButton_localizationsGraphView->setChecked(false);
01500                 _ui->radioButton_nochangeGraphView->setChecked(false);
01501                 _ui->checkbox_odomDisabled->setChecked(false);
01502                 _ui->checkbox_groundTruthAlign->setChecked(true);
01503         }
01504         else if(groupBox->objectName() == _ui->groupBox_cloudRendering1->objectName())
01505         {
01506                 for(int i=0; i<2; ++i)
01507                 {
01508                         _3dRenderingShowClouds[i]->setChecked(true);
01509                         _3dRenderingDecimation[i]->setValue(4);
01510                         _3dRenderingMaxDepth[i]->setValue(0.0);
01511                         _3dRenderingMinDepth[i]->setValue(0.0);
01512                         _3dRenderingRoiRatios[i]->setText("0.0 0.0 0.0 0.0");
01513                         _3dRenderingShowScans[i]->setChecked(true);
01514                         _3dRenderingShowFeatures[i]->setChecked(i==0?false:true);
01515                         _3dRenderingShowFrustums[i]->setChecked(false);
01516 
01517                         _3dRenderingDownsamplingScan[i]->setValue(1);
01518                         _3dRenderingMaxRange[i]->setValue(0.0);
01519                         _3dRenderingMinRange[i]->setValue(0.0);
01520                         _3dRenderingVoxelSizeScan[i]->setValue(0.0);
01521                         _3dRenderingColorScheme[i]->setValue(0);
01522                         _3dRenderingOpacity[i]->setValue(i==0?1.0:0.75);
01523                         _3dRenderingPtSize[i]->setValue(2);
01524                         _3dRenderingColorSchemeScan[i]->setValue(0);
01525                         _3dRenderingOpacityScan[i]->setValue(i==0?1.0:0.5);
01526                         _3dRenderingPtSizeScan[i]->setValue(2);
01527                         _3dRenderingPtSizeFeatures[i]->setValue(3);
01528                 }
01529                 _ui->doubleSpinBox_voxel->setValue(0);
01530                 _ui->doubleSpinBox_noiseRadius->setValue(0);
01531                 _ui->spinBox_noiseMinNeighbors->setValue(5);
01532 
01533                 _ui->doubleSpinBox_ceilingFilterHeight->setValue(0);
01534                 _ui->doubleSpinBox_floorFilterHeight->setValue(0);
01535                 _ui->spinBox_normalKSearch->setValue(10);
01536                 _ui->doubleSpinBox_normalRadiusSearch->setValue(0.0);
01537 
01538                 _ui->doubleSpinBox_ceilingFilterHeight_scan->setValue(0);
01539                 _ui->doubleSpinBox_floorFilterHeight_scan->setValue(0);
01540                 _ui->spinBox_normalKSearch_scan->setValue(0);
01541                 _ui->doubleSpinBox_normalRadiusSearch_scan->setValue(0.0);
01542 
01543                 _ui->checkBox_showGraphs->setChecked(true);
01544                 _ui->checkBox_showLabels->setChecked(false);
01545 
01546                 _ui->doubleSpinBox_mesh_angleTolerance->setValue(15.0);
01547                 _ui->groupBox_organized->setChecked(false);
01548 #if PCL_VERSION_COMPARE(>=, 1, 7, 2)
01549                 _ui->checkBox_mesh_quad->setChecked(true);
01550 #else
01551                 _ui->checkBox_mesh_quad->setChecked(false);
01552 #endif
01553                 _ui->checkBox_mesh_texture->setChecked(false);
01554                 _ui->spinBox_mesh_triangleSize->setValue(2);
01555         }
01556         else if(groupBox->objectName() == _ui->groupBox_filtering2->objectName())
01557         {
01558                 _ui->radioButton_noFiltering->setChecked(true);
01559                 _ui->radioButton_nodeFiltering->setChecked(false);
01560                 _ui->radioButton_subtractFiltering->setChecked(false);
01561                 _ui->doubleSpinBox_cloudFilterRadius->setValue(0.1);
01562                 _ui->doubleSpinBox_cloudFilterAngle->setValue(30);
01563                 _ui->spinBox_subtractFilteringMinPts->setValue(5);
01564                 _ui->doubleSpinBox_subtractFilteringRadius->setValue(0.02);
01565                 _ui->doubleSpinBox_subtractFilteringAngle->setValue(0);
01566         }
01567         else if(groupBox->objectName() == _ui->groupBox_gridMap2->objectName())
01568         {
01569                 _ui->checkBox_map_shown->setChecked(false);
01570                 _ui->doubleSpinBox_map_opacity->setValue(0.75);
01571 
01572                 _ui->groupBox_octomap->setChecked(false);
01573                 _ui->spinBox_octomap_treeDepth->setValue(16);
01574                 _ui->checkBox_octomap_2dgrid->setChecked(true);
01575                 _ui->checkBox_octomap_show3dMap->setChecked(true);
01576                 _ui->comboBox_octomap_renderingType->setCurrentIndex(0);
01577                 _ui->spinBox_octomap_pointSize->setValue(5);
01578         }
01579         else if(groupBox->objectName() == _ui->groupBox_logging1->objectName())
01580         {
01581                 _ui->comboBox_loggerLevel->setCurrentIndex(2);
01582                 _ui->comboBox_loggerEventLevel->setCurrentIndex(3);
01583                 _ui->comboBox_loggerPauseLevel->setCurrentIndex(3);
01584                 _ui->checkBox_logger_printTime->setChecked(true);
01585                 _ui->checkBox_logger_printThreadId->setChecked(false);
01586                 _ui->comboBox_loggerType->setCurrentIndex(1);
01587                 for(int i=0; i<_ui->comboBox_loggerFilter->count(); ++i)
01588                 {
01589                         _ui->comboBox_loggerFilter->setItemChecked(i, false);
01590                 }
01591         }
01592         else if(groupBox->objectName() == _ui->groupBox_source0->objectName())
01593         {
01594                 _ui->general_doubleSpinBox_imgRate->setValue(0.0);
01595                 _ui->source_mirroring->setChecked(false);
01596                 _ui->lineEdit_calibrationFile->clear();
01597                 _ui->comboBox_sourceType->setCurrentIndex(kSrcRGBD);
01598                 _ui->lineEdit_sourceDevice->setText("");
01599                 _ui->lineEdit_sourceLocalTransform->setText("0 0 1 -1 0 0 0 -1 0");
01600 
01601                 _ui->source_comboBox_image_type->setCurrentIndex(kSrcUsbDevice-kSrcUsbDevice);
01602                 _ui->source_images_spinBox_startPos->setValue(0);
01603                 _ui->checkBox_rgb_rectify->setChecked(false);
01604                 _ui->comboBox_cameraImages_bayerMode->setCurrentIndex(0);
01605 
01606                 _ui->source_checkBox_ignoreOdometry->setChecked(false);
01607                 _ui->source_checkBox_ignoreGoalDelay->setChecked(true);
01608                 _ui->source_checkBox_ignoreGoals->setChecked(true);
01609                 _ui->source_spinBox_databaseStartPos->setValue(0);
01610                 _ui->source_spinBox_database_cameraIndex->setValue(-1);
01611                 _ui->source_checkBox_useDbStamps->setChecked(true);
01612 
01613 #ifdef _WIN32
01614                 _ui->comboBox_cameraRGBD->setCurrentIndex(kSrcOpenNI2-kSrcRGBD); // openni2
01615 #else
01616                 if(CameraFreenect::available())
01617                 {
01618                         _ui->comboBox_cameraRGBD->setCurrentIndex(kSrcFreenect-kSrcRGBD); // freenect
01619                 }
01620                 else if(CameraOpenNI2::available())
01621                 {
01622                         _ui->comboBox_cameraRGBD->setCurrentIndex(kSrcOpenNI2-kSrcRGBD); // openni2
01623                 }
01624                 else
01625                 {
01626                         _ui->comboBox_cameraRGBD->setCurrentIndex(kSrcOpenNI_PCL-kSrcRGBD); // openni-pcl
01627                 }
01628 #endif
01629                 if(CameraStereoDC1394::available())
01630                 {
01631                         _ui->comboBox_cameraStereo->setCurrentIndex(kSrcDC1394-kSrcStereo); // dc1394
01632                 }
01633                 else if(CameraStereoFlyCapture2::available())
01634                 {
01635                         _ui->comboBox_cameraStereo->setCurrentIndex(kSrcFlyCapture2-kSrcStereo); // flycapture
01636                 }
01637                 else
01638                 {
01639                         _ui->comboBox_cameraStereo->setCurrentIndex(kSrcStereoImages-kSrcStereo); // stereo images
01640                 }
01641 
01642                 _ui->checkbox_rgbd_colorOnly->setChecked(false);
01643                 _ui->spinBox_source_imageDecimation->setValue(1);
01644                 _ui->checkbox_stereo_depthGenerated->setChecked(false);
01645                 _ui->checkBox_stereo_exposureCompensation->setChecked(false);
01646                 _ui->openni2_autoWhiteBalance->setChecked(true);
01647                 _ui->openni2_autoExposure->setChecked(true);
01648                 _ui->openni2_exposure->setValue(0);
01649                 _ui->openni2_gain->setValue(100);
01650                 _ui->openni2_mirroring->setChecked(false);
01651                 _ui->openni2_stampsIdsUsed->setChecked(false);
01652                 _ui->openni2_hshift->setValue(0);
01653                 _ui->openni2_vshift->setValue(0);
01654                 _ui->comboBox_freenect2Format->setCurrentIndex(1);
01655                 _ui->doubleSpinBox_freenect2MinDepth->setValue(0.3);
01656                 _ui->doubleSpinBox_freenect2MaxDepth->setValue(12.0);
01657                 _ui->checkBox_freenect2BilateralFiltering->setChecked(true);
01658                 _ui->checkBox_freenect2EdgeAwareFiltering->setChecked(true);
01659                 _ui->checkBox_freenect2NoiseFiltering->setChecked(true);
01660                 _ui->lineEdit_freenect2Pipeline->setText("");
01661                 _ui->comboBox_k4w2Format->setCurrentIndex(1);
01662                 _ui->comboBox_realsensePresetRGB->setCurrentIndex(0);
01663                 _ui->comboBox_realsensePresetDepth->setCurrentIndex(2);
01664                 _ui->checkbox_realsenseOdom->setChecked(false);
01665                 _ui->checkbox_realsenseDepthScaledToRGBSize->setChecked(false);
01666                 _ui->comboBox_realsenseRGBSource->setCurrentIndex(0);
01667                 _ui->checkbox_rs2_emitter->setChecked(true);
01668                 _ui->checkbox_rs2_irDepth->setChecked(false);
01669                 _ui->lineEdit_openniOniPath->clear();
01670                 _ui->lineEdit_openni2OniPath->clear();
01671                 _ui->lineEdit_cameraRGBDImages_path_rgb->setText("");
01672                 _ui->lineEdit_cameraRGBDImages_path_depth->setText("");
01673                 _ui->doubleSpinBox_cameraRGBDImages_scale->setValue(1.0);
01674                 _ui->spinBox_cameraRGBDImages_startIndex->setValue(0);
01675                 _ui->lineEdit_source_distortionModel->setText("");
01676                 _ui->groupBox_bilateral->setChecked(false);
01677                 _ui->doubleSpinBox_bilateral_sigmaS->setValue(10.0);
01678                 _ui->doubleSpinBox_bilateral_sigmaR->setValue(0.1);
01679 
01680                 _ui->source_comboBox_image_type->setCurrentIndex(kSrcDC1394-kSrcDC1394);
01681                 _ui->lineEdit_cameraStereoImages_path_left->setText("");
01682                 _ui->lineEdit_cameraStereoImages_path_right->setText("");
01683                 _ui->checkBox_stereo_rectify->setChecked(false);
01684                 _ui->spinBox_cameraStereoImages_startIndex->setValue(0);
01685                 _ui->lineEdit_cameraStereoVideo_path->setText("");
01686                 _ui->lineEdit_cameraStereoVideo_path_2->setText("");
01687                 _ui->spinBox_stereo_right_device->setValue(-1);
01688                 _ui->comboBox_stereoZed_resolution->setCurrentIndex(2);
01689                 _ui->comboBox_stereoZed_quality->setCurrentIndex(1);
01690                 _ui->checkbox_stereoZed_selfCalibration->setChecked(true);
01691                 _ui->comboBox_stereoZed_sensingMode->setCurrentIndex(0);
01692                 _ui->spinBox_stereoZed_confidenceThr->setValue(100);
01693                 _ui->checkbox_stereoZed_odom->setChecked(false);
01694                 _ui->lineEdit_zedSvoPath->clear();
01695 
01696                 _ui->checkBox_cameraImages_timestamps->setChecked(false);
01697                 _ui->checkBox_cameraImages_syncTimeStamps->setChecked(true);
01698                 _ui->lineEdit_cameraImages_timestamps->setText("");
01699                 _ui->lineEdit_cameraImages_path_scans->setText("");
01700                 _ui->lineEdit_cameraImages_laser_transform->setText("0 0 0 0 0 0");
01701                 _ui->spinBox_cameraImages_max_scan_pts->setValue(0);
01702                 _ui->spinBox_cameraImages_scanDownsampleStep->setValue(1);
01703                 _ui->doubleSpinBox_cameraImages_scanVoxelSize->setValue(0.0f);
01704                 _ui->lineEdit_cameraImages_odom->setText("");
01705                 _ui->comboBox_cameraImages_odomFormat->setCurrentIndex(0);
01706                 _ui->lineEdit_cameraImages_gt->setText("");
01707                 _ui->comboBox_cameraImages_gtFormat->setCurrentIndex(0);
01708                 _ui->doubleSpinBox_maxPoseTimeDiff->setValue(0.02);
01709                 _ui->lineEdit_cameraImages_path_imu->setText("");
01710                 _ui->lineEdit_cameraImages_imu_transform->setText("0 0 1 0 -1 0 1 0 0");
01711                 _ui->spinBox_cameraImages_max_imu_rate->setValue(0);
01712 
01713                 _ui->groupBox_scanFromDepth->setChecked(false);
01714                 _ui->spinBox_cameraScanFromDepth_decimation->setValue(8);
01715                 _ui->doubleSpinBox_cameraSCanFromDepth_maxDepth->setValue(4.0);
01716                 _ui->doubleSpinBox_cameraImages_scanVoxelSize->setValue(0.025f);
01717                 _ui->spinBox_cameraImages_scanNormalsK->setValue(20);
01718                 _ui->doubleSpinBox_cameraImages_scanNormalsRadius->setValue(0.0);
01719                 _ui->checkBox_cameraImages_scanForceGroundNormalsUp->setChecked(false);
01720 
01721                 _ui->groupBox_depthFromScan->setChecked(false);
01722                 _ui->groupBox_depthFromScan_fillHoles->setChecked(true);
01723                 _ui->radioButton_depthFromScan_vertical->setChecked(true);
01724                 _ui->radioButton_depthFromScan_horizontal->setChecked(false);
01725                 _ui->checkBox_depthFromScan_fillBorders->setChecked(false);
01726         }
01727         else if(groupBox->objectName() == _ui->groupBox_rtabmap_basic0->objectName())
01728         {
01729                 _ui->general_doubleSpinBox_timeThr_2->setValue(Parameters::defaultRtabmapTimeThr());
01730                 _ui->general_doubleSpinBox_hardThr_2->setValue(Parameters::defaultRtabmapLoopThr());
01731                 _ui->doubleSpinBox_similarityThreshold_2->setValue(Parameters::defaultMemRehearsalSimilarity());
01732                 _ui->general_spinBox_imagesBufferSize_2->setValue(Parameters::defaultRtabmapImageBufferSize());
01733                 _ui->general_spinBox_maxStMemSize_2->setValue(Parameters::defaultMemSTMSize());
01734                 _ui->general_checkBox_publishStats_2->setChecked(Parameters::defaultRtabmapPublishStats());
01735                 _ui->general_checkBox_activateRGBD_2->setChecked(Parameters::defaultRGBDEnabled());
01736                 _ui->general_checkBox_SLAM_mode_2->setChecked(Parameters::defaultMemIncrementalMemory());
01737                 _ui->general_doubleSpinBox_detectionRate_2->setValue(Parameters::defaultRtabmapDetectionRate());
01738                 // match the advanced (spin and doubleSpin boxes)
01739                 _ui->general_doubleSpinBox_timeThr->setValue(Parameters::defaultRtabmapTimeThr());
01740                 _ui->general_doubleSpinBox_hardThr->setValue(Parameters::defaultRtabmapLoopThr());
01741                 _ui->doubleSpinBox_similarityThreshold->setValue(Parameters::defaultMemRehearsalSimilarity());
01742                 _ui->general_spinBox_imagesBufferSize->setValue(Parameters::defaultRtabmapImageBufferSize());
01743                 _ui->general_spinBox_maxStMemSize->setValue(Parameters::defaultMemSTMSize());
01744                 _ui->general_doubleSpinBox_detectionRate->setValue(Parameters::defaultRtabmapDetectionRate());
01745         }
01746         else
01747         {
01748                 QObjectList children = groupBox->children();
01749                 rtabmap::ParametersMap defaults = Parameters::getDefaultParameters();
01750                 std::string key;
01751                 for(int i=0; i<children.size(); ++i)
01752                 {
01753                         key = children.at(i)->objectName().toStdString();
01754                         if(uContains(defaults, key))
01755                         {
01756                                 if(key.compare(Parameters::kRtabmapWorkingDirectory().c_str()) == 0)
01757                                 {
01758                                         this->setParameter(key, getDefaultWorkingDirectory().toStdString());
01759                                 }
01760                                 else
01761                                 {
01762                                         this->setParameter(key, defaults.at(key));
01763                                 }
01764                                 if(qobject_cast<const QGroupBox*>(children.at(i)))
01765                                 {
01766                                         this->resetSettings((QGroupBox*)children.at(i));
01767                                 }
01768                         }
01769                         else if(qobject_cast<const QGroupBox*>(children.at(i)))
01770                         {
01771                                 this->resetSettings((QGroupBox*)children.at(i));
01772                         }
01773                         else if(qobject_cast<const QStackedWidget*>(children.at(i)))
01774                         {
01775                                 QStackedWidget * stackedWidget = (QStackedWidget*)children.at(i);
01776                                 for(int j=0; j<stackedWidget->count(); ++j)
01777                                 {
01778                                         const QObjectList & children2 = stackedWidget->widget(j)->children();
01779                                         for(int k=0; k<children2.size(); ++k)
01780                                         {
01781                                                 if(qobject_cast<QGroupBox *>(children2.at(k)))
01782                                                 {
01783                                                         this->resetSettings((QGroupBox*)children2.at(k));
01784                                                 }
01785                                         }
01786                                 }
01787                         }
01788                 }
01789 
01790                 if(groupBox->findChild<QLineEdit*>(_ui->lineEdit_kp_roi->objectName()))
01791                 {
01792                         this->setupKpRoiPanel();
01793                 }
01794 
01795                 if(groupBox->objectName() == _ui->groupBox_odometry1->objectName())
01796                 {
01797                         _ui->odom_registration->setCurrentIndex(3);
01798                 }
01799         }
01800 }
01801 
01802 void PreferencesDialog::resetSettings(int panelNumber)
01803 {
01804         QList<QGroupBox*> boxes = this->getGroupBoxes();
01805         if(panelNumber >= 0 && panelNumber < boxes.size())
01806         {
01807                 this->resetSettings(boxes.at(panelNumber));
01808         }
01809         else if(panelNumber == -1)
01810         {
01811                 for(QList<QGroupBox*>::iterator iter = boxes.begin(); iter!=boxes.end(); ++iter)
01812                 {
01813                         this->resetSettings(*iter);
01814                 }
01815         }
01816         else
01817         {
01818                 ULOGGER_WARN("panel number and the number of stacked widget doesn't match");
01819         }
01820 
01821 }
01822 
01823 QString PreferencesDialog::getWorkingDirectory() const
01824 {
01825         return _ui->lineEdit_workingDirectory->text();
01826 }
01827 
01828 QString PreferencesDialog::getIniFilePath() const
01829 {
01830         QString privatePath = QDir::homePath() + "/.rtabmap";
01831         if(!QDir(privatePath).exists())
01832         {
01833                 QDir::home().mkdir(".rtabmap");
01834         }
01835         return privatePath + "/rtabmap.ini";
01836 }
01837 
01838 QString PreferencesDialog::getTmpIniFilePath() const
01839 {
01840         return getIniFilePath()+".tmp";
01841 }
01842 
01843 void PreferencesDialog::loadConfigFrom()
01844 {
01845         QString path = QFileDialog::getOpenFileName(this, tr("Load settings..."), this->getWorkingDirectory(), "*.ini");
01846         if(!path.isEmpty())
01847         {
01848                 this->readSettings(path);
01849         }
01850 }
01851 
01852 void PreferencesDialog::readSettings(const QString & filePath)
01853 {
01854         ULOGGER_DEBUG("%s", filePath.toStdString().c_str());
01855         readGuiSettings(filePath);
01856         readCameraSettings(filePath);
01857         if(!readCoreSettings(filePath))
01858         {
01859                 _modifiedParameters.clear();
01860                 _obsoletePanels = kPanelDummy;
01861 
01862                 // only keep GUI settings
01863                 QStandardItem * parentItem = _indexModel->invisibleRootItem();
01864                 if(parentItem)
01865                 {
01866                         for(int i=1; i<parentItem->rowCount(); ++i)
01867                         {
01868                                 parentItem->child(i)->setEnabled(false);
01869                         }
01870                 }
01871                 _ui->radioButton_basic->setEnabled(false);
01872                 _ui->radioButton_advanced->setEnabled(false);
01873         }
01874         else
01875         {
01876                 // enable settings
01877                 QStandardItem * parentItem = _indexModel->invisibleRootItem();
01878                 if(parentItem)
01879                 {
01880                         for(int i=0; i<parentItem->rowCount(); ++i)
01881                         {
01882                                 parentItem->child(i)->setEnabled(true);
01883                         }
01884                 }
01885                 _ui->radioButton_basic->setEnabled(true);
01886                 _ui->radioButton_advanced->setEnabled(true);
01887         }
01888 }
01889 
01890 void PreferencesDialog::readGuiSettings(const QString & filePath)
01891 {
01892         QString path = getIniFilePath();
01893         if(!filePath.isEmpty())
01894         {
01895                 path = filePath;
01896         }
01897         QSettings settings(path, QSettings::IniFormat);
01898         settings.beginGroup("Gui");
01899         settings.beginGroup("General");
01900         _ui->general_checkBox_imagesKept->setChecked(settings.value("imagesKept", _ui->general_checkBox_imagesKept->isChecked()).toBool());
01901         _ui->general_checkBox_cloudsKept->setChecked(settings.value("cloudsKept", _ui->general_checkBox_cloudsKept->isChecked()).toBool());
01902         _ui->comboBox_loggerLevel->setCurrentIndex(settings.value("loggerLevel", _ui->comboBox_loggerLevel->currentIndex()).toInt());
01903         _ui->comboBox_loggerEventLevel->setCurrentIndex(settings.value("loggerEventLevel", _ui->comboBox_loggerEventLevel->currentIndex()).toInt());
01904         _ui->comboBox_loggerPauseLevel->setCurrentIndex(settings.value("loggerPauseLevel", _ui->comboBox_loggerPauseLevel->currentIndex()).toInt());
01905         _ui->comboBox_loggerType->setCurrentIndex(settings.value("loggerType", _ui->comboBox_loggerType->currentIndex()).toInt());
01906         _ui->checkBox_logger_printTime->setChecked(settings.value("loggerPrintTime", _ui->checkBox_logger_printTime->isChecked()).toBool());
01907         _ui->checkBox_logger_printThreadId->setChecked(settings.value("loggerPrintThreadId", _ui->checkBox_logger_printThreadId->isChecked()).toBool());
01908         _ui->checkBox_verticalLayoutUsed->setChecked(settings.value("verticalLayoutUsed", _ui->checkBox_verticalLayoutUsed->isChecked()).toBool());
01909         _ui->checkBox_imageRejectedShown->setChecked(settings.value("imageRejectedShown", _ui->checkBox_imageRejectedShown->isChecked()).toBool());
01910         _ui->checkBox_imageHighestHypShown->setChecked(settings.value("imageHighestHypShown", _ui->checkBox_imageHighestHypShown->isChecked()).toBool());
01911         _ui->checkBox_beep->setChecked(settings.value("beep", _ui->checkBox_beep->isChecked()).toBool());
01912         _ui->checkBox_stamps->setChecked(settings.value("figure_time", _ui->checkBox_stamps->isChecked()).toBool());
01913         _ui->checkBox_cacheStatistics->setChecked(settings.value("figure_cache", _ui->checkBox_cacheStatistics->isChecked()).toBool());
01914         _ui->checkBox_notifyWhenNewGlobalPathIsReceived->setChecked(settings.value("notifyNewGlobalPath", _ui->checkBox_notifyWhenNewGlobalPathIsReceived->isChecked()).toBool());
01915         _ui->spinBox_odomQualityWarnThr->setValue(settings.value("odomQualityThr", _ui->spinBox_odomQualityWarnThr->value()).toInt());
01916         _ui->checkBox_odom_onlyInliersShown->setChecked(settings.value("odomOnlyInliersShown", _ui->checkBox_odom_onlyInliersShown->isChecked()).toBool());
01917         _ui->radioButton_posteriorGraphView->setChecked(settings.value("posteriorGraphView", _ui->radioButton_posteriorGraphView->isChecked()).toBool());
01918         _ui->radioButton_wordsGraphView->setChecked(settings.value("wordsGraphView", _ui->radioButton_wordsGraphView->isChecked()).toBool());
01919         _ui->radioButton_localizationsGraphView->setChecked(settings.value("localizationsGraphView", _ui->radioButton_localizationsGraphView->isChecked()).toBool());
01920         _ui->radioButton_nochangeGraphView->setChecked(settings.value("nochangeGraphView", _ui->radioButton_nochangeGraphView->isChecked()).toBool());
01921         _ui->checkbox_odomDisabled->setChecked(settings.value("odomDisabled", _ui->checkbox_odomDisabled->isChecked()).toBool());
01922         _ui->odom_registration->setCurrentIndex(settings.value("odomRegistration", _ui->odom_registration->currentIndex()).toInt());
01923         _ui->checkbox_groundTruthAlign->setChecked(settings.value("gtAlign", _ui->checkbox_groundTruthAlign->isChecked()).toBool());
01924 
01925         for(int i=0; i<2; ++i)
01926         {
01927                 _3dRenderingShowClouds[i]->setChecked(settings.value(QString("showClouds%1").arg(i), _3dRenderingShowClouds[i]->isChecked()).toBool());
01928                 _3dRenderingDecimation[i]->setValue(settings.value(QString("decimation%1").arg(i), _3dRenderingDecimation[i]->value()).toInt());
01929                 _3dRenderingMaxDepth[i]->setValue(settings.value(QString("maxDepth%1").arg(i), _3dRenderingMaxDepth[i]->value()).toDouble());
01930                 _3dRenderingMinDepth[i]->setValue(settings.value(QString("minDepth%1").arg(i), _3dRenderingMinDepth[i]->value()).toDouble());
01931                 _3dRenderingRoiRatios[i]->setText(settings.value(QString("roiRatios%1").arg(i), _3dRenderingRoiRatios[i]->text()).toString());
01932                 _3dRenderingShowScans[i]->setChecked(settings.value(QString("showScans%1").arg(i), _3dRenderingShowScans[i]->isChecked()).toBool());
01933                 _3dRenderingShowFeatures[i]->setChecked(settings.value(QString("showFeatures%1").arg(i), _3dRenderingShowFeatures[i]->isChecked()).toBool());
01934                 _3dRenderingShowFrustums[i]->setChecked(settings.value(QString("showFrustums%1").arg(i), _3dRenderingShowFrustums[i]->isChecked()).toBool());
01935 
01936                 _3dRenderingDownsamplingScan[i]->setValue(settings.value(QString("downsamplingScan%1").arg(i), _3dRenderingDownsamplingScan[i]->value()).toInt());
01937                 _3dRenderingMaxRange[i]->setValue(settings.value(QString("maxRange%1").arg(i), _3dRenderingMaxRange[i]->value()).toDouble());
01938                 _3dRenderingMinRange[i]->setValue(settings.value(QString("minRange%1").arg(i), _3dRenderingMinRange[i]->value()).toDouble());
01939                 _3dRenderingVoxelSizeScan[i]->setValue(settings.value(QString("voxelSizeScan%1").arg(i), _3dRenderingVoxelSizeScan[i]->value()).toDouble());
01940                 _3dRenderingColorScheme[i]->setValue(settings.value(QString("colorScheme%1").arg(i), _3dRenderingColorScheme[i]->value()).toInt());
01941                 _3dRenderingOpacity[i]->setValue(settings.value(QString("opacity%1").arg(i), _3dRenderingOpacity[i]->value()).toDouble());
01942                 _3dRenderingPtSize[i]->setValue(settings.value(QString("ptSize%1").arg(i), _3dRenderingPtSize[i]->value()).toInt());
01943                 _3dRenderingColorSchemeScan[i]->setValue(settings.value(QString("colorSchemeScan%1").arg(i), _3dRenderingColorSchemeScan[i]->value()).toInt());
01944                 _3dRenderingOpacityScan[i]->setValue(settings.value(QString("opacityScan%1").arg(i), _3dRenderingOpacityScan[i]->value()).toDouble());
01945                 _3dRenderingPtSizeScan[i]->setValue(settings.value(QString("ptSizeScan%1").arg(i), _3dRenderingPtSizeScan[i]->value()).toInt());
01946                 _3dRenderingPtSizeFeatures[i]->setValue(settings.value(QString("ptSizeFeatures%1").arg(i), _3dRenderingPtSizeFeatures[i]->value()).toInt());
01947         }
01948         _ui->doubleSpinBox_voxel->setValue(settings.value("cloudVoxel", _ui->doubleSpinBox_voxel->value()).toDouble());
01949         _ui->doubleSpinBox_noiseRadius->setValue(settings.value("cloudNoiseRadius", _ui->doubleSpinBox_noiseRadius->value()).toDouble());
01950         _ui->spinBox_noiseMinNeighbors->setValue(settings.value("cloudNoiseMinNeighbors", _ui->spinBox_noiseMinNeighbors->value()).toInt());
01951         _ui->doubleSpinBox_ceilingFilterHeight->setValue(settings.value("cloudCeilingHeight", _ui->doubleSpinBox_ceilingFilterHeight->value()).toDouble());
01952         _ui->doubleSpinBox_floorFilterHeight->setValue(settings.value("cloudFloorHeight", _ui->doubleSpinBox_floorFilterHeight->value()).toDouble());
01953         _ui->spinBox_normalKSearch->setValue(settings.value("normalKSearch", _ui->spinBox_normalKSearch->value()).toInt());
01954         _ui->doubleSpinBox_normalRadiusSearch->setValue(settings.value("normalRadiusSearch", _ui->doubleSpinBox_normalRadiusSearch->value()).toDouble());
01955         _ui->doubleSpinBox_ceilingFilterHeight_scan->setValue(settings.value("scanCeilingHeight", _ui->doubleSpinBox_ceilingFilterHeight_scan->value()).toDouble());
01956         _ui->doubleSpinBox_floorFilterHeight_scan->setValue(settings.value("scanFloorHeight", _ui->doubleSpinBox_floorFilterHeight_scan->value()).toDouble());
01957         _ui->spinBox_normalKSearch_scan->setValue(settings.value("scanNormalKSearch", _ui->spinBox_normalKSearch_scan->value()).toInt());
01958         _ui->doubleSpinBox_normalRadiusSearch_scan->setValue(settings.value("scanNormalRadiusSearch", _ui->doubleSpinBox_normalRadiusSearch_scan->value()).toDouble());
01959 
01960         _ui->checkBox_showGraphs->setChecked(settings.value("showGraphs", _ui->checkBox_showGraphs->isChecked()).toBool());
01961         _ui->checkBox_showLabels->setChecked(settings.value("showLabels", _ui->checkBox_showLabels->isChecked()).toBool());
01962 
01963         _ui->radioButton_noFiltering->setChecked(settings.value("noFiltering", _ui->radioButton_noFiltering->isChecked()).toBool());
01964         _ui->radioButton_nodeFiltering->setChecked(settings.value("cloudFiltering", _ui->radioButton_nodeFiltering->isChecked()).toBool());
01965         _ui->doubleSpinBox_cloudFilterRadius->setValue(settings.value("cloudFilteringRadius", _ui->doubleSpinBox_cloudFilterRadius->value()).toDouble());
01966         _ui->doubleSpinBox_cloudFilterAngle->setValue(settings.value("cloudFilteringAngle", _ui->doubleSpinBox_cloudFilterAngle->value()).toDouble());
01967         _ui->radioButton_subtractFiltering->setChecked(settings.value("subtractFiltering", _ui->radioButton_subtractFiltering->isChecked()).toBool());
01968         _ui->spinBox_subtractFilteringMinPts->setValue(settings.value("subtractFilteringMinPts", _ui->spinBox_subtractFilteringMinPts->value()).toInt());
01969         _ui->doubleSpinBox_subtractFilteringRadius->setValue(settings.value("subtractFilteringRadius", _ui->doubleSpinBox_subtractFilteringRadius->value()).toDouble());
01970         _ui->doubleSpinBox_subtractFilteringAngle->setValue(settings.value("subtractFilteringAngle", _ui->doubleSpinBox_subtractFilteringAngle->value()).toDouble());
01971 
01972         _ui->checkBox_map_shown->setChecked(settings.value("gridMapShown", _ui->checkBox_map_shown->isChecked()).toBool());
01973         _ui->doubleSpinBox_map_opacity->setValue(settings.value("gridMapOpacity", _ui->doubleSpinBox_map_opacity->value()).toDouble());
01974 
01975         _ui->groupBox_octomap->setChecked(settings.value("octomap", _ui->groupBox_octomap->isChecked()).toBool());
01976         _ui->spinBox_octomap_treeDepth->setValue(settings.value("octomap_depth", _ui->spinBox_octomap_treeDepth->value()).toInt());
01977         _ui->checkBox_octomap_2dgrid->setChecked(settings.value("octomap_2dgrid", _ui->checkBox_octomap_2dgrid->isChecked()).toBool());
01978         _ui->checkBox_octomap_show3dMap->setChecked(settings.value("octomap_3dmap", _ui->checkBox_octomap_show3dMap->isChecked()).toBool());
01979         _ui->comboBox_octomap_renderingType->setCurrentIndex(settings.value("octomap_rendering_type", _ui->comboBox_octomap_renderingType->currentIndex()).toInt());
01980         _ui->spinBox_octomap_pointSize->setValue(settings.value("octomap_point_size", _ui->spinBox_octomap_pointSize->value()).toInt());
01981 
01982         _ui->groupBox_organized->setChecked(settings.value("meshing", _ui->groupBox_organized->isChecked()).toBool());
01983         _ui->doubleSpinBox_mesh_angleTolerance->setValue(settings.value("meshing_angle", _ui->doubleSpinBox_mesh_angleTolerance->value()).toDouble());
01984         _ui->checkBox_mesh_quad->setChecked(settings.value("meshing_quad", _ui->checkBox_mesh_quad->isChecked()).toBool());
01985         _ui->checkBox_mesh_texture->setChecked(settings.value("meshing_texture", _ui->checkBox_mesh_texture->isChecked()).toBool());
01986         _ui->spinBox_mesh_triangleSize->setValue(settings.value("meshing_triangle_size", _ui->spinBox_mesh_triangleSize->value()).toInt());
01987 
01988         settings.endGroup(); // General
01989 
01990         settings.endGroup(); // rtabmap
01991 }
01992 
01993 void PreferencesDialog::readCameraSettings(const QString & filePath)
01994 {
01995         QString path = getIniFilePath();
01996         if(!filePath.isEmpty())
01997         {
01998                 path = filePath;
01999         }
02000         QSettings settings(path, QSettings::IniFormat);
02001 
02002         settings.beginGroup("Camera");
02003         _ui->general_doubleSpinBox_imgRate->setValue(settings.value("imgRate", _ui->general_doubleSpinBox_imgRate->value()).toDouble());
02004         _ui->source_mirroring->setChecked(settings.value("mirroring", _ui->source_mirroring->isChecked()).toBool());
02005         _ui->lineEdit_calibrationFile->setText(settings.value("calibrationName", _ui->lineEdit_calibrationFile->text()).toString());
02006         _ui->comboBox_sourceType->setCurrentIndex(settings.value("type", _ui->comboBox_sourceType->currentIndex()).toInt());
02007         _ui->lineEdit_sourceDevice->setText(settings.value("device",_ui->lineEdit_sourceDevice->text()).toString());
02008         _ui->lineEdit_sourceLocalTransform->setText(settings.value("localTransform",_ui->lineEdit_sourceLocalTransform->text()).toString());
02009         _ui->spinBox_source_imageDecimation->setValue(settings.value("imageDecimation",_ui->spinBox_source_imageDecimation->value()).toInt());
02010 
02011         settings.beginGroup("rgbd");
02012         _ui->comboBox_cameraRGBD->setCurrentIndex(settings.value("driver", _ui->comboBox_cameraRGBD->currentIndex()).toInt());
02013         _ui->checkbox_rgbd_colorOnly->setChecked(settings.value("rgbdColorOnly", _ui->checkbox_rgbd_colorOnly->isChecked()).toBool());
02014         _ui->lineEdit_source_distortionModel->setText(settings.value("distortion_model", _ui->lineEdit_source_distortionModel->text()).toString());
02015         _ui->groupBox_bilateral->setChecked(settings.value("bilateral", _ui->groupBox_bilateral->isChecked()).toBool());
02016         _ui->doubleSpinBox_bilateral_sigmaS->setValue(settings.value("bilateral_sigma_s", _ui->doubleSpinBox_bilateral_sigmaS->value()).toDouble());
02017         _ui->doubleSpinBox_bilateral_sigmaR->setValue(settings.value("bilateral_sigma_r", _ui->doubleSpinBox_bilateral_sigmaR->value()).toDouble());
02018         settings.endGroup(); // rgbd
02019 
02020         settings.beginGroup("stereo");
02021         _ui->comboBox_cameraStereo->setCurrentIndex(settings.value("driver", _ui->comboBox_cameraStereo->currentIndex()).toInt());
02022         _ui->checkbox_stereo_depthGenerated->setChecked(settings.value("depthGenerated", _ui->checkbox_stereo_depthGenerated->isChecked()).toBool());
02023         _ui->checkBox_stereo_exposureCompensation->setChecked(settings.value("exposureCompensation", _ui->checkBox_stereo_exposureCompensation->isChecked()).toBool());
02024         settings.endGroup(); // stereo
02025 
02026         settings.beginGroup("rgb");
02027         _ui->source_comboBox_image_type->setCurrentIndex(settings.value("driver", _ui->source_comboBox_image_type->currentIndex()).toInt());
02028         _ui->checkBox_rgb_rectify->setChecked(settings.value("rectify",_ui->checkBox_rgb_rectify->isChecked()).toBool());
02029         settings.endGroup(); // rgb
02030 
02031         settings.beginGroup("Openni");
02032         _ui->lineEdit_openniOniPath->setText(settings.value("oniPath", _ui->lineEdit_openniOniPath->text()).toString());
02033         settings.endGroup(); // Openni
02034 
02035         settings.beginGroup("Openni2");
02036         _ui->openni2_autoWhiteBalance->setChecked(settings.value("autoWhiteBalance", _ui->openni2_autoWhiteBalance->isChecked()).toBool());
02037         _ui->openni2_autoExposure->setChecked(settings.value("autoExposure", _ui->openni2_autoExposure->isChecked()).toBool());
02038         _ui->openni2_exposure->setValue(settings.value("exposure", _ui->openni2_exposure->value()).toInt());
02039         _ui->openni2_gain->setValue(settings.value("gain", _ui->openni2_gain->value()).toInt());
02040         _ui->openni2_mirroring->setChecked(settings.value("mirroring", _ui->openni2_mirroring->isChecked()).toBool());
02041         _ui->openni2_stampsIdsUsed->setChecked(settings.value("stampsIdsUsed", _ui->openni2_stampsIdsUsed->isChecked()).toBool());
02042         _ui->lineEdit_openni2OniPath->setText(settings.value("oniPath", _ui->lineEdit_openni2OniPath->text()).toString());
02043         _ui->openni2_hshift->setValue(settings.value("hshift", _ui->openni2_hshift->value()).toInt());
02044         _ui->openni2_vshift->setValue(settings.value("vshift", _ui->openni2_vshift->value()).toInt());
02045         settings.endGroup(); // Openni2
02046 
02047         settings.beginGroup("Freenect2");
02048         _ui->comboBox_freenect2Format->setCurrentIndex(settings.value("format", _ui->comboBox_freenect2Format->currentIndex()).toInt());
02049         _ui->doubleSpinBox_freenect2MinDepth->setValue(settings.value("minDepth", _ui->doubleSpinBox_freenect2MinDepth->value()).toDouble());
02050         _ui->doubleSpinBox_freenect2MaxDepth->setValue(settings.value("maxDepth", _ui->doubleSpinBox_freenect2MaxDepth->value()).toDouble());
02051         _ui->checkBox_freenect2BilateralFiltering->setChecked(settings.value("bilateralFiltering", _ui->checkBox_freenect2BilateralFiltering->isChecked()).toBool());
02052         _ui->checkBox_freenect2EdgeAwareFiltering->setChecked(settings.value("edgeAwareFiltering", _ui->checkBox_freenect2EdgeAwareFiltering->isChecked()).toBool());
02053         _ui->checkBox_freenect2NoiseFiltering->setChecked(settings.value("noiseFiltering", _ui->checkBox_freenect2NoiseFiltering->isChecked()).toBool());
02054         _ui->lineEdit_freenect2Pipeline->setText(settings.value("pipeline", _ui->lineEdit_freenect2Pipeline->text()).toString());
02055         settings.endGroup(); // Freenect2
02056 
02057         settings.beginGroup("K4W2");
02058         _ui->comboBox_k4w2Format->setCurrentIndex(settings.value("format", _ui->comboBox_k4w2Format->currentIndex()).toInt());
02059         settings.endGroup(); // K4W2
02060 
02061         settings.beginGroup("RealSense");
02062         _ui->comboBox_realsensePresetRGB->setCurrentIndex(settings.value("presetRGB", _ui->comboBox_realsensePresetRGB->currentIndex()).toInt());
02063         _ui->comboBox_realsensePresetDepth->setCurrentIndex(settings.value("presetDepth", _ui->comboBox_realsensePresetDepth->currentIndex()).toInt());
02064         _ui->checkbox_realsenseOdom->setChecked(settings.value("odom", _ui->checkbox_realsenseOdom->isChecked()).toBool());
02065         _ui->checkbox_realsenseDepthScaledToRGBSize->setChecked(settings.value("depthScaled", _ui->checkbox_realsenseDepthScaledToRGBSize->isChecked()).toBool());
02066         _ui->comboBox_realsenseRGBSource->setCurrentIndex(settings.value("rgbSource", _ui->comboBox_realsenseRGBSource->currentIndex()).toInt());
02067         settings.endGroup(); // RealSense
02068 
02069         settings.beginGroup("RealSense2");
02070         _ui->checkbox_rs2_emitter->setChecked(settings.value("emitter", _ui->checkbox_rs2_emitter->isChecked()).toBool());
02071         _ui->checkbox_rs2_irDepth->setChecked(settings.value("irdepth", _ui->checkbox_rs2_irDepth->isChecked()).toBool());
02072         settings.endGroup(); // RealSense
02073 
02074         settings.beginGroup("RGBDImages");
02075         _ui->lineEdit_cameraRGBDImages_path_rgb->setText(settings.value("path_rgb", _ui->lineEdit_cameraRGBDImages_path_rgb->text()).toString());
02076         _ui->lineEdit_cameraRGBDImages_path_depth->setText(settings.value("path_depth", _ui->lineEdit_cameraRGBDImages_path_depth->text()).toString());
02077         _ui->doubleSpinBox_cameraRGBDImages_scale->setValue(settings.value("scale", _ui->doubleSpinBox_cameraRGBDImages_scale->value()).toDouble());
02078         _ui->spinBox_cameraRGBDImages_startIndex->setValue(settings.value("start_index", _ui->spinBox_cameraRGBDImages_startIndex->value()).toInt());
02079         settings.endGroup(); // RGBDImages
02080 
02081         settings.beginGroup("StereoImages");
02082         _ui->lineEdit_cameraStereoImages_path_left->setText(settings.value("path_left", _ui->lineEdit_cameraStereoImages_path_left->text()).toString());
02083         _ui->lineEdit_cameraStereoImages_path_right->setText(settings.value("path_right", _ui->lineEdit_cameraStereoImages_path_right->text()).toString());
02084         _ui->checkBox_stereo_rectify->setChecked(settings.value("rectify",_ui->checkBox_stereo_rectify->isChecked()).toBool());
02085         _ui->spinBox_cameraStereoImages_startIndex->setValue(settings.value("start_index",_ui->spinBox_cameraStereoImages_startIndex->value()).toInt());
02086         settings.endGroup(); // StereoImages
02087 
02088         settings.beginGroup("StereoVideo");
02089         _ui->lineEdit_cameraStereoVideo_path->setText(settings.value("path", _ui->lineEdit_cameraStereoVideo_path->text()).toString());
02090         _ui->lineEdit_cameraStereoVideo_path_2->setText(settings.value("path2", _ui->lineEdit_cameraStereoVideo_path_2->text()).toString());
02091         _ui->spinBox_stereo_right_device->setValue(settings.value("device2", _ui->spinBox_stereo_right_device->value()).toInt());
02092         settings.endGroup(); // StereoVideo
02093 
02094         settings.beginGroup("StereoZed");
02095         _ui->comboBox_stereoZed_resolution->setCurrentIndex(settings.value("resolution", _ui->comboBox_stereoZed_resolution->currentIndex()).toInt());
02096         _ui->comboBox_stereoZed_quality->setCurrentIndex(settings.value("quality", _ui->comboBox_stereoZed_quality->currentIndex()).toInt());
02097         _ui->checkbox_stereoZed_selfCalibration->setChecked(settings.value("self_calibration", _ui->checkbox_stereoZed_selfCalibration->isChecked()).toBool());
02098         _ui->comboBox_stereoZed_sensingMode->setCurrentIndex(settings.value("sensing_mode", _ui->comboBox_stereoZed_sensingMode->currentIndex()).toInt());
02099         _ui->spinBox_stereoZed_confidenceThr->setValue(settings.value("confidence_thr", _ui->spinBox_stereoZed_confidenceThr->value()).toInt());
02100         _ui->checkbox_stereoZed_odom->setChecked(settings.value("odom", _ui->checkbox_stereoZed_odom->isChecked()).toBool());
02101         _ui->lineEdit_zedSvoPath->setText(settings.value("svo_path", _ui->lineEdit_zedSvoPath->text()).toString());
02102         settings.endGroup(); // StereoZed
02103         
02104 
02105         settings.beginGroup("Images");
02106         _ui->source_images_lineEdit_path->setText(settings.value("path", _ui->source_images_lineEdit_path->text()).toString());
02107         _ui->source_images_spinBox_startPos->setValue(settings.value("startPos",_ui->source_images_spinBox_startPos->value()).toInt());
02108         _ui->comboBox_cameraImages_bayerMode->setCurrentIndex(settings.value("bayerMode",_ui->comboBox_cameraImages_bayerMode->currentIndex()).toInt());
02109 
02110         _ui->checkBox_cameraImages_timestamps->setChecked(settings.value("filenames_as_stamps",_ui->checkBox_cameraImages_timestamps->isChecked()).toBool());
02111         _ui->checkBox_cameraImages_syncTimeStamps->setChecked(settings.value("sync_stamps",_ui->checkBox_cameraImages_syncTimeStamps->isChecked()).toBool());
02112         _ui->lineEdit_cameraImages_timestamps->setText(settings.value("stamps", _ui->lineEdit_cameraImages_timestamps->text()).toString());
02113         _ui->lineEdit_cameraImages_path_scans->setText(settings.value("path_scans", _ui->lineEdit_cameraImages_path_scans->text()).toString());
02114         _ui->lineEdit_cameraImages_laser_transform->setText(settings.value("scan_transform", _ui->lineEdit_cameraImages_laser_transform->text()).toString());
02115         _ui->spinBox_cameraImages_max_scan_pts->setValue(settings.value("scan_max_pts", _ui->spinBox_cameraImages_max_scan_pts->value()).toInt());
02116         _ui->spinBox_cameraImages_scanDownsampleStep->setValue(settings.value("scan_downsample_step", _ui->spinBox_cameraImages_scanDownsampleStep->value()).toInt());
02117         _ui->doubleSpinBox_cameraImages_scanVoxelSize->setValue(settings.value("scan_voxel_size", _ui->doubleSpinBox_cameraImages_scanVoxelSize->value()).toDouble());
02118         _ui->lineEdit_cameraImages_odom->setText(settings.value("odom_path", _ui->lineEdit_cameraImages_odom->text()).toString());
02119         _ui->comboBox_cameraImages_odomFormat->setCurrentIndex(settings.value("odom_format", _ui->comboBox_cameraImages_odomFormat->currentIndex()).toInt());
02120         _ui->lineEdit_cameraImages_gt->setText(settings.value("gt_path", _ui->lineEdit_cameraImages_gt->text()).toString());
02121         _ui->comboBox_cameraImages_gtFormat->setCurrentIndex(settings.value("gt_format", _ui->comboBox_cameraImages_gtFormat->currentIndex()).toInt());
02122         _ui->doubleSpinBox_maxPoseTimeDiff->setValue(settings.value("max_pose_time_diff", _ui->doubleSpinBox_maxPoseTimeDiff->value()).toDouble());
02123 
02124         _ui->lineEdit_cameraImages_path_imu->setText(settings.value("imu_path", _ui->lineEdit_cameraImages_path_imu->text()).toString());
02125         _ui->lineEdit_cameraImages_imu_transform->setText(settings.value("imu_local_transform", _ui->lineEdit_cameraImages_imu_transform->text()).toString());
02126         _ui->spinBox_cameraImages_max_imu_rate->setValue(settings.value("imu_rate", _ui->spinBox_cameraImages_max_imu_rate->value()).toInt());
02127         settings.endGroup(); // images
02128 
02129         settings.beginGroup("Video");
02130         _ui->source_video_lineEdit_path->setText(settings.value("path", _ui->source_video_lineEdit_path->text()).toString());
02131         settings.endGroup(); // video
02132 
02133         settings.beginGroup("ScanFromDepth");
02134         _ui->groupBox_scanFromDepth->setChecked(settings.value("enabled", _ui->groupBox_scanFromDepth->isChecked()).toBool());
02135         _ui->spinBox_cameraScanFromDepth_decimation->setValue(settings.value("decimation", _ui->spinBox_cameraScanFromDepth_decimation->value()).toInt());
02136         _ui->doubleSpinBox_cameraSCanFromDepth_maxDepth->setValue(settings.value("maxDepth", _ui->doubleSpinBox_cameraSCanFromDepth_maxDepth->value()).toDouble());
02137         _ui->doubleSpinBox_cameraImages_scanVoxelSize->setValue(settings.value("voxelSize", _ui->doubleSpinBox_cameraImages_scanVoxelSize->value()).toDouble());
02138         _ui->spinBox_cameraImages_scanNormalsK->setValue(settings.value("normalsK", _ui->spinBox_cameraImages_scanNormalsK->value()).toInt());
02139         _ui->doubleSpinBox_cameraImages_scanNormalsRadius->setValue(settings.value("normalsRadius", _ui->doubleSpinBox_cameraImages_scanNormalsRadius->value()).toDouble());
02140         _ui->checkBox_cameraImages_scanForceGroundNormalsUp->setChecked(settings.value("normalsUp", _ui->checkBox_cameraImages_scanForceGroundNormalsUp->isChecked()).toBool());
02141 
02142         settings.endGroup();//ScanFromDepth
02143 
02144         settings.beginGroup("DepthFromScan");
02145         _ui->groupBox_depthFromScan->setChecked(settings.value("depthFromScan", _ui->groupBox_depthFromScan->isChecked()).toBool());
02146         _ui->groupBox_depthFromScan_fillHoles->setChecked(settings.value("depthFromScanFillHoles", _ui->groupBox_depthFromScan_fillHoles->isChecked()).toBool());
02147         _ui->radioButton_depthFromScan_vertical->setChecked(settings.value("depthFromScanVertical", _ui->radioButton_depthFromScan_vertical->isChecked()).toBool());
02148         _ui->radioButton_depthFromScan_horizontal->setChecked(settings.value("depthFromScanHorizontal", _ui->radioButton_depthFromScan_horizontal->isChecked()).toBool());
02149         _ui->checkBox_depthFromScan_fillBorders->setChecked(settings.value("depthFromScanFillBorders", _ui->checkBox_depthFromScan_fillBorders->isChecked()).toBool());
02150         settings.endGroup();
02151 
02152         settings.beginGroup("Database");
02153         _ui->source_database_lineEdit_path->setText(settings.value("path",_ui->source_database_lineEdit_path->text()).toString());
02154         _ui->source_checkBox_ignoreOdometry->setChecked(settings.value("ignoreOdometry", _ui->source_checkBox_ignoreOdometry->isChecked()).toBool());
02155         _ui->source_checkBox_ignoreGoalDelay->setChecked(settings.value("ignoreGoalDelay", _ui->source_checkBox_ignoreGoalDelay->isChecked()).toBool());
02156         _ui->source_checkBox_ignoreGoals->setChecked(settings.value("ignoreGoals", _ui->source_checkBox_ignoreGoals->isChecked()).toBool());
02157         _ui->source_spinBox_databaseStartPos->setValue(settings.value("startPos", _ui->source_spinBox_databaseStartPos->value()).toInt());
02158         _ui->source_spinBox_database_cameraIndex->setValue(settings.value("cameraIndex", _ui->source_spinBox_database_cameraIndex->value()).toInt());
02159         _ui->source_checkBox_useDbStamps->setChecked(settings.value("useDatabaseStamps", _ui->source_checkBox_useDbStamps->isChecked()).toBool());
02160         settings.endGroup(); // Database
02161 
02162         settings.endGroup(); // Camera
02163 
02164         _calibrationDialog->loadSettings(settings, "CalibrationDialog");
02165 
02166 }
02167 
02168 QString PreferencesDialog::getDefaultWorkingDirectory() const
02169 {
02170         return Parameters::createDefaultWorkingDirectory().c_str();
02171 }
02172 
02173 bool PreferencesDialog::readCoreSettings(const QString & filePath)
02174 {
02175         QString path = getIniFilePath();
02176         if(!filePath.isEmpty())
02177         {
02178                 path = filePath;
02179         }
02180 
02181         UDEBUG("%s", path.toStdString().c_str());
02182 
02183         if(!QFile::exists(path))
02184         {
02185                 QMessageBox::information(this, tr("INI file doesn't exist..."), tr("The configuration file \"%1\" does not exist, it will be created with default parameters.").arg(path));
02186         }
02187 
02188         ParametersMap parameters;
02189         Parameters::readINI(path.toStdString(), parameters);
02190 
02191         for(rtabmap::ParametersMap::const_iterator iter = parameters.begin(); iter!=parameters.end(); ++iter)
02192         {
02193                 std::string value = iter->second;
02194                 if(iter->first.compare(Parameters::kRtabmapWorkingDirectory()) == 0)
02195                 {
02196                         // The directory should exist if not the default one
02197                         if(!QDir(value.c_str()).exists() && value.compare(getDefaultWorkingDirectory().toStdString()) != 0)
02198                         {
02199                                 if(QDir(this->getWorkingDirectory().toStdString().c_str()).exists())
02200                                 {
02201                                         UWARN("Reading config: Not existing working directory \"%s\". Keeping old one (\"%s\").",
02202                                                 value.c_str(),
02203                                                 this->getWorkingDirectory().toStdString().c_str());
02204                                         value = this->getWorkingDirectory().toStdString();
02205                                 }
02206                                 else
02207                                 {
02208                                         std::string defaultWorkingDir = getDefaultWorkingDirectory().toStdString();
02209                                         UWARN("Reading config: Not existing working directory \"%s\". Using default one (\"%s\").",
02210                                                 value.c_str(),
02211                                                 defaultWorkingDir.c_str());
02212                                         value = defaultWorkingDir;
02213                                 }
02214                         }
02215                 }
02216                 this->setParameter(iter->first, value);
02217         }
02218 
02219         // Add information about the working directory if not in the config file
02220         if(parameters.find(Parameters::kRtabmapWorkingDirectory()) == parameters.end())
02221         {
02222                 if(!_initialized)
02223                 {
02224                         QMessageBox::information(this,
02225                                         tr("Working directory"),
02226                                         tr("RTAB-Map needs a working directory to put the database.\n\n"
02227                                            "By default, the directory \"%1\" is used.\n\n"
02228                                            "The working directory can be changed any time in the "
02229                                            "preferences menu.").arg(getDefaultWorkingDirectory()));
02230                 }
02231                 this->setParameter(Parameters::kRtabmapWorkingDirectory(), getDefaultWorkingDirectory().toStdString());
02232                 UDEBUG("key.toStdString()=%s", getDefaultWorkingDirectory().toStdString().c_str());
02233         }
02234 
02235         return true;
02236 }
02237 
02238 bool PreferencesDialog::saveConfigTo()
02239 {
02240         QString path = QFileDialog::getSaveFileName(this, tr("Save settings..."), this->getWorkingDirectory()+QDir::separator()+"config.ini", "*.ini");
02241         if(!path.isEmpty())
02242         {
02243                 writeGuiSettings(path);
02244                 writeCameraSettings(path);
02245                 writeCoreSettings(path);
02246                 return true;
02247         }
02248         return false;
02249 }
02250 
02251 void PreferencesDialog::resetConfig()
02252 {
02253         int button = QMessageBox::warning(this,
02254                         tr("Reset settings..."),
02255                         tr("This will reset all settings. Restore all settings to default without saving them first?"),
02256                            QMessageBox::Cancel | QMessageBox::Yes | QMessageBox::Save,
02257                            QMessageBox::Cancel);
02258         if(button == QMessageBox::Yes ||
02259            (button == QMessageBox::Save && saveConfigTo()))
02260         {
02261                 this->resetSettings(-1);
02262 
02263                 _calibrationDialog->resetSettings();
02264         }
02265 }
02266 
02267 void PreferencesDialog::writeSettings(const QString & filePath)
02268 {
02269         writeGuiSettings(filePath);
02270         writeCameraSettings(filePath);
02271         writeCoreSettings(filePath);
02272 
02273         UDEBUG("_obsoletePanels=%d modified parameters=%d", (int)_obsoletePanels, (int)_modifiedParameters.size());
02274 
02275         if(_modifiedParameters.size())
02276         {
02277                 Q_EMIT settingsChanged(_modifiedParameters);
02278         }
02279 
02280         if(_obsoletePanels)
02281         {
02282                 Q_EMIT settingsChanged(_obsoletePanels);
02283         }
02284 
02285         for(ParametersMap::iterator iter = _modifiedParameters.begin(); iter!=_modifiedParameters.end(); ++iter)
02286         {
02287                 if (_parameters.at(iter->first).compare(iter->second) != 0)
02288                 {
02289                         bool different = true;
02290                         if (Parameters::getType(iter->first).compare("double") == 0 ||
02291                                 Parameters::getType(iter->first).compare("float") == 0)
02292                         {
02293                                 if (uStr2Double(_parameters.at(iter->first)) == uStr2Double(iter->second))
02294                                 {
02295                                         different = false;
02296                                 }
02297                         }
02298                         if (different)
02299                         {
02300                                 UINFO("modified %s = %s->%s", iter->first.c_str(), _parameters.at(iter->first).c_str(), iter->second.c_str());
02301                         }
02302                 }
02303         }
02304 
02305         uInsert(_parameters, _modifiedParameters); // update cached parameters
02306         _modifiedParameters.clear();
02307         _obsoletePanels = kPanelDummy;
02308 }
02309 
02310 void PreferencesDialog::writeGuiSettings(const QString & filePath) const
02311 {
02312         QString path = getIniFilePath();
02313         if(!filePath.isEmpty())
02314         {
02315                 path = filePath;
02316         }
02317         QSettings settings(path, QSettings::IniFormat);
02318         settings.beginGroup("Gui");
02319 
02320         settings.beginGroup("General");
02321         settings.remove("");
02322         settings.setValue("imagesKept",           _ui->general_checkBox_imagesKept->isChecked());
02323         settings.setValue("cloudsKept",           _ui->general_checkBox_cloudsKept->isChecked());
02324         settings.setValue("loggerLevel",          _ui->comboBox_loggerLevel->currentIndex());
02325         settings.setValue("loggerEventLevel",     _ui->comboBox_loggerEventLevel->currentIndex());
02326         settings.setValue("loggerPauseLevel",     _ui->comboBox_loggerPauseLevel->currentIndex());
02327         settings.setValue("loggerType",           _ui->comboBox_loggerType->currentIndex());
02328         settings.setValue("loggerPrintTime",      _ui->checkBox_logger_printTime->isChecked());
02329         settings.setValue("loggerPrintThreadId",  _ui->checkBox_logger_printThreadId->isChecked());
02330         settings.setValue("verticalLayoutUsed",   _ui->checkBox_verticalLayoutUsed->isChecked());
02331         settings.setValue("imageRejectedShown",   _ui->checkBox_imageRejectedShown->isChecked());
02332         settings.setValue("imageHighestHypShown", _ui->checkBox_imageHighestHypShown->isChecked());
02333         settings.setValue("beep",                 _ui->checkBox_beep->isChecked());
02334         settings.setValue("figure_time",          _ui->checkBox_stamps->isChecked());
02335         settings.setValue("figure_cache",         _ui->checkBox_cacheStatistics->isChecked());
02336         settings.setValue("notifyNewGlobalPath",  _ui->checkBox_notifyWhenNewGlobalPathIsReceived->isChecked());
02337         settings.setValue("odomQualityThr",       _ui->spinBox_odomQualityWarnThr->value());
02338         settings.setValue("odomOnlyInliersShown", _ui->checkBox_odom_onlyInliersShown->isChecked());
02339         settings.setValue("posteriorGraphView",   _ui->radioButton_posteriorGraphView->isChecked());
02340         settings.setValue("wordsGraphView",       _ui->radioButton_wordsGraphView->isChecked());
02341         settings.setValue("localizationsGraphView", _ui->radioButton_localizationsGraphView->isChecked());
02342         settings.setValue("nochangeGraphView",    _ui->radioButton_nochangeGraphView->isChecked());
02343         settings.setValue("odomDisabled",         _ui->checkbox_odomDisabled->isChecked());
02344         settings.setValue("odomRegistration",     _ui->odom_registration->currentIndex());
02345         settings.setValue("gtAlign",              _ui->checkbox_groundTruthAlign->isChecked());
02346 
02347         for(int i=0; i<2; ++i)
02348         {
02349                 settings.setValue(QString("showClouds%1").arg(i), _3dRenderingShowClouds[i]->isChecked());
02350                 settings.setValue(QString("decimation%1").arg(i), _3dRenderingDecimation[i]->value());
02351                 settings.setValue(QString("maxDepth%1").arg(i), _3dRenderingMaxDepth[i]->value());
02352                 settings.setValue(QString("minDepth%1").arg(i), _3dRenderingMinDepth[i]->value());
02353                 settings.setValue(QString("roiRatios%1").arg(i), _3dRenderingRoiRatios[i]->text());
02354                 settings.setValue(QString("showScans%1").arg(i), _3dRenderingShowScans[i]->isChecked());
02355                 settings.setValue(QString("showFeatures%1").arg(i), _3dRenderingShowFeatures[i]->isChecked());
02356                 settings.setValue(QString("showFrustums%1").arg(i), _3dRenderingShowFrustums[i]->isChecked());
02357 
02358                 settings.setValue(QString("downsamplingScan%1").arg(i), _3dRenderingDownsamplingScan[i]->value());
02359                 settings.setValue(QString("maxRange%1").arg(i), _3dRenderingMaxRange[i]->value());
02360                 settings.setValue(QString("minRange%1").arg(i), _3dRenderingMinRange[i]->value());
02361                 settings.setValue(QString("voxelSizeScan%1").arg(i), _3dRenderingVoxelSizeScan[i]->value());
02362                 settings.setValue(QString("colorScheme%1").arg(i), _3dRenderingColorScheme[i]->value());
02363                 settings.setValue(QString("opacity%1").arg(i), _3dRenderingOpacity[i]->value());
02364                 settings.setValue(QString("ptSize%1").arg(i), _3dRenderingPtSize[i]->value());
02365                 settings.setValue(QString("colorSchemeScan%1").arg(i), _3dRenderingColorSchemeScan[i]->value());
02366                 settings.setValue(QString("opacityScan%1").arg(i), _3dRenderingOpacityScan[i]->value());
02367                 settings.setValue(QString("ptSizeScan%1").arg(i), _3dRenderingPtSizeScan[i]->value());
02368                 settings.setValue(QString("ptSizeFeatures%1").arg(i), _3dRenderingPtSizeFeatures[i]->value());
02369         }
02370         settings.setValue("cloudVoxel",             _ui->doubleSpinBox_voxel->value());
02371         settings.setValue("cloudNoiseRadius",       _ui->doubleSpinBox_noiseRadius->value());
02372         settings.setValue("cloudNoiseMinNeighbors", _ui->spinBox_noiseMinNeighbors->value());
02373         settings.setValue("cloudCeilingHeight",     _ui->doubleSpinBox_ceilingFilterHeight->value());
02374         settings.setValue("cloudFloorHeight",       _ui->doubleSpinBox_floorFilterHeight->value());
02375         settings.setValue("normalKSearch",          _ui->spinBox_normalKSearch->value());
02376         settings.setValue("normalRadiusSearch",     _ui->doubleSpinBox_normalRadiusSearch->value());
02377         settings.setValue("scanCeilingHeight",      _ui->doubleSpinBox_ceilingFilterHeight_scan->value());
02378         settings.setValue("scanFloorHeight",        _ui->doubleSpinBox_floorFilterHeight_scan->value());
02379         settings.setValue("scanNormalKSearch",      _ui->spinBox_normalKSearch_scan->value());
02380         settings.setValue("scanNormalRadiusSearch", _ui->doubleSpinBox_normalRadiusSearch_scan->value());
02381 
02382         settings.setValue("showGraphs", _ui->checkBox_showGraphs->isChecked());
02383         settings.setValue("showLabels", _ui->checkBox_showLabels->isChecked());
02384 
02385         settings.setValue("noFiltering",             _ui->radioButton_noFiltering->isChecked());
02386         settings.setValue("cloudFiltering",          _ui->radioButton_nodeFiltering->isChecked());
02387         settings.setValue("cloudFilteringRadius",    _ui->doubleSpinBox_cloudFilterRadius->value());
02388         settings.setValue("cloudFilteringAngle",     _ui->doubleSpinBox_cloudFilterAngle->value());
02389         settings.setValue("subtractFiltering",       _ui->radioButton_subtractFiltering->isChecked());
02390         settings.setValue("subtractFilteringMinPts", _ui->spinBox_subtractFilteringMinPts->value());
02391         settings.setValue("subtractFilteringRadius", _ui->doubleSpinBox_subtractFilteringRadius->value());
02392         settings.setValue("subtractFilteringAngle",  _ui->doubleSpinBox_subtractFilteringAngle->value());
02393 
02394         settings.setValue("gridMapShown",                _ui->checkBox_map_shown->isChecked());
02395         settings.setValue("gridMapOpacity",              _ui->doubleSpinBox_map_opacity->value());
02396 
02397         settings.setValue("octomap",                     _ui->groupBox_octomap->isChecked());
02398         settings.setValue("octomap_depth",               _ui->spinBox_octomap_treeDepth->value());
02399         settings.setValue("octomap_2dgrid",              _ui->checkBox_octomap_2dgrid->isChecked());
02400         settings.setValue("octomap_3dmap",               _ui->checkBox_octomap_show3dMap->isChecked());
02401         settings.setValue("octomap_rendering_type",      _ui->comboBox_octomap_renderingType->currentIndex());
02402         settings.setValue("octomap_point_size",          _ui->spinBox_octomap_pointSize->value());
02403 
02404 
02405         settings.setValue("meshing",               _ui->groupBox_organized->isChecked());
02406         settings.setValue("meshing_angle",         _ui->doubleSpinBox_mesh_angleTolerance->value());
02407         settings.setValue("meshing_quad",          _ui->checkBox_mesh_quad->isChecked());
02408         settings.setValue("meshing_texture",       _ui->checkBox_mesh_texture->isChecked());
02409         settings.setValue("meshing_triangle_size", _ui->spinBox_mesh_triangleSize->value());
02410 
02411         settings.endGroup(); // General
02412 
02413         settings.endGroup(); // rtabmap
02414 }
02415 
02416 void PreferencesDialog::writeCameraSettings(const QString & filePath) const
02417 {
02418         QString path = getIniFilePath();
02419         if(!filePath.isEmpty())
02420         {
02421                 path = filePath;
02422         }
02423         QSettings settings(path, QSettings::IniFormat);
02424 
02425         settings.beginGroup("Camera");
02426         settings.remove("");
02427         settings.setValue("imgRate",             _ui->general_doubleSpinBox_imgRate->value());
02428         settings.setValue("mirroring",       _ui->source_mirroring->isChecked());
02429         settings.setValue("calibrationName", _ui->lineEdit_calibrationFile->text());
02430         settings.setValue("type",            _ui->comboBox_sourceType->currentIndex());
02431         settings.setValue("device",              _ui->lineEdit_sourceDevice->text());
02432         settings.setValue("localTransform",  _ui->lineEdit_sourceLocalTransform->text());
02433         settings.setValue("imageDecimation",  _ui->spinBox_source_imageDecimation->value());
02434 
02435         settings.beginGroup("rgbd");
02436         settings.setValue("driver",            _ui->comboBox_cameraRGBD->currentIndex());
02437         settings.setValue("rgbdColorOnly",     _ui->checkbox_rgbd_colorOnly->isChecked());
02438         settings.setValue("distortion_model",  _ui->lineEdit_source_distortionModel->text());
02439         settings.setValue("bilateral",         _ui->groupBox_bilateral->isChecked());
02440         settings.setValue("bilateral_sigma_s", _ui->doubleSpinBox_bilateral_sigmaS->value());
02441         settings.setValue("bilateral_sigma_r", _ui->doubleSpinBox_bilateral_sigmaR->value());
02442         settings.endGroup(); // rgbd
02443 
02444         settings.beginGroup("stereo");
02445         settings.setValue("driver",     _ui->comboBox_cameraStereo->currentIndex());
02446         settings.setValue("depthGenerated", _ui->checkbox_stereo_depthGenerated->isChecked());
02447         settings.setValue("exposureCompensation", _ui->checkBox_stereo_exposureCompensation->isChecked());
02448         settings.endGroup(); // stereo
02449 
02450         settings.beginGroup("rgb");
02451         settings.setValue("driver",     _ui->source_comboBox_image_type->currentIndex());
02452         settings.setValue("rectify",        _ui->checkBox_rgb_rectify->isChecked());
02453         settings.endGroup(); // rgb
02454 
02455         settings.beginGroup("Openni");
02456         settings.setValue("oniPath",    _ui->lineEdit_openniOniPath->text());
02457         settings.endGroup(); // Openni
02458 
02459         settings.beginGroup("Openni2");
02460         settings.setValue("autoWhiteBalance", _ui->openni2_autoWhiteBalance->isChecked());
02461         settings.setValue("autoExposure",         _ui->openni2_autoExposure->isChecked());
02462         settings.setValue("exposure",             _ui->openni2_exposure->value());
02463         settings.setValue("gain",                     _ui->openni2_gain->value());
02464         settings.setValue("mirroring",            _ui->openni2_mirroring->isChecked());
02465         settings.setValue("stampsIdsUsed",    _ui->openni2_stampsIdsUsed->isChecked());
02466         settings.setValue("oniPath",              _ui->lineEdit_openni2OniPath->text());
02467         settings.setValue("hshift",           _ui->openni2_hshift->value());
02468         settings.setValue("vshift",           _ui->openni2_vshift->value());
02469         settings.endGroup(); // Openni2
02470 
02471         settings.beginGroup("Freenect2");
02472         settings.setValue("format",             _ui->comboBox_freenect2Format->currentIndex());
02473         settings.setValue("minDepth",           _ui->doubleSpinBox_freenect2MinDepth->value());
02474         settings.setValue("maxDepth",           _ui->doubleSpinBox_freenect2MaxDepth->value());
02475         settings.setValue("bilateralFiltering", _ui->checkBox_freenect2BilateralFiltering->isChecked());
02476         settings.setValue("edgeAwareFiltering", _ui->checkBox_freenect2EdgeAwareFiltering->isChecked());
02477         settings.setValue("noiseFiltering",     _ui->checkBox_freenect2NoiseFiltering->isChecked());
02478         settings.setValue("pipeline",           _ui->lineEdit_freenect2Pipeline->text());
02479         settings.endGroup(); // Freenect2
02480 
02481         settings.beginGroup("K4W2");
02482         settings.setValue("format",                             _ui->comboBox_k4w2Format->currentIndex());
02483         settings.endGroup(); // K4W2
02484 
02485         settings.beginGroup("RealSense");
02486         settings.setValue("presetRGB",           _ui->comboBox_realsensePresetRGB->currentIndex());
02487         settings.setValue("presetDepth",         _ui->comboBox_realsensePresetDepth->currentIndex());
02488         settings.setValue("odom",                _ui->checkbox_realsenseOdom->isChecked());
02489         settings.setValue("depthScaled",         _ui->checkbox_realsenseDepthScaledToRGBSize->isChecked());
02490         settings.setValue("rgbSource",           _ui->comboBox_realsenseRGBSource->currentIndex());
02491         settings.endGroup(); // RealSense
02492 
02493         settings.beginGroup("RealSense2");
02494         settings.setValue("emitter",                _ui->checkbox_rs2_emitter->isChecked());
02495         settings.setValue("irdepth",                _ui->checkbox_rs2_irDepth->isChecked());
02496         settings.endGroup(); // RealSense2
02497 
02498         settings.beginGroup("RGBDImages");
02499         settings.setValue("path_rgb",            _ui->lineEdit_cameraRGBDImages_path_rgb->text());
02500         settings.setValue("path_depth",          _ui->lineEdit_cameraRGBDImages_path_depth->text());
02501         settings.setValue("scale",               _ui->doubleSpinBox_cameraRGBDImages_scale->value());
02502         settings.setValue("start_index",         _ui->spinBox_cameraRGBDImages_startIndex->value());
02503         settings.endGroup(); // RGBDImages
02504 
02505         settings.beginGroup("StereoImages");
02506         settings.setValue("path_left",      _ui->lineEdit_cameraStereoImages_path_left->text());
02507         settings.setValue("path_right",     _ui->lineEdit_cameraStereoImages_path_right->text());
02508         settings.setValue("rectify",        _ui->checkBox_stereo_rectify->isChecked());
02509         settings.setValue("start_index",    _ui->spinBox_cameraStereoImages_startIndex->value());
02510         settings.endGroup(); // StereoImages
02511 
02512         settings.beginGroup("StereoVideo");
02513         settings.setValue("path",                       _ui->lineEdit_cameraStereoVideo_path->text());
02514         settings.setValue("path2",                      _ui->lineEdit_cameraStereoVideo_path_2->text());
02515         settings.setValue("device2",            _ui->spinBox_stereo_right_device->value());
02516         settings.endGroup(); // StereoVideo
02517 
02518         settings.beginGroup("StereoZed");
02519         settings.setValue("resolution", _ui->comboBox_stereoZed_resolution->currentIndex());
02520         settings.setValue("quality", _ui->comboBox_stereoZed_quality->currentIndex());
02521         settings.setValue("self_calibration", _ui->checkbox_stereoZed_selfCalibration->isChecked());
02522         settings.setValue("sensing_mode", _ui->comboBox_stereoZed_sensingMode->currentIndex());
02523         settings.setValue("confidence_thr", _ui->spinBox_stereoZed_confidenceThr->value());
02524         settings.setValue("odom", _ui->checkbox_stereoZed_odom->isChecked());
02525         settings.setValue("svo_path", _ui->lineEdit_zedSvoPath->text());
02526         settings.endGroup(); // StereoZed
02527 
02528         
02529 
02530         settings.beginGroup("Images");
02531         settings.setValue("path",                       _ui->source_images_lineEdit_path->text());
02532         settings.setValue("startPos",           _ui->source_images_spinBox_startPos->value());
02533         settings.setValue("bayerMode",      _ui->comboBox_cameraImages_bayerMode->currentIndex());
02534         settings.setValue("filenames_as_stamps", _ui->checkBox_cameraImages_timestamps->isChecked());
02535         settings.setValue("sync_stamps",    _ui->checkBox_cameraImages_syncTimeStamps->isChecked());
02536         settings.setValue("stamps",              _ui->lineEdit_cameraImages_timestamps->text());
02537         settings.setValue("path_scans",          _ui->lineEdit_cameraImages_path_scans->text());
02538         settings.setValue("scan_transform",      _ui->lineEdit_cameraImages_laser_transform->text());
02539         settings.setValue("scan_max_pts",        _ui->spinBox_cameraImages_max_scan_pts->value());
02540         settings.setValue("scan_downsample_step", _ui->spinBox_cameraImages_scanDownsampleStep->value());
02541         settings.setValue("scan_voxel_size",     _ui->doubleSpinBox_cameraImages_scanVoxelSize->value());
02542         settings.setValue("odom_path",           _ui->lineEdit_cameraImages_odom->text());
02543         settings.setValue("odom_format",         _ui->comboBox_cameraImages_odomFormat->currentIndex());
02544         settings.setValue("gt_path",             _ui->lineEdit_cameraImages_gt->text());
02545         settings.setValue("gt_format",           _ui->comboBox_cameraImages_gtFormat->currentIndex());
02546         settings.setValue("max_pose_time_diff",  _ui->doubleSpinBox_maxPoseTimeDiff->value());
02547         settings.setValue("imu_path",            _ui->lineEdit_cameraImages_path_imu->text());
02548         settings.setValue("imu_local_transform", _ui->lineEdit_cameraImages_imu_transform->text());
02549         settings.setValue("imu_rate",            _ui->spinBox_cameraImages_max_imu_rate->value());
02550         settings.endGroup(); // images
02551 
02552         settings.beginGroup("Video");
02553         settings.setValue("path",                       _ui->source_video_lineEdit_path->text());
02554         settings.endGroup(); // video
02555 
02556         settings.beginGroup("ScanFromDepth");
02557         settings.setValue("enabled",                    _ui->groupBox_scanFromDepth->isChecked());
02558         settings.setValue("decimation",                 _ui->spinBox_cameraScanFromDepth_decimation->value());
02559         settings.setValue("maxDepth",                   _ui->doubleSpinBox_cameraSCanFromDepth_maxDepth->value());
02560         settings.setValue("voxelSize",                  _ui->doubleSpinBox_cameraImages_scanVoxelSize->value());
02561         settings.setValue("normalsK",                   _ui->spinBox_cameraImages_scanNormalsK->value());
02562         settings.setValue("normalsRadius",              _ui->doubleSpinBox_cameraImages_scanNormalsRadius->value());
02563         settings.setValue("normalsUp",          _ui->checkBox_cameraImages_scanForceGroundNormalsUp->isChecked());
02564         settings.endGroup();
02565 
02566         settings.beginGroup("DepthFromScan");
02567         settings.setValue("depthFromScan", _ui->groupBox_depthFromScan->isChecked());
02568         settings.setValue("depthFromScanFillHoles", _ui->groupBox_depthFromScan_fillHoles->isChecked());
02569         settings.setValue("depthFromScanVertical", _ui->radioButton_depthFromScan_vertical->isChecked());
02570         settings.setValue("depthFromScanHorizontal", _ui->radioButton_depthFromScan_horizontal->isChecked());
02571         settings.setValue("depthFromScanFillBorders", _ui->checkBox_depthFromScan_fillBorders->isChecked());
02572         settings.endGroup();
02573 
02574         settings.beginGroup("Database");
02575         settings.setValue("path",                          _ui->source_database_lineEdit_path->text());
02576         settings.setValue("ignoreOdometry",    _ui->source_checkBox_ignoreOdometry->isChecked());
02577         settings.setValue("ignoreGoalDelay",   _ui->source_checkBox_ignoreGoalDelay->isChecked());
02578         settings.setValue("ignoreGoals",       _ui->source_checkBox_ignoreGoals->isChecked());
02579         settings.setValue("startPos",          _ui->source_spinBox_databaseStartPos->value());
02580         settings.setValue("cameraIndex",       _ui->source_spinBox_database_cameraIndex->value());
02581         settings.setValue("useDatabaseStamps", _ui->source_checkBox_useDbStamps->isChecked());
02582         settings.endGroup(); // Database
02583 
02584         settings.endGroup(); // Camera
02585 
02586         _calibrationDialog->saveSettings(settings, "CalibrationDialog");
02587 }
02588 
02589 void PreferencesDialog::writeCoreSettings(const QString & filePath) const
02590 {
02591         QString path = getIniFilePath();
02592         if(!filePath.isEmpty())
02593         {
02594                 path = filePath;
02595         }
02596 
02597         Parameters::writeINI(path.toStdString(), this->getAllParameters());
02598 }
02599 
02600 bool PreferencesDialog::validateForm()
02601 {
02602 #ifndef RTABMAP_NONFREE
02603         // verify that SURF/SIFT cannot be selected if not built with OpenCV nonfree module
02604         // BOW dictionary type
02605         if(_ui->comboBox_detector_strategy->currentIndex() <= 1)
02606         {
02607                 QMessageBox::warning(this, tr("Parameter warning"),
02608                                 tr("Selected feature type (SURF/SIFT) is not available. RTAB-Map is not built "
02609                                    "with the nonfree module from OpenCV. ORB is set instead for the bag-of-words dictionary."));
02610                 _ui->comboBox_detector_strategy->setCurrentIndex(Feature2D::kFeatureOrb);
02611         }
02612         // BOW Reextract features type
02613         if(_ui->reextract_type->currentIndex() <= 1)
02614         {
02615                 QMessageBox::warning(this, tr("Parameter warning"),
02616                                 tr("Selected feature type (SURF/SIFT) is not available. RTAB-Map is not built "
02617                                    "with the nonfree module from OpenCV. Fast/Brief is set instead for the re-extraction "
02618                                    "of features on loop closure."));
02619                 _ui->reextract_type->setCurrentIndex(Feature2D::kFeatureFastBrief);
02620         }
02621 #endif
02622 
02623 #if CV_MAJOR_VERSION < 3
02624         if (_ui->comboBox_detector_strategy->currentIndex() == Feature2D::kFeatureKaze)
02625         {
02626 #ifdef RTABMAP_NONFREE
02627                 QMessageBox::warning(this, tr("Parameter warning"),
02628                         tr("Selected feature type (KAZE) is not available on OpenCV2. SURF is set instead "
02629                                 "for the bag-of-words dictionary."));
02630                 _ui->comboBox_detector_strategy->setCurrentIndex(Feature2D::kFeatureSurf);
02631 #else
02632                 QMessageBox::warning(this, tr("Parameter warning"),
02633                         tr("Selected feature type (KAZE) is not available on OpenCV2. ORB is set instead "
02634                                 "for the bag-of-words dictionary."));
02635                 _ui->comboBox_detector_strategy->setCurrentIndex(Feature2D::kFeatureOrb);
02636 #endif
02637         }
02638         if (_ui->reextract_type->currentIndex() == Feature2D::kFeatureKaze)
02639         {
02640 #ifdef RTABMAP_NONFREE
02641                 QMessageBox::warning(this, tr("Parameter warning"),
02642                         tr("Selected feature type (KAZE) is not available on OpenCV2. SURF is set instead "
02643                                 "for the re-extraction of features on loop closure."));
02644                                 _ui->reextract_type->setCurrentIndex(Feature2D::kFeatureSurf);
02645 #else
02646                 QMessageBox::warning(this, tr("Parameter warning"),
02647                         tr("Selected feature type (KAZE) is not available on OpenCV2. ORB is set instead "
02648                                 "for the re-extraction of features on loop closure."));
02649                                 _ui->reextract_type->setCurrentIndex(Feature2D::kFeatureOrb);
02650 #endif
02651         }
02652 #endif
02653 
02654         // optimization strategy
02655         if(_ui->graphOptimization_type->currentIndex() == 0 && !Optimizer::isAvailable(Optimizer::kTypeTORO))
02656         {
02657                 if(Optimizer::isAvailable(Optimizer::kTypeGTSAM))
02658                 {
02659                         QMessageBox::warning(this, tr("Parameter warning"),
02660                                         tr("Selected graph optimization strategy (TORO) is not available. RTAB-Map is not built "
02661                                            "with TORO. GTSAM is set instead for graph optimization strategy."));
02662                         _ui->graphOptimization_type->setCurrentIndex(Optimizer::kTypeGTSAM);
02663                 }
02664 #ifndef RTABMAP_ORB_SLAM2
02665                 else if(Optimizer::isAvailable(Optimizer::kTypeG2O))
02666                 {
02667                         QMessageBox::warning(this, tr("Parameter warning"),
02668                                         tr("Selected graph optimization strategy (TORO) is not available. RTAB-Map is not built "
02669                                            "with TORO. g2o is set instead for graph optimization strategy."));
02670                         _ui->graphOptimization_type->setCurrentIndex(Optimizer::kTypeG2O);
02671                 }
02672 #endif
02673         }
02674 #ifdef RTABMAP_ORB_SLAM2
02675         if(_ui->graphOptimization_type->currentIndex() == 1)
02676 #else
02677         if(_ui->graphOptimization_type->currentIndex() == 1 && !Optimizer::isAvailable(Optimizer::kTypeG2O))
02678 #endif
02679         {
02680                 if(Optimizer::isAvailable(Optimizer::kTypeGTSAM))
02681                 {
02682                         QMessageBox::warning(this, tr("Parameter warning"),
02683                                         tr("Selected graph optimization strategy (g2o) is not available. RTAB-Map is not built "
02684                                            "with g2o. GTSAM is set instead for graph optimization strategy."));
02685                         _ui->graphOptimization_type->setCurrentIndex(Optimizer::kTypeGTSAM);
02686                 }
02687                 else if(Optimizer::isAvailable(Optimizer::kTypeTORO))
02688                 {
02689                         QMessageBox::warning(this, tr("Parameter warning"),
02690                                         tr("Selected graph optimization strategy (g2o) is not available. RTAB-Map is not built "
02691                                            "with g2o. TORO is set instead for graph optimization strategy."));
02692                         _ui->graphOptimization_type->setCurrentIndex(Optimizer::kTypeTORO);
02693                 }
02694         }
02695         if(_ui->graphOptimization_type->currentIndex() == 2 && !Optimizer::isAvailable(Optimizer::kTypeGTSAM))
02696         {
02697 #ifndef RTABMAP_ORB_SLAM2
02698                 if(Optimizer::isAvailable(Optimizer::kTypeG2O))
02699                 {
02700                         QMessageBox::warning(this, tr("Parameter warning"),
02701                                         tr("Selected graph optimization strategy (GTSAM) is not available. RTAB-Map is not built "
02702                                            "with GTSAM. g2o is set instead for graph optimization strategy."));
02703                         _ui->graphOptimization_type->setCurrentIndex(Optimizer::kTypeG2O);
02704                 }
02705                 else
02706 #endif
02707                         if(Optimizer::isAvailable(Optimizer::kTypeTORO))
02708                 {
02709                         QMessageBox::warning(this, tr("Parameter warning"),
02710                                         tr("Selected graph optimization strategy (GTSAM) is not available. RTAB-Map is not built "
02711                                            "with GTSAM. TORO is set instead for graph optimization strategy."));
02712                         _ui->graphOptimization_type->setCurrentIndex(Optimizer::kTypeTORO);
02713                 }
02714         }
02715 
02716         // Registration bundle adjustment strategy
02717         if(_ui->loopClosure_bundle->currentIndex() == 1 && !Optimizer::isAvailable(Optimizer::kTypeG2O))
02718         {
02719                 QMessageBox::warning(this, tr("Parameter warning"),
02720                                 tr("Selected visual registration bundle adjustment optimization strategy (g2o) is not available. RTAB-Map is not built "
02721                                    "with g2o. Bundle adjustment is disabled."));
02722                 _ui->loopClosure_bundle->setCurrentIndex(0);
02723         }
02724         if(_ui->loopClosure_bundle->currentIndex() == 2 && !Optimizer::isAvailable(Optimizer::kTypeCVSBA))
02725         {
02726                 QMessageBox::warning(this, tr("Parameter warning"),
02727                                 tr("Selected visual registration bundle adjustment optimization strategy (cvsba) is not available. RTAB-Map is not built "
02728                                    "with cvsba. Bundle adjustment is disabled."));
02729                 _ui->loopClosure_bundle->setCurrentIndex(0);
02730         }
02731 
02732         // Local bundle adjustment strategy for odometry F2M
02733         if(_ui->odom_f2m_bundleStrategy->currentIndex() == 1 && !Optimizer::isAvailable(Optimizer::kTypeG2O))
02734         {
02735                 QMessageBox::warning(this, tr("Parameter warning"),
02736                                 tr("Selected odometry local bundle adjustment optimization strategy (g2o) is not available. RTAB-Map is not built "
02737                                    "with g2o. Bundle adjustment is disabled."));
02738                 _ui->odom_f2m_bundleStrategy->setCurrentIndex(0);
02739         }
02740         if(_ui->odom_f2m_bundleStrategy->currentIndex() == 2 && !Optimizer::isAvailable(Optimizer::kTypeCVSBA))
02741         {
02742                 QMessageBox::warning(this, tr("Parameter warning"),
02743                                 tr("Selected odometry local bundle adjustment optimization strategy (cvsba) is not available. RTAB-Map is not built "
02744                                    "with cvsba. Bundle adjustment is disabled."));
02745                 _ui->odom_f2m_bundleStrategy->setCurrentIndex(0);
02746         }
02747 
02748         // verify that Robust and Reject threshold are not set at the same time
02749         if(_ui->graphOptimization_robust->isChecked() && _ui->graphOptimization_maxError->value()>0.0)
02750         {
02751                 QMessageBox::warning(this, tr("Parameter warning"),
02752                                 tr("Robust graph optimization and maximum optimization error threshold cannot be "
02753                                    "both used at the same time. Disabling robust optimization."));
02754                 _ui->graphOptimization_robust->setChecked(false);
02755         }
02756 
02757         //verify binary features and nearest neighbor
02758         // BOW dictionary type
02759         if(_ui->comboBox_dictionary_strategy->currentIndex() == VWDictionary::kNNFlannLSH && _ui->comboBox_detector_strategy->currentIndex() <= 1)
02760         {
02761                 QMessageBox::warning(this, tr("Parameter warning"),
02762                                 tr("With the selected feature type (SURF or SIFT), parameter \"Visual word->Nearest Neighbor\" "
02763                                    "cannot be LSH (used for binary descriptor). KD-tree is set instead for the bag-of-words dictionary."));
02764                 _ui->comboBox_dictionary_strategy->setCurrentIndex(VWDictionary::kNNFlannKdTree);
02765         }
02766 
02767         // BOW Reextract features type
02768         if(_ui->reextract_nn->currentIndex() == VWDictionary::kNNFlannLSH && _ui->reextract_type->currentIndex() <= 1)
02769         {
02770                 QMessageBox::warning(this, tr("Parameter warning"),
02771                                 tr("With the selected feature type (SURF or SIFT), parameter \"Visual word->Nearest Neighbor\" "
02772                                    "cannot be LSH (used for binary descriptor). KD-tree is set instead for the re-extraction "
02773                                            "of features on loop closure."));
02774                 _ui->reextract_nn->setCurrentIndex(VWDictionary::kNNFlannKdTree);
02775         }
02776 
02777         if(_ui->doubleSpinBox_freenect2MinDepth->value() >= _ui->doubleSpinBox_freenect2MaxDepth->value())
02778         {
02779                 QMessageBox::warning(this, tr("Parameter warning"),
02780                                 tr("Freenect2 minimum depth (%1 m) should be lower than maximum depth (%2 m). Setting maximum depth to %3 m.")
02781                                    .arg(_ui->doubleSpinBox_freenect2MinDepth->value())
02782                                    .arg(_ui->doubleSpinBox_freenect2MaxDepth->value())
02783                                    .arg(_ui->doubleSpinBox_freenect2MaxDepth->value()+1));
02784                 _ui->doubleSpinBox_freenect2MaxDepth->setValue(_ui->doubleSpinBox_freenect2MaxDepth->value()+1);
02785         }
02786 
02787         if(_ui->surf_doubleSpinBox_maxDepth->value() > 0.0 &&
02788            _ui->surf_doubleSpinBox_minDepth->value() >= _ui->surf_doubleSpinBox_maxDepth->value())
02789         {
02790                 QMessageBox::warning(this, tr("Parameter warning"),
02791                                 tr("Visual word minimum depth (%1 m) should be lower than maximum depth (%2 m). Setting maximum depth to %3 m.")
02792                                    .arg(_ui->surf_doubleSpinBox_minDepth->value())
02793                                    .arg(_ui->surf_doubleSpinBox_maxDepth->value())
02794                                    .arg(_ui->surf_doubleSpinBox_maxDepth->value()+1));
02795                 _ui->doubleSpinBox_freenect2MinDepth->setValue(0);
02796         }
02797 
02798         if(_ui->loopClosure_bowMaxDepth->value() > 0.0 &&
02799            _ui->loopClosure_bowMinDepth->value() >= _ui->loopClosure_bowMaxDepth->value())
02800         {
02801                 QMessageBox::warning(this, tr("Parameter warning"),
02802                                 tr("Visual registration word minimum depth (%1 m) should be lower than maximum depth (%2 m). Setting maximum depth to %3 m.")
02803                                    .arg(_ui->loopClosure_bowMinDepth->value())
02804                                    .arg(_ui->loopClosure_bowMaxDepth->value())
02805                                    .arg(_ui->loopClosure_bowMaxDepth->value()+1));
02806                 _ui->loopClosure_bowMinDepth->setValue(0);
02807         }
02808 
02809         if(_ui->fastThresholdMax->value() < _ui->fastThresholdMin->value())
02810         {
02811                 QMessageBox::warning(this, tr("Parameter warning"),
02812                                 tr("FAST minimum threshold cannot be lower than maximum threshold. Setting minimum to 1."));
02813                 _ui->fastThresholdMin->setValue(1);
02814         }
02815         if(_ui->fastThreshold->value() > _ui->fastThresholdMax->value())
02816         {
02817                 QMessageBox::warning(this, tr("Parameter warning"),
02818                                 tr("FAST threshold cannot be higher than maximum threshold. Maximum value set to current threshold."));
02819                 _ui->fastThresholdMax->setValue(_ui->fastThreshold->value());
02820         }
02821         if(_ui->fastThreshold->value() < _ui->fastThresholdMin->value())
02822         {
02823                 QMessageBox::warning(this, tr("Parameter warning"),
02824                                 tr("FAST threshold cannot be lower than minimum threshold. Minimum value set to current threshold."));
02825                 _ui->fastThresholdMin->setValue(_ui->fastThreshold->value());
02826         }
02827 
02828         if(_ui->checkbox_odomDisabled->isChecked() &&
02829                 _ui->general_checkBox_SLAM_mode->isChecked() &&
02830                 _ui->general_checkBox_activateRGBD->isChecked())
02831         {
02832                 QMessageBox::warning(this, tr("Parameter warning"),
02833                                 tr("Odometry is disabled but incremental RGB-D SLAM is activated! Re-enabling odometry."));
02834                 _ui->checkbox_odomDisabled->setChecked(false);
02835         }
02836 
02837         return true;
02838 }
02839 
02840 QString PreferencesDialog::getParamMessage()
02841 {
02842         return tr("Reading parameters from the configuration file...");
02843 }
02844 
02845 void PreferencesDialog::showEvent ( QShowEvent * event )
02846 {
02847         if(_monitoringState)
02848         {
02849                 // In monitoring state, you cannot change remote paths
02850                 _ui->lineEdit_dictionaryPath->setEnabled(false);
02851                 _ui->toolButton_dictionaryPath->setEnabled(false);
02852                 _ui->label_dictionaryPath->setEnabled(false);
02853 
02854                 _ui->groupBox_source0->setEnabled(false);
02855                 _ui->groupBox_odometry1->setEnabled(false);
02856 
02857                 _ui->checkBox_useOdomFeatures->setChecked(false);
02858                 _ui->checkBox_useOdomFeatures->setEnabled(false);
02859 
02860                 this->setWindowTitle(tr("Preferences [Monitoring mode]"));
02861         }
02862         else
02863         {
02864                 _ui->lineEdit_dictionaryPath->setEnabled(true);
02865                 _ui->toolButton_dictionaryPath->setEnabled(true);
02866                 _ui->label_dictionaryPath->setEnabled(true);
02867 
02868                 _ui->groupBox_source0->setEnabled(true);
02869                 _ui->groupBox_odometry1->setEnabled(true);
02870 
02871                 _ui->checkBox_useOdomFeatures->setEnabled(true);
02872 
02873                 this->setWindowTitle(tr("Preferences"));
02874         }
02875 
02876         // setup logger filter
02877         std::map<std::string, unsigned long> threads = ULogger::getRegisteredThreads();
02878         std::vector<std::string> threadsChecked = this->getGeneralLoggerThreads();
02879         std::set<std::string> threadsCheckedSet(threadsChecked.begin(), threadsChecked.end());
02880         _ui->comboBox_loggerFilter->clear();
02881         for(std::map<std::string, unsigned long>::iterator iter=threads.begin(); iter!=threads.end(); ++iter)
02882         {
02883                 if(threadsCheckedSet.find(iter->first.c_str()) != threadsCheckedSet.end())
02884                 {
02885                         _ui->comboBox_loggerFilter->addItem(QString(iter->first.c_str()), QVariant(true));
02886                 }
02887                 else
02888                 {
02889                         _ui->comboBox_loggerFilter->addItem(QString(iter->first.c_str()), QVariant(false));
02890                 }
02891         }
02892 
02893         this->readSettingsBegin();
02894 }
02895 
02896 void PreferencesDialog::readSettingsBegin()
02897 {
02898         _progressDialog->setLabelText(this->getParamMessage());
02899         _progressDialog->show();
02900 
02901         // this will let the MainThread to display the progress dialog before reading the parameters...
02902         QTimer::singleShot(10, this, SLOT(readSettingsEnd()));
02903 }
02904 
02905 void PreferencesDialog::readSettingsEnd()
02906 {
02907         QApplication::processEvents();
02908 
02909         this->readSettings(getTmpIniFilePath());
02910 
02911         _progressDialog->setValue(1);
02912         if(this->isVisible())
02913         {
02914                 _progressDialog->setLabelText(tr("Setup dialog..."));
02915 
02916                 this->updatePredictionPlot();
02917                 this->setupKpRoiPanel();
02918         }
02919 
02920         _progressDialog->setValue(2); // this will make closing...
02921 }
02922 
02923 void PreferencesDialog::saveWindowGeometry(const QWidget * window)
02924 {
02925         if(!window->objectName().isEmpty() && !window->isMaximized())
02926         {
02927                 QSettings settings(getIniFilePath(), QSettings::IniFormat);
02928                 settings.beginGroup("Gui");
02929                 settings.beginGroup(window->objectName());
02930                 settings.setValue("geometry", window->saveGeometry());
02931                 settings.endGroup(); // "windowName"
02932                 settings.endGroup(); // rtabmap
02933 
02934                 QSettings settingsTmp(getTmpIniFilePath(), QSettings::IniFormat);
02935                 settingsTmp.beginGroup("Gui");
02936                 settingsTmp.beginGroup(window->objectName());
02937                 settingsTmp.setValue("geometry", window->saveGeometry());
02938                 settingsTmp.endGroup(); // "windowName"
02939                 settingsTmp.endGroup(); // rtabmap
02940         }
02941 }
02942 
02943 void PreferencesDialog::loadWindowGeometry(QWidget * window)
02944 {
02945         if(!window->objectName().isEmpty())
02946         {
02947                 QByteArray bytes;
02948                 QSettings settings(getIniFilePath(), QSettings::IniFormat);
02949                 settings.beginGroup("Gui");
02950                 settings.beginGroup(window->objectName());
02951                 bytes = settings.value("geometry", QByteArray()).toByteArray();
02952                 if(!bytes.isEmpty())
02953                 {
02954                         window->restoreGeometry(bytes);
02955                 }
02956                 settings.endGroup(); // "windowName"
02957                 settings.endGroup(); // rtabmap
02958 
02959                 QSettings settingsTmp(getTmpIniFilePath(), QSettings::IniFormat);
02960                 settingsTmp.beginGroup("Gui");
02961                 settingsTmp.beginGroup(window->objectName());
02962                 settingsTmp.setValue("geometry", window->saveGeometry());
02963                 settingsTmp.endGroup(); // "windowName"
02964                 settingsTmp.endGroup(); // rtabmap
02965         }
02966 }
02967 
02968 void PreferencesDialog::saveMainWindowState(const QMainWindow * mainWindow)
02969 {
02970         if(!mainWindow->objectName().isEmpty())
02971         {
02972                 saveWindowGeometry(mainWindow);
02973 
02974                 QSettings settings(getIniFilePath(), QSettings::IniFormat);
02975                 settings.beginGroup("Gui");
02976                 settings.beginGroup(mainWindow->objectName());
02977                 settings.setValue("state", mainWindow->saveState());
02978                 settings.setValue("maximized", mainWindow->isMaximized());
02979                 settings.setValue("status_bar", mainWindow->statusBar()->isVisible());
02980                 settings.endGroup(); // "MainWindow"
02981                 settings.endGroup(); // rtabmap
02982 
02983                 QSettings settingsTmp(getTmpIniFilePath(), QSettings::IniFormat);
02984                 settingsTmp.beginGroup("Gui");
02985                 settingsTmp.beginGroup(mainWindow->objectName());
02986                 settingsTmp.setValue("state", mainWindow->saveState());
02987                 settingsTmp.setValue("maximized", mainWindow->isMaximized());
02988                 settingsTmp.setValue("status_bar", mainWindow->statusBar()->isVisible());
02989                 settingsTmp.endGroup(); // "MainWindow"
02990                 settingsTmp.endGroup(); // rtabmap
02991         }
02992 }
02993 
02994 void PreferencesDialog::loadMainWindowState(QMainWindow * mainWindow,  bool & maximized, bool & statusBarShown)
02995 {
02996         if(!mainWindow->objectName().isEmpty())
02997         {
02998                 loadWindowGeometry(mainWindow);
02999 
03000                 QByteArray bytes;
03001                 QSettings settings(getIniFilePath(), QSettings::IniFormat);
03002                 settings.beginGroup("Gui");
03003                 settings.beginGroup(mainWindow->objectName());
03004                 bytes = settings.value("state", QByteArray()).toByteArray();
03005                 if(!bytes.isEmpty())
03006                 {
03007                         mainWindow->restoreState(bytes);
03008                 }
03009                 maximized = settings.value("maximized", false).toBool();
03010                 statusBarShown = settings.value("status_bar", false).toBool();
03011                 mainWindow->statusBar()->setVisible(statusBarShown);
03012                 settings.endGroup(); // "MainWindow"
03013                 settings.endGroup(); // rtabmap
03014 
03015                 QSettings settingsTmp(getTmpIniFilePath(), QSettings::IniFormat);
03016                 settingsTmp.beginGroup("Gui");
03017                 settingsTmp.beginGroup(mainWindow->objectName());
03018                 settingsTmp.setValue("state", mainWindow->saveState());
03019                 settingsTmp.setValue("maximized", maximized);
03020                 settingsTmp.setValue("status_bar", statusBarShown);
03021                 settingsTmp.endGroup(); // "MainWindow"
03022                 settingsTmp.endGroup(); // rtabmap
03023         }
03024 }
03025 
03026 void PreferencesDialog::saveWidgetState(const QWidget * widget)
03027 {
03028         if(!widget->objectName().isEmpty())
03029         {
03030                 QSettings settings(getIniFilePath(), QSettings::IniFormat);
03031                 settings.beginGroup("Gui");
03032                 settings.beginGroup(widget->objectName());
03033 
03034                 QSettings settingsTmp(getTmpIniFilePath(), QSettings::IniFormat);
03035                 settingsTmp.beginGroup("Gui");
03036                 settingsTmp.beginGroup(widget->objectName());
03037 
03038                 const CloudViewer * cloudViewer = qobject_cast<const CloudViewer*>(widget);
03039                 const ImageView * imageView = qobject_cast<const ImageView*>(widget);
03040                 const ExportCloudsDialog * exportCloudsDialog = qobject_cast<const ExportCloudsDialog*>(widget);
03041                 const ExportBundlerDialog * exportBundlerDialog = qobject_cast<const ExportBundlerDialog*>(widget);
03042                 const PostProcessingDialog * postProcessingDialog = qobject_cast<const PostProcessingDialog *>(widget);
03043                 const GraphViewer * graphViewer = qobject_cast<const GraphViewer *>(widget);
03044                 const CalibrationDialog * calibrationDialog = qobject_cast<const CalibrationDialog *>(widget);
03045                 const DepthCalibrationDialog * depthCalibrationDialog = qobject_cast<const DepthCalibrationDialog *>(widget);
03046 
03047                 if(cloudViewer)
03048                 {
03049                         cloudViewer->saveSettings(settings);
03050                         cloudViewer->saveSettings(settingsTmp);
03051                 }
03052                 else if(imageView)
03053                 {
03054                         imageView->saveSettings(settings);
03055                         imageView->saveSettings(settingsTmp);
03056                 }
03057                 else if(exportCloudsDialog)
03058                 {
03059                         exportCloudsDialog->saveSettings(settings);
03060                         exportCloudsDialog->saveSettings(settingsTmp);
03061                 }
03062                 else if(exportBundlerDialog)
03063                 {
03064                         exportBundlerDialog->saveSettings(settings);
03065                         exportBundlerDialog->saveSettings(settingsTmp);
03066                 }
03067                 else if(postProcessingDialog)
03068                 {
03069                         postProcessingDialog->saveSettings(settings);
03070                         postProcessingDialog->saveSettings(settingsTmp);
03071                 }
03072                 else if(graphViewer)
03073                 {
03074                         graphViewer->saveSettings(settings);
03075                         graphViewer->saveSettings(settingsTmp);
03076                 }
03077                 else if(calibrationDialog)
03078                 {
03079                         calibrationDialog->saveSettings(settings);
03080                         calibrationDialog->saveSettings(settingsTmp);
03081                 }
03082                 else if(depthCalibrationDialog)
03083                 {
03084                         depthCalibrationDialog->saveSettings(settings);
03085                         depthCalibrationDialog->saveSettings(settingsTmp);
03086                 }
03087                 else
03088                 {
03089                         UERROR("Widget \"%s\" cannot be exported in config file.", widget->objectName().toStdString().c_str());
03090                 }
03091 
03092                 settings.endGroup(); // "name"
03093                 settings.endGroup(); // Gui
03094                 settingsTmp.endGroup();
03095                 settingsTmp.endGroup();
03096         }
03097 }
03098 
03099 void PreferencesDialog::loadWidgetState(QWidget * widget)
03100 {
03101         if(!widget->objectName().isEmpty())
03102         {
03103                 QByteArray bytes;
03104                 QSettings settings(getIniFilePath(), QSettings::IniFormat);
03105                 settings.beginGroup("Gui");
03106                 settings.beginGroup(widget->objectName());
03107 
03108                 QSettings settingsTmp(getTmpIniFilePath(), QSettings::IniFormat);
03109                 settingsTmp.beginGroup("Gui");
03110                 settingsTmp.beginGroup(widget->objectName());
03111 
03112                 CloudViewer * cloudViewer = qobject_cast<CloudViewer*>(widget);
03113                 ImageView * imageView = qobject_cast<ImageView*>(widget);
03114                 ExportCloudsDialog * exportCloudsDialog = qobject_cast<ExportCloudsDialog*>(widget);
03115                 ExportBundlerDialog * exportBundlerDialog = qobject_cast<ExportBundlerDialog*>(widget);
03116                 PostProcessingDialog * postProcessingDialog = qobject_cast<PostProcessingDialog *>(widget);
03117                 GraphViewer * graphViewer = qobject_cast<GraphViewer *>(widget);
03118                 CalibrationDialog * calibrationDialog = qobject_cast<CalibrationDialog *>(widget);
03119                 DepthCalibrationDialog * depthCalibrationDialog = qobject_cast<DepthCalibrationDialog *>(widget);
03120 
03121                 if(cloudViewer)
03122                 {
03123                         cloudViewer->loadSettings(settings);
03124                         cloudViewer->saveSettings(settingsTmp);
03125                 }
03126                 else if(imageView)
03127                 {
03128                         imageView->loadSettings(settings);
03129                         imageView->saveSettings(settingsTmp);
03130                 }
03131                 else if(exportCloudsDialog)
03132                 {
03133                         exportCloudsDialog->loadSettings(settings);
03134                         exportCloudsDialog->saveSettings(settingsTmp);
03135                 }
03136                 else if(exportBundlerDialog)
03137                 {
03138                         exportBundlerDialog->loadSettings(settings);
03139                         exportBundlerDialog->saveSettings(settingsTmp);
03140                 }
03141                 else if(postProcessingDialog)
03142                 {
03143                         postProcessingDialog->loadSettings(settings);
03144                         postProcessingDialog->saveSettings(settingsTmp);
03145                 }
03146                 else if(graphViewer)
03147                 {
03148                         graphViewer->loadSettings(settings);
03149                         graphViewer->saveSettings(settingsTmp);
03150                 }
03151                 else if(calibrationDialog)
03152                 {
03153                         calibrationDialog->loadSettings(settings);
03154                         calibrationDialog->saveSettings(settingsTmp);
03155                 }
03156                 else if(depthCalibrationDialog)
03157                 {
03158                         depthCalibrationDialog->loadSettings(settings);
03159                         depthCalibrationDialog->saveSettings(settingsTmp);
03160                 }
03161                 else
03162                 {
03163                         UERROR("Widget \"%s\" cannot be loaded from config file.", widget->objectName().toStdString().c_str());
03164                 }
03165 
03166                 settings.endGroup(); //"name"
03167                 settings.endGroup(); // Gui
03168                 settingsTmp.endGroup(); //"name"
03169                 settingsTmp.endGroup(); // Gui
03170         }
03171 }
03172 
03173 
03174 void PreferencesDialog::saveCustomConfig(const QString & section, const QString & key, const QString & value)
03175 {
03176         QSettings settings(getIniFilePath(), QSettings::IniFormat);
03177         settings.beginGroup("Gui");
03178         settings.beginGroup(section);
03179         settings.setValue(key, value);
03180         settings.endGroup(); // "section"
03181         settings.endGroup(); // rtabmap
03182 
03183         QSettings settingsTmp(getTmpIniFilePath(), QSettings::IniFormat);
03184         settingsTmp.beginGroup("Gui");
03185         settingsTmp.beginGroup(section);
03186         settingsTmp.setValue(key, value);
03187         settingsTmp.endGroup(); // "section"
03188         settingsTmp.endGroup(); // rtabmap
03189 }
03190 
03191 QString PreferencesDialog::loadCustomConfig(const QString & section, const QString & key)
03192 {
03193         QString value;
03194         QSettings settings(getIniFilePath(), QSettings::IniFormat);
03195         settings.beginGroup("Gui");
03196         settings.beginGroup(section);
03197         value = settings.value(key, QString()).toString();
03198         settings.endGroup(); // "section"
03199         settings.endGroup(); // rtabmap
03200 
03201         QSettings settingsTmp(getTmpIniFilePath(), QSettings::IniFormat);
03202         settingsTmp.beginGroup("Gui");
03203         settingsTmp.beginGroup(section);
03204         settingsTmp.setValue(key, value);
03205         settingsTmp.endGroup(); // "section"
03206         settingsTmp.endGroup(); // rtabmap
03207 
03208         return value;
03209 }
03210 
03211 rtabmap::ParametersMap PreferencesDialog::getAllParameters() const
03212 {
03213         if(_parameters.size() != Parameters::getDefaultParameters().size())
03214         {
03215                 UWARN("%d vs %d (Is PreferencesDialog::init() called?)", (int)_parameters.size(), (int)Parameters::getDefaultParameters().size());
03216         }
03217         ParametersMap parameters = _parameters;
03218         uInsert(parameters, _modifiedParameters);
03219 
03220         // It will be added manually for odometry
03221         parameters.erase(Parameters::kVisCorType());
03222 
03223         return parameters;
03224 }
03225 
03226 std::string PreferencesDialog::getParameter(const std::string & key) const
03227 {
03228         if(_modifiedParameters.find(key) != _modifiedParameters.end())
03229         {
03230                 return _modifiedParameters.at(key);
03231         }
03232 
03233         UASSERT(_parameters.find(key) != _parameters.end());
03234         return _parameters.at(key);
03235 }
03236 
03237 void PreferencesDialog::updateParameters(const ParametersMap & parameters, bool setOtherParametersToDefault)
03238 {
03239         if(parameters.size())
03240         {
03241                 for(rtabmap::ParametersMap::const_iterator iter = parameters.begin(); iter!=parameters.end(); ++iter)
03242                 {
03243                         this->setParameter(iter->first, iter->second);
03244                 }
03245                 if(setOtherParametersToDefault)
03246                 {
03247                         for(ParametersMap::const_iterator iter=Parameters::getDefaultParameters().begin();
03248                                 iter!=Parameters::getDefaultParameters().end();
03249                                 ++iter)
03250                         {
03251                                 if(parameters.find(iter->first) == parameters.end() &&
03252                                         iter->first.compare(Parameters::kRtabmapWorkingDirectory())!=0)
03253                                 {
03254                                         this->setParameter(iter->first, iter->second);
03255                                 }
03256                         }
03257                 }
03258                 if(!this->isVisible())
03259                 {
03260                         this->writeSettings(getTmpIniFilePath());
03261                 }
03262         }
03263 }
03264 
03265 void PreferencesDialog::selectSourceDriver(Src src)
03266 {
03267         if(src >= kSrcRGBD && src<kSrcStereo)
03268         {
03269                 _ui->comboBox_sourceType->setCurrentIndex(0);
03270                 _ui->comboBox_cameraRGBD->setCurrentIndex(src - kSrcRGBD);
03271                 if(src == kSrcOpenNI_PCL)
03272                 {
03273                         _ui->lineEdit_openniOniPath->clear();
03274                 }
03275                 else if(src == kSrcOpenNI2)
03276                 {
03277                         _ui->lineEdit_openni2OniPath->clear();
03278                 }
03279         }
03280         else if(src >= kSrcStereo && src<kSrcRGB)
03281         {
03282                 _ui->comboBox_sourceType->setCurrentIndex(1);
03283                 _ui->comboBox_cameraStereo->setCurrentIndex(src - kSrcStereo);
03284         }
03285         else if(src >= kSrcRGB && src<kSrcDatabase)
03286         {
03287                 _ui->comboBox_sourceType->setCurrentIndex(2);
03288                 _ui->source_comboBox_image_type->setCurrentIndex(src - kSrcRGB);
03289         }
03290         else if(src >= kSrcDatabase)
03291         {
03292                 _ui->comboBox_sourceType->setCurrentIndex(3);
03293         }
03294 
03295         if(validateForm())
03296         {
03297                 // Even if there is no change, MainWindow should be notified
03298                 makeObsoleteSourcePanel();
03299 
03300                 this->writeSettings(getTmpIniFilePath());
03301         }
03302         else
03303         {
03304                 this->readSettingsBegin();
03305         }
03306 }
03307 
03308 bool sortCallback(const std::string & a, const std::string & b)
03309 {
03310         return uStrNumCmp(a,b) < 0;
03311 }
03312 
03313 void PreferencesDialog::selectSourceDatabase()
03314 {
03315         QString dir = _ui->source_database_lineEdit_path->text();
03316         if(dir.isEmpty())
03317         {
03318                 dir = getWorkingDirectory();
03319         }
03320         QStringList paths = QFileDialog::getOpenFileNames(this, tr("Select file"), dir, tr("RTAB-Map database files (*.db)"));
03321         if(paths.size())
03322         {
03323                 int r = QMessageBox::question(this, tr("Odometry in database..."), tr("Use odometry saved in database (if some saved)?"), QMessageBox::Yes | QMessageBox::No, QMessageBox::Yes);
03324                 _ui->source_checkBox_ignoreOdometry->setChecked(r != QMessageBox::Yes);
03325                 
03326                 if (_ui->general_doubleSpinBox_detectionRate->value() != 0 && _ui->general_spinBox_imagesBufferSize->value() != 0)
03327                 {
03328                         r = QMessageBox::question(this, tr("Detection rate..."), 
03329                                 tr("Do you want to process all frames? \n\nClicking \"Yes\" will set "
03330                                         "RTAB-Map's detection rate (%1 Hz) and buffer size (%2) to 0 to make "
03331                                         "sure that all frames are processed.")
03332                                         .arg(_ui->general_doubleSpinBox_detectionRate->value())
03333                                         .arg(_ui->general_spinBox_imagesBufferSize->value()),
03334                                                 QMessageBox::Yes | QMessageBox::No, QMessageBox::Yes);
03335                         if (r == QMessageBox::Yes)
03336                         {
03337                                 _ui->general_doubleSpinBox_detectionRate->setValue(0.0);
03338                                 _ui->general_spinBox_imagesBufferSize->setValue(0);
03339                         }
03340                 }
03341 
03342                 if(paths.size() > 1)
03343                 {
03344                         std::vector<std::string> vFileNames(paths.size());
03345                         for(int i=0; i<paths.size(); ++i)
03346                         {
03347                                 vFileNames[i] = paths[i].toStdString();
03348                         }
03349                         std::sort(vFileNames.begin(), vFileNames.end(), sortCallback);
03350                         for(int i=0; i<paths.size(); ++i)
03351                         {
03352                                 paths[i] = vFileNames[i].c_str();
03353                         }
03354                 }
03355 
03356                 _ui->source_database_lineEdit_path->setText(paths.size()==1?paths.front():paths.join(";"));
03357                 _ui->source_spinBox_databaseStartPos->setValue(0);
03358                 _ui->source_spinBox_database_cameraIndex->setValue(-1);
03359         }
03360 }
03361 
03362 void PreferencesDialog::openDatabaseViewer()
03363 {
03364         DatabaseViewer * viewer = new DatabaseViewer(getIniFilePath(), this);
03365         viewer->setWindowModality(Qt::WindowModal);
03366         viewer->setAttribute(Qt::WA_DeleteOnClose, true);
03367         viewer->showCloseButton();
03368         if(viewer->openDatabase(_ui->source_database_lineEdit_path->text()))
03369         {
03370                 viewer->show();
03371         }
03372         else
03373         {
03374                 delete viewer;
03375         }
03376 }
03377 
03378 void PreferencesDialog::visualizeDistortionModel()
03379 {
03380         if(!_ui->lineEdit_source_distortionModel->text().isEmpty() &&
03381                         QFileInfo(_ui->lineEdit_source_distortionModel->text()).exists())
03382         {
03383                 clams::DiscreteDepthDistortionModel model;
03384                 model.load(_ui->lineEdit_source_distortionModel->text().toStdString());
03385                 if(model.isValid())
03386                 {
03387                         cv::Mat img = model.visualize();
03388                         QString name = QFileInfo(_ui->lineEdit_source_distortionModel->text()).baseName()+".png";
03389                         cv::imwrite(name.toStdString(), img);
03390                         QDesktopServices::openUrl(QUrl::fromLocalFile(name));
03391                 }
03392                 else
03393                 {
03394                         QMessageBox::warning(this, tr("Distortion Model"), tr("Model loaded from \"%1\" is not valid!").arg(_ui->lineEdit_source_distortionModel->text()));
03395                 }
03396         }
03397         else
03398         {
03399                 QMessageBox::warning(this, tr("Distortion Model"), tr("File \"%1\" doesn't exist!").arg(_ui->lineEdit_source_distortionModel->text()));
03400         }
03401 }
03402 
03403 void PreferencesDialog::selectCalibrationPath()
03404 {
03405         QString dir = _ui->lineEdit_calibrationFile->text();
03406         if(dir.isEmpty())
03407         {
03408                 dir = getWorkingDirectory()+"/camera_info";
03409         }
03410         else if(!dir.contains('.'))
03411         {
03412                 dir = getWorkingDirectory()+"/camera_info/"+dir;
03413         }
03414         QString path = QFileDialog::getOpenFileName(this, tr("Select file"), dir, tr("Calibration file (*.yaml)"));
03415         if(path.size())
03416         {
03417                 _ui->lineEdit_calibrationFile->setText(path);
03418         }
03419 }
03420 
03421 void PreferencesDialog::selectSourceImagesStamps()
03422 {
03423         QString dir = _ui->lineEdit_cameraImages_timestamps->text();
03424         if(dir.isEmpty())
03425         {
03426                 dir = getWorkingDirectory();
03427         }
03428         QString path = QFileDialog::getOpenFileName(this, tr("Select file"), dir, tr("Timestamps file (*.txt)"));
03429         if(path.size())
03430         {
03431                 _ui->lineEdit_cameraImages_timestamps->setText(path);
03432         }
03433 }
03434 
03435 void PreferencesDialog::selectSourceRGBDImagesPathRGB()
03436 {
03437         QString dir = _ui->lineEdit_cameraRGBDImages_path_rgb->text();
03438         if(dir.isEmpty())
03439         {
03440                 dir = getWorkingDirectory();
03441         }
03442         QString path = QFileDialog::getExistingDirectory(this, tr("Select RGB images directory"), dir);
03443         if(path.size())
03444         {
03445                 _ui->lineEdit_cameraRGBDImages_path_rgb->setText(path);
03446         }
03447 }
03448 
03449 
03450 void PreferencesDialog::selectSourceImagesPathScans()
03451 {
03452         QString dir = _ui->lineEdit_cameraImages_path_scans->text();
03453         if(dir.isEmpty())
03454         {
03455                 dir = getWorkingDirectory();
03456         }
03457         QString path = QFileDialog::getExistingDirectory(this, tr("Select scans directory"), dir);
03458         if(path.size())
03459         {
03460                 _ui->lineEdit_cameraImages_path_scans->setText(path);
03461         }
03462 }
03463 
03464 void PreferencesDialog::selectSourceImagesPathIMU()
03465 {
03466         QString dir = _ui->lineEdit_cameraImages_path_imu->text();
03467         if(dir.isEmpty())
03468         {
03469                 dir = getWorkingDirectory();
03470         }
03471         QString path = QFileDialog::getOpenFileName(this, tr("Select file "), dir, tr("EuRoC IMU file (*.csv)"));
03472         if(path.size())
03473         {
03474                 _ui->lineEdit_cameraImages_path_imu->setText(path);
03475         }
03476 }
03477 
03478 
03479 void PreferencesDialog::selectSourceRGBDImagesPathDepth()
03480 {
03481         QString dir = _ui->lineEdit_cameraRGBDImages_path_depth->text();
03482         if(dir.isEmpty())
03483         {
03484                 dir = getWorkingDirectory();
03485         }
03486         QString path = QFileDialog::getExistingDirectory(this, tr("Select depth images directory"), dir);
03487         if(path.size())
03488         {
03489                 _ui->lineEdit_cameraRGBDImages_path_depth->setText(path);
03490         }
03491 }
03492 
03493 void PreferencesDialog::selectSourceImagesPathOdom()
03494 {
03495         QString dir = _ui->lineEdit_cameraImages_odom->text();
03496         if(dir.isEmpty())
03497         {
03498                 dir = getWorkingDirectory();
03499         }
03500         QString path = QFileDialog::getOpenFileName(this, tr("Select file"), dir, tr("Odometry (*.txt *.log *.toro *.g2o *.csv)"));
03501         if(path.size())
03502         {
03503                 QStringList list;
03504                 for(int i=0; i<_ui->comboBox_cameraImages_odomFormat->count(); ++i)
03505                 {
03506                         list.push_back(_ui->comboBox_cameraImages_odomFormat->itemText(i));
03507                 }
03508                 QString item = QInputDialog::getItem(this, tr("Odometry Format"), tr("Format:"), list, _ui->comboBox_cameraImages_odomFormat->currentIndex(), false);
03509                 if(!item.isEmpty())
03510                 {
03511                         _ui->lineEdit_cameraImages_odom->setText(path);
03512                         _ui->comboBox_cameraImages_odomFormat->setCurrentIndex(_ui->comboBox_cameraImages_odomFormat->findText(item));
03513                 }
03514         }
03515 }
03516 
03517 void PreferencesDialog::selectSourceImagesPathGt()
03518 {
03519         QString dir = _ui->lineEdit_cameraImages_gt->text();
03520         if(dir.isEmpty())
03521         {
03522                 dir = getWorkingDirectory();
03523         }
03524         QString path = QFileDialog::getOpenFileName(this, tr("Select file"), dir, tr("Ground Truth (*.txt *.log *.toro *.g2o *.csv)"));
03525         if(path.size())
03526         {
03527                 QStringList list;
03528                 for(int i=0; i<_ui->comboBox_cameraImages_gtFormat->count(); ++i)
03529                 {
03530                         list.push_back(_ui->comboBox_cameraImages_gtFormat->itemText(i));
03531                 }
03532                 QString item = QInputDialog::getItem(this, tr("Ground Truth Format"), tr("Format:"), list, _ui->comboBox_cameraImages_gtFormat->currentIndex(), false);
03533                 if(!item.isEmpty())
03534                 {
03535                         _ui->lineEdit_cameraImages_gt->setText(path);
03536                         _ui->comboBox_cameraImages_gtFormat->setCurrentIndex(_ui->comboBox_cameraImages_gtFormat->findText(item));
03537                 }
03538         }
03539 }
03540 
03541 void PreferencesDialog::selectSourceStereoImagesPathLeft()
03542 {
03543         QString dir = _ui->lineEdit_cameraStereoImages_path_left->text();
03544         if(dir.isEmpty())
03545         {
03546                 dir = getWorkingDirectory();
03547         }
03548         QString path = QFileDialog::getExistingDirectory(this, tr("Select left images directory"), dir);
03549         if(path.size())
03550         {
03551                 _ui->lineEdit_cameraStereoImages_path_left->setText(path);
03552         }
03553 }
03554 
03555 void PreferencesDialog::selectSourceStereoImagesPathRight()
03556 {
03557         QString dir = _ui->lineEdit_cameraStereoImages_path_right->text();
03558         if(dir.isEmpty())
03559         {
03560                 dir = getWorkingDirectory();
03561         }
03562         QString path = QFileDialog::getExistingDirectory(this, tr("Select right images directory"), dir);
03563         if(path.size())
03564         {
03565                 _ui->lineEdit_cameraStereoImages_path_right->setText(path);
03566         }
03567 }
03568 
03569 void PreferencesDialog::selectSourceImagesPath()
03570 {
03571         QString dir = _ui->source_images_lineEdit_path->text();
03572         if(dir.isEmpty())
03573         {
03574                 dir = getWorkingDirectory();
03575         }
03576         QString path = QFileDialog::getExistingDirectory(this, tr("Select images directory"), _ui->source_images_lineEdit_path->text());
03577         if(!path.isEmpty())
03578         {
03579                 _ui->source_images_lineEdit_path->setText(path);
03580                 _ui->source_images_spinBox_startPos->setValue(0);
03581         }
03582 }
03583 
03584 void PreferencesDialog::selectSourceVideoPath()
03585 {
03586         QString dir = _ui->source_video_lineEdit_path->text();
03587         if(dir.isEmpty())
03588         {
03589                 dir = getWorkingDirectory();
03590         }
03591         QString path = QFileDialog::getOpenFileName(this, tr("Select file"), _ui->source_video_lineEdit_path->text(), tr("Videos (*.avi *.mpg *.mp4 *.mov *.mkv)"));
03592         if(!path.isEmpty())
03593         {
03594                 _ui->source_video_lineEdit_path->setText(path);
03595         }
03596 }
03597 
03598 void PreferencesDialog::selectSourceStereoVideoPath()
03599 {
03600         QString dir = _ui->lineEdit_cameraStereoVideo_path->text();
03601         if(dir.isEmpty())
03602         {
03603                 dir = getWorkingDirectory();
03604         }
03605         QString path = QFileDialog::getOpenFileName(this, tr("Select file"), _ui->lineEdit_cameraStereoVideo_path->text(), tr("Videos (*.avi *.mpg *.mp4 *.mov *.mkv)"));
03606         if(!path.isEmpty())
03607         {
03608                 _ui->lineEdit_cameraStereoVideo_path->setText(path);
03609         }
03610 }
03611 
03612 void PreferencesDialog::selectSourceStereoVideoPath2()
03613 {
03614         QString dir = _ui->lineEdit_cameraStereoVideo_path_2->text();
03615         if(dir.isEmpty())
03616         {
03617                 dir = getWorkingDirectory();
03618         }
03619         QString path = QFileDialog::getOpenFileName(this, tr("Select file"), _ui->lineEdit_cameraStereoVideo_path_2->text(), tr("Videos (*.avi *.mpg *.mp4 *.mov *.mkv)"));
03620         if(!path.isEmpty())
03621         {
03622                 _ui->lineEdit_cameraStereoVideo_path_2->setText(path);
03623         }
03624 }
03625 
03626 void PreferencesDialog::selectSourceDistortionModel()
03627 {
03628         QString dir = _ui->lineEdit_source_distortionModel->text();
03629         if(dir.isEmpty())
03630         {
03631                 dir = getWorkingDirectory();
03632         }
03633         QString path = QFileDialog::getOpenFileName(this, tr("Select file"), _ui->lineEdit_source_distortionModel->text(), tr("Distortion model (*.bin *.txt)"));
03634         if(!path.isEmpty())
03635         {
03636                 _ui->lineEdit_source_distortionModel->setText(path);
03637         }
03638 }
03639 
03640 void PreferencesDialog::selectSourceOniPath()
03641 {
03642         QString dir = _ui->lineEdit_openniOniPath->text();
03643         if(dir.isEmpty())
03644         {
03645                 dir = getWorkingDirectory();
03646         }
03647         QString path = QFileDialog::getOpenFileName(this, tr("Select file"), _ui->lineEdit_openniOniPath->text(), tr("OpenNI (*.oni)"));
03648         if(!path.isEmpty())
03649         {
03650                 _ui->lineEdit_openniOniPath->setText(path);
03651         }
03652 }
03653 
03654 void PreferencesDialog::selectSourceOni2Path()
03655 {
03656         QString dir = _ui->lineEdit_openni2OniPath->text();
03657         if(dir.isEmpty())
03658         {
03659                 dir = getWorkingDirectory();
03660         }
03661         QString path = QFileDialog::getOpenFileName(this, tr("Select file"), _ui->lineEdit_openni2OniPath->text(), tr("OpenNI (*.oni)"));
03662         if(!path.isEmpty())
03663         {
03664                 _ui->lineEdit_openni2OniPath->setText(path);
03665         }
03666 }
03667 
03668 void PreferencesDialog::selectSourceSvoPath()
03669 {
03670         QString dir = _ui->lineEdit_zedSvoPath->text();
03671         if(dir.isEmpty())
03672         {
03673                 dir = getWorkingDirectory();
03674         }
03675         QString path = QFileDialog::getOpenFileName(this, tr("Select file"), _ui->lineEdit_zedSvoPath->text(), tr("ZED (*.svo)"));
03676         if(!path.isEmpty())
03677         {
03678                 _ui->lineEdit_zedSvoPath->setText(path);
03679         }
03680 }
03681 
03682 void PreferencesDialog::setParameter(const std::string & key, const std::string & value)
03683 {
03684         UDEBUG("%s=%s", key.c_str(), value.c_str());
03685         QWidget * obj = _ui->stackedWidget->findChild<QWidget*>(key.c_str());
03686         if(obj)
03687         {
03688                 uInsert(_parameters, ParametersPair(key, value));
03689 
03690                 QSpinBox * spin = qobject_cast<QSpinBox *>(obj);
03691                 QDoubleSpinBox * doubleSpin = qobject_cast<QDoubleSpinBox *>(obj);
03692                 QComboBox * combo = qobject_cast<QComboBox *>(obj);
03693                 QCheckBox * check = qobject_cast<QCheckBox *>(obj);
03694                 QRadioButton * radio = qobject_cast<QRadioButton *>(obj);
03695                 QLineEdit * lineEdit = qobject_cast<QLineEdit *>(obj);
03696                 QGroupBox * groupBox = qobject_cast<QGroupBox *>(obj);
03697                 bool ok;
03698                 if(spin)
03699                 {
03700                         spin->setValue(QString(value.c_str()).toInt(&ok));
03701                         if(!ok)
03702                         {
03703                                 UERROR("Conversion failed from \"%s\" for parameter %s", value.c_str(), key.c_str());
03704                         }
03705                 }
03706                 else if(doubleSpin)
03707                 {
03708                         doubleSpin->setValue(QString(value.c_str()).toDouble(&ok));
03709                         if(!ok)
03710                         {
03711                                 UERROR("Conversion failed from \"%s\" for parameter %s", value.c_str(), key.c_str());
03712                         }
03713                 }
03714                 else if(combo)
03715                 {
03716                         int valueInt = QString(value.c_str()).toInt(&ok);
03717                         if(!ok)
03718                         {
03719                                 UERROR("Conversion failed from \"%s\" for parameter %s", value.c_str(), key.c_str());
03720                         }
03721                         else
03722                         {
03723 #ifndef RTABMAP_NONFREE
03724                                 if(valueInt <= 1 &&
03725                                                 (combo->objectName().toStdString().compare(Parameters::kKpDetectorStrategy()) == 0 ||
03726                                                  combo->objectName().toStdString().compare(Parameters::kVisFeatureType()) == 0))
03727                                 {
03728                                         UWARN("Trying to set \"%s\" to SIFT/SURF but RTAB-Map isn't built "
03729                                                   "with the nonfree module from OpenCV. Keeping default combo value: %s.",
03730                                                   combo->objectName().toStdString().c_str(),
03731                                                   combo->currentText().toStdString().c_str());
03732                                         ok = false;
03733                                 }
03734 #endif
03735 #ifndef RTABMAP_ORB_SLAM2
03736                                 if(!Optimizer::isAvailable(Optimizer::kTypeG2O))
03737 #endif
03738                                 {
03739                                         if(valueInt==1 && combo->objectName().toStdString().compare(Parameters::kOptimizerStrategy()) == 0)
03740                                         {
03741                                                 UWARN("Trying to set \"%s\" to g2o but RTAB-Map isn't built "
03742                                                           "with g2o. Keeping default combo value: %s.",
03743                                                           combo->objectName().toStdString().c_str(),
03744                                                           combo->currentText().toStdString().c_str());
03745                                                 ok = false;
03746                                         }
03747                                 }
03748                                 if(!Optimizer::isAvailable(Optimizer::kTypeGTSAM))
03749                                 {
03750                                         if(valueInt==2 && combo->objectName().toStdString().compare(Parameters::kOptimizerStrategy()) == 0)
03751                                         {
03752                                                 UWARN("Trying to set \"%s\" to GTSAM but RTAB-Map isn't built "
03753                                                           "with GTSAM. Keeping default combo value: %s.",
03754                                                           combo->objectName().toStdString().c_str(),
03755                                                           combo->currentText().toStdString().c_str());
03756                                                 ok = false;
03757                                         }
03758                                 }
03759                                 if(ok)
03760                                 {
03761                                         combo->setCurrentIndex(valueInt);
03762                                 }
03763                         }
03764 
03765                 }
03766                 else if(check)
03767                 {
03768                         _ui->checkBox_useOdomFeatures->blockSignals(true);
03769                         check->setChecked(uStr2Bool(value.c_str()));
03770                         _ui->checkBox_useOdomFeatures->blockSignals(false);
03771                 }
03772                 else if(radio)
03773                 {
03774                         radio->setChecked(uStr2Bool(value.c_str()));
03775                 }
03776                 else if(lineEdit)
03777                 {
03778                         lineEdit->setText(value.c_str());
03779                 }
03780                 else if(groupBox)
03781                 {
03782                         groupBox->setChecked(uStr2Bool(value.c_str()));
03783                 }
03784                 else
03785                 {
03786                         ULOGGER_WARN("QObject called %s can't be cast to a supported widget", key.c_str());
03787                 }
03788         }
03789         else
03790         {
03791                 ULOGGER_WARN("Can't find the related QObject for parameter %s", key.c_str());
03792         }
03793 }
03794 
03795 void PreferencesDialog::addParameter(int value)
03796 {
03797         if(sender())
03798         {
03799                 this->addParameter(sender(), value);
03800         }
03801         else
03802         {
03803                 ULOGGER_ERROR("This slot must be triggered by a signal, not a direct call...");
03804         }
03805 }
03806 
03807 void PreferencesDialog::addParameter(bool value)
03808 {
03809         if(sender())
03810         {
03811                 this->addParameter(sender(), value);
03812         }
03813         else
03814         {
03815                 ULOGGER_ERROR("This slot must be triggered by a signal, not a direct call...");
03816         }
03817 }
03818 
03819 void PreferencesDialog::addParameter(double value)
03820 {
03821         if(sender())
03822         {
03823                 this->addParameter(sender(), value);
03824         }
03825         else
03826         {
03827                 ULOGGER_ERROR("This slot must be triggered by a signal, not a direct call...");
03828         }
03829 }
03830 
03831 void PreferencesDialog::addParameter(const QString & value)
03832 {
03833         if(sender())
03834         {
03835                 this->addParameter(sender(), value);
03836         }
03837         else
03838         {
03839                 ULOGGER_ERROR("This slot must be triggered by a signal, not a direct call...");
03840         }
03841 }
03842 
03843 void PreferencesDialog::addParameter(const QObject * object, int value)
03844 {
03845         if(object)
03846         {
03847                 const QComboBox * comboBox = qobject_cast<const QComboBox*>(object);
03848                 const QSpinBox * spinbox = qobject_cast<const QSpinBox*>(object);
03849                 if(comboBox || spinbox)
03850                 {
03851                         // Add parameter
03852                         UDEBUG("modify param %s=%s", object->objectName().toStdString().c_str(), uNumber2Str(value).c_str());
03853                         uInsert(_modifiedParameters, rtabmap::ParametersPair(object->objectName().toStdString(), QString::number(value).toStdString()));
03854                 }
03855                 else
03856                 {
03857                         UWARN("Undefined object \"%s\"", object->objectName().toStdString().c_str());
03858                 }
03859 
03860         }
03861         else
03862         {
03863                 ULOGGER_ERROR("Object is null");
03864         }
03865 }
03866 
03867 void PreferencesDialog::addParameter(const QObject * object, bool value)
03868 {
03869         if(object)
03870         {
03871                 const QCheckBox * checkbox = qobject_cast<const QCheckBox*>(object);
03872                 const QRadioButton * radio = qobject_cast<const QRadioButton*>(object);
03873                 const QGroupBox * groupBox = qobject_cast<const QGroupBox*>(object);
03874                 if(checkbox || radio || groupBox)
03875                 {
03876                         // Add parameter
03877                         UDEBUG("modify param %s=%s", object->objectName().toStdString().c_str(), uBool2Str(value).c_str());
03878                         uInsert(_modifiedParameters, rtabmap::ParametersPair(object->objectName().toStdString(), uBool2Str(value)));
03879                 }
03880                 else
03881                 {
03882                         UWARN("Undefined object \"%s\"", object->objectName().toStdString().c_str());
03883                 }
03884 
03885         }
03886         else
03887         {
03888                 ULOGGER_ERROR("Object is null");
03889         }
03890 }
03891 
03892 void PreferencesDialog::addParameter(const QObject * object, double value)
03893 {
03894         if(object)
03895         {
03896                 UDEBUG("modify param %s=%f", object->objectName().toStdString().c_str(), value);
03897                 uInsert(_modifiedParameters, rtabmap::ParametersPair(object->objectName().toStdString(), QString::number(value).toStdString()));
03898         }
03899         else
03900         {
03901                 ULOGGER_ERROR("Object is null");
03902         }
03903 }
03904 
03905 void PreferencesDialog::addParameter(const QObject * object, const QString & value)
03906 {
03907         if(object)
03908         {
03909                 UDEBUG("modify param %s=%s", object->objectName().toStdString().c_str(), value.toStdString().c_str());
03910                 uInsert(_modifiedParameters, rtabmap::ParametersPair(object->objectName().toStdString(), value.toStdString()));
03911         }
03912         else
03913         {
03914                 ULOGGER_ERROR("Object is null");
03915         }
03916 }
03917 
03918 void PreferencesDialog::addParameters(const QObjectList & children)
03919 {
03920         //ULOGGER_DEBUG("PreferencesDialog::addParameters(QGroupBox) box %s has %d children", box->objectName().toStdString().c_str(), children.size());
03921         for(int i=0; i<children.size(); ++i)
03922         {
03923                 const QSpinBox * spin = qobject_cast<const QSpinBox *>(children[i]);
03924                 const QDoubleSpinBox * doubleSpin = qobject_cast<const QDoubleSpinBox *>(children[i]);
03925                 const QComboBox * combo = qobject_cast<const QComboBox *>(children[i]);
03926                 const QCheckBox * check = qobject_cast<const QCheckBox *>(children[i]);
03927                 const QRadioButton * radio = qobject_cast<const QRadioButton *>(children[i]);
03928                 const QLineEdit * lineEdit = qobject_cast<const QLineEdit *>(children[i]);
03929                 const QGroupBox * groupBox = qobject_cast<const QGroupBox *>(children[i]);
03930                 const QStackedWidget * stackedWidget = qobject_cast<const QStackedWidget *>(children[i]);
03931                 if(spin)
03932                 {
03933                         this->addParameter(spin, spin->value());
03934                 }
03935                 else if(doubleSpin)
03936                 {
03937                         this->addParameter(doubleSpin, doubleSpin->value());
03938                 }
03939                 else if(combo)
03940                 {
03941                         this->addParameter(combo, combo->currentIndex());
03942                 }
03943                 else if(check)
03944                 {
03945                         this->addParameter(check, check->isChecked());
03946                 }
03947                 else if(radio)
03948                 {
03949                         this->addParameter(radio, radio->isChecked());
03950                 }
03951                 else if(lineEdit)
03952                 {
03953                         this->addParameter(lineEdit, lineEdit->text());
03954                 }
03955                 else if(groupBox)
03956                 {
03957                         if(groupBox->isCheckable())
03958                         {
03959                                 this->addParameter(groupBox, groupBox->isChecked());
03960                         }
03961                         else
03962                         {
03963                                 this->addParameters(groupBox);
03964                         }
03965                 }
03966                 else if(stackedWidget)
03967                 {
03968                         this->addParameters(stackedWidget);
03969                 }
03970         }
03971 }
03972 
03973 void PreferencesDialog::addParameters(const QStackedWidget * stackedWidget, int panel)
03974 {
03975         if(stackedWidget)
03976         {
03977                 if(panel == -1)
03978                 {
03979                         for(int i=0; i<stackedWidget->count(); ++i)
03980                         {
03981                                 const QObjectList & children = stackedWidget->widget(i)->children();
03982                                 addParameters(children);
03983                         }
03984                 }
03985                 else
03986                 {
03987                         UASSERT(panel<stackedWidget->count());
03988                         const QObjectList & children = stackedWidget->widget(panel)->children();
03989                         addParameters(children);
03990                 }
03991         }
03992 }
03993 
03994 void PreferencesDialog::addParameters(const QGroupBox * box)
03995 {
03996         if(box)
03997         {
03998                 const QObjectList & children = box->children();
03999                 addParameters(children);
04000         }
04001 }
04002 
04003 void PreferencesDialog::updateBasicParameter()
04004 {
04005         // This method is used to update basic/advanced referred parameters, see above editingFinished()
04006 
04007         // basic to advanced (advanced to basic must be done by connecting signal valueChanged())
04008         if(sender() == _ui->general_doubleSpinBox_timeThr_2)
04009         {
04010                 _ui->general_doubleSpinBox_timeThr->setValue(_ui->general_doubleSpinBox_timeThr_2->value());
04011         }
04012         else if(sender() == _ui->general_doubleSpinBox_hardThr_2)
04013         {
04014                 _ui->general_doubleSpinBox_hardThr->setValue(_ui->general_doubleSpinBox_hardThr_2->value());
04015         }
04016         else if(sender() == _ui->general_doubleSpinBox_detectionRate_2)
04017         {
04018                 _ui->general_doubleSpinBox_detectionRate->setValue(_ui->general_doubleSpinBox_detectionRate_2->value());
04019         }
04020         else if(sender() == _ui->general_spinBox_imagesBufferSize_2)
04021         {
04022                 _ui->general_spinBox_imagesBufferSize->setValue(_ui->general_spinBox_imagesBufferSize_2->value());
04023         }
04024         else if(sender() == _ui->general_spinBox_maxStMemSize_2)
04025         {
04026                 _ui->general_spinBox_maxStMemSize->setValue(_ui->general_spinBox_maxStMemSize_2->value());
04027         }
04028         else if(sender() == _ui->groupBox_publishing)
04029         {
04030                 _ui->general_checkBox_publishStats_2->setChecked(_ui->groupBox_publishing->isChecked());
04031         }
04032         else if(sender() == _ui->general_checkBox_publishStats_2)
04033         {
04034                 _ui->groupBox_publishing->setChecked(_ui->general_checkBox_publishStats_2->isChecked());
04035         }
04036         else if(sender() == _ui->doubleSpinBox_similarityThreshold_2)
04037         {
04038                 _ui->doubleSpinBox_similarityThreshold->setValue(_ui->doubleSpinBox_similarityThreshold_2->value());
04039         }
04040         else if(sender() == _ui->general_checkBox_activateRGBD)
04041         {
04042                 _ui->general_checkBox_activateRGBD_2->setChecked(_ui->general_checkBox_activateRGBD->isChecked());
04043         }
04044         else if(sender() == _ui->general_checkBox_activateRGBD_2)
04045         {
04046                 _ui->general_checkBox_activateRGBD->setChecked(_ui->general_checkBox_activateRGBD_2->isChecked());
04047         }
04048         else if(sender() == _ui->general_checkBox_SLAM_mode)
04049         {
04050                 _ui->general_checkBox_SLAM_mode_2->setChecked(_ui->general_checkBox_SLAM_mode->isChecked());
04051         }
04052         else if(sender() == _ui->general_checkBox_SLAM_mode_2)
04053         {
04054                 _ui->general_checkBox_SLAM_mode->setChecked(_ui->general_checkBox_SLAM_mode_2->isChecked());
04055         }
04056         else
04057         {
04058                 //update all values (only those using editingFinished signal)
04059                 _ui->general_doubleSpinBox_timeThr->setValue(_ui->general_doubleSpinBox_timeThr_2->value());
04060                 _ui->general_doubleSpinBox_hardThr->setValue(_ui->general_doubleSpinBox_hardThr_2->value());
04061                 _ui->general_doubleSpinBox_detectionRate->setValue(_ui->general_doubleSpinBox_detectionRate_2->value());
04062                 _ui->general_spinBox_imagesBufferSize->setValue(_ui->general_spinBox_imagesBufferSize_2->value());
04063                 _ui->general_spinBox_maxStMemSize->setValue(_ui->general_spinBox_maxStMemSize_2->value());
04064                 _ui->doubleSpinBox_similarityThreshold->setValue(_ui->doubleSpinBox_similarityThreshold_2->value());
04065         }
04066 }
04067 
04068 void PreferencesDialog::makeObsoleteGeneralPanel()
04069 {
04070         ULOGGER_DEBUG("");
04071         _obsoletePanels = _obsoletePanels | kPanelGeneral;
04072 }
04073 
04074 void PreferencesDialog::makeObsoleteCloudRenderingPanel()
04075 {
04076         ULOGGER_DEBUG("");
04077         _obsoletePanels = _obsoletePanels | kPanelCloudRendering;
04078 }
04079 
04080 void PreferencesDialog::makeObsoleteLoggingPanel()
04081 {
04082         ULOGGER_DEBUG("");
04083         _obsoletePanels = _obsoletePanels | kPanelLogging;
04084 }
04085 
04086 void PreferencesDialog::makeObsoleteSourcePanel()
04087 {
04088         _obsoletePanels = _obsoletePanels | kPanelSource;
04089 }
04090 
04091 QList<QGroupBox*> PreferencesDialog::getGroupBoxes()
04092 {
04093         QList<QGroupBox*> boxes;
04094         for(int i=0; i<_ui->stackedWidget->count(); ++i)
04095         {
04096                 QGroupBox * gb = 0;
04097                 const QObjectList & children = _ui->stackedWidget->widget(i)->children();
04098                 for(int j=0; j<children.size(); ++j)
04099                 {
04100                         if((gb = qobject_cast<QGroupBox *>(children.at(j))))
04101                         {
04102                                 //ULOGGER_DEBUG("PreferencesDialog::setupTreeView() index(%d) Added %s, box name=%s", i, gb->title().toStdString().c_str(), gb->objectName().toStdString().c_str());
04103                                 break;
04104                         }
04105                 }
04106                 if(gb)
04107                 {
04108                         boxes.append(gb);
04109                 }
04110                 else
04111                 {
04112                         ULOGGER_ERROR("A QGroupBox must be included in the first level of children in stacked widget, index=%d", i);
04113                 }
04114         }
04115         return boxes;
04116 }
04117 
04118 void PreferencesDialog::updatePredictionPlot()
04119 {
04120         QStringList values = _ui->lineEdit_bayes_predictionLC->text().simplified().split(' ');
04121         if(values.size() < 2)
04122         {
04123                 UERROR("Error parsing prediction (must have at least 2 items) : %s",
04124                                 _ui->lineEdit_bayes_predictionLC->text().toStdString().c_str());
04125                 return;
04126         }
04127         QVector<float> dataX((values.size()-2)*2 + 1);
04128         QVector<float> dataY((values.size()-2)*2 + 1);
04129         double value;
04130         double sum = 0;
04131         int lvl = 1;
04132         bool ok = false;
04133         bool error = false;
04134         int loopClosureIndex = (dataX.size()-1)/2;
04135         for(int i=0; i<values.size(); ++i)
04136         {
04137                 value = values.at(i).toDouble(&ok);
04138                 if(!ok)
04139                 {
04140                         UERROR("Error parsing prediction : \"%s\"", values.at(i).toStdString().c_str());
04141                         error = true;
04142                 }
04143                 sum+=value;
04144                 if(i==0)
04145                 {
04146                         //do nothing
04147                 }
04148                 else if(i == 1)
04149                 {
04150                         dataY[loopClosureIndex] = value;
04151                         dataX[loopClosureIndex] = 0;
04152                 }
04153                 else
04154                 {
04155                         dataY[loopClosureIndex-lvl] = value;
04156                         dataX[loopClosureIndex-lvl] = -lvl;
04157                         dataY[loopClosureIndex+lvl] = value;
04158                         dataX[loopClosureIndex+lvl] = lvl;
04159                         ++lvl;
04160                 }
04161         }
04162 
04163         _ui->label_prediction_sum->setNum(sum);
04164         if(error)
04165         {
04166                 _ui->label_prediction_sum->setText(QString("<font color=#FF0000>") + _ui->label_prediction_sum->text() + "</font>");
04167         }
04168         else if(sum == 1.0)
04169         {
04170                 _ui->label_prediction_sum->setText(QString("<font color=#00FF00>") + _ui->label_prediction_sum->text() + "</font>");
04171         }
04172         else if(sum > 1.0)
04173         {
04174                 _ui->label_prediction_sum->setText(QString("<font color=#FFa500>") + _ui->label_prediction_sum->text() + "</font>");
04175         }
04176         else
04177         {
04178                 _ui->label_prediction_sum->setText(QString("<font color=#000000>") + _ui->label_prediction_sum->text() + "</font>");
04179         }
04180 
04181         _ui->predictionPlot->removeCurves();
04182         _ui->predictionPlot->addCurve(new UPlotCurve("Prediction", dataX, dataY, _ui->predictionPlot));
04183 }
04184 
04185 void PreferencesDialog::setupKpRoiPanel()
04186 {
04187         QStringList strings = _ui->lineEdit_kp_roi->text().split(' ');
04188         if(strings.size()!=4)
04189         {
04190                 UERROR("ROI must have 4 values (%s)", _ui->lineEdit_kp_roi->text().toStdString().c_str());
04191                 return;
04192         }
04193         _ui->doubleSpinBox_kp_roi0->setValue(strings[0].toDouble()*100.0);
04194         _ui->doubleSpinBox_kp_roi1->setValue(strings[1].toDouble()*100.0);
04195         _ui->doubleSpinBox_kp_roi2->setValue(strings[2].toDouble()*100.0);
04196         _ui->doubleSpinBox_kp_roi3->setValue(strings[3].toDouble()*100.0);
04197 }
04198 
04199 void PreferencesDialog::updateKpROI()
04200 {
04201         QStringList strings;
04202         strings.append(QString::number(_ui->doubleSpinBox_kp_roi0->value()/100.0));
04203         strings.append(QString::number(_ui->doubleSpinBox_kp_roi1->value()/100.0));
04204         strings.append(QString::number(_ui->doubleSpinBox_kp_roi2->value()/100.0));
04205         strings.append(QString::number(_ui->doubleSpinBox_kp_roi3->value()/100.0));
04206         _ui->lineEdit_kp_roi->setText(strings.join(" "));
04207 }
04208 
04209 void PreferencesDialog::updateStereoDisparityVisibility()
04210 {
04211         Src driver = this->getSourceDriver();
04212         _ui->checkbox_stereo_depthGenerated->setVisible(
04213                 driver != PreferencesDialog::kSrcStereoZed ||
04214                 _ui->comboBox_stereoZed_quality->currentIndex() == 0);
04215         _ui->label_stereo_depthGenerated->setVisible(
04216                 driver != PreferencesDialog::kSrcStereoZed ||
04217                 _ui->comboBox_stereoZed_quality->currentIndex() == 0);
04218 
04219         _ui->checkBox_stereo_rectify->setEnabled(
04220                          _ui->comboBox_cameraStereo->currentIndex() == kSrcStereoImages - kSrcStereo ||
04221                          _ui->comboBox_cameraStereo->currentIndex() == kSrcStereoUsb - kSrcStereo ||
04222                          _ui->comboBox_cameraStereo->currentIndex() == kSrcStereoVideo - kSrcStereo ||
04223                          _ui->comboBox_cameraStereo->currentIndex() == kSrcDC1394 - kSrcStereo);
04224         _ui->checkBox_stereo_rectify->setVisible(_ui->checkBox_stereo_rectify->isEnabled());
04225         _ui->label_stereo_rectify->setVisible(_ui->checkBox_stereo_rectify->isEnabled());
04226 }
04227 
04228 void PreferencesDialog::useOdomFeatures()
04229 {
04230         if(this->isVisible() && _ui->checkBox_useOdomFeatures->isChecked())
04231         {
04232                 int r = QMessageBox::question(this, tr("Using odometry features for vocabulary..."),
04233                                 tr("Do you want to match vocabulary feature parameters "
04234                                    "with corresponding ones used for odometry?"), QMessageBox::Yes | QMessageBox::No, QMessageBox::Yes);
04235 
04236                 if(r == QMessageBox::Yes)
04237                 {
04238                         _ui->comboBox_detector_strategy->setCurrentIndex(_ui->reextract_type->currentIndex());
04239                         _ui->surf_doubleSpinBox_maxDepth->setValue(_ui->loopClosure_bowMaxDepth->value());
04240                         _ui->surf_doubleSpinBox_minDepth->setValue(_ui->loopClosure_bowMinDepth->value());
04241                         _ui->surf_spinBox_wordsPerImageTarget->setValue(_ui->reextract_maxFeatures->value());
04242                         _ui->spinBox_KPGridRows->setValue(_ui->reextract_gridrows->value());
04243                         _ui->spinBox_KPGridCols->setValue(_ui->reextract_gridcols->value());
04244                         _ui->lineEdit_kp_roi->setText(_ui->loopClosure_roi->text());
04245                         _ui->subpix_winSize_kp->setValue(_ui->subpix_winSize->value());
04246                         _ui->subpix_iterations_kp->setValue(_ui->subpix_iterations->value());
04247                         _ui->subpix_eps_kp->setValue(_ui->subpix_eps->value());
04248                 }
04249         }
04250 }
04251 
04252 void PreferencesDialog::changeWorkingDirectory()
04253 {
04254         QString directory = QFileDialog::getExistingDirectory(this, tr("Working directory"), _ui->lineEdit_workingDirectory->text());
04255         if(!directory.isEmpty())
04256         {
04257                 ULOGGER_DEBUG("New working directory = %s", directory.toStdString().c_str());
04258                 _ui->lineEdit_workingDirectory->setText(directory);
04259         }
04260 }
04261 
04262 void PreferencesDialog::changeDictionaryPath()
04263 {
04264         QString path;
04265         if(_ui->lineEdit_dictionaryPath->text().isEmpty())
04266         {
04267                 path = QFileDialog::getOpenFileName(this, tr("Dictionary"), this->getWorkingDirectory(), tr("Dictionary (*.txt *.db)"));
04268         }
04269         else
04270         {
04271                 path = QFileDialog::getOpenFileName(this, tr("Dictionary"), _ui->lineEdit_dictionaryPath->text(), tr("Dictionary (*.txt *.db)"));
04272         }
04273         if(!path.isEmpty())
04274         {
04275                 _ui->lineEdit_dictionaryPath->setText(path);
04276         }
04277 }
04278 
04279 void PreferencesDialog::changeOdometryORBSLAM2Vocabulary()
04280 {
04281         QString path;
04282         if(_ui->lineEdit_OdomORBSLAM2VocPath->text().isEmpty())
04283         {
04284                 path = QFileDialog::getOpenFileName(this, tr("ORBSLAM2 Vocabulary"), this->getWorkingDirectory(), tr("Vocabulary (*.txt)"));
04285         }
04286         else
04287         {
04288                 path = QFileDialog::getOpenFileName(this, tr("ORBSLAM2 Vocabulary"), _ui->lineEdit_OdomORBSLAM2VocPath->text(),  tr("Vocabulary (*.txt)"));
04289         }
04290         if(!path.isEmpty())
04291         {
04292                 _ui->lineEdit_OdomORBSLAM2VocPath->setText(path);
04293         }
04294 }
04295 
04296 void PreferencesDialog::changeOdometryOKVISConfigPath()
04297 {
04298         QString path;
04299         if(_ui->lineEdit_OdomOkvisPath->text().isEmpty())
04300         {
04301                 path = QFileDialog::getOpenFileName(this, tr("OKVIS Config"), this->getWorkingDirectory(), tr("OKVIS config (*.yaml)"));
04302         }
04303         else
04304         {
04305                 path = QFileDialog::getOpenFileName(this, tr("OKVIS Config"), _ui->lineEdit_OdomOkvisPath->text(), tr("OKVIS config (*.yaml)"));
04306         }
04307         if(!path.isEmpty())
04308         {
04309                 _ui->lineEdit_OdomOkvisPath->setText(path);
04310         }
04311 }
04312 
04313 void PreferencesDialog::changeIcpPMConfigPath()
04314 {
04315         QString path;
04316         if(_ui->lineEdit_IcpPMConfigPath->text().isEmpty())
04317         {
04318                 path = QFileDialog::getOpenFileName(this, tr("Select file"), this->getWorkingDirectory(), tr("libpointmatcher (*.yaml)"));
04319         }
04320         else
04321         {
04322                 path = QFileDialog::getOpenFileName(this, tr("Select file"), _ui->lineEdit_IcpPMConfigPath->text(), tr("libpointmatcher (*.yaml)"));
04323         }
04324         if(!path.isEmpty())
04325         {
04326                 _ui->lineEdit_IcpPMConfigPath->setText(path);
04327         }
04328 }
04329 
04330 void PreferencesDialog::updateSourceGrpVisibility()
04331 {
04332         _ui->groupBox_sourceRGBD->setVisible(_ui->comboBox_sourceType->currentIndex() == 0);
04333         _ui->groupBox_sourceStereo->setVisible(_ui->comboBox_sourceType->currentIndex() == 1);
04334         _ui->groupBox_sourceRGB->setVisible(_ui->comboBox_sourceType->currentIndex() == 2);
04335         _ui->groupBox_sourceDatabase->setVisible(_ui->comboBox_sourceType->currentIndex() == 3);
04336 
04337         _ui->groupBox_scanFromDepth->setVisible(_ui->comboBox_sourceType->currentIndex() <= 1 || _ui->comboBox_sourceType->currentIndex() == 3);
04338 
04339         _ui->stackedWidget_rgbd->setVisible(_ui->comboBox_sourceType->currentIndex() == 0 &&
04340                         (_ui->comboBox_cameraRGBD->currentIndex() == kSrcOpenNI2-kSrcRGBD ||
04341                          _ui->comboBox_cameraRGBD->currentIndex() == kSrcFreenect2-kSrcRGBD ||
04342                          _ui->comboBox_cameraRGBD->currentIndex() == kSrcK4W2 - kSrcRGBD ||
04343                          _ui->comboBox_cameraRGBD->currentIndex() == kSrcRealSense - kSrcRGBD ||
04344                          _ui->comboBox_cameraRGBD->currentIndex() == kSrcRGBDImages-kSrcRGBD ||
04345                          _ui->comboBox_cameraRGBD->currentIndex() == kSrcOpenNI_PCL-kSrcRGBD ||
04346                          _ui->comboBox_cameraRGBD->currentIndex() == kSrcRealSense2-kSrcRGBD));
04347         _ui->groupBox_openni2->setVisible(_ui->comboBox_sourceType->currentIndex() == 0 && _ui->comboBox_cameraRGBD->currentIndex() == kSrcOpenNI2-kSrcRGBD);
04348         _ui->groupBox_freenect2->setVisible(_ui->comboBox_sourceType->currentIndex() == 0 && _ui->comboBox_cameraRGBD->currentIndex() == kSrcFreenect2-kSrcRGBD);
04349         _ui->groupBox_k4w2->setVisible(_ui->comboBox_sourceType->currentIndex() == 0 && _ui->comboBox_cameraRGBD->currentIndex() == kSrcK4W2 - kSrcRGBD);
04350         _ui->groupBox_realsense->setVisible(_ui->comboBox_sourceType->currentIndex() == 0 && _ui->comboBox_cameraRGBD->currentIndex() == kSrcRealSense - kSrcRGBD);
04351         _ui->groupBox_realsense2->setVisible(_ui->comboBox_sourceType->currentIndex() == 0 && _ui->comboBox_cameraRGBD->currentIndex() == kSrcRealSense2 - kSrcRGBD);
04352         _ui->groupBox_cameraRGBDImages->setVisible(_ui->comboBox_sourceType->currentIndex() == 0 && _ui->comboBox_cameraRGBD->currentIndex() == kSrcRGBDImages-kSrcRGBD);
04353         _ui->groupBox_openni->setVisible(_ui->comboBox_sourceType->currentIndex() == 0 && _ui->comboBox_cameraRGBD->currentIndex() == kSrcOpenNI_PCL-kSrcRGBD);
04354 
04355         _ui->stackedWidget_stereo->setVisible(_ui->comboBox_sourceType->currentIndex() == 1 && 
04356                 (_ui->comboBox_cameraStereo->currentIndex() == kSrcStereoVideo-kSrcStereo || 
04357                  _ui->comboBox_cameraStereo->currentIndex() == kSrcStereoImages-kSrcStereo ||
04358                  _ui->comboBox_cameraStereo->currentIndex() == kSrcStereoZed - kSrcStereo ||
04359                  _ui->comboBox_cameraStereo->currentIndex() == kSrcStereoUsb - kSrcStereo));
04360         _ui->groupBox_cameraStereoImages->setVisible(_ui->comboBox_sourceType->currentIndex() == 1 && _ui->comboBox_cameraStereo->currentIndex() == kSrcStereoImages-kSrcStereo);
04361         _ui->groupBox_cameraStereoVideo->setVisible(_ui->comboBox_sourceType->currentIndex() == 1 && _ui->comboBox_cameraStereo->currentIndex() == kSrcStereoVideo - kSrcStereo);
04362         _ui->groupBox_cameraStereoUsb->setVisible(_ui->comboBox_sourceType->currentIndex() == 1 && _ui->comboBox_cameraStereo->currentIndex() == kSrcStereoUsb - kSrcStereo);
04363         _ui->groupBox_cameraStereoZed->setVisible(_ui->comboBox_sourceType->currentIndex() == 1 && _ui->comboBox_cameraStereo->currentIndex() == kSrcStereoZed - kSrcStereo);
04364 
04365         _ui->stackedWidget_image->setVisible(_ui->comboBox_sourceType->currentIndex() == 2 && (_ui->source_comboBox_image_type->currentIndex() == kSrcImages-kSrcRGB || _ui->source_comboBox_image_type->currentIndex() == kSrcVideo-kSrcRGB));
04366         _ui->source_groupBox_images->setVisible(_ui->comboBox_sourceType->currentIndex() == 2 && _ui->source_comboBox_image_type->currentIndex() == kSrcImages-kSrcRGB);
04367         _ui->source_groupBox_video->setVisible(_ui->comboBox_sourceType->currentIndex() == 2 && _ui->source_comboBox_image_type->currentIndex() == kSrcVideo-kSrcRGB);
04368 
04369         _ui->groupBox_sourceImages_optional->setVisible(
04370                         (_ui->comboBox_sourceType->currentIndex() == 0 && _ui->comboBox_cameraRGBD->currentIndex() == kSrcRGBDImages-kSrcRGBD) ||
04371                         (_ui->comboBox_sourceType->currentIndex() == 1 && _ui->comboBox_cameraStereo->currentIndex() == kSrcStereoImages-kSrcStereo) ||
04372                         (_ui->comboBox_sourceType->currentIndex() == 2 && _ui->source_comboBox_image_type->currentIndex() == kSrcImages-kSrcRGB));
04373 
04374         _ui->groupBox_depthImageFiltering->setEnabled(
04375                                 _ui->comboBox_sourceType->currentIndex() == 0 || // RGBD
04376                                 _ui->comboBox_sourceType->currentIndex() == 3);  // Database
04377         _ui->groupBox_depthImageFiltering->setVisible(_ui->groupBox_depthImageFiltering->isEnabled());
04378 
04379         //_ui->groupBox_scan->setVisible(_ui->comboBox_sourceType->currentIndex() != 3);
04380 
04381         _ui->groupBox_depthFromScan->setVisible(_ui->comboBox_sourceType->currentIndex() == 2 && _ui->source_comboBox_image_type->currentIndex() == kSrcImages-kSrcRGB);
04382 }
04383 
04384 /*** GETTERS ***/
04385 //General
04386 int PreferencesDialog::getGeneralLoggerLevel() const
04387 {
04388         return _ui->comboBox_loggerLevel->currentIndex();
04389 }
04390 int PreferencesDialog::getGeneralLoggerEventLevel() const
04391 {
04392         return _ui->comboBox_loggerEventLevel->currentIndex();
04393 }
04394 int PreferencesDialog::getGeneralLoggerPauseLevel() const
04395 {
04396         return _ui->comboBox_loggerPauseLevel->currentIndex();
04397 }
04398 int PreferencesDialog::getGeneralLoggerType() const
04399 {
04400         return _ui->comboBox_loggerType->currentIndex();
04401 }
04402 bool PreferencesDialog::getGeneralLoggerPrintTime() const
04403 {
04404         return _ui->checkBox_logger_printTime->isChecked();
04405 }
04406 bool PreferencesDialog::getGeneralLoggerPrintThreadId() const
04407 {
04408         return _ui->checkBox_logger_printThreadId->isChecked();
04409 }
04410 std::vector<std::string> PreferencesDialog::getGeneralLoggerThreads() const
04411 {
04412         std::vector<std::string> threads;
04413         for(int i=0; i<_ui->comboBox_loggerFilter->count(); ++i)
04414         {
04415                 if(_ui->comboBox_loggerFilter->itemData(i).toBool())
04416                 {
04417                         threads.push_back(_ui->comboBox_loggerFilter->itemText(i).toStdString());
04418                 }
04419         }
04420         return threads;
04421 }
04422 bool PreferencesDialog::isVerticalLayoutUsed() const
04423 {
04424         return _ui->checkBox_verticalLayoutUsed->isChecked();
04425 }
04426 bool PreferencesDialog::imageRejectedShown() const
04427 {
04428         return _ui->checkBox_imageRejectedShown->isChecked();
04429 }
04430 bool PreferencesDialog::imageHighestHypShown() const
04431 {
04432         return _ui->checkBox_imageHighestHypShown->isChecked();
04433 }
04434 bool PreferencesDialog::beepOnPause() const
04435 {
04436         return _ui->checkBox_beep->isChecked();
04437 }
04438 bool PreferencesDialog::isTimeUsedInFigures() const
04439 {
04440         return _ui->checkBox_stamps->isChecked();
04441 }
04442 bool PreferencesDialog::isCacheSavedInFigures() const
04443 {
04444         return _ui->checkBox_cacheStatistics->isChecked();
04445 }
04446 bool PreferencesDialog::notifyWhenNewGlobalPathIsReceived() const
04447 {
04448         return _ui->checkBox_notifyWhenNewGlobalPathIsReceived->isChecked();
04449 }
04450 int PreferencesDialog::getOdomQualityWarnThr() const
04451 {
04452         return _ui->spinBox_odomQualityWarnThr->value();
04453 }
04454 bool PreferencesDialog::isOdomOnlyInliersShown() const
04455 {
04456         return _ui->checkBox_odom_onlyInliersShown->isChecked();
04457 }
04458 bool PreferencesDialog::isPosteriorGraphView() const
04459 {
04460         return _ui->radioButton_posteriorGraphView->isChecked();
04461 }
04462 bool PreferencesDialog::isWordsCountGraphView() const
04463 {
04464         return _ui->radioButton_wordsGraphView->isChecked();
04465 }
04466 bool PreferencesDialog::isLocalizationsCountGraphView() const
04467 {
04468         return _ui->radioButton_localizationsGraphView->isChecked();
04469 }
04470 bool PreferencesDialog::isOdomDisabled() const
04471 {
04472         return _ui->checkbox_odomDisabled->isChecked();
04473 }
04474 int PreferencesDialog::getOdomRegistrationApproach() const
04475 {
04476         return _ui->odom_registration->currentIndex();
04477 }
04478 bool PreferencesDialog::isGroundTruthAligned() const
04479 {
04480         return _ui->checkbox_groundTruthAlign->isChecked();
04481 }
04482 
04483 bool PreferencesDialog::isCloudsShown(int index) const
04484 {
04485         UASSERT(index >= 0 && index <= 1);
04486         return _3dRenderingShowClouds[index]->isChecked();
04487 }
04488 bool PreferencesDialog::isOctomapUpdated() const
04489 {
04490 #ifdef RTABMAP_OCTOMAP
04491         return _ui->groupBox_octomap->isChecked();
04492 #endif
04493         return false;
04494 }
04495 bool PreferencesDialog::isOctomapShown() const
04496 {
04497 #ifdef RTABMAP_OCTOMAP
04498         return _ui->groupBox_octomap->isChecked() && _ui->checkBox_octomap_show3dMap->isChecked();
04499 #endif
04500         return false;
04501 }
04502 int PreferencesDialog::getOctomapRenderingType() const
04503 {
04504         return _ui->comboBox_octomap_renderingType->currentIndex();
04505 }
04506 bool PreferencesDialog::isOctomap2dGrid() const
04507 {
04508 #ifdef RTABMAP_OCTOMAP
04509         return _ui->groupBox_octomap->isChecked() && _ui->checkBox_octomap_2dgrid->isChecked();
04510 #endif
04511         return false;
04512 }
04513 int PreferencesDialog::getOctomapTreeDepth() const
04514 {
04515         return _ui->spinBox_octomap_treeDepth->value();
04516 }
04517 int PreferencesDialog::getOctomapPointSize() const
04518 {
04519         return _ui->spinBox_octomap_pointSize->value();
04520 }
04521 
04522 double PreferencesDialog::getVoxel() const
04523 {
04524         return _ui->doubleSpinBox_voxel->value();
04525 }
04526 double PreferencesDialog::getNoiseRadius() const
04527 {
04528         return _ui->doubleSpinBox_noiseRadius->value();
04529 }
04530 int PreferencesDialog::getNoiseMinNeighbors() const
04531 {
04532         return _ui->spinBox_noiseMinNeighbors->value();
04533 }
04534 double PreferencesDialog::getCeilingFilteringHeight() const
04535 {
04536         return _ui->doubleSpinBox_ceilingFilterHeight->value();
04537 }
04538 double PreferencesDialog::getFloorFilteringHeight() const
04539 {
04540         return _ui->doubleSpinBox_floorFilterHeight->value();
04541 }
04542 int PreferencesDialog::getNormalKSearch() const
04543 {
04544         return _ui->spinBox_normalKSearch->value();
04545 }
04546 double PreferencesDialog::getNormalRadiusSearch() const
04547 {
04548         return _ui->doubleSpinBox_normalRadiusSearch->value();
04549 }
04550 double PreferencesDialog::getScanCeilingFilteringHeight() const
04551 {
04552         return _ui->doubleSpinBox_ceilingFilterHeight_scan->value();
04553 }
04554 double PreferencesDialog::getScanFloorFilteringHeight() const
04555 {
04556         return _ui->doubleSpinBox_floorFilterHeight_scan->value();
04557 }
04558 int PreferencesDialog::getScanNormalKSearch() const
04559 {
04560         return _ui->spinBox_normalKSearch_scan->value();
04561 }
04562 double PreferencesDialog::getScanNormalRadiusSearch() const
04563 {
04564         return _ui->doubleSpinBox_normalRadiusSearch_scan->value();
04565 }
04566 
04567 bool PreferencesDialog::isGraphsShown() const
04568 {
04569         return _ui->checkBox_showGraphs->isChecked();
04570 }
04571 bool PreferencesDialog::isLabelsShown() const
04572 {
04573         return _ui->checkBox_showLabels->isChecked();
04574 }
04575 bool PreferencesDialog::isCloudMeshing() const
04576 {
04577         return _ui->groupBox_organized->isChecked();
04578 }
04579 double PreferencesDialog::getCloudMeshingAngle() const
04580 {
04581         return _ui->doubleSpinBox_mesh_angleTolerance->value()*M_PI/180.0;
04582 }
04583 bool PreferencesDialog::isCloudMeshingQuad() const
04584 {
04585         return _ui->checkBox_mesh_quad->isChecked();
04586 }
04587 bool PreferencesDialog::isCloudMeshingTexture() const
04588 {
04589         return _ui->checkBox_mesh_texture->isChecked();
04590 }
04591 int PreferencesDialog::getCloudMeshingTriangleSize()
04592 {
04593         return _ui->spinBox_mesh_triangleSize->value();
04594 }
04595 int PreferencesDialog::getCloudDecimation(int index) const
04596 {
04597         UASSERT(index >= 0 && index <= 1);
04598         return _3dRenderingDecimation[index]->value()==0?1:_3dRenderingDecimation[index]->value();
04599 }
04600 double PreferencesDialog::getCloudMaxDepth(int index) const
04601 {
04602         UASSERT(index >= 0 && index <= 1);
04603         return _3dRenderingMaxDepth[index]->value();
04604 }
04605 double PreferencesDialog::getCloudMinDepth(int index) const
04606 {
04607         UASSERT(index >= 0 && index <= 1);
04608         return _3dRenderingMinDepth[index]->value();
04609 }
04610 std::vector<float> PreferencesDialog::getCloudRoiRatios(int index) const
04611 {
04612         UASSERT(index >= 0 && index <= 1);
04613         std::vector<float> roiRatios;
04614         if(!_3dRenderingRoiRatios[index]->text().isEmpty())
04615         {
04616                 QStringList values = _3dRenderingRoiRatios[index]->text().split(' ');
04617                 if(values.size() == 4)
04618                 {
04619                         roiRatios.resize(4);
04620                         for(int i=0; i<values.size(); ++i)
04621                         {
04622                                 roiRatios[i] = uStr2Float(values[i].toStdString().c_str());
04623                         }
04624                 }
04625         }
04626         return roiRatios;
04627 }
04628 int PreferencesDialog::getCloudColorScheme(int index) const
04629 {
04630         UASSERT(index >= 0 && index <= 1);
04631         return _3dRenderingColorScheme[index]->value();
04632 }
04633 double PreferencesDialog::getCloudOpacity(int index) const
04634 {
04635         UASSERT(index >= 0 && index <= 1);
04636         return _3dRenderingOpacity[index]->value();
04637 }
04638 int PreferencesDialog::getCloudPointSize(int index) const
04639 {
04640         UASSERT(index >= 0 && index <= 1);
04641         return _3dRenderingPtSize[index]->value();
04642 }
04643 
04644 bool PreferencesDialog::isScansShown(int index) const
04645 {
04646         UASSERT(index >= 0 && index <= 1);
04647         return _3dRenderingShowScans[index]->isChecked();
04648 }
04649 int PreferencesDialog::getDownsamplingStepScan(int index) const
04650 {
04651         UASSERT(index >= 0 && index <= 1);
04652         return _3dRenderingDownsamplingScan[index]->value();
04653 }
04654 double PreferencesDialog::getScanMaxRange(int index) const
04655 {
04656         UASSERT(index >= 0 && index <= 1);
04657         return _3dRenderingMaxRange[index]->value();
04658 }
04659 double PreferencesDialog::getScanMinRange(int index) const
04660 {
04661         UASSERT(index >= 0 && index <= 1);
04662         return _3dRenderingMinRange[index]->value();
04663 }
04664 double PreferencesDialog::getCloudVoxelSizeScan(int index) const
04665 {
04666         UASSERT(index >= 0 && index <= 1);
04667         return _3dRenderingVoxelSizeScan[index]->value();
04668 }
04669 int PreferencesDialog::getScanColorScheme(int index) const
04670 {
04671         UASSERT(index >= 0 && index <= 1);
04672         return _3dRenderingColorSchemeScan[index]->value();
04673 }
04674 double PreferencesDialog::getScanOpacity(int index) const
04675 {
04676         UASSERT(index >= 0 && index <= 1);
04677         return _3dRenderingOpacityScan[index]->value();
04678 }
04679 int PreferencesDialog::getScanPointSize(int index) const
04680 {
04681         UASSERT(index >= 0 && index <= 1);
04682         return _3dRenderingPtSizeScan[index]->value();
04683 }
04684 
04685 bool PreferencesDialog::isFeaturesShown(int index) const
04686 {
04687         UASSERT(index >= 0 && index <= 1);
04688         return _3dRenderingShowFeatures[index]->isChecked();
04689 }
04690 bool PreferencesDialog::isFrustumsShown(int index) const
04691 {
04692         UASSERT(index >= 0 && index <= 1);
04693         return _3dRenderingShowFrustums[index]->isEnabled() && _3dRenderingShowFrustums[index]->isChecked();
04694 }
04695 int PreferencesDialog::getFeaturesPointSize(int index) const
04696 {
04697         UASSERT(index >= 0 && index <= 1);
04698         return _3dRenderingPtSizeFeatures[index]->value();
04699 }
04700 
04701 bool PreferencesDialog::isCloudFiltering() const
04702 {
04703         return _ui->radioButton_nodeFiltering->isChecked();
04704 }
04705 bool PreferencesDialog::isSubtractFiltering() const
04706 {
04707         return _ui->radioButton_subtractFiltering->isChecked();
04708 }
04709 double PreferencesDialog::getCloudFilteringRadius() const
04710 {
04711         return _ui->doubleSpinBox_cloudFilterRadius->value();
04712 }
04713 double PreferencesDialog::getCloudFilteringAngle() const
04714 {
04715         return _ui->doubleSpinBox_cloudFilterAngle->value();
04716 }
04717 int PreferencesDialog::getSubtractFilteringMinPts() const
04718 {
04719         return _ui->spinBox_subtractFilteringMinPts->value();
04720 }
04721 double PreferencesDialog::getSubtractFilteringRadius() const
04722 {
04723         return _ui->doubleSpinBox_subtractFilteringRadius->value();
04724 }
04725 double PreferencesDialog::getSubtractFilteringAngle() const
04726 {
04727         return _ui->doubleSpinBox_subtractFilteringAngle->value()*M_PI/180.0;
04728 }
04729 bool PreferencesDialog::getGridMapShown() const
04730 {
04731         return _ui->checkBox_map_shown->isChecked();
04732 }
04733 bool PreferencesDialog::isGridMapFrom3DCloud() const
04734 {
04735         return _ui->groupBox_grid_fromDepthImage->isChecked();
04736 }
04737 bool PreferencesDialog::projMapFrame() const
04738 {
04739         return _ui->checkBox_grid_projMapFrame->isChecked();
04740 }
04741 double PreferencesDialog::projMaxGroundAngle() const
04742 {
04743         return _ui->doubleSpinBox_grid_maxGroundAngle->value()*M_PI/180.0;
04744 }
04745 double PreferencesDialog::projMaxGroundHeight() const
04746 {
04747         return _ui->doubleSpinBox_grid_maxGroundHeight->value();
04748 }
04749 int PreferencesDialog::projMinClusterSize() const
04750 {
04751         return _ui->spinBox_grid_minClusterSize->value();
04752 }
04753 double PreferencesDialog::projMaxObstaclesHeight() const
04754 {
04755         return _ui->doubleSpinBox_grid_maxObstacleHeight->value();
04756 }
04757 bool PreferencesDialog::projFlatObstaclesDetected() const
04758 {
04759         return _ui->checkBox_grid_flatObstaclesDetected->isChecked();
04760 }
04761 double PreferencesDialog::getGridMapOpacity() const
04762 {
04763         return _ui->doubleSpinBox_map_opacity->value();
04764 }
04765 
04766 
04767 // Source
04768 double PreferencesDialog::getGeneralInputRate() const
04769 {
04770         return _ui->general_doubleSpinBox_imgRate->value();
04771 }
04772 bool PreferencesDialog::isSourceMirroring() const
04773 {
04774         return _ui->source_mirroring->isChecked();
04775 }
04776 PreferencesDialog::Src PreferencesDialog::getSourceType() const
04777 {
04778         int index = _ui->comboBox_sourceType->currentIndex();
04779         if(index == 0)
04780         {
04781                 return kSrcRGBD;
04782         }
04783         else if(index == 1)
04784         {
04785                 return kSrcStereo;
04786         }
04787         else if(index == 2)
04788         {
04789                 return kSrcRGB;
04790         }
04791         else if(index == 3)
04792         {
04793                 return kSrcDatabase;
04794         }
04795         return kSrcUndef;
04796 }
04797 PreferencesDialog::Src PreferencesDialog::getSourceDriver() const
04798 {
04799         PreferencesDialog::Src type = getSourceType();
04800         if(type==kSrcRGBD)
04801         {
04802                 return (PreferencesDialog::Src)(_ui->comboBox_cameraRGBD->currentIndex()+kSrcRGBD);
04803         }
04804         else if(type==kSrcStereo)
04805         {
04806                 return (PreferencesDialog::Src)(_ui->comboBox_cameraStereo->currentIndex()+kSrcStereo);
04807         }
04808         else if(type==kSrcRGB)
04809         {
04810                 return (PreferencesDialog::Src)(_ui->source_comboBox_image_type->currentIndex()+kSrcRGB);
04811         }
04812         else if(type==kSrcDatabase)
04813         {
04814                 return kSrcDatabase;
04815         }
04816         return kSrcUndef;
04817 }
04818 QString PreferencesDialog::getSourceDriverStr() const
04819 {
04820         PreferencesDialog::Src type = getSourceType();
04821         if(type==kSrcRGBD)
04822         {
04823                 return _ui->comboBox_cameraRGBD->currentText();
04824         }
04825         else if(type==kSrcStereo)
04826         {
04827                 return _ui->comboBox_cameraStereo->currentText();
04828         }
04829         else if(type==kSrcRGB)
04830         {
04831                 return _ui->source_comboBox_image_type->currentText();
04832         }
04833         else if(type==kSrcDatabase)
04834         {
04835                 return "Database";
04836         }
04837         return "";
04838 }
04839 
04840 QString PreferencesDialog::getSourceDevice() const
04841 {
04842         return _ui->lineEdit_sourceDevice->text();
04843 }
04844 
04845 Transform PreferencesDialog::getSourceLocalTransform() const
04846 {
04847         Transform t = Transform::fromString(_ui->lineEdit_sourceLocalTransform->text().replace("PI_2", QString::number(3.141592/2.0)).toStdString());
04848         if(t.isNull())
04849         {
04850                 return Transform::getIdentity();
04851         }
04852         return t;
04853 }
04854 
04855 Transform PreferencesDialog::getLaserLocalTransform() const
04856 {
04857         Transform t = Transform::fromString(_ui->lineEdit_cameraImages_laser_transform->text().replace("PI_2", QString::number(3.141592/2.0)).toStdString());
04858         if(t.isNull())
04859         {
04860                 return Transform::getIdentity();
04861         }
04862         return t;
04863 }
04864 
04865 QString PreferencesDialog::getIMUPath() const
04866 {
04867         return _ui->lineEdit_cameraImages_path_imu->text();
04868 }
04869 Transform PreferencesDialog::getIMULocalTransform() const
04870 {
04871         Transform t = Transform::fromString(_ui->lineEdit_cameraImages_imu_transform->text().replace("PI_2", QString::number(3.141592/2.0)).toStdString());
04872         if(t.isNull())
04873         {
04874                 return Transform::getIdentity();
04875         }
04876         return t;
04877 }
04878 int PreferencesDialog::getIMURate() const
04879 {
04880         return _ui->spinBox_cameraImages_max_imu_rate->value();
04881 }
04882 
04883 bool PreferencesDialog::isSourceDatabaseStampsUsed() const
04884 {
04885         return _ui->source_checkBox_useDbStamps->isChecked();
04886 }
04887 bool PreferencesDialog::isSourceRGBDColorOnly() const
04888 {
04889         return _ui->checkbox_rgbd_colorOnly->isChecked();
04890 }
04891 bool PreferencesDialog::isDepthFilteringAvailable() const
04892 {
04893         return _ui->groupBox_depthImageFiltering->isEnabled();
04894 }
04895 QString PreferencesDialog::getSourceDistortionModel() const
04896 {
04897         return _ui->lineEdit_source_distortionModel->text();
04898 }
04899 bool PreferencesDialog::isBilateralFiltering() const
04900 {
04901         return _ui->groupBox_bilateral->isChecked();
04902 }
04903 double PreferencesDialog::getBilateralSigmaS() const
04904 {
04905         return _ui->doubleSpinBox_bilateral_sigmaS->value();
04906 }
04907 double PreferencesDialog::getBilateralSigmaR() const
04908 {
04909         return _ui->doubleSpinBox_bilateral_sigmaR->value();
04910 }
04911 int PreferencesDialog::getSourceImageDecimation() const
04912 {
04913         return _ui->spinBox_source_imageDecimation->value();
04914 }
04915 bool PreferencesDialog::isSourceStereoDepthGenerated() const
04916 {
04917         return _ui->checkbox_stereo_depthGenerated->isChecked();
04918 }
04919 bool PreferencesDialog::isSourceStereoExposureCompensation() const
04920 {
04921         return _ui->checkBox_stereo_exposureCompensation->isChecked();
04922 }
04923 bool PreferencesDialog::isSourceScanFromDepth() const
04924 {
04925         return _ui->groupBox_scanFromDepth->isChecked();
04926 }
04927 int PreferencesDialog::getSourceScanFromDepthDecimation() const
04928 {
04929         return _ui->spinBox_cameraScanFromDepth_decimation->value();
04930 }
04931 double PreferencesDialog::getSourceScanFromDepthMaxDepth() const
04932 {
04933         return _ui->doubleSpinBox_cameraSCanFromDepth_maxDepth->value();
04934 }
04935 double PreferencesDialog::getSourceScanVoxelSize() const
04936 {
04937         return _ui->doubleSpinBox_cameraImages_scanVoxelSize->value();
04938 }
04939 int PreferencesDialog::getSourceScanNormalsK() const
04940 {
04941         return _ui->spinBox_cameraImages_scanNormalsK->value();
04942 }
04943 double PreferencesDialog::getSourceScanNormalsRadius() const
04944 {
04945         return _ui->doubleSpinBox_cameraImages_scanNormalsRadius->value();
04946 }
04947 
04948 Camera * PreferencesDialog::createCamera(bool useRawImages, bool useColor)
04949 {
04950         UDEBUG("");
04951         Src driver = this->getSourceDriver();
04952         Camera * camera = 0;
04953         if(driver == PreferencesDialog::kSrcOpenNI_PCL)
04954         {
04955                 if(useRawImages)
04956                 {
04957                         QMessageBox::warning(this, tr("Calibration"),
04958                                         tr("Using raw images for \"OpenNI\" driver is not yet supported. "
04959                                             "Factory calibration loaded from OpenNI is used."), QMessageBox::Ok);
04960                         return 0;
04961                 }
04962                 else
04963                 {
04964                         camera = new CameraOpenni(
04965                                         _ui->lineEdit_openniOniPath->text().isEmpty()?this->getSourceDevice().toStdString():_ui->lineEdit_openniOniPath->text().toStdString(),
04966                                         this->getGeneralInputRate(),
04967                                         this->getSourceLocalTransform());
04968                 }
04969         }
04970         else if(driver == PreferencesDialog::kSrcOpenNI2)
04971         {
04972                 camera = new CameraOpenNI2(
04973                                 _ui->lineEdit_openni2OniPath->text().isEmpty()?this->getSourceDevice().toStdString():_ui->lineEdit_openni2OniPath->text().toStdString(),
04974                                 useColor?CameraOpenNI2::kTypeColorDepth:CameraOpenNI2::kTypeIRDepth,
04975                                 this->getGeneralInputRate(),
04976                                 this->getSourceLocalTransform());
04977         }
04978         else if(driver == PreferencesDialog::kSrcFreenect)
04979         {
04980                 camera = new CameraFreenect(
04981                                 this->getSourceDevice().isEmpty()?0:atoi(this->getSourceDevice().toStdString().c_str()),
04982                                 useColor?CameraFreenect::kTypeColorDepth:CameraFreenect::kTypeIRDepth,
04983                                 this->getGeneralInputRate(),
04984                                 this->getSourceLocalTransform());
04985         }
04986         else if(driver == PreferencesDialog::kSrcOpenNI_CV ||
04987                         driver == PreferencesDialog::kSrcOpenNI_CV_ASUS)
04988         {
04989                 if(useRawImages)
04990                 {
04991                         QMessageBox::warning(this, tr("Calibration"),
04992                                         tr("Using raw images for \"OpenNI\" driver is not yet supported. "
04993                                                 "Factory calibration loaded from OpenNI is used."), QMessageBox::Ok);
04994                         return 0;
04995                 }
04996                 else
04997                 {
04998                         camera = new CameraOpenNICV(
04999                                         driver == PreferencesDialog::kSrcOpenNI_CV_ASUS,
05000                                         this->getGeneralInputRate(),
05001                                         this->getSourceLocalTransform());
05002                 }
05003         }
05004         else if(driver == kSrcFreenect2)
05005         {
05006                 camera = new CameraFreenect2(
05007                         this->getSourceDevice().isEmpty()?0:atoi(this->getSourceDevice().toStdString().c_str()),
05008                         useRawImages?CameraFreenect2::kTypeColorIR:(CameraFreenect2::Type)_ui->comboBox_freenect2Format->currentIndex(),
05009                         this->getGeneralInputRate(),
05010                         this->getSourceLocalTransform(),
05011                         _ui->doubleSpinBox_freenect2MinDepth->value(),
05012                         _ui->doubleSpinBox_freenect2MaxDepth->value(),
05013                         _ui->checkBox_freenect2BilateralFiltering->isChecked(),
05014                         _ui->checkBox_freenect2EdgeAwareFiltering->isChecked(),
05015                         _ui->checkBox_freenect2NoiseFiltering->isChecked(),
05016                         _ui->lineEdit_freenect2Pipeline->text().toStdString());
05017         }
05018         else if (driver == kSrcK4W2)
05019         {
05020                 camera = new CameraK4W2(
05021                         this->getSourceDevice().isEmpty() ? 0 : atoi(this->getSourceDevice().toStdString().c_str()),
05022                         (CameraK4W2::Type)_ui->comboBox_k4w2Format->currentIndex(),
05023                         this->getGeneralInputRate(),
05024                         this->getSourceLocalTransform());
05025         }
05026         else if (driver == kSrcRealSense)
05027         {
05028                 if(useRawImages && _ui->comboBox_realsenseRGBSource->currentIndex()!=2)
05029                 {
05030                         QMessageBox::warning(this, tr("Calibration"),
05031                                         tr("Using raw images for \"RealSense\" driver is not yet supported for color and infrared streams. "
05032                                                 "Factory calibration loaded from RealSense is used."), QMessageBox::Ok);
05033                         return 0;
05034                 }
05035                 else
05036                 {
05037                         camera = new CameraRealSense(
05038                                 this->getSourceDevice().isEmpty() ? 0 : atoi(this->getSourceDevice().toStdString().c_str()),
05039                                 _ui->comboBox_realsensePresetRGB->currentIndex(),
05040                                 _ui->comboBox_realsensePresetDepth->currentIndex(),
05041                                 _ui->checkbox_realsenseOdom->isChecked(),
05042                                 this->getGeneralInputRate(),
05043                                 this->getSourceLocalTransform());
05044                         ((CameraRealSense*)camera)->setDepthScaledToRGBSize(_ui->checkbox_realsenseDepthScaledToRGBSize->isChecked());
05045                         ((CameraRealSense*)camera)->setRGBSource((CameraRealSense::RGBSource)_ui->comboBox_realsenseRGBSource->currentIndex());
05046                 }
05047         }
05048         else if (driver == kSrcRealSense2)
05049         {
05050                 if(useRawImages)
05051                 {
05052                         QMessageBox::warning(this, tr("Calibration"),
05053                                         tr("Using raw images for \"RealSense\" driver is not yet supported. "
05054                                                 "Factory calibration loaded from RealSense2 is used."), QMessageBox::Ok);
05055                         return 0;
05056                 }
05057                 else
05058                 {
05059                         camera = new CameraRealSense2(
05060                                 this->getSourceDevice().toStdString(),
05061                                 this->getGeneralInputRate(),
05062                                 this->getSourceLocalTransform());
05063                         ((CameraRealSense2*)camera)->setEmitterEnabled(_ui->checkbox_rs2_emitter->isChecked());
05064                         ((CameraRealSense2*)camera)->setIRDepthFormat(_ui->checkbox_rs2_irDepth->isChecked());
05065                 }
05066         }
05067         else if(driver == kSrcRGBDImages)
05068         {
05069                 camera = new CameraRGBDImages(
05070                         _ui->lineEdit_cameraRGBDImages_path_rgb->text().append(QDir::separator()).toStdString(),
05071                         _ui->lineEdit_cameraRGBDImages_path_depth->text().append(QDir::separator()).toStdString(),
05072                         _ui->doubleSpinBox_cameraRGBDImages_scale->value(),
05073                         this->getGeneralInputRate(),
05074                         this->getSourceLocalTransform());
05075                 ((CameraRGBDImages*)camera)->setStartIndex(_ui->spinBox_cameraRGBDImages_startIndex->value());
05076                 ((CameraRGBDImages*)camera)->setBayerMode(_ui->comboBox_cameraImages_bayerMode->currentIndex()-1);
05077                 ((CameraRGBDImages*)camera)->setOdometryPath(_ui->lineEdit_cameraImages_odom->text().toStdString(), _ui->comboBox_cameraImages_odomFormat->currentIndex());
05078                 ((CameraRGBDImages*)camera)->setGroundTruthPath(_ui->lineEdit_cameraImages_gt->text().toStdString(), _ui->comboBox_cameraImages_gtFormat->currentIndex());
05079                 ((CameraRGBDImages*)camera)->setMaxPoseTimeDiff(_ui->doubleSpinBox_maxPoseTimeDiff->value());
05080                 ((CameraRGBDImages*)camera)->setScanPath(
05081                                                 _ui->lineEdit_cameraImages_path_scans->text().isEmpty()?"":_ui->lineEdit_cameraImages_path_scans->text().append(QDir::separator()).toStdString(),
05082                                                 _ui->spinBox_cameraImages_max_scan_pts->value(),
05083                                                 _ui->spinBox_cameraImages_scanDownsampleStep->value(),
05084                                                 _ui->doubleSpinBox_cameraImages_scanVoxelSize->value(),
05085                                                 _ui->spinBox_cameraImages_scanNormalsK->value(),
05086                                                 _ui->doubleSpinBox_cameraImages_scanNormalsRadius->value(),
05087                                                 this->getLaserLocalTransform(),
05088                                                 _ui->checkBox_cameraImages_scanForceGroundNormalsUp->isChecked());
05089                 ((CameraRGBDImages*)camera)->setTimestamps(
05090                                 _ui->checkBox_cameraImages_timestamps->isChecked(),
05091                                 _ui->lineEdit_cameraImages_timestamps->text().toStdString(),
05092                                 _ui->checkBox_cameraImages_syncTimeStamps->isChecked());
05093         }
05094         else if(driver == kSrcDC1394)
05095         {
05096                 camera = new CameraStereoDC1394(
05097                         this->getGeneralInputRate(),
05098                         this->getSourceLocalTransform());
05099         }
05100         else if(driver == kSrcFlyCapture2)
05101         {
05102                 if(useRawImages)
05103                 {
05104                         QMessageBox::warning(this, tr("Calibration"),
05105                                         tr("Using raw images for \"FlyCapture2\" driver is not yet supported. "
05106                                                 "Factory calibration loaded from FlyCapture2 is used."), QMessageBox::Ok);
05107                         return 0;
05108                 }
05109                 else
05110                 {
05111                         camera = new CameraStereoFlyCapture2(
05112                                 this->getGeneralInputRate(),
05113                                 this->getSourceLocalTransform());
05114                 }
05115         }
05116         else if(driver == kSrcStereoImages)
05117         {
05118                 camera = new CameraStereoImages(
05119                         _ui->lineEdit_cameraStereoImages_path_left->text().append(QDir::separator()).toStdString(),
05120                         _ui->lineEdit_cameraStereoImages_path_right->text().append(QDir::separator()).toStdString(),
05121                         _ui->checkBox_stereo_rectify->isChecked() && !useRawImages,
05122                         this->getGeneralInputRate(),
05123                         this->getSourceLocalTransform());
05124                 ((CameraStereoImages*)camera)->setStartIndex(_ui->spinBox_cameraStereoImages_startIndex->value());
05125                 ((CameraStereoImages*)camera)->setBayerMode(_ui->comboBox_cameraImages_bayerMode->currentIndex()-1);
05126                 ((CameraStereoImages*)camera)->setOdometryPath(_ui->lineEdit_cameraImages_odom->text().toStdString(), _ui->comboBox_cameraImages_odomFormat->currentIndex());
05127                 ((CameraStereoImages*)camera)->setGroundTruthPath(_ui->lineEdit_cameraImages_gt->text().toStdString(), _ui->comboBox_cameraImages_gtFormat->currentIndex());
05128                 ((CameraStereoImages*)camera)->setMaxPoseTimeDiff(_ui->doubleSpinBox_maxPoseTimeDiff->value());
05129                 ((CameraStereoImages*)camera)->setScanPath(
05130                                                 _ui->lineEdit_cameraImages_path_scans->text().isEmpty()?"":_ui->lineEdit_cameraImages_path_scans->text().append(QDir::separator()).toStdString(),
05131                                                 _ui->spinBox_cameraImages_max_scan_pts->value(),
05132                                                 _ui->spinBox_cameraImages_scanDownsampleStep->value(),
05133                                                 _ui->doubleSpinBox_cameraImages_scanVoxelSize->value(),
05134                                                 _ui->spinBox_cameraImages_scanNormalsK->value(),
05135                                                 _ui->doubleSpinBox_cameraImages_scanNormalsRadius->value(),
05136                                                 this->getLaserLocalTransform(),
05137                                                 _ui->checkBox_cameraImages_scanForceGroundNormalsUp->isChecked());
05138                 ((CameraStereoImages*)camera)->setTimestamps(
05139                                 _ui->checkBox_cameraImages_timestamps->isChecked(),
05140                                 _ui->lineEdit_cameraImages_timestamps->text().toStdString(),
05141                                 _ui->checkBox_cameraImages_syncTimeStamps->isChecked());
05142 
05143         }
05144         else if (driver == kSrcStereoUsb)
05145         {
05146                 if(_ui->spinBox_stereo_right_device->value()>=0)
05147                 {
05148                         camera = new CameraStereoVideo(
05149                                 this->getSourceDevice().isEmpty() ? 0 : atoi(this->getSourceDevice().toStdString().c_str()),
05150                                 _ui->spinBox_stereo_right_device->value(),
05151                                 _ui->checkBox_stereo_rectify->isChecked() && !useRawImages,
05152                                 this->getGeneralInputRate(),
05153                                 this->getSourceLocalTransform());
05154                 }
05155                 else
05156                 {
05157                         camera = new CameraStereoVideo(
05158                                 this->getSourceDevice().isEmpty() ? 0 : atoi(this->getSourceDevice().toStdString().c_str()),
05159                                 _ui->checkBox_stereo_rectify->isChecked() && !useRawImages,
05160                                 this->getGeneralInputRate(),
05161                                 this->getSourceLocalTransform());
05162                 }
05163         }
05164         else if(driver == kSrcStereoVideo)
05165         {
05166                 if(!_ui->lineEdit_cameraStereoVideo_path_2->text().isEmpty())
05167                 {
05168                         // left and right videos
05169                         camera = new CameraStereoVideo(
05170                                         _ui->lineEdit_cameraStereoVideo_path->text().toStdString(),
05171                                         _ui->lineEdit_cameraStereoVideo_path_2->text().toStdString(),
05172                                         _ui->checkBox_stereo_rectify->isChecked() && !useRawImages,
05173                                         this->getGeneralInputRate(),
05174                                         this->getSourceLocalTransform());
05175                 }
05176                 else
05177                 {
05178                         // side-by-side video
05179                         camera = new CameraStereoVideo(
05180                                         _ui->lineEdit_cameraStereoVideo_path->text().toStdString(),
05181                                         _ui->checkBox_stereo_rectify->isChecked() && !useRawImages,
05182                                         this->getGeneralInputRate(),
05183                                         this->getSourceLocalTransform());
05184                 }
05185         }
05186         else if (driver == kSrcStereoZed)
05187         {
05188                 UDEBUG("ZED");
05189                 if(!_ui->lineEdit_zedSvoPath->text().isEmpty())
05190                 {
05191                         camera = new CameraStereoZed(
05192                                 _ui->lineEdit_zedSvoPath->text().toStdString(),
05193                                 _ui->comboBox_stereoZed_quality->currentIndex(),
05194                                 _ui->comboBox_stereoZed_sensingMode->currentIndex(),
05195                                 _ui->spinBox_stereoZed_confidenceThr->value(),
05196                                 _ui->checkbox_stereoZed_odom->isChecked(),
05197                                 this->getGeneralInputRate(),
05198                                 this->getSourceLocalTransform(),
05199                                 _ui->checkbox_stereoZed_selfCalibration->isChecked());
05200                 }
05201                 else
05202                 {
05203                         camera = new CameraStereoZed(
05204                                 this->getSourceDevice().isEmpty()?0:atoi(this->getSourceDevice().toStdString().c_str()),
05205                                 _ui->comboBox_stereoZed_resolution->currentIndex(),
05206                                 _ui->comboBox_stereoZed_quality->currentIndex(),
05207                                 _ui->comboBox_stereoZed_sensingMode->currentIndex(),
05208                                 _ui->spinBox_stereoZed_confidenceThr->value(),
05209                                 _ui->checkbox_stereoZed_odom->isChecked(),
05210                                 this->getGeneralInputRate(),
05211                                 this->getSourceLocalTransform(),
05212                                 _ui->checkbox_stereoZed_selfCalibration->isChecked());
05213                 }
05214         }
05215         else if(driver == kSrcUsbDevice)
05216         {
05217                 camera = new CameraVideo(
05218                         this->getSourceDevice().isEmpty()?0:atoi(this->getSourceDevice().toStdString().c_str()),
05219                         _ui->checkBox_rgb_rectify->isChecked() && !useRawImages,
05220                         this->getGeneralInputRate(),
05221                         this->getSourceLocalTransform());
05222         }
05223         else if(driver == kSrcVideo)
05224         {
05225                 camera = new CameraVideo(
05226                         _ui->source_video_lineEdit_path->text().toStdString(),
05227                         _ui->checkBox_rgb_rectify->isChecked() && !useRawImages,
05228                         this->getGeneralInputRate(),
05229                         this->getSourceLocalTransform());
05230         }
05231         else if(driver == kSrcImages)
05232         {
05233                 camera = new CameraImages(
05234                         _ui->source_images_lineEdit_path->text().toStdString(),
05235                         this->getGeneralInputRate(),
05236                         this->getSourceLocalTransform());
05237 
05238                 ((CameraImages*)camera)->setStartIndex(_ui->source_images_spinBox_startPos->value());
05239                 ((CameraImages*)camera)->setImagesRectified(_ui->checkBox_rgb_rectify->isChecked() && !useRawImages);
05240 
05241                 ((CameraImages*)camera)->setBayerMode(_ui->comboBox_cameraImages_bayerMode->currentIndex()-1);
05242                 ((CameraImages*)camera)->setOdometryPath(
05243                                 _ui->lineEdit_cameraImages_odom->text().toStdString(),
05244                                 _ui->comboBox_cameraImages_odomFormat->currentIndex());
05245                 ((CameraImages*)camera)->setGroundTruthPath(
05246                                 _ui->lineEdit_cameraImages_gt->text().toStdString(),
05247                                 _ui->comboBox_cameraImages_gtFormat->currentIndex());
05248                 ((CameraImages*)camera)->setMaxPoseTimeDiff(_ui->doubleSpinBox_maxPoseTimeDiff->value());
05249                 ((CameraImages*)camera)->setScanPath(
05250                                                 _ui->lineEdit_cameraImages_path_scans->text().isEmpty()?"":_ui->lineEdit_cameraImages_path_scans->text().append(QDir::separator()).toStdString(),
05251                                                 _ui->spinBox_cameraImages_max_scan_pts->value(),
05252                                                 _ui->spinBox_cameraImages_scanDownsampleStep->value(),
05253                                                 _ui->doubleSpinBox_cameraImages_scanVoxelSize->value(),
05254                                                 _ui->spinBox_cameraImages_scanNormalsK->value(),
05255                                                 _ui->doubleSpinBox_cameraImages_scanNormalsRadius->value(),
05256                                                 this->getLaserLocalTransform(),
05257                                                 _ui->checkBox_cameraImages_scanForceGroundNormalsUp->isChecked());
05258                 ((CameraImages*)camera)->setDepthFromScan(
05259                                 _ui->groupBox_depthFromScan->isChecked(),
05260                                 !_ui->groupBox_depthFromScan_fillHoles->isChecked()?0:_ui->radioButton_depthFromScan_vertical->isChecked()?1:-1,
05261                                 _ui->checkBox_depthFromScan_fillBorders->isChecked());
05262                 ((CameraImages*)camera)->setTimestamps(
05263                                 _ui->checkBox_cameraImages_timestamps->isChecked(),
05264                                 _ui->lineEdit_cameraImages_timestamps->text().toStdString(),
05265                                 _ui->checkBox_cameraImages_syncTimeStamps->isChecked());
05266         }
05267         else if(driver == kSrcDatabase)
05268         {
05269                 camera = new DBReader(_ui->source_database_lineEdit_path->text().toStdString(),
05270                                 _ui->source_checkBox_useDbStamps->isChecked()?-1:this->getGeneralInputRate(),
05271                                 _ui->source_checkBox_ignoreOdometry->isChecked(),
05272                                 _ui->source_checkBox_ignoreGoalDelay->isChecked(),
05273                                 _ui->source_checkBox_ignoreGoals->isChecked(),
05274                                 _ui->source_spinBox_databaseStartPos->value(),
05275                                 _ui->source_spinBox_database_cameraIndex->value());
05276         }
05277         else
05278         {
05279                 UFATAL("Source driver undefined (%d)!", driver);
05280         }
05281 
05282         if(camera)
05283         {
05284                 UDEBUG("Init");
05285                 QString dir = this->getCameraInfoDir();
05286                 QString calibrationFile = _ui->lineEdit_calibrationFile->text();
05287                 if(!(driver >= kSrcRGB && driver <= kSrcVideo))
05288                 {
05289                         calibrationFile.remove("_left.yaml").remove("_right.yaml").remove("_pose.yaml").remove("_rgb.yaml").remove("_depth.yaml");
05290                 }
05291                 QString name = QFileInfo(calibrationFile.remove(".yaml")).baseName();
05292                 if(!_ui->lineEdit_calibrationFile->text().isEmpty())
05293                 {
05294                         QDir d = QFileInfo(_ui->lineEdit_calibrationFile->text()).dir();
05295                         if(!_ui->lineEdit_calibrationFile->text().remove(QFileInfo(_ui->lineEdit_calibrationFile->text()).baseName()).isEmpty())
05296                         {
05297                                 dir = d.absolutePath();
05298                         }
05299                 }
05300 
05301                 // don't set calibration folder if we want raw images
05302                 if(!camera->init(useRawImages?"":dir.toStdString(), name.toStdString()))
05303                 {
05304                         UWARN("init camera failed... ");
05305                         QMessageBox::warning(this,
05306                                            tr("RTAB-Map"),
05307                                            tr("Camera initialization failed..."));
05308                         delete camera;
05309                         camera = 0;
05310                 }
05311                 else
05312                 {
05313                         //should be after initialization
05314                         if(driver == kSrcOpenNI2)
05315                         {
05316                                 ((CameraOpenNI2*)camera)->setAutoWhiteBalance(_ui->openni2_autoWhiteBalance->isChecked());
05317                                 ((CameraOpenNI2*)camera)->setAutoExposure(_ui->openni2_autoExposure->isChecked());
05318                                 ((CameraOpenNI2*)camera)->setMirroring(_ui->openni2_mirroring->isChecked());
05319                                 ((CameraOpenNI2*)camera)->setOpenNI2StampsAndIDsUsed(_ui->openni2_stampsIdsUsed->isChecked());
05320                                 if(CameraOpenNI2::exposureGainAvailable())
05321                                 {
05322                                         ((CameraOpenNI2*)camera)->setExposure(_ui->openni2_exposure->value());
05323                                         ((CameraOpenNI2*)camera)->setGain(_ui->openni2_gain->value());
05324                                 }
05325                                 ((CameraOpenNI2*)camera)->setIRDepthShift(_ui->openni2_hshift->value(), _ui->openni2_vshift->value());
05326                                 ((CameraOpenNI2*)camera)->setMirroring(_ui->openni2_mirroring->isChecked());
05327                         }
05328                 }
05329         }
05330 
05331         UDEBUG("");
05332         return camera;
05333 }
05334 
05335 bool PreferencesDialog::isStatisticsPublished() const
05336 {
05337         return _ui->groupBox_publishing->isChecked();
05338 }
05339 double PreferencesDialog::getLoopThr() const
05340 {
05341         return _ui->general_doubleSpinBox_hardThr->value();
05342 }
05343 double PreferencesDialog::getVpThr() const
05344 {
05345         return _ui->general_doubleSpinBox_vp->value();
05346 }
05347 double PreferencesDialog::getSimThr() const
05348 {
05349         return _ui->doubleSpinBox_similarityThreshold->value();
05350 }
05351 int PreferencesDialog::getOdomStrategy() const
05352 {
05353         return _ui->odom_strategy->currentIndex();
05354 }
05355 int PreferencesDialog::getOdomBufferSize() const
05356 {
05357         return _ui->odom_dataBufferSize->value();
05358 }
05359 
05360 QString PreferencesDialog::getCameraInfoDir() const
05361 {
05362         return (this->getWorkingDirectory().isEmpty()?".":this->getWorkingDirectory())+"/camera_info";
05363 }
05364 
05365 bool PreferencesDialog::isImagesKept() const
05366 {
05367         return _ui->general_checkBox_imagesKept->isChecked();
05368 }
05369 bool PreferencesDialog::isCloudsKept() const
05370 {
05371         return _ui->general_checkBox_cloudsKept->isChecked();
05372 }
05373 float PreferencesDialog::getTimeLimit() const
05374 {
05375         return _ui->general_doubleSpinBox_timeThr->value();
05376 }
05377 float PreferencesDialog::getDetectionRate() const
05378 {
05379         return _ui->general_doubleSpinBox_detectionRate->value();
05380 }
05381 bool PreferencesDialog::isSLAMMode() const
05382 {
05383         return _ui->general_checkBox_SLAM_mode->isChecked();
05384 }
05385 bool PreferencesDialog::isRGBDMode() const
05386 {
05387         return _ui->general_checkBox_activateRGBD->isChecked();
05388 }
05389 int PreferencesDialog::getKpMaxFeatures() const
05390 {
05391         return _ui->surf_spinBox_wordsPerImageTarget->value();
05392 }
05393 
05394 /*** SETTERS ***/
05395 void PreferencesDialog::setInputRate(double value)
05396 {
05397         ULOGGER_DEBUG("imgRate=%2.2f", value);
05398         if(_ui->general_doubleSpinBox_imgRate->value() != value)
05399         {
05400                 _ui->general_doubleSpinBox_imgRate->setValue(value);
05401                 if(validateForm())
05402                 {
05403                         this->writeSettings(getTmpIniFilePath());
05404                 }
05405                 else
05406                 {
05407                         this->readSettingsBegin();
05408                 }
05409         }
05410 }
05411 
05412 void PreferencesDialog::setDetectionRate(double value)
05413 {
05414         ULOGGER_DEBUG("detectionRate=%2.2f", value);
05415         if(_ui->general_doubleSpinBox_detectionRate->value() != value)
05416         {
05417                 _ui->general_doubleSpinBox_detectionRate->setValue(value);
05418                 if(validateForm())
05419                 {
05420                         this->writeSettings(getTmpIniFilePath());
05421                 }
05422                 else
05423                 {
05424                         this->readSettingsBegin();
05425                 }
05426         }
05427 }
05428 
05429 void PreferencesDialog::setTimeLimit(float value)
05430 {
05431         ULOGGER_DEBUG("timeLimit=%fs", value);
05432         if(_ui->general_doubleSpinBox_timeThr->value() != value)
05433         {
05434                 _ui->general_doubleSpinBox_timeThr->setValue(value);
05435                 if(validateForm())
05436                 {
05437                         this->writeSettings(getTmpIniFilePath());
05438                 }
05439                 else
05440                 {
05441                         this->readSettingsBegin();
05442                 }
05443         }
05444 }
05445 
05446 void PreferencesDialog::setSLAMMode(bool enabled)
05447 {
05448         ULOGGER_DEBUG("slam mode=%s", enabled?"true":"false");
05449         if(_ui->general_checkBox_SLAM_mode->isChecked() != enabled)
05450         {
05451                 _ui->general_checkBox_SLAM_mode->setChecked(enabled);
05452                 if(validateForm())
05453                 {
05454                         this->writeSettings(getTmpIniFilePath());
05455                 }
05456                 else
05457                 {
05458                         this->readSettingsBegin();
05459                 }
05460         }
05461 }
05462 
05463 void PreferencesDialog::testOdometry()
05464 {
05465         Camera * camera = this->createCamera();
05466         if(!camera)
05467         {
05468                 return;
05469         }
05470 
05471         IMUThread * imuThread = 0;
05472         if((this->getSourceDriver() == kSrcStereoImages ||
05473            this->getSourceDriver() == kSrcRGBDImages ||
05474            this->getSourceDriver() == kSrcImages) &&
05475            !_ui->lineEdit_cameraImages_path_imu->text().isEmpty())
05476         {
05477                 if(this->getOdomStrategy() != Odometry::kTypeOkvis && this->getOdomStrategy() != Odometry::kTypeMSCKF)
05478                 {
05479                         QMessageBox::warning(this, tr("Source IMU Path"),
05480                                         tr("IMU path is set but odometry chosen doesn't support IMU, ignoring IMU..."), QMessageBox::Ok);
05481                 }
05482                 else
05483                 {
05484                         imuThread = new IMUThread(_ui->spinBox_cameraImages_max_imu_rate->value(), this->getIMULocalTransform());
05485                         if(!imuThread->init(_ui->lineEdit_cameraImages_path_imu->text().toStdString()))
05486                         {
05487                                 QMessageBox::warning(this, tr("Source IMU Path"),
05488                                         tr("Initialization of IMU data has failed! Path=%1.").arg(_ui->lineEdit_cameraImages_path_imu->text()), QMessageBox::Ok);
05489                                 delete camera;
05490                                 delete imuThread;
05491                                 return;
05492                         }
05493                 }
05494         }
05495 
05496         ParametersMap parameters = this->getAllParameters();
05497         if(getOdomRegistrationApproach() < 3)
05498         {
05499                 uInsert(parameters, ParametersPair(Parameters::kRegStrategy(), uNumber2Str(getOdomRegistrationApproach())));
05500         }
05501 
05502         int odomStrategy = Parameters::defaultOdomStrategy();
05503         Parameters::parse(parameters, Parameters::kOdomStrategy(), odomStrategy);
05504         if(odomStrategy == 1)
05505         {
05506                 // Only Frame To Frame supports  all VisCorType
05507                 parameters.insert(ParametersPair(Parameters::kVisCorType(), this->getParameter(Parameters::kVisCorType())));
05508         }
05509 
05510         Odometry * odometry = Odometry::create(parameters);
05511 
05512         OdometryThread odomThread(
05513                         odometry, // take ownership of odometry
05514                         _ui->odom_dataBufferSize->value());
05515         odomThread.registerToEventsManager();
05516 
05517         OdometryViewer * odomViewer = new OdometryViewer(10,
05518                                         _ui->spinBox_decimation_odom->value(),
05519                                         0.0f,
05520                                         _ui->doubleSpinBox_maxDepth_odom->value(),
05521                                         this->getOdomQualityWarnThr(),
05522                                         this,
05523                                         this->getAllParameters());
05524         odomViewer->setWindowTitle(tr("Odometry viewer"));
05525         odomViewer->resize(1280, 480+QPushButton().minimumHeight());
05526         odomViewer->registerToEventsManager();
05527 
05528         CameraThread cameraThread(camera, this->getAllParameters()); // take ownership of camera
05529         cameraThread.setMirroringEnabled(isSourceMirroring());
05530         cameraThread.setColorOnly(_ui->checkbox_rgbd_colorOnly->isChecked());
05531         cameraThread.setImageDecimation(_ui->spinBox_source_imageDecimation->value());
05532         cameraThread.setStereoToDepth(_ui->checkbox_stereo_depthGenerated->isChecked());
05533         cameraThread.setStereoExposureCompensation(_ui->checkBox_stereo_exposureCompensation->isChecked());
05534         cameraThread.setScanFromDepth(
05535                         _ui->groupBox_scanFromDepth->isChecked(),
05536                         _ui->spinBox_cameraScanFromDepth_decimation->value(),
05537                         _ui->doubleSpinBox_cameraSCanFromDepth_maxDepth->value(),
05538                         _ui->doubleSpinBox_cameraImages_scanVoxelSize->value(),
05539                         _ui->spinBox_cameraImages_scanNormalsK->value(),
05540                         _ui->doubleSpinBox_cameraImages_scanNormalsRadius->value());
05541         if(isDepthFilteringAvailable())
05542         {
05543                 if(_ui->groupBox_bilateral->isChecked())
05544                 {
05545                         cameraThread.enableBilateralFiltering(
05546                                         _ui->doubleSpinBox_bilateral_sigmaS->value(),
05547                                         _ui->doubleSpinBox_bilateral_sigmaR->value());
05548                 }
05549                 if(!_ui->lineEdit_source_distortionModel->text().isEmpty())
05550                 {
05551                         cameraThread.setDistortionModel(_ui->lineEdit_source_distortionModel->text().toStdString());
05552                 }
05553         }
05554 
05555         UEventsManager::createPipe(&cameraThread, &odomThread, "CameraEvent");
05556         if(imuThread)
05557         {
05558                 UEventsManager::createPipe(imuThread, &odomThread, "IMUEvent");
05559         }
05560         UEventsManager::createPipe(&odomThread, odomViewer, "OdometryEvent");
05561         UEventsManager::createPipe(odomViewer, &odomThread, "OdometryResetEvent");
05562 
05563         odomThread.start();
05564         cameraThread.start();
05565 
05566         if(imuThread)
05567         {
05568                 imuThread->start();
05569         }
05570 
05571         odomViewer->exec();
05572         delete odomViewer;
05573 
05574         if(imuThread)
05575         {
05576                 imuThread->join(true);
05577                 delete imuThread;
05578         }
05579         cameraThread.join(true);
05580         odomThread.join(true);
05581 }
05582 
05583 void PreferencesDialog::testCamera()
05584 {
05585         CameraViewer * window = new CameraViewer(this, this->getAllParameters());
05586         window->setWindowTitle(tr("Camera viewer"));
05587         window->resize(1280, 480+QPushButton().minimumHeight());
05588         window->registerToEventsManager();
05589 
05590         Camera * camera = this->createCamera();
05591         if(camera)
05592         {
05593                 CameraThread cameraThread(camera, this->getAllParameters());
05594                 cameraThread.setMirroringEnabled(isSourceMirroring());
05595                 cameraThread.setColorOnly(_ui->checkbox_rgbd_colorOnly->isChecked());
05596                 cameraThread.setImageDecimation(_ui->spinBox_source_imageDecimation->value());
05597                 cameraThread.setStereoToDepth(_ui->checkbox_stereo_depthGenerated->isChecked());
05598                 cameraThread.setStereoExposureCompensation(_ui->checkBox_stereo_exposureCompensation->isChecked());
05599                 cameraThread.setScanFromDepth(
05600                                 _ui->groupBox_scanFromDepth->isChecked(),
05601                                 _ui->spinBox_cameraScanFromDepth_decimation->value(),
05602                                 _ui->doubleSpinBox_cameraSCanFromDepth_maxDepth->value(),
05603                                 _ui->doubleSpinBox_cameraImages_scanVoxelSize->value(),
05604                                 _ui->spinBox_cameraImages_scanNormalsK->value(),
05605                                 _ui->doubleSpinBox_cameraImages_scanNormalsRadius->value());
05606                 if(isDepthFilteringAvailable())
05607                 {
05608                         if(_ui->groupBox_bilateral->isChecked())
05609                         {
05610                                 cameraThread.enableBilateralFiltering(
05611                                                 _ui->doubleSpinBox_bilateral_sigmaS->value(),
05612                                                 _ui->doubleSpinBox_bilateral_sigmaR->value());
05613                         }
05614                         if(!_ui->lineEdit_source_distortionModel->text().isEmpty())
05615                         {
05616                                 cameraThread.setDistortionModel(_ui->lineEdit_source_distortionModel->text().toStdString());
05617                         }
05618                 }
05619                 UEventsManager::createPipe(&cameraThread, window, "CameraEvent");
05620 
05621                 cameraThread.start();
05622                 window->exec();
05623                 delete window;
05624                 cameraThread.join(true);
05625         }
05626         else
05627         {
05628                 delete window;
05629         }
05630 }
05631 
05632 void PreferencesDialog::calibrate()
05633 {
05634         if(this->getSourceType() == kSrcDatabase)
05635         {
05636                 QMessageBox::warning(this,
05637                                    tr("Calibration"),
05638                                    tr("Cannot calibrate database source!"));
05639                 return;
05640         }
05641 
05642         if(!this->getCameraInfoDir().isEmpty())
05643         {
05644                 QDir dir(this->getCameraInfoDir());
05645                 if (!dir.exists())
05646                 {
05647                         UINFO("Creating camera_info directory: \"%s\"", this->getCameraInfoDir().toStdString().c_str());
05648                         if(!dir.mkpath(this->getCameraInfoDir()))
05649                         {
05650                                 UWARN("Could create camera_info directory: \"%s\"", this->getCameraInfoDir().toStdString().c_str());
05651                         }
05652                 }
05653         }
05654 
05655         Src driver = this->getSourceDriver();
05656         if(driver == PreferencesDialog::kSrcFreenect || driver == PreferencesDialog::kSrcOpenNI2)
05657         {
05658                 // 3 steps calibration: RGB -> IR -> Extrinsic
05659                 QMessageBox::StandardButton button = QMessageBox::question(this, tr("Calibration"),
05660                                 tr("With \"%1\" driver, Color and IR cameras cannot be streamed at the "
05661                                         "same time. A 3-steps calibration is required (Color -> IR -> extrinsics). We will "
05662                                         "start with the Color camera calibration. Do you want to continue?").arg(this->getSourceDriverStr()),
05663                                         QMessageBox::Yes | QMessageBox::No | QMessageBox::Ignore, QMessageBox::Yes);
05664 
05665                 if(button == QMessageBox::Yes || button == QMessageBox::Ignore)
05666                 {
05667                         _calibrationDialog->setSavingDirectory(this->getCameraInfoDir());
05668 
05669                         Camera * camera = 0;
05670 
05671                         // Step 1: RGB
05672                         if(button != QMessageBox::Ignore)
05673                         {
05674                                 camera = this->createCamera(true, true); // RAW color
05675                                 if(!camera)
05676                                 {
05677                                         return;
05678                                 }
05679 
05680                                 _calibrationDialog->setStereoMode(false); // this forces restart
05681                                 _calibrationDialog->setCameraName(QString(camera->getSerial().c_str())+"_rgb");
05682                                 _calibrationDialog->registerToEventsManager();
05683                                 CameraThread cameraThread(camera, this->getAllParameters());
05684                                 UEventsManager::createPipe(&cameraThread, _calibrationDialog, "CameraEvent");
05685                                 cameraThread.start();
05686                                 _calibrationDialog->exec();
05687                                 _calibrationDialog->unregisterFromEventsManager();
05688                                 cameraThread.join(true);
05689                                 camera = 0;
05690                         }
05691 
05692                         button = QMessageBox::question(this, tr("Calibration"),
05693                                                 tr("We will now calibrate the IR camera. Hide the IR projector with a Post-It and "
05694                                                         "make sure you have enough ambient IR light (e.g., external IR source or sunlight!) to see the "
05695                                                         "checkboard with the IR camera. Do you want to continue?"),
05696                                                         QMessageBox::Yes | QMessageBox::No | QMessageBox::Ignore, QMessageBox::Yes);
05697                         if(button == QMessageBox::Yes || button == QMessageBox::Ignore)
05698                         {
05699                                 // Step 2: IR
05700                                 if(button != QMessageBox::Ignore)
05701                                 {
05702                                         camera = this->createCamera(true, false); // RAW ir
05703                                         if(!camera)
05704                                         {
05705                                                 return;
05706                                         }
05707 
05708                                         _calibrationDialog->setStereoMode(false); // this forces restart
05709                                         _calibrationDialog->setCameraName(QString(camera->getSerial().c_str())+"_depth");
05710                                         _calibrationDialog->registerToEventsManager();
05711                                         CameraThread cameraThread(camera, this->getAllParameters());
05712                                         UEventsManager::createPipe(&cameraThread, _calibrationDialog, "CameraEvent");
05713                                         cameraThread.start();
05714                                         _calibrationDialog->exec();
05715                                         _calibrationDialog->unregisterFromEventsManager();
05716                                         cameraThread.join(true);
05717                                         camera = 0;
05718                                 }
05719 
05720                                 button = QMessageBox::question(this, tr("Calibration"),
05721                                                         tr("We will now calibrate the extrinsics. Important: Make sure "
05722                                                                 "the cameras and the checkboard don't move and that both "
05723                                                                 "cameras can see the checkboard. We will repeat this "
05724                                                                 "multiple times. Each time, you will have to move the camera (or "
05725                                                                 "checkboard) for a different point of view. Do you want to "
05726                                                                 "continue?"),
05727                                                                 QMessageBox::Yes | QMessageBox::No, QMessageBox::Yes);
05728 
05729                                 bool ok = false;
05730                                 int totalSamples = 0;
05731                                 if(button == QMessageBox::Yes)
05732                                 {
05733                                         totalSamples = QInputDialog::getInt(this, tr("Calibration"), tr("Samples: "), 3, 1, 99, 1, &ok);
05734                                 }
05735 
05736                                 if(ok)
05737                                 {
05738                                         int count = 0;
05739                                         _calibrationDialog->setStereoMode(true, "depth", "rgb"); // this forces restart
05740                                         _calibrationDialog->setCameraName("");
05741                                         _calibrationDialog->setModal(true);
05742                                         _calibrationDialog->setProgressVisibility(false);
05743                                         _calibrationDialog->show();
05744                                         CameraModel irModel;
05745                                         CameraModel rgbModel;
05746                                         std::string serial;
05747                                         for(;count < totalSamples && button == QMessageBox::Yes; )
05748                                         {
05749                                                 // Step 3: Extrinsics
05750                                                 camera = this->createCamera(false, true); // Rectified color
05751                                                 if(!camera)
05752                                                 {
05753                                                         return;
05754                                                 }
05755                                                 SensorData rgbData = camera->takeImage();
05756                                                 UASSERT(rgbData.cameraModels().size() == 1);
05757                                                 rgbModel = rgbData.cameraModels()[0];
05758                                                 delete camera;
05759                                                 camera = this->createCamera(false, false); // Rectified ir
05760                                                 if(!camera)
05761                                                 {
05762                                                         return;
05763                                                 }
05764                                                 SensorData irData = camera->takeImage();
05765                                                 serial = camera->getSerial();
05766                                                 UASSERT(irData.cameraModels().size() == 1);
05767                                                 irModel = irData.cameraModels()[0];
05768                                                 delete camera;
05769 
05770                                                 if(!rgbData.imageRaw().empty() && !irData.imageRaw().empty())
05771                                                 {
05772                                                         // assume rgb sensor is on right (e.g., Kinect, Xtion Live Pro)
05773                                                         int pair = _calibrationDialog->getStereoPairs();
05774                                                         _calibrationDialog->processImages(irData.imageRaw(), rgbData.imageRaw(), serial.c_str());
05775                                                         if(_calibrationDialog->getStereoPairs() - pair > 0)
05776                                                         {
05777                                                                 ++count;
05778                                                                 if(count < totalSamples)
05779                                                                 {
05780                                                                         button = QMessageBox::question(this, tr("Calibration"),
05781                                                                                 tr("A stereo pair has been taken (total=%1/%2). Move the checkboard or "
05782                                                                                         "camera to another position. Press \"Yes\" when you are ready "
05783                                                                                         "for the next capture.").arg(count).arg(totalSamples),
05784                                                                                         QMessageBox::Yes | QMessageBox::Abort, QMessageBox::Yes);
05785                                                                 }
05786                                                         }
05787                                                         else
05788                                                         {
05789                                                                 button = QMessageBox::question(this, tr("Calibration"),
05790                                                                                 tr("Could not detect the checkboard on both images or "
05791                                                                                    "the point of view didn't change enough. Try again?"),
05792                                                                                         QMessageBox::Yes | QMessageBox::No, QMessageBox::Yes);
05793                                                         }
05794                                                 }
05795                                                 else
05796                                                 {
05797                                                         button = QMessageBox::question(this, tr("Calibration"),
05798                                                                                 tr("Failed to start the camera. Try again?"), QMessageBox::Yes | QMessageBox::No, QMessageBox::Yes);
05799                                                 }
05800                                         }
05801                                         if(count == totalSamples && button == QMessageBox::Yes)
05802                                         {
05803                                                 StereoCameraModel stereoModel = _calibrationDialog->stereoCalibration(irModel, rgbModel, true);
05804                                                 stereoModel.setName(stereoModel.name(), "depth", "rgb");
05805                                                 if(stereoModel.stereoTransform().isNull())
05806                                                 {
05807                                                         QMessageBox::warning(this, tr("Calibration"),
05808                                                                         tr("Extrinsic calibration has failed! Look on the terminal "
05809                                                                            "for possible error messages. Make sure corresponding calibration files exist "
05810                                                                            "in \"%1\" folder for camera \"%2\" or calibration name set. If not, re-do "
05811                                                                            "step 1 and 2 and make sure to export the calibration files.").arg(this->getCameraInfoDir()).arg(serial.c_str()), QMessageBox::Ok);
05812                                                 }
05813                                                 else if(stereoModel.saveStereoTransform(this->getCameraInfoDir().toStdString()))
05814                                                 {
05815                                                         QMessageBox::information(this, tr("Calibration"),
05816                                                                         tr("Calibration is completed! Extrinsics have been saved to \"%1/%2_pose.yaml\"").arg(this->getCameraInfoDir()).arg(stereoModel.name().c_str()), QMessageBox::Ok);
05817                                                 }
05818                                         }
05819                                 }
05820                         }
05821                 }
05822         }
05823         else // standard calibration
05824         {
05825                 Camera * camera = this->createCamera(true);
05826                 if(!camera)
05827                 {
05828                         return;
05829                 }
05830 
05831                 bool freenect2 = driver == kSrcFreenect2;
05832                 _calibrationDialog->setStereoMode(this->getSourceType() != kSrcRGB && driver != kSrcRealSense, freenect2?"rgb":"left", freenect2?"depth":"right"); // RGB+Depth or left+right
05833                 _calibrationDialog->setSwitchedImages(freenect2);
05834                 _calibrationDialog->setSavingDirectory(this->getCameraInfoDir());
05835                 _calibrationDialog->registerToEventsManager();
05836 
05837                 CameraThread cameraThread(camera, this->getAllParameters());
05838                 UEventsManager::createPipe(&cameraThread, _calibrationDialog, "CameraEvent");
05839 
05840                 cameraThread.start();
05841 
05842                 _calibrationDialog->exec();
05843                 _calibrationDialog->unregisterFromEventsManager();
05844 
05845                 cameraThread.join(true);
05846         }
05847 }
05848 
05849 void PreferencesDialog::calibrateSimple()
05850 {
05851         _createCalibrationDialog->setCameraInfoDir(this->getCameraInfoDir());
05852         if(_createCalibrationDialog->exec() == QMessageBox::Accepted)
05853         {
05854                 _ui->lineEdit_calibrationFile->setText(_createCalibrationDialog->cameraName());
05855         }
05856 }
05857 
05858 }
05859 


rtabmap
Author(s): Mathieu Labbe
autogenerated on Thu Jun 6 2019 21:59:21