PreferencesDialog.cpp
Go to the documentation of this file.
00001 /*
00002 Copyright (c) 2010-2014, 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 
00037 #include <QFileDialog>
00038 #include <QMessageBox>
00039 #include <QtGui/QStandardItemModel>
00040 #include <QMainWindow>
00041 #include <QProgressDialog>
00042 #include <QScrollBar>
00043 #include <QtGui/QCloseEvent>
00044 
00045 #include "ui_preferencesDialog.h"
00046 
00047 #include "rtabmap/core/Version.h"
00048 #include "rtabmap/core/Rtabmap.h"
00049 #include "rtabmap/core/Parameters.h"
00050 #include "rtabmap/core/Odometry.h"
00051 #include "rtabmap/core/OdometryThread.h"
00052 #include "rtabmap/core/CameraRGBD.h"
00053 #include "rtabmap/core/CameraThread.h"
00054 #include "rtabmap/core/Camera.h"
00055 #include "rtabmap/core/Memory.h"
00056 #include "rtabmap/core/VWDictionary.h"
00057 #include "rtabmap/core/Graph.h"
00058 
00059 #include "rtabmap/gui/LoopClosureViewer.h"
00060 #include "rtabmap/gui/CameraViewer.h"
00061 #include "rtabmap/gui/CloudViewer.h"
00062 #include "rtabmap/gui/ImageView.h"
00063 #include "GraphViewer.h"
00064 #include "ExportCloudsDialog.h"
00065 #include "PostProcessingDialog.h"
00066 
00067 #include <rtabmap/utilite/ULogger.h>
00068 #include <rtabmap/utilite/UConversion.h>
00069 #include <rtabmap/utilite/UStl.h>
00070 #include <rtabmap/utilite/UEventsManager.h>
00071 #include "utilite/UPlot.h"
00072 
00073 #include <opencv2/gpu/gpu.hpp>
00074 
00075 using namespace rtabmap;
00076 
00077 namespace rtabmap {
00078 
00079 PreferencesDialog::PreferencesDialog(QWidget * parent) :
00080         QDialog(parent),
00081         _obsoletePanels(kPanelDummy),
00082         _ui(0),
00083         _indexModel(0),
00084         _initialized(false),
00085         _calibrationDialog(new CalibrationDialog(false, ".", this))
00086 {
00087         ULOGGER_DEBUG("");
00088         _calibrationDialog->setWindowFlags(Qt::Window);
00089         _calibrationDialog->setWindowTitle(tr("Calibration"));
00090 
00091         _ui = new Ui_preferencesDialog();
00092         _ui->setupUi(this);
00093 
00094         if(cv::gpu::getCudaEnabledDeviceCount() == 0)
00095         {
00096                 _ui->surf_checkBox_gpuVersion->setChecked(false);
00097                 _ui->surf_checkBox_gpuVersion->setEnabled(false);
00098                 _ui->label_surf_checkBox_gpuVersion->setEnabled(false);
00099                 _ui->surf_doubleSpinBox_gpuKeypointsRatio->setEnabled(false);
00100                 _ui->label_surf_checkBox_gpuKeypointsRatio->setEnabled(false);
00101 
00102                 _ui->fastGpu->setChecked(false);
00103                 _ui->fastGpu->setEnabled(false);
00104                 _ui->label_fastGPU->setEnabled(false);
00105                 _ui->fastKeypointRatio->setEnabled(false);
00106                 _ui->label_fastGPUKptRatio->setEnabled(false);
00107 
00108                 _ui->checkBox_ORBGpu->setChecked(false);
00109                 _ui->checkBox_ORBGpu->setEnabled(false);
00110                 _ui->label_orbGpu->setEnabled(false);
00111 
00112                 // remove BruteForceGPU option
00113                 _ui->comboBox_dictionary_strategy->removeItem(4);
00114                 _ui->odom_bin_nn->removeItem(4);
00115                 _ui->reextract_nn->removeItem(4);
00116         }
00117 
00118 #if PCL_VERSION_COMPARE(<, 1, 7, 2)
00119         _ui->checkBox_map_shown->setChecked(false);
00120         _ui->checkBox_map_shown->setEnabled(false);
00121         _ui->label_map_shown->setText(_ui->label_map_shown->text() + " (Disabled, PCL >=1.7.2 required)");
00122 #endif
00123 
00124         if(RTABMAP_NONFREE == 0)
00125         {
00126                 _ui->comboBox_detector_strategy->setItemData(0, 0, Qt::UserRole - 1);
00127                 _ui->comboBox_detector_strategy->setItemData(1, 0, Qt::UserRole - 1);
00128                 _ui->reextract_type->setItemData(0, 0, Qt::UserRole - 1);
00129                 _ui->reextract_type->setItemData(1, 0, Qt::UserRole - 1);
00130                 _ui->odom_type->setItemData(0, 0, Qt::UserRole - 1);
00131                 _ui->odom_type->setItemData(1, 0, Qt::UserRole - 1);
00132 
00133                 _ui->comboBox_dictionary_strategy->setItemData(1, 0, Qt::UserRole - 1);
00134                 _ui->reextract_nn->setItemData(1, 0, Qt::UserRole - 1);
00135                 _ui->odom_bin_nn->setItemData(1, 0, Qt::UserRole - 1);
00136         }
00137         if(!graph::G2OOptimizer::available())
00138         {
00139                 _ui->graphOptimization_type->setItemData(1, 0, Qt::UserRole - 1);
00140         }
00141         if(!CameraFreenect::available())
00142         {
00143                 _ui->comboBox_cameraRGBD->setItemData(1, 0, Qt::UserRole - 1);
00144         }
00145         if(!CameraOpenNICV::available())
00146         {
00147                 _ui->comboBox_cameraRGBD->setItemData(2, 0, Qt::UserRole - 1);
00148                 _ui->comboBox_cameraRGBD->setItemData(3, 0, Qt::UserRole - 1);
00149         }
00150         if(!CameraOpenNI2::available())
00151         {
00152                 _ui->comboBox_cameraRGBD->setItemData(4, 0, Qt::UserRole - 1);
00153         }
00154         if(!CameraFreenect2::available())
00155         {
00156                 _ui->comboBox_cameraRGBD->setItemData(5, 0, Qt::UserRole - 1);
00157         }
00158         if(!CameraStereoDC1394::available())
00159         {
00160                 _ui->comboBox_cameraRGBD->setItemData(6, 0, Qt::UserRole - 1);
00161         }
00162         if(!CameraStereoFlyCapture2::available())
00163         {
00164                 _ui->comboBox_cameraRGBD->setItemData(7, 0, Qt::UserRole - 1);
00165         }
00166         _ui->openni2_exposure->setEnabled(CameraOpenNI2::exposureGainAvailable());
00167         _ui->openni2_gain->setEnabled(CameraOpenNI2::exposureGainAvailable());
00168 
00169         // Default Driver
00170         connect(_ui->comboBox_cameraRGBD, SIGNAL(currentIndexChanged(int)), this, SLOT(updateRGBDCameraGroupBoxVisibility()));
00171         this->resetSettings(_ui->groupBox_source0);
00172 
00173         _ui->predictionPlot->showLegend(false);
00174 
00175         QButtonGroup * buttonGroup = new QButtonGroup(this);
00176         buttonGroup->addButton(_ui->radioButton_basic);
00177         buttonGroup->addButton(_ui->radioButton_advanced);
00178 
00179         // Connect
00180         connect(_ui->buttonBox_global, SIGNAL(clicked(QAbstractButton *)), this, SLOT(closeDialog(QAbstractButton *)));
00181         connect(_ui->buttonBox_local, SIGNAL(clicked(QAbstractButton *)), this, SLOT(resetApply(QAbstractButton *)));
00182         connect(_ui->pushButton_loadConfig, SIGNAL(clicked()), this, SLOT(loadConfigFrom()));
00183         connect(_ui->pushButton_saveConfig, SIGNAL(clicked()), this, SLOT(saveConfigTo()));
00184         connect(_ui->pushButton_resetConfig, SIGNAL(clicked()), this, SLOT(resetConfig()));
00185         connect(_ui->radioButton_basic, SIGNAL(toggled(bool)), this, SLOT(setupTreeView()));
00186         connect(_ui->pushButton_testOdometry, SIGNAL(clicked()), this, SLOT(testOdometry()));
00187         connect(_ui->pushButton_test_rgbd_camera, SIGNAL(clicked()), this, SLOT(testRGBDCamera()));
00188 
00189         // General panel
00190         connect(_ui->general_checkBox_imagesKept, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteGeneralPanel()));
00191         connect(_ui->checkBox_verticalLayoutUsed, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteGeneralPanel()));
00192         connect(_ui->checkBox_imageRejectedShown, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteGeneralPanel()));
00193         connect(_ui->checkBox_imageHighestHypShown, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteGeneralPanel()));
00194         connect(_ui->checkBox_beep, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteGeneralPanel()));
00195         connect(_ui->checkBox_notifyWhenNewGlobalPathIsReceived, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteGeneralPanel()));
00196         connect(_ui->spinBox_odomQualityWarnThr, SIGNAL(valueChanged(int)), this, SLOT(makeObsoleteGeneralPanel()));
00197         connect(_ui->checkBox_posteriorGraphView, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteGeneralPanel()));
00198 
00199         // Cloud rendering panel
00200         _3dRenderingShowClouds.resize(2);
00201         _3dRenderingShowClouds[0] = _ui->checkBox_showClouds;
00202         _3dRenderingShowClouds[1] = _ui->checkBox_showOdomClouds;
00203 
00204         _3dRenderingVoxelSize.resize(2);
00205         _3dRenderingVoxelSize[0] = _ui->doubleSpinBox_voxelSize;
00206         _3dRenderingVoxelSize[1] = _ui->doubleSpinBox_voxelSize_odom;
00207 
00208         _3dRenderingDecimation.resize(2);
00209         _3dRenderingDecimation[0] = _ui->spinBox_decimation;
00210         _3dRenderingDecimation[1] = _ui->spinBox_decimation_odom;
00211 
00212         _3dRenderingMaxDepth.resize(2);
00213         _3dRenderingMaxDepth[0] = _ui->doubleSpinBox_maxDepth;
00214         _3dRenderingMaxDepth[1] = _ui->doubleSpinBox_maxDepth_odom;
00215 
00216         _3dRenderingOpacity.resize(2);
00217         _3dRenderingOpacity[0] = _ui->doubleSpinBox_opacity;
00218         _3dRenderingOpacity[1] = _ui->doubleSpinBox_opacity_odom;
00219 
00220         _3dRenderingPtSize.resize(2);
00221         _3dRenderingPtSize[0] = _ui->spinBox_ptsize;
00222         _3dRenderingPtSize[1] = _ui->spinBox_ptsize_odom;
00223 
00224         _3dRenderingShowScans.resize(2);
00225         _3dRenderingShowScans[0] = _ui->checkBox_showScans;
00226         _3dRenderingShowScans[1] = _ui->checkBox_showOdomScans;
00227 
00228         _3dRenderingOpacityScan.resize(2);
00229         _3dRenderingOpacityScan[0] = _ui->doubleSpinBox_opacity_scan;
00230         _3dRenderingOpacityScan[1] = _ui->doubleSpinBox_opacity_odom_scan;
00231 
00232         _3dRenderingPtSizeScan.resize(2);
00233         _3dRenderingPtSizeScan[0] = _ui->spinBox_ptsize_scan;
00234         _3dRenderingPtSizeScan[1] = _ui->spinBox_ptsize_odom_scan;
00235 
00236         for(int i=0; i<2; ++i)
00237         {
00238                 connect(_3dRenderingShowClouds[i], SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteCloudRenderingPanel()));
00239                 connect(_3dRenderingVoxelSize[i], SIGNAL(valueChanged(double)), this, SLOT(makeObsoleteCloudRenderingPanel()));
00240                 connect(_3dRenderingDecimation[i], SIGNAL(valueChanged(int)), this, SLOT(makeObsoleteCloudRenderingPanel()));
00241                 connect(_3dRenderingMaxDepth[i], SIGNAL(valueChanged(double)), this, SLOT(makeObsoleteCloudRenderingPanel()));
00242                 connect(_3dRenderingShowScans[i], SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteCloudRenderingPanel()));
00243 
00244                 connect(_3dRenderingOpacity[i], SIGNAL(valueChanged(double)), this, SLOT(makeObsoleteCloudRenderingPanel()));
00245                 connect(_3dRenderingPtSize[i], SIGNAL(valueChanged(int)), this, SLOT(makeObsoleteCloudRenderingPanel()));
00246                 connect(_3dRenderingOpacityScan[i], SIGNAL(valueChanged(double)), this, SLOT(makeObsoleteCloudRenderingPanel()));
00247                 connect(_3dRenderingPtSizeScan[i], SIGNAL(valueChanged(int)), this, SLOT(makeObsoleteCloudRenderingPanel()));
00248         }
00249 
00250         connect(_ui->checkBox_showGraphs, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteCloudRenderingPanel()));
00251 
00252         connect(_ui->checkBox_meshing, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteCloudRenderingPanel()));
00253         connect(_ui->doubleSpinBox_gp3Radius, SIGNAL(valueChanged(double)), this, SLOT(makeObsoleteCloudRenderingPanel()));
00254         connect(_ui->spinBox_normalKSearch, SIGNAL(valueChanged(int)), this, SLOT(makeObsoleteCloudRenderingPanel()));
00255         connect(_ui->checkBox_mls, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteCloudRenderingPanel()));
00256         connect(_ui->doubleSpinBox_mlsRadius, SIGNAL(valueChanged(double)), this, SLOT(makeObsoleteCloudRenderingPanel()));
00257 
00258         connect(_ui->groupBox_poseFiltering, SIGNAL(clicked(bool)), this, SLOT(makeObsoleteCloudRenderingPanel()));
00259         connect(_ui->doubleSpinBox_cloudFilterRadius, SIGNAL(valueChanged(double)), this, SLOT(makeObsoleteCloudRenderingPanel()));
00260         connect(_ui->doubleSpinBox_cloudFilterAngle, SIGNAL(valueChanged(double)), this, SLOT(makeObsoleteCloudRenderingPanel()));
00261 
00262         connect(_ui->checkBox_map_shown, SIGNAL(clicked(bool)), this, SLOT(makeObsoleteCloudRenderingPanel()));
00263         connect(_ui->doubleSpinBox_map_resolution, SIGNAL(valueChanged(double)), this, SLOT(makeObsoleteCloudRenderingPanel()));
00264         connect(_ui->doubleSpinBox_map_opacity, SIGNAL(valueChanged(double)), this, SLOT(makeObsoleteCloudRenderingPanel()));
00265         connect(_ui->checkBox_map_occupancyFrom3DCloud, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteCloudRenderingPanel()));
00266         connect(_ui->checkBox_map_erode, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteCloudRenderingPanel()));
00267 
00268         //Logging panel
00269         connect(_ui->comboBox_loggerLevel, SIGNAL(currentIndexChanged(int)), this, SLOT(makeObsoleteLoggingPanel()));
00270         connect(_ui->comboBox_loggerEventLevel, SIGNAL(currentIndexChanged(int)), this, SLOT(makeObsoleteLoggingPanel()));
00271         connect(_ui->comboBox_loggerPauseLevel, SIGNAL(currentIndexChanged(int)), this, SLOT(makeObsoleteLoggingPanel()));
00272         connect(_ui->checkBox_logger_printTime, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteLoggingPanel()));
00273         connect(_ui->comboBox_loggerType, SIGNAL(currentIndexChanged(int)), this, SLOT(makeObsoleteLoggingPanel()));
00274 
00275         //Source panel
00276         connect(_ui->general_doubleSpinBox_imgRate, SIGNAL(valueChanged(double)), this, SLOT(makeObsoleteSourcePanel()));
00277         connect(_ui->source_mirroring, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
00278         //Image source
00279         connect(_ui->groupBox_sourceImage, SIGNAL(toggled(bool)), this, SLOT(makeObsoleteSourcePanel()));
00280         _ui->stackedWidget_image->setCurrentIndex(_ui->source_comboBox_image_type->currentIndex());
00281         connect(_ui->source_comboBox_image_type, SIGNAL(currentIndexChanged(int)), _ui->stackedWidget_image, SLOT(setCurrentIndex(int)));
00282         connect(_ui->source_comboBox_image_type, SIGNAL(currentIndexChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
00283         //usbDevice group
00284         connect(_ui->source_usbDevice_spinBox_id, SIGNAL(valueChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
00285         connect(_ui->source_spinBox_imgWidth, SIGNAL(valueChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
00286         connect(_ui->source_spinBox_imgheight, SIGNAL(valueChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
00287         //images group
00288         connect(_ui->source_images_toolButton_selectSource, SIGNAL(clicked()), this, SLOT(selectSourceImage()));
00289         connect(_ui->source_images_lineEdit_path, SIGNAL(textChanged(const QString &)), this, SLOT(makeObsoleteSourcePanel()));
00290         connect(_ui->source_images_spinBox_startPos, SIGNAL(valueChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
00291         connect(_ui->source_images_refreshDir, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
00292         //video group
00293         connect(_ui->source_video_toolButton_selectSource, SIGNAL(clicked()), this, SLOT(selectSourceImage()));
00294         connect(_ui->source_video_lineEdit_path, SIGNAL(textChanged(const QString &)), this, SLOT(makeObsoleteSourcePanel()));
00295         //database group
00296         connect(_ui->source_database_toolButton_selectSource, SIGNAL(clicked()), this, SLOT(selectSourceDatabase()));
00297         connect(_ui->toolButton_dbViewer, SIGNAL(clicked()), this, SLOT(openDatabaseViewer()));
00298         connect(_ui->groupBox_sourceDatabase, SIGNAL(toggled(bool)), this, SLOT(makeObsoleteSourcePanel()));
00299         connect(_ui->source_database_lineEdit_path, SIGNAL(textChanged(const QString &)), this, SLOT(makeObsoleteSourcePanel()));
00300         connect(_ui->source_checkBox_ignoreOdometry, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
00301         connect(_ui->source_checkBox_ignoreGoalDelay, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
00302         connect(_ui->source_spinBox_databaseStartPos, SIGNAL(valueChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
00303         connect(_ui->source_checkBox_useDbStamps, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
00304 
00305         //openni group
00306         connect(_ui->groupBox_sourceOpenni, SIGNAL(toggled(bool)), this, SLOT(makeObsoleteSourcePanel()));
00307         connect(_ui->comboBox_cameraRGBD, SIGNAL(currentIndexChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
00308         connect(_ui->openni2_autoWhiteBalance, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
00309         connect(_ui->openni2_autoExposure, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
00310         connect(_ui->openni2_exposure, SIGNAL(valueChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
00311         connect(_ui->openni2_gain, SIGNAL(valueChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
00312         connect(_ui->openni2_mirroring, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
00313         connect(_ui->comboBox_freenect2Format, SIGNAL(currentIndexChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
00314         connect(_ui->checkbox_rgbd_colorOnly, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
00315         connect(_ui->lineEdit_openniDevice, SIGNAL(textChanged(const QString &)), this, SLOT(makeObsoleteSourcePanel()));
00316         connect(_ui->lineEdit_openniLocalTransform, SIGNAL(textChanged(const QString &)), this, SLOT(makeObsoleteSourcePanel()));
00317         connect(_ui->pushButton_calibrate, SIGNAL(clicked()), this, SLOT(calibrate()));
00318 
00319 
00320         //Rtabmap basic
00321         connect(_ui->general_doubleSpinBox_timeThr, SIGNAL(valueChanged(double)), _ui->general_doubleSpinBox_timeThr_2, SLOT(setValue(double)));
00322         connect(_ui->general_doubleSpinBox_hardThr, SIGNAL(valueChanged(double)), _ui->general_doubleSpinBox_hardThr_2, SLOT(setValue(double)));
00323         connect(_ui->doubleSpinBox_similarityThreshold, SIGNAL(valueChanged(double)), _ui->doubleSpinBox_similarityThreshold_2, SLOT(setValue(double)));
00324         connect(_ui->general_doubleSpinBox_detectionRate, SIGNAL(valueChanged(double)), _ui->general_doubleSpinBox_detectionRate_2, SLOT(setValue(double)));
00325         connect(_ui->general_spinBox_imagesBufferSize, SIGNAL(valueChanged(int)), _ui->general_spinBox_imagesBufferSize_2, SLOT(setValue(int)));
00326         connect(_ui->general_spinBox_maxStMemSize, SIGNAL(valueChanged(int)), _ui->general_spinBox_maxStMemSize_2, SLOT(setValue(int)));
00327 
00328         connect(_ui->general_doubleSpinBox_timeThr_2, SIGNAL(editingFinished()), this, SLOT(updateBasicParameter()));
00329         connect(_ui->general_doubleSpinBox_hardThr_2, SIGNAL(editingFinished()), this, SLOT(updateBasicParameter()));
00330         connect(_ui->doubleSpinBox_similarityThreshold_2, SIGNAL(editingFinished()), this, SLOT(updateBasicParameter()));
00331         connect(_ui->general_doubleSpinBox_detectionRate_2, SIGNAL(editingFinished()), this, SLOT(updateBasicParameter()));
00332         connect(_ui->general_spinBox_imagesBufferSize_2, SIGNAL(editingFinished()), this, SLOT(updateBasicParameter()));
00333         connect(_ui->general_spinBox_maxStMemSize_2, SIGNAL(editingFinished()), this, SLOT(updateBasicParameter()));
00334         connect(_ui->groupBox_publishing, SIGNAL(clicked(bool)), this, SLOT(updateBasicParameter()));
00335         connect(_ui->general_checkBox_publishStats_2, SIGNAL(stateChanged(int)), this, SLOT(updateBasicParameter()));
00336         connect(_ui->general_checkBox_activateRGBD, SIGNAL(stateChanged(int)), this, SLOT(updateBasicParameter()));
00337         connect(_ui->general_checkBox_activateRGBD_2, SIGNAL(stateChanged(int)), this, SLOT(updateBasicParameter()));
00338         connect(_ui->general_checkBox_SLAM_mode, SIGNAL(stateChanged(int)), this, SLOT(updateBasicParameter()));
00339         connect(_ui->general_checkBox_SLAM_mode_2, SIGNAL(stateChanged(int)), this, SLOT(updateBasicParameter()));
00340 
00341         // Map objects name with the corresponding parameter key, needed for the addParameter() slots
00342         //Rtabmap
00343         _ui->groupBox_publishing->setObjectName(Parameters::kRtabmapPublishStats().c_str());
00344         _ui->general_checkBox_publishRawData->setObjectName(Parameters::kRtabmapPublishLastSignature().c_str());
00345         _ui->general_checkBox_publishPdf->setObjectName(Parameters::kRtabmapPublishPdf().c_str());
00346         _ui->general_checkBox_publishLikelihood->setObjectName(Parameters::kRtabmapPublishLikelihood().c_str());
00347         _ui->general_checkBox_statisticLogsBufferedInRAM->setObjectName(Parameters::kRtabmapStatisticLogsBufferedInRAM().c_str());
00348         _ui->groupBox_statistics->setObjectName(Parameters::kRtabmapStatisticLogged().c_str());
00349         _ui->general_checkBox_statisticLoggedHeaders->setObjectName(Parameters::kRtabmapStatisticLoggedHeaders().c_str());
00350         _ui->general_doubleSpinBox_timeThr->setObjectName(Parameters::kRtabmapTimeThr().c_str());
00351         _ui->general_spinBox_memoryThr->setObjectName(Parameters::kRtabmapMemoryThr().c_str());
00352         _ui->general_doubleSpinBox_detectionRate->setObjectName(Parameters::kRtabmapDetectionRate().c_str());
00353         _ui->general_spinBox_imagesBufferSize->setObjectName(Parameters::kRtabmapImageBufferSize().c_str());
00354         _ui->general_spinBox_maxRetrieved->setObjectName(Parameters::kRtabmapMaxRetrieved().c_str());
00355         _ui->general_checkBox_startNewMapOnLoopClosure->setObjectName(Parameters::kRtabmapStartNewMapOnLoopClosure().c_str());
00356         _ui->lineEdit_workingDirectory->setObjectName(Parameters::kRtabmapWorkingDirectory().c_str());
00357         connect(_ui->toolButton_workingDirectory, SIGNAL(clicked()), this, SLOT(changeWorkingDirectory()));
00358 
00359         // Memory
00360         _ui->general_checkBox_keepRawData->setObjectName(Parameters::kMemImageKept().c_str());
00361         _ui->general_checkBox_keepBinaryData->setObjectName(Parameters::kMemBinDataKept().c_str());
00362         _ui->general_checkBox_keepNotLinkedNodes->setObjectName(Parameters::kMemNotLinkedNodesKept().c_str());
00363         _ui->general_spinBox_maxStMemSize->setObjectName(Parameters::kMemSTMSize().c_str());
00364         _ui->doubleSpinBox_similarityThreshold->setObjectName(Parameters::kMemRehearsalSimilarity().c_str());
00365         _ui->general_checkBox_SLAM_mode->setObjectName(Parameters::kMemIncrementalMemory().c_str());
00366         _ui->general_doubleSpinBox_recentWmRatio->setObjectName(Parameters::kMemRecentWmRatio().c_str());
00367         _ui->general_checkBox_transferSortingByWeightId->setObjectName(Parameters::kMemTransferSortingByWeightId().c_str());
00368         _ui->general_checkBox_RehearsalIdUpdatedToNewOne->setObjectName(Parameters::kMemRehearsalIdUpdatedToNewOne().c_str());
00369         _ui->general_checkBox_generateIds->setObjectName(Parameters::kMemGenerateIds().c_str());
00370         _ui->general_checkBox_badSignaturesIgnored->setObjectName(Parameters::kMemBadSignaturesIgnored().c_str());
00371         _ui->general_checkBox_initWMWithAllNodes->setObjectName(Parameters::kMemInitWMWithAllNodes().c_str());
00372         _ui->checkBox_localSpaceLinksKeptInWM->setObjectName(Parameters::kMemLocalSpaceLinksKeptInWM().c_str());
00373         _ui->spinBox_imageDecimation->setObjectName(Parameters::kMemImageDecimation().c_str());
00374         _ui->general_doubleSpinBox_laserScanVoxel->setObjectName(Parameters::kMemLaserScanVoxelSize().c_str());
00375 
00376 
00377         // Database
00378         _ui->checkBox_dbInMemory->setObjectName(Parameters::kDbSqlite3InMemory().c_str());
00379         _ui->spinBox_dbCacheSize->setObjectName(Parameters::kDbSqlite3CacheSize().c_str());
00380         _ui->comboBox_dbJournalMode->setObjectName(Parameters::kDbSqlite3JournalMode().c_str());
00381         _ui->comboBox_dbSynchronous->setObjectName(Parameters::kDbSqlite3Synchronous().c_str());
00382         _ui->comboBox_dbTempStore->setObjectName(Parameters::kDbSqlite3TempStore().c_str());
00383 
00384         // Create hypotheses
00385         _ui->general_doubleSpinBox_hardThr->setObjectName(Parameters::kRtabmapLoopThr().c_str());
00386         _ui->general_doubleSpinBox_loopRatio->setObjectName(Parameters::kRtabmapLoopRatio().c_str());
00387 
00388         //Bayes
00389         _ui->general_doubleSpinBox_vp->setObjectName(Parameters::kBayesVirtualPlacePriorThr().c_str());
00390         _ui->lineEdit_bayes_predictionLC->setObjectName(Parameters::kBayesPredictionLC().c_str());
00391         _ui->checkBox_bayes_fullPredictionUpdate->setObjectName(Parameters::kBayesFullPredictionUpdate().c_str());
00392         connect(_ui->lineEdit_bayes_predictionLC, SIGNAL(textChanged(const QString &)), this, SLOT(updatePredictionPlot()));
00393 
00394         //Keypoint-based
00395         _ui->comboBox_dictionary_strategy->setObjectName(Parameters::kKpNNStrategy().c_str());
00396         _ui->checkBox_dictionary_incremental->setObjectName(Parameters::kKpIncrementalDictionary().c_str());
00397         _ui->comboBox_detector_strategy->setObjectName(Parameters::kKpDetectorStrategy().c_str());
00398         _ui->surf_doubleSpinBox_nndrRatio->setObjectName(Parameters::kKpNndrRatio().c_str());
00399         _ui->surf_doubleSpinBox_maxDepth->setObjectName(Parameters::kKpMaxDepth().c_str());
00400         _ui->surf_spinBox_wordsPerImageTarget->setObjectName(Parameters::kKpWordsPerImage().c_str());
00401         _ui->surf_doubleSpinBox_ratioBadSign->setObjectName(Parameters::kKpBadSignRatio().c_str());
00402         _ui->checkBox_kp_tfIdfLikelihoodUsed->setObjectName(Parameters::kKpTfIdfLikelihoodUsed().c_str());
00403         _ui->checkBox_kp_parallelized->setObjectName(Parameters::kKpParallelized().c_str());
00404         _ui->lineEdit_kp_roi->setObjectName(Parameters::kKpRoiRatios().c_str());
00405         _ui->lineEdit_dictionaryPath->setObjectName(Parameters::kKpDictionaryPath().c_str());
00406         connect(_ui->toolButton_dictionaryPath, SIGNAL(clicked()), this, SLOT(changeDictionaryPath()));
00407         _ui->checkBox_kp_newWordsComparedTogether->setObjectName(Parameters::kKpNewWordsComparedTogether().c_str());
00408 
00409         _ui->subpix_winSize->setObjectName(Parameters::kKpSubPixWinSize().c_str());
00410         _ui->subpix_iterations->setObjectName(Parameters::kKpSubPixIterations().c_str());
00411         _ui->subpix_eps->setObjectName(Parameters::kKpSubPixEps().c_str());
00412 
00413         //SURF detector
00414         _ui->surf_doubleSpinBox_hessianThr->setObjectName(Parameters::kSURFHessianThreshold().c_str());
00415         _ui->surf_spinBox_octaves->setObjectName(Parameters::kSURFOctaves().c_str());
00416         _ui->surf_spinBox_octaveLayers->setObjectName(Parameters::kSURFOctaveLayers().c_str());
00417         _ui->checkBox_surfExtended->setObjectName(Parameters::kSURFExtended().c_str());
00418         _ui->surf_checkBox_upright->setObjectName(Parameters::kSURFUpright().c_str());
00419         _ui->surf_checkBox_gpuVersion->setObjectName(Parameters::kSURFGpuVersion().c_str());
00420         _ui->surf_doubleSpinBox_gpuKeypointsRatio->setObjectName(Parameters::kSURFGpuKeypointsRatio().c_str());
00421 
00422         //SIFT detector
00423         _ui->sift_spinBox_nFeatures->setObjectName(Parameters::kSIFTNFeatures().c_str());
00424         _ui->sift_spinBox_nOctaveLayers->setObjectName(Parameters::kSIFTNOctaveLayers().c_str());
00425         _ui->sift_doubleSpinBox_contrastThr->setObjectName(Parameters::kSIFTContrastThreshold().c_str());
00426         _ui->sift_doubleSpinBox_edgeThr->setObjectName(Parameters::kSIFTEdgeThreshold().c_str());
00427         _ui->sift_doubleSpinBox_sigma->setObjectName(Parameters::kSIFTSigma().c_str());
00428 
00429         //BRIEF descriptor
00430         _ui->briefBytes->setObjectName(Parameters::kBRIEFBytes().c_str());
00431 
00432         //FAST detector
00433         _ui->fastSuppressNonMax->setObjectName(Parameters::kFASTNonmaxSuppression().c_str());
00434         _ui->fastThreshold->setObjectName(Parameters::kFASTThreshold().c_str());
00435         _ui->fastGpu->setObjectName(Parameters::kFASTGpu().c_str());
00436         _ui->fastKeypointRatio->setObjectName(Parameters::kFASTGpuKeypointsRatio().c_str());
00437 
00438         //ORB detector
00439         _ui->doubleSpinBox_ORBScaleFactor->setObjectName(Parameters::kORBScaleFactor().c_str());
00440         _ui->spinBox_ORBNLevels->setObjectName(Parameters::kORBNLevels().c_str());
00441         _ui->spinBox_ORBEdgeThreshold->setObjectName(Parameters::kORBEdgeThreshold().c_str());
00442         _ui->spinBox_ORBFirstLevel->setObjectName(Parameters::kORBFirstLevel().c_str());
00443         _ui->spinBox_ORBWTA_K->setObjectName(Parameters::kORBWTA_K().c_str());
00444         _ui->spinBox_ORBScoreType->setObjectName(Parameters::kORBScoreType().c_str());
00445         _ui->spinBox_ORBPatchSize->setObjectName(Parameters::kORBPatchSize().c_str());
00446         _ui->checkBox_ORBGpu->setObjectName(Parameters::kORBGpu().c_str());
00447 
00448         //FREAK descriptor
00449         _ui->checkBox_FREAKOrientationNormalized->setObjectName(Parameters::kFREAKOrientationNormalized().c_str());
00450         _ui->checkBox_FREAKScaleNormalized->setObjectName(Parameters::kFREAKScaleNormalized().c_str());
00451         _ui->doubleSpinBox_FREAKPatternScale->setObjectName(Parameters::kFREAKPatternScale().c_str());
00452         _ui->spinBox_FREAKNOctaves->setObjectName(Parameters::kFREAKNOctaves().c_str());
00453 
00454         //GFTT detector
00455         _ui->doubleSpinBox_GFTT_qualityLevel->setObjectName(Parameters::kGFTTQualityLevel().c_str());
00456         _ui->doubleSpinBox_GFTT_minDistance->setObjectName(Parameters::kGFTTMinDistance().c_str());
00457         _ui->spinBox_GFTT_blockSize->setObjectName(Parameters::kGFTTBlockSize().c_str());
00458         _ui->checkBox_GFTT_useHarrisDetector->setObjectName(Parameters::kGFTTUseHarrisDetector().c_str());
00459         _ui->doubleSpinBox_GFTT_k->setObjectName(Parameters::kGFTTK().c_str());
00460 
00461         //BRISK
00462         _ui->spinBox_BRISK_thresh->setObjectName(Parameters::kBRISKThresh().c_str());
00463         _ui->spinBox_BRISK_octaves->setObjectName(Parameters::kBRISKOctaves().c_str());
00464         _ui->doubleSpinBox_BRISK_patterScale->setObjectName(Parameters::kBRISKPatternScale().c_str());
00465 
00466         // verifyHypotheses
00467         _ui->comboBox_vh_strategy->setObjectName(Parameters::kRtabmapVhStrategy().c_str());
00468         _ui->surf_spinBox_matchCountMinAccepted->setObjectName(Parameters::kVhEpMatchCountMin().c_str());
00469         _ui->surf_doubleSpinBox_ransacParam1->setObjectName(Parameters::kVhEpRansacParam1().c_str());
00470         _ui->surf_doubleSpinBox_ransacParam2->setObjectName(Parameters::kVhEpRansacParam2().c_str());
00471 
00472         // RGB-D SLAM
00473         _ui->general_checkBox_activateRGBD->setObjectName(Parameters::kRGBDEnabled().c_str());
00474         _ui->rgdb_linearUpdate->setObjectName(Parameters::kRGBDLinearUpdate().c_str());
00475         _ui->rgdb_angularUpdate->setObjectName(Parameters::kRGBDAngularUpdate().c_str());
00476         _ui->rgdb_rehearsalWeightIgnoredWhileMoving->setObjectName(Parameters::kMemRehearsalWeightIgnoredWhileMoving().c_str());
00477         _ui->rgdb_newMapOdomChange->setObjectName(Parameters::kRGBDNewMapOdomChangeDistance().c_str());
00478         _ui->odomScanHistory->setObjectName(Parameters::kRGBDPoseScanMatching().c_str());
00479         _ui->spinBox_maxLocalLocationsRetrieved->setObjectName(Parameters::kRGBDMaxLocalRetrieved().c_str());
00480 
00481         _ui->graphOptimization_type->setObjectName(Parameters::kRGBDOptimizeStrategy().c_str());
00482         _ui->graphOptimization_slam2d->setObjectName(Parameters::kRGBDOptimizeSlam2D().c_str());
00483         _ui->graphOptimization_iterations->setObjectName(Parameters::kRGBDOptimizeIterations().c_str());
00484         _ui->graphOptimization_covarianceIgnored->setObjectName(Parameters::kRGBDOptimizeVarianceIgnored().c_str());
00485         _ui->graphOptimization_fromGraphEnd->setObjectName(Parameters::kRGBDOptimizeFromGraphEnd().c_str());
00486 
00487         _ui->graphPlan_goalReachedRadius->setObjectName(Parameters::kRGBDGoalReachedRadius().c_str());
00488         _ui->graphPlan_planWithNearNodesLinked->setObjectName(Parameters::kRGBDPlanVirtualLinks().c_str());
00489         _ui->graphPlan_goalsSavedInUserData->setObjectName(Parameters::kRGBDGoalsSavedInUserData().c_str());
00490 
00491         _ui->groupBox_localDetection_time->setObjectName(Parameters::kRGBDLocalLoopDetectionTime().c_str());
00492         _ui->groupBox_localDetection_space->setObjectName(Parameters::kRGBDLocalLoopDetectionSpace().c_str());
00493         _ui->localDetection_radius->setObjectName(Parameters::kRGBDLocalRadius().c_str());
00494         _ui->localDetection_maxDiffID->setObjectName(Parameters::kRGBDLocalLoopDetectionMaxGraphDepth().c_str());
00495         _ui->localDetection_pathFilteringRadius->setObjectName(Parameters::kRGBDLocalLoopDetectionPathFilteringRadius().c_str());
00496         _ui->checkBox_localSpacePathOdomPosesUsed->setObjectName(Parameters::kRGBDLocalLoopDetectionPathOdomPosesUsed().c_str());
00497         _ui->rgdb_localImmunizationRatio->setObjectName(Parameters::kRGBDLocalImmunizationRatio().c_str());
00498 
00499         _ui->loopClosure_bowMinInliers->setObjectName(Parameters::kLccBowMinInliers().c_str());
00500         _ui->loopClosure_bowInlierDistance->setObjectName(Parameters::kLccBowInlierDistance().c_str());
00501         _ui->loopClosure_bowIterations->setObjectName(Parameters::kLccBowIterations().c_str());
00502         _ui->loopClosure_bowMaxDepth->setObjectName(Parameters::kLccBowMaxDepth().c_str());
00503         _ui->loopClosure_bowForce2D->setObjectName(Parameters::kLccBowForce2D().c_str());
00504         _ui->loopClosure_bowEpipolarGeometry->setObjectName(Parameters::kLccBowEpipolarGeometry().c_str());
00505         _ui->loopClosure_bowEpipolarGeometryVar->setObjectName(Parameters::kLccBowEpipolarGeometryVar().c_str());
00506 
00507         _ui->groupBox_reextract->setObjectName(Parameters::kLccReextractActivated().c_str());
00508         _ui->reextract_nn->setObjectName(Parameters::kLccReextractNNType().c_str());
00509         _ui->reextract_nndrRatio->setObjectName(Parameters::kLccReextractNNDR().c_str());
00510         _ui->reextract_type->setObjectName(Parameters::kLccReextractFeatureType().c_str());
00511         _ui->reextract_maxFeatures->setObjectName(Parameters::kLccReextractMaxWords().c_str());
00512 
00513         _ui->globalDetection_icpType->setObjectName(Parameters::kLccIcpType().c_str());
00514         _ui->globalDetection_icpMaxTranslation->setObjectName(Parameters::kLccIcpMaxTranslation().c_str());
00515         _ui->globalDetection_icpMaxRotation->setObjectName(Parameters::kLccIcpMaxRotation().c_str());
00516 
00517         _ui->loopClosure_icpDecimation->setObjectName(Parameters::kLccIcp3Decimation().c_str());
00518         _ui->loopClosure_icpMaxDepth->setObjectName(Parameters::kLccIcp3MaxDepth().c_str());
00519         _ui->loopClosure_icpVoxelSize->setObjectName(Parameters::kLccIcp3VoxelSize().c_str());
00520         _ui->loopClosure_icpSamples->setObjectName(Parameters::kLccIcp3Samples().c_str());
00521         _ui->loopClosure_icpMaxCorrespondenceDistance->setObjectName(Parameters::kLccIcp3MaxCorrespondenceDistance().c_str());
00522         _ui->loopClosure_icpIterations->setObjectName(Parameters::kLccIcp3Iterations().c_str());
00523         _ui->loopClosure_icpRatio->setObjectName(Parameters::kLccIcp3CorrespondenceRatio().c_str());
00524         _ui->loopClosure_icpPointToPlane->setObjectName(Parameters::kLccIcp3PointToPlane().c_str());
00525         _ui->loopClosure_icpPointToPlaneNormals->setObjectName(Parameters::kLccIcp3PointToPlaneNormalNeighbors().c_str());
00526 
00527         _ui->loopClosure_icp2MaxCorrespondenceDistance->setObjectName(Parameters::kLccIcp2MaxCorrespondenceDistance().c_str());
00528         _ui->loopClosure_icp2Iterations->setObjectName(Parameters::kLccIcp2Iterations().c_str());
00529         _ui->loopClosure_icp2Ratio->setObjectName(Parameters::kLccIcp2CorrespondenceRatio().c_str());
00530         _ui->loopClosure_icp2Voxel->setObjectName(Parameters::kLccIcp2VoxelSize().c_str());
00531 
00532 
00533         //Odometry
00534         _ui->odom_strategy->setObjectName(Parameters::kOdomStrategy().c_str());
00535         _ui->odom_type->setObjectName(Parameters::kOdomFeatureType().c_str());
00536         _ui->odom_countdown->setObjectName(Parameters::kOdomResetCountdown().c_str());
00537         _ui->odom_maxFeatures->setObjectName(Parameters::kOdomMaxFeatures().c_str());
00538         _ui->odom_inlierDistance->setObjectName(Parameters::kOdomInlierDistance().c_str());
00539         _ui->odom_iterations->setObjectName(Parameters::kOdomIterations().c_str());
00540         _ui->odom_maxDepth->setObjectName(Parameters::kOdomMaxDepth().c_str());
00541         _ui->odom_minInliers->setObjectName(Parameters::kOdomMinInliers().c_str());
00542         _ui->odom_refine_iterations->setObjectName(Parameters::kOdomRefineIterations().c_str());
00543         _ui->odom_force2D->setObjectName(Parameters::kOdomForce2D().c_str());
00544         _ui->odom_fillInfoData->setObjectName(Parameters::kOdomFillInfoData().c_str());
00545         _ui->lineEdit_odom_roi->setObjectName(Parameters::kOdomRoiRatios().c_str());
00546         _ui->odom_pnpEstimation->setObjectName(Parameters::kOdomPnPEstimation().c_str());
00547         _ui->odom_pnpReprojError->setObjectName(Parameters::kOdomPnPReprojError().c_str());
00548         _ui->odom_pnpFlags->setObjectName(Parameters::kOdomPnPFlags().c_str());
00549 
00550         //Odometry BOW
00551         _ui->odom_localHistory->setObjectName(Parameters::kOdomBowLocalHistorySize().c_str());
00552         _ui->odom_bin_nn->setObjectName(Parameters::kOdomBowNNType().c_str());
00553         _ui->odom_bin_nndrRatio->setObjectName(Parameters::kOdomBowNNDR().c_str());
00554 
00555         //Odometry Optical Flow
00556         _ui->odom_flow_winSize->setObjectName(Parameters::kOdomFlowWinSize().c_str());
00557         _ui->odom_flow_maxLevel->setObjectName(Parameters::kOdomFlowMaxLevel().c_str());
00558         _ui->odom_flow_iterations->setObjectName(Parameters::kOdomFlowIterations().c_str());
00559         _ui->odom_flow_eps->setObjectName(Parameters::kOdomFlowEps().c_str());
00560         _ui->odom_subpix_winSize->setObjectName(Parameters::kOdomSubPixWinSize().c_str());
00561         _ui->odom_subpix_iterations->setObjectName(Parameters::kOdomSubPixIterations().c_str());
00562         _ui->odom_subpix_eps->setObjectName(Parameters::kOdomSubPixEps().c_str());
00563 
00564         //Odometry Mono
00565         _ui->doubleSpinBox_minFlow->setObjectName(Parameters::kOdomMonoInitMinFlow().c_str());
00566         _ui->doubleSpinBox_minInitTranslation->setObjectName(Parameters::kOdomMonoInitMinTranslation().c_str());
00567         _ui->doubleSpinBox_minTranslation->setObjectName(Parameters::kOdomMonoMinTranslation().c_str());
00568         _ui->doubleSpinBox_maxVariance->setObjectName(Parameters::kOdomMonoMaxVariance().c_str());
00569 
00570         //Stereo
00571         _ui->stereo_flow_winSize->setObjectName(Parameters::kStereoWinSize().c_str());
00572         _ui->stereo_flow_maxLevel->setObjectName(Parameters::kStereoMaxLevel().c_str());
00573         _ui->stereo_flow_iterations->setObjectName(Parameters::kStereoIterations().c_str());
00574         _ui->stereo_flow_eps->setObjectName(Parameters::kStereoEps().c_str());
00575         _ui->stereo_maxSlope->setObjectName(Parameters::kStereoMaxSlope().c_str());
00576 
00577 
00578         setupSignals();
00579         // custom signals
00580         connect(_ui->doubleSpinBox_kp_roi0, SIGNAL(valueChanged(double)), this, SLOT(updateKpROI()));
00581         connect(_ui->doubleSpinBox_kp_roi1, SIGNAL(valueChanged(double)), this, SLOT(updateKpROI()));
00582         connect(_ui->doubleSpinBox_kp_roi2, SIGNAL(valueChanged(double)), this, SLOT(updateKpROI()));
00583         connect(_ui->doubleSpinBox_kp_roi3, SIGNAL(valueChanged(double)), this, SLOT(updateKpROI()));
00584 
00585         //Create a model from the stacked widgets
00586         // This will add all parameters to the parameters Map
00587         _ui->stackedWidget->setCurrentIndex(0);
00588         this->setupTreeView();
00589         connect(_ui->treeView, SIGNAL(clicked(QModelIndex)), this, SLOT(clicked(QModelIndex)));
00590 
00591         _obsoletePanels = kPanelAll;
00592 
00593         _progressDialog = new QProgressDialog(this);
00594         _progressDialog->setWindowTitle(tr("Read parameters..."));
00595         _progressDialog->setMaximum(2);
00596 }
00597 
00598 PreferencesDialog::~PreferencesDialog() {
00599         // remove tmp ini file
00600         QFile::remove(getTmpIniFilePath());
00601         delete _ui;
00602 }
00603 
00604 void PreferencesDialog::init()
00605 {
00606         //First set all default values
00607         const ParametersMap & defaults = Parameters::getDefaultParameters();
00608         for(ParametersMap::const_iterator iter=defaults.begin(); iter!=defaults.end(); ++iter)
00609         {
00610                 this->setParameter(iter->first, iter->second);
00611         }
00612 
00613         this->readSettings();
00614         this->writeSettings(getTmpIniFilePath());
00615 
00616         _initialized = true;
00617 }
00618 
00619 void PreferencesDialog::saveSettings()
00620 {
00621         writeSettings();
00622 }
00623 
00624 void PreferencesDialog::setupTreeView()
00625 {
00626         if(_indexModel)
00627         {
00628                 _ui->treeView->setModel(0);
00629                 delete _indexModel;
00630         }
00631         _indexModel = new QStandardItemModel(this);
00632         // Parse the model
00633         QList<QGroupBox*> boxes = this->getGroupBoxes();
00634         if(_ui->radioButton_basic->isChecked())
00635         {
00636                 boxes = boxes.mid(0,5);
00637         }
00638         else // Advanced
00639         {
00640                 boxes.removeAt(4);
00641         }
00642 
00643         QStandardItem * parentItem = _indexModel->invisibleRootItem();
00644         int index = 0;
00645         this->parseModel(boxes, parentItem, 0, index); // recursive method
00646         if(_ui->radioButton_advanced->isChecked() && index != _ui->stackedWidget->count()-1)
00647         {
00648                 ULOGGER_ERROR("The tree model is not the same size of the stacked widgets...%d vs %d advanced stacks", index, _ui->stackedWidget->count()-1);
00649         }
00650         int currentIndex = _ui->stackedWidget->currentIndex();
00651         if(_ui->radioButton_basic->isChecked())
00652         {
00653                 if(currentIndex >= 4)
00654                 {
00655                         _ui->stackedWidget->setCurrentIndex(4);
00656                         currentIndex = 4;
00657                 }
00658         }
00659         else // Advanced
00660         {
00661                 if(currentIndex == 4)
00662                 {
00663                         _ui->stackedWidget->setCurrentIndex(5);
00664                 }
00665         }
00666         _ui->treeView->setModel(_indexModel);
00667         if(currentIndex == 0) // GUI
00668         {
00669                 _ui->treeView->setCurrentIndex(_indexModel->index(0, 0));
00670         }
00671         else if(currentIndex == 1) //3d rendering
00672         {
00673                 _ui->treeView->setCurrentIndex(_indexModel->index(0, 0).child(0,0));
00674         }
00675         else if(currentIndex == 2) // logging
00676         {
00677                 _ui->treeView->setCurrentIndex(_indexModel->index(0, 0).child(1,0));
00678         }
00679         else // source, rtabmap
00680         {
00681                 _ui->treeView->setCurrentIndex(_indexModel->index(currentIndex-2, 0));
00682         }
00683         _ui->treeView->expandToDepth(0);
00684 }
00685 
00686 // recursive...
00687 bool PreferencesDialog::parseModel(QList<QGroupBox*> & boxes, QStandardItem * parentItem, int currentLevel, int & absoluteIndex)
00688 {
00689         if(parentItem == 0)
00690         {
00691                 ULOGGER_ERROR("Parent item is null !");
00692                 return false;
00693         }
00694 
00695         QStandardItem * currentItem = 0;
00696         while(absoluteIndex < boxes.size())
00697         {
00698                 QString objectName = boxes.at(absoluteIndex)->objectName();
00699                 QString title = boxes.at(absoluteIndex)->title();
00700                 bool ok = false;
00701                 int lvl = QString(objectName.at(objectName.size()-1)).toInt(&ok);
00702                 if(!ok)
00703                 {
00704                         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());
00705                         return false;
00706                 }
00707 
00708 
00709                 if(lvl == currentLevel)
00710                 {
00711                         QStandardItem * item = new QStandardItem(title);
00712                         item->setData(absoluteIndex);
00713                         currentItem = item;
00714                         //ULOGGER_DEBUG("PreferencesDialog::parseModel() lvl(%d) Added %s", currentLevel, title.toStdString().c_str());
00715                         parentItem->appendRow(item);
00716                         ++absoluteIndex;
00717                 }
00718                 else if(lvl > currentLevel)
00719                 {
00720                         if(lvl>currentLevel+1)
00721                         {
00722                                 ULOGGER_ERROR("Intermediary lvl doesn't exist, lvl %d to %d, indexes %d and %d", currentLevel, lvl, absoluteIndex-1, absoluteIndex);
00723                                 return false;
00724                         }
00725                         else
00726                         {
00727                                 parseModel(boxes, currentItem, currentLevel+1, absoluteIndex); // recursive
00728                         }
00729                 }
00730                 else
00731                 {
00732                         return false;
00733                 }
00734         }
00735         return true;
00736 }
00737 
00738 void PreferencesDialog::setupSignals()
00739 {
00740         const rtabmap::ParametersMap & parameters = Parameters::getDefaultParameters();
00741         for(rtabmap::ParametersMap::const_iterator iter=parameters.begin(); iter!=parameters.end(); ++iter)
00742         {
00743                 QWidget * obj = _ui->stackedWidget->findChild<QWidget*>((*iter).first.c_str());
00744                 if(obj)
00745                 {
00746                         // set tooltip as the parameter name
00747                         obj->setToolTip(tr("%1 (Default=\"%2\")").arg(iter->first.c_str()).arg(iter->second.c_str()));
00748 
00749                         QSpinBox * spin = qobject_cast<QSpinBox *>(obj);
00750                         QDoubleSpinBox * doubleSpin = qobject_cast<QDoubleSpinBox *>(obj);
00751                         QComboBox * combo = qobject_cast<QComboBox *>(obj);
00752                         QCheckBox * check = qobject_cast<QCheckBox *>(obj);
00753                         QRadioButton * radio = qobject_cast<QRadioButton *>(obj);
00754                         QLineEdit * lineEdit = qobject_cast<QLineEdit *>(obj);
00755                         QGroupBox * groupBox = qobject_cast<QGroupBox *>(obj);
00756                         if(spin)
00757                         {
00758                                 connect(spin, SIGNAL(valueChanged(int)), this, SLOT(addParameter(int)));
00759                         }
00760                         else if(doubleSpin)
00761                         {
00762                                 connect(doubleSpin, SIGNAL(valueChanged(double)), this, SLOT(addParameter(double)));
00763                         }
00764                         else if(combo)
00765                         {
00766                                 connect(combo, SIGNAL(currentIndexChanged(int)), this, SLOT(addParameter(int)));
00767                         }
00768                         else if(check)
00769                         {
00770                                 connect(check, SIGNAL(toggled(bool)), this, SLOT(addParameter(bool)));
00771                         }
00772                         else if(radio)
00773                         {
00774                                 connect(radio, SIGNAL(toggled(bool)), this, SLOT(addParameter(bool)));
00775                         }
00776                         else if(lineEdit)
00777                         {
00778                                 connect(lineEdit, SIGNAL(textChanged(const QString &)), this, SLOT(addParameter(const QString &)));
00779                         }
00780                         else if(groupBox)
00781                         {
00782                                 connect(groupBox, SIGNAL(clicked(bool)), this, SLOT(addParameter(bool)));
00783                         }
00784                         else
00785                         {
00786                                 ULOGGER_WARN("QWidget called %s can't be cast to a supported widget", (*iter).first.c_str());
00787                         }
00788                 }
00789                 else
00790                 {
00791                         ULOGGER_WARN("Can't find the related QWidget for parameter %s", (*iter).first.c_str());
00792                 }
00793         }
00794 }
00795 
00796 void PreferencesDialog::clicked(const QModelIndex &index)
00797  {
00798         QStandardItem * item = _indexModel->itemFromIndex(index);
00799         if(item && item->isEnabled())
00800         {
00801                 int index = item->data().toInt();
00802                 if(_ui->radioButton_advanced->isChecked() && index >= 4)
00803                 {
00804                         ++index;
00805                 }
00806                 _ui->stackedWidget->setCurrentIndex(index);
00807                 _ui->scrollArea->horizontalScrollBar()->setValue(0);
00808                 _ui->scrollArea->verticalScrollBar()->setValue(0);
00809         }
00810  }
00811 
00812 void PreferencesDialog::closeEvent(QCloseEvent *event)
00813 {
00814         UDEBUG("");
00815         _parameters.clear();
00816         _obsoletePanels = kPanelDummy;
00817         this->readGuiSettings(getTmpIniFilePath());
00818         this->readCameraSettings(getTmpIniFilePath());
00819         event->accept();
00820 }
00821 
00822 void PreferencesDialog::closeDialog ( QAbstractButton * button )
00823 {
00824         UDEBUG("");
00825 
00826         QDialogButtonBox::ButtonRole role = _ui->buttonBox_global->buttonRole(button);
00827         switch(role)
00828         {
00829         case QDialogButtonBox::RejectRole:
00830                 _parameters.clear();
00831                 _obsoletePanels = kPanelDummy;
00832                 this->readGuiSettings(getTmpIniFilePath());
00833                 this->readCameraSettings(getTmpIniFilePath());
00834                 this->reject();
00835                 break;
00836 
00837         case QDialogButtonBox::AcceptRole:
00838                 updateBasicParameter();// make that changes without editing finished signal are updated.
00839                 if((_obsoletePanels & kPanelAll) || _parameters.size())
00840                 {
00841                         if(validateForm())
00842                         {
00843                                 writeSettings(getTmpIniFilePath());
00844                                 this->accept();
00845                         }
00846                 }
00847                 else
00848                 {
00849                         this->accept();
00850                 }
00851                 break;
00852 
00853         default:
00854                 break;
00855         }
00856 }
00857 
00858 void PreferencesDialog::resetApply ( QAbstractButton * button )
00859 {
00860         QDialogButtonBox::ButtonRole role = _ui->buttonBox_local->buttonRole(button);
00861         switch(role)
00862         {
00863         case QDialogButtonBox::ApplyRole:
00864                 updateBasicParameter();// make that changes without editing finished signal are updated.
00865                 if(validateForm())
00866                 {
00867                         writeSettings(getTmpIniFilePath());
00868                 }
00869                 break;
00870 
00871         case QDialogButtonBox::ResetRole:
00872                 resetSettings(_ui->stackedWidget->currentIndex());
00873                 break;
00874 
00875         default:
00876                 break;
00877         }
00878 }
00879 
00880 void PreferencesDialog::resetSettings(QGroupBox * groupBox)
00881 {
00882         if(groupBox->objectName() == _ui->groupBox_generalSettingsGui0->objectName())
00883         {
00884                 _ui->general_checkBox_imagesKept->setChecked(true);
00885                 _ui->checkBox_beep->setChecked(false);
00886                 _ui->checkBox_notifyWhenNewGlobalPathIsReceived->setChecked(false);
00887                 _ui->checkBox_verticalLayoutUsed->setChecked(true);
00888                 _ui->checkBox_imageRejectedShown->setChecked(true);
00889                 _ui->checkBox_imageHighestHypShown->setChecked(false);
00890                 _ui->spinBox_odomQualityWarnThr->setValue(50);
00891                 _ui->checkBox_posteriorGraphView->setChecked(true);
00892         }
00893         else if(groupBox->objectName() == _ui->groupBox_cloudRendering1->objectName())
00894         {
00895                 for(int i=0; i<2; ++i)
00896                 {
00897                         _3dRenderingShowClouds[i]->setChecked(true);
00898                         _3dRenderingVoxelSize[i]->setValue(i==2?0.005:0.00);
00899                         _3dRenderingDecimation[i]->setValue(i==0?4:i==1?2:1);
00900                         _3dRenderingMaxDepth[i]->setValue(i==1?0.0:4.0);
00901                         _3dRenderingShowScans[i]->setChecked(true);
00902 
00903                         _3dRenderingOpacity[i]->setValue(1.0);
00904                         _3dRenderingPtSize[i]->setValue(i==0?1:2);
00905                         _3dRenderingOpacityScan[i]->setValue(1.0);
00906                         _3dRenderingPtSizeScan[i]->setValue(1);
00907                 }
00908 
00909                 _ui->checkBox_showGraphs->setChecked(true);
00910 
00911                 _ui->checkBox_meshing->setChecked(false);
00912                 _ui->doubleSpinBox_gp3Radius->setValue(0.04);
00913                 _ui->spinBox_normalKSearch->setValue(20);
00914                 _ui->checkBox_mls->setChecked(false);
00915                 _ui->doubleSpinBox_mlsRadius->setValue(0.04);
00916 
00917                 _ui->groupBox_poseFiltering->setChecked(true);
00918                 _ui->doubleSpinBox_cloudFilterRadius->setValue(0.1);
00919                 _ui->doubleSpinBox_cloudFilterAngle->setValue(30);
00920 
00921                 _ui->checkBox_map_shown->setChecked(false);
00922                 _ui->doubleSpinBox_map_resolution->setValue(0.05);
00923                 _ui->checkBox_map_occupancyFrom3DCloud->setChecked(false);
00924                 _ui->checkBox_map_erode->setChecked(false);
00925                 _ui->doubleSpinBox_map_opacity->setValue(0.75);
00926         }
00927         else if(groupBox->objectName() == _ui->groupBox_logging1->objectName())
00928         {
00929                 _ui->comboBox_loggerLevel->setCurrentIndex(2);
00930                 _ui->comboBox_loggerEventLevel->setCurrentIndex(3);
00931                 _ui->comboBox_loggerPauseLevel->setCurrentIndex(3);
00932                 _ui->checkBox_logger_printTime->setChecked(true);
00933                 _ui->comboBox_loggerType->setCurrentIndex(1);
00934         }
00935         else if(groupBox->objectName() == _ui->groupBox_source0->objectName())
00936         {
00937                 _ui->general_doubleSpinBox_imgRate->setValue(30.0);
00938                 _ui->source_mirroring->setChecked(false);
00939 
00940                 _ui->groupBox_sourceImage->setChecked(false);
00941                 _ui->source_spinBox_imgWidth->setValue(0);
00942                 _ui->source_spinBox_imgheight->setValue(0);
00943                 _ui->source_images_spinBox_startPos->setValue(1);
00944                 _ui->source_images_refreshDir->setChecked(false);
00945 
00946                 _ui->groupBox_sourceDatabase->setChecked(false);
00947                 _ui->source_checkBox_ignoreOdometry->setChecked(false);
00948                 _ui->source_checkBox_ignoreGoalDelay->setChecked(false);
00949                 _ui->source_spinBox_databaseStartPos->setValue(0);
00950                 _ui->source_checkBox_useDbStamps->setChecked(false);
00951 
00952                 _ui->groupBox_sourceOpenni->setChecked(true);
00953 #ifdef _WIN32
00954                 _ui->comboBox_cameraRGBD->setCurrentIndex(4); // openni2
00955 #else
00956                 if(CameraFreenect::available())
00957                 {
00958                         _ui->comboBox_cameraRGBD->setCurrentIndex(1); // freenect
00959                 }
00960                 else if(CameraOpenNI2::available())
00961                 {
00962                         _ui->comboBox_cameraRGBD->setCurrentIndex(4); // openni2
00963                 }
00964                 else
00965                 {
00966                         _ui->comboBox_cameraRGBD->setCurrentIndex(0); // openni-pcl
00967                 }
00968 #endif
00969                 _ui->openni2_autoWhiteBalance->setChecked(true);
00970                 _ui->openni2_autoExposure->setChecked(true);
00971                 _ui->openni2_exposure->setValue(0);
00972                 _ui->openni2_gain->setValue(100);
00973                 _ui->openni2_mirroring->setChecked(false);
00974                 _ui->comboBox_freenect2Format->setCurrentIndex(0);
00975                 _ui->checkbox_rgbd_colorOnly->setChecked(false);
00976                 _ui->lineEdit_openniDevice->setText("");
00977                 _ui->lineEdit_openniLocalTransform->setText("0 0 0 -PI_2 0 -PI_2");
00978         }
00979         else if(groupBox->objectName() == _ui->groupBox_rtabmap_basic0->objectName())
00980         {
00981                 _ui->general_doubleSpinBox_timeThr_2->setValue(Parameters::defaultRtabmapTimeThr());
00982                 _ui->general_doubleSpinBox_hardThr_2->setValue(Parameters::defaultRtabmapLoopThr());
00983                 _ui->doubleSpinBox_similarityThreshold_2->setValue(Parameters::defaultMemRehearsalSimilarity());
00984                 _ui->general_spinBox_imagesBufferSize_2->setValue(Parameters::defaultRtabmapImageBufferSize());
00985                 _ui->general_spinBox_maxStMemSize_2->setValue(Parameters::defaultMemSTMSize());
00986                 _ui->general_checkBox_publishStats_2->setChecked(Parameters::defaultRtabmapPublishStats());
00987                 _ui->general_checkBox_activateRGBD_2->setChecked(Parameters::defaultRGBDEnabled());
00988                 _ui->general_checkBox_SLAM_mode_2->setChecked(Parameters::defaultMemIncrementalMemory());
00989                 _ui->general_doubleSpinBox_detectionRate_2->setValue(Parameters::defaultRtabmapDetectionRate());
00990                 // match the advanced (spin and doubleSpin boxes)
00991                 _ui->general_doubleSpinBox_timeThr->setValue(Parameters::defaultRtabmapTimeThr());
00992                 _ui->general_doubleSpinBox_hardThr->setValue(Parameters::defaultRtabmapLoopThr());
00993                 _ui->doubleSpinBox_similarityThreshold->setValue(Parameters::defaultMemRehearsalSimilarity());
00994                 _ui->general_spinBox_imagesBufferSize->setValue(Parameters::defaultRtabmapImageBufferSize());
00995                 _ui->general_spinBox_maxStMemSize->setValue(Parameters::defaultMemSTMSize());
00996                 _ui->general_doubleSpinBox_detectionRate->setValue(Parameters::defaultRtabmapDetectionRate());
00997         }
00998         else
00999         {
01000                 QObjectList children = groupBox->children();
01001                 rtabmap::ParametersMap defaults = Parameters::getDefaultParameters();
01002                 std::string key;
01003                 for(int i=0; i<children.size(); ++i)
01004                 {
01005                         key = children.at(i)->objectName().toStdString();
01006                         if(uContains(defaults, key))
01007                         {
01008                                 this->setParameter(key, defaults.at(key));
01009                                 if(qobject_cast<const QGroupBox*>(children.at(i)))
01010                                 {
01011                                         this->resetSettings((QGroupBox*)children.at(i));
01012                                 }
01013                         }
01014                         else if(qobject_cast<const QGroupBox*>(children.at(i)))
01015                         {
01016                                 this->resetSettings((QGroupBox*)children.at(i));
01017                         }
01018                         else if(qobject_cast<const QStackedWidget*>(children.at(i)))
01019                         {
01020                                 QStackedWidget * stackedWidget = (QStackedWidget*)children.at(i);
01021                                 for(int j=0; j<stackedWidget->count(); ++j)
01022                                 {
01023                                         const QObjectList & children2 = stackedWidget->widget(j)->children();
01024                                         for(int k=0; k<children2.size(); ++k)
01025                                         {
01026                                                 if(qobject_cast<QGroupBox *>(children2.at(k)))
01027                                                 {
01028                                                         this->resetSettings((QGroupBox*)children2.at(k));
01029                                                 }
01030                                         }
01031                                 }
01032                         }
01033                 }
01034 
01035                 if(groupBox->findChild<QLineEdit*>(_ui->lineEdit_kp_roi->objectName()))
01036                 {
01037                         this->setupKpRoiPanel();
01038                 }
01039         }
01040 }
01041 
01042 void PreferencesDialog::resetSettings(int panelNumber)
01043 {
01044         QList<QGroupBox*> boxes = this->getGroupBoxes();
01045         if(panelNumber >= 0 && panelNumber < boxes.size())
01046         {
01047                 this->resetSettings(boxes.at(panelNumber));
01048         }
01049         else if(panelNumber == -1)
01050         {
01051                 for(QList<QGroupBox*>::iterator iter = boxes.begin(); iter!=boxes.end(); ++iter)
01052                 {
01053                         this->resetSettings(*iter);
01054                 }
01055         }
01056         else
01057         {
01058                 ULOGGER_WARN("panel number and the number of stacked widget doesn't match");
01059         }
01060 
01061 }
01062 
01063 QString PreferencesDialog::getWorkingDirectory() const
01064 {
01065         return _ui->lineEdit_workingDirectory->text();
01066 }
01067 
01068 QString PreferencesDialog::getIniFilePath() const
01069 {
01070         QString privatePath = QDir::homePath() + "/.rtabmap";
01071         if(!QDir(privatePath).exists())
01072         {
01073                 QDir::home().mkdir(".rtabmap");
01074         }
01075         return privatePath + "/rtabmap.ini";
01076 }
01077 
01078 QString PreferencesDialog::getTmpIniFilePath() const
01079 {
01080         return getIniFilePath()+".tmp";
01081 }
01082 
01083 void PreferencesDialog::loadConfigFrom()
01084 {
01085         QString path = QFileDialog::getOpenFileName(this, tr("Load settings..."), this->getWorkingDirectory(), "*.ini");
01086         if(!path.isEmpty())
01087         {
01088                 this->readSettings(path);
01089         }
01090 }
01091 
01092 void PreferencesDialog::readSettings(const QString & filePath)
01093 {
01094         ULOGGER_DEBUG("");
01095         readGuiSettings(filePath);
01096         readCameraSettings(filePath);
01097         if(!readCoreSettings(filePath))
01098         {
01099                 _parameters.clear();
01100                 _obsoletePanels = kPanelDummy;
01101 
01102                 // only keep GUI settings
01103                 QStandardItem * parentItem = _indexModel->invisibleRootItem();
01104                 if(parentItem)
01105                 {
01106                         for(int i=1; i<parentItem->rowCount(); ++i)
01107                         {
01108                                 parentItem->child(i)->setEnabled(false);
01109                         }
01110                 }
01111                 _ui->radioButton_basic->setEnabled(false);
01112                 _ui->radioButton_advanced->setEnabled(false);
01113         }
01114         else
01115         {
01116                 // enable settings
01117                 QStandardItem * parentItem = _indexModel->invisibleRootItem();
01118                 if(parentItem)
01119                 {
01120                         for(int i=0; i<parentItem->rowCount(); ++i)
01121                         {
01122                                 parentItem->child(i)->setEnabled(true);
01123                         }
01124                 }
01125                 _ui->radioButton_basic->setEnabled(true);
01126                 _ui->radioButton_advanced->setEnabled(true);
01127         }
01128 }
01129 
01130 void PreferencesDialog::readGuiSettings(const QString & filePath)
01131 {
01132         QString path = getIniFilePath();
01133         if(!filePath.isEmpty())
01134         {
01135                 path = filePath;
01136         }
01137         QSettings settings(path, QSettings::IniFormat);
01138         settings.beginGroup("Gui");
01139         settings.beginGroup("General");
01140         _ui->general_checkBox_imagesKept->setChecked(settings.value("imagesKept", _ui->general_checkBox_imagesKept->isChecked()).toBool());
01141         _ui->comboBox_loggerLevel->setCurrentIndex(settings.value("loggerLevel", _ui->comboBox_loggerLevel->currentIndex()).toInt());
01142         _ui->comboBox_loggerEventLevel->setCurrentIndex(settings.value("loggerEventLevel", _ui->comboBox_loggerEventLevel->currentIndex()).toInt());
01143         _ui->comboBox_loggerPauseLevel->setCurrentIndex(settings.value("loggerPauseLevel", _ui->comboBox_loggerPauseLevel->currentIndex()).toInt());
01144         _ui->comboBox_loggerType->setCurrentIndex(settings.value("loggerType", _ui->comboBox_loggerType->currentIndex()).toInt());
01145         _ui->checkBox_logger_printTime->setChecked(settings.value("loggerPrintTime", _ui->checkBox_logger_printTime->isChecked()).toBool());
01146         _ui->checkBox_verticalLayoutUsed->setChecked(settings.value("verticalLayoutUsed", _ui->checkBox_verticalLayoutUsed->isChecked()).toBool());
01147         _ui->checkBox_imageRejectedShown->setChecked(settings.value("imageRejectedShown", _ui->checkBox_imageRejectedShown->isChecked()).toBool());
01148         _ui->checkBox_imageHighestHypShown->setChecked(settings.value("imageHighestHypShown", _ui->checkBox_imageHighestHypShown->isChecked()).toBool());
01149         _ui->checkBox_beep->setChecked(settings.value("beep", _ui->checkBox_beep->isChecked()).toBool());
01150         _ui->checkBox_notifyWhenNewGlobalPathIsReceived->setChecked(settings.value("notifyNewGlobalPath", _ui->checkBox_notifyWhenNewGlobalPathIsReceived->isChecked()).toBool());
01151         _ui->spinBox_odomQualityWarnThr->setValue(settings.value("odomQualityThr", _ui->spinBox_odomQualityWarnThr->value()).toInt());
01152         _ui->checkBox_posteriorGraphView->setChecked(settings.value("posteriorGraphView", _ui->checkBox_posteriorGraphView->isChecked()).toBool());
01153 
01154         for(int i=0; i<2; ++i)
01155         {
01156                 _3dRenderingShowClouds[i]->setChecked(settings.value(QString("showClouds%1").arg(i), _3dRenderingShowClouds[i]->isChecked()).toBool());
01157                 _3dRenderingVoxelSize[i]->setValue(settings.value(QString("voxelSize%1").arg(i), _3dRenderingVoxelSize[i]->value()).toDouble());
01158                 _3dRenderingDecimation[i]->setValue(settings.value(QString("decimation%1").arg(i), _3dRenderingDecimation[i]->value()).toInt());
01159                 _3dRenderingMaxDepth[i]->setValue(settings.value(QString("maxDepth%1").arg(i), _3dRenderingMaxDepth[i]->value()).toDouble());
01160                 _3dRenderingShowScans[i]->setChecked(settings.value(QString("showScans%1").arg(i), _3dRenderingShowScans[i]->isChecked()).toBool());
01161 
01162                 _3dRenderingOpacity[i]->setValue(settings.value(QString("opacity%1").arg(i), _3dRenderingOpacity[i]->value()).toDouble());
01163                 _3dRenderingPtSize[i]->setValue(settings.value(QString("ptSize%1").arg(i), _3dRenderingPtSize[i]->value()).toInt());
01164                 _3dRenderingOpacityScan[i]->setValue(settings.value(QString("opacityScan%1").arg(i), _3dRenderingOpacityScan[i]->value()).toDouble());
01165                 _3dRenderingPtSizeScan[i]->setValue(settings.value(QString("ptSizeScan%1").arg(i), _3dRenderingPtSizeScan[i]->value()).toInt());
01166         }
01167         _ui->checkBox_showGraphs->setChecked(settings.value("showGraphs", _ui->checkBox_showGraphs->isChecked()).toBool());
01168 
01169         _ui->checkBox_meshing->setChecked(settings.value("meshing", _ui->checkBox_meshing->isChecked()).toBool());
01170         _ui->doubleSpinBox_gp3Radius->setValue(settings.value("meshGP3Radius", _ui->doubleSpinBox_gp3Radius->value()).toDouble());
01171         _ui->spinBox_normalKSearch->setValue(settings.value("meshNormalKSearch", _ui->spinBox_normalKSearch->value()).toInt());
01172         _ui->checkBox_mls->setChecked(settings.value("meshSmoothing", _ui->checkBox_mls->isChecked()).toBool());
01173         _ui->doubleSpinBox_mlsRadius->setValue(settings.value("meshSmoothingRadius", _ui->doubleSpinBox_mlsRadius->value()).toDouble());
01174 
01175         _ui->groupBox_poseFiltering->setChecked(settings.value("cloudFiltering", _ui->groupBox_poseFiltering->isChecked()).toBool());
01176         _ui->doubleSpinBox_cloudFilterRadius->setValue(settings.value("cloudFilteringRadius", _ui->doubleSpinBox_cloudFilterRadius->value()).toDouble());
01177         _ui->doubleSpinBox_cloudFilterAngle->setValue(settings.value("cloudFilteringAngle", _ui->doubleSpinBox_cloudFilterAngle->value()).toDouble());
01178 
01179         _ui->checkBox_map_shown->setChecked(settings.value("gridMapShown", _ui->checkBox_map_shown->isChecked()).toBool());
01180         _ui->doubleSpinBox_map_resolution->setValue(settings.value("gridMapResolution", _ui->doubleSpinBox_map_resolution->value()).toDouble());
01181         _ui->checkBox_map_occupancyFrom3DCloud->setChecked(settings.value("gridMapOccupancyFrom3DCloud", _ui->checkBox_map_occupancyFrom3DCloud->isChecked()).toBool());
01182         _ui->checkBox_map_erode->setChecked(settings.value("gridMapEroded", _ui->checkBox_map_erode->isChecked()).toBool());
01183         _ui->doubleSpinBox_map_opacity->setValue(settings.value("gridMapOpacity", _ui->doubleSpinBox_map_opacity->value()).toDouble());
01184 
01185         settings.endGroup(); // General
01186 
01187         settings.endGroup(); // rtabmap
01188 }
01189 
01190 void PreferencesDialog::readCameraSettings(const QString & filePath)
01191 {
01192         QString path = getIniFilePath();
01193         if(!filePath.isEmpty())
01194         {
01195                 path = filePath;
01196         }
01197         QSettings settings(path, QSettings::IniFormat);
01198 
01199         settings.beginGroup("Camera");
01200         _ui->groupBox_sourceImage->setChecked(settings.value("imageUsed", _ui->groupBox_sourceImage->isChecked()).toBool());
01201         _ui->general_doubleSpinBox_imgRate->setValue(settings.value("imgRate", _ui->general_doubleSpinBox_imgRate->value()).toDouble());
01202         _ui->source_mirroring->setChecked(settings.value("mirroring", _ui->source_mirroring->isChecked()).toBool());
01203         _ui->source_comboBox_image_type->setCurrentIndex(settings.value("type", _ui->source_comboBox_image_type->currentIndex()).toInt());
01204         _ui->source_spinBox_imgWidth->setValue(settings.value("imgWidth",_ui->source_spinBox_imgWidth->value()).toInt());
01205         _ui->source_spinBox_imgheight->setValue(settings.value("imgHeight",_ui->source_spinBox_imgheight->value()).toInt());
01206         //usbDevice group
01207         settings.beginGroup("usbDevice");
01208         _ui->source_usbDevice_spinBox_id->setValue(settings.value("id",_ui->source_usbDevice_spinBox_id->value()).toInt());
01209         settings.endGroup(); // usbDevice
01210         //images group
01211         settings.beginGroup("images");
01212         _ui->source_images_lineEdit_path->setText(settings.value("path", _ui->source_images_lineEdit_path->text()).toString());
01213         _ui->source_images_spinBox_startPos->setValue(settings.value("startPos",_ui->source_images_spinBox_startPos->value()).toInt());
01214         _ui->source_images_refreshDir->setChecked(settings.value("refreshDir",_ui->source_images_refreshDir->isChecked()).toBool());
01215         settings.endGroup(); // images
01216         //video group
01217         settings.beginGroup("video");
01218         _ui->source_video_lineEdit_path->setText(settings.value("path", _ui->source_video_lineEdit_path->text()).toString());
01219         settings.endGroup(); // video
01220         settings.endGroup(); // Camera
01221 
01222         settings.beginGroup("Database");
01223         _ui->groupBox_sourceDatabase->setChecked(settings.value("databaseUsed", _ui->groupBox_sourceDatabase->isChecked()).toBool());
01224         _ui->source_database_lineEdit_path->setText(settings.value("path",_ui->source_database_lineEdit_path->text()).toString());
01225         _ui->source_checkBox_ignoreOdometry->setChecked(settings.value("ignoreOdometry", _ui->source_checkBox_ignoreOdometry->isChecked()).toBool());
01226         _ui->source_checkBox_ignoreGoalDelay->setChecked(settings.value("ignoreGoalDelay", _ui->source_checkBox_ignoreGoalDelay->isChecked()).toBool());
01227         _ui->source_spinBox_databaseStartPos->setValue(settings.value("startPos", _ui->source_spinBox_databaseStartPos->value()).toInt());
01228         _ui->source_checkBox_useDbStamps->setChecked(settings.value("useDatabaseStamps", _ui->source_checkBox_useDbStamps->isChecked()).toBool());
01229         settings.endGroup(); // Database
01230 
01231         settings.beginGroup("Openni");
01232         _ui->groupBox_sourceOpenni->setChecked(settings.value("openniUsed", _ui->groupBox_sourceOpenni->isChecked()).toBool());
01233         _ui->comboBox_cameraRGBD->setCurrentIndex(settings.value("cameraRGBDType", _ui->comboBox_cameraRGBD->currentIndex()).toInt());
01234         _ui->openni2_autoWhiteBalance->setChecked(settings.value("openni2AutoWhiteBalance", _ui->openni2_autoWhiteBalance->isChecked()).toBool());
01235         _ui->openni2_autoExposure->setChecked(settings.value("openni2AutoExposure", _ui->openni2_autoExposure->isChecked()).toBool());
01236         _ui->openni2_exposure->setValue(settings.value("openni2Exposure", _ui->openni2_exposure->value()).toInt());
01237         _ui->openni2_gain->setValue(settings.value("openni2Gain", _ui->openni2_gain->value()).toInt());
01238         _ui->openni2_mirroring->setChecked(settings.value("openni2Mirroring", _ui->openni2_mirroring->isChecked()).toBool());
01239         _ui->comboBox_freenect2Format->setCurrentIndex(settings.value("freenect2Format", _ui->comboBox_freenect2Format->currentIndex()).toInt());
01240         _ui->checkbox_rgbd_colorOnly->setChecked(settings.value("rgbdColorOnly", _ui->checkbox_rgbd_colorOnly->isChecked()).toBool());
01241         _ui->lineEdit_openniDevice->setText(settings.value("device",_ui->lineEdit_openniDevice->text()).toString());
01242         _ui->lineEdit_openniLocalTransform->setText(settings.value("localTransform",_ui->lineEdit_openniLocalTransform->text()).toString());
01243         _calibrationDialog->loadSettings(settings, "CalibrationDialog");
01244         settings.endGroup(); // Openni
01245 }
01246 
01247 bool PreferencesDialog::readCoreSettings(const QString & filePath)
01248 {
01249         UDEBUG("");
01250         QString path = getIniFilePath();
01251         if(!filePath.isEmpty())
01252         {
01253                 path = filePath;
01254         }
01255 
01256         if(!QFile::exists(path))
01257         {
01258                 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));
01259         }
01260 
01261         QSettings settings(path, QSettings::IniFormat);
01262 
01263 
01264         settings.beginGroup("Core");
01265 
01266         // Compare version in ini with the current RTAB-Map version
01267         QStringList version = settings.value("Version", "").toString().split('.');
01268         if(version.size() == 3)
01269         {
01270                 if(!RTABMAP_VERSION_COMPARE(version[0].toInt(), version[1].toInt(), version[2].toInt()))
01271                 {
01272                         if(path.contains(".rtabmap"))
01273                         {
01274                                 UWARN("Version in the config file \"%s\" is more recent (\"%s\") than "
01275                                            "current RTAB-Map version used (\"%s\"). The config file will be upgraded "
01276                                            "to new version.",
01277                                            path.toStdString().c_str(),
01278                                            settings.value("Version", "").toString().toStdString().c_str(),
01279                                            RTABMAP_VERSION);
01280                         }
01281                         else
01282                         {
01283                                 UERROR("Version in the config file \"%s\" is more recent (\"%s\") than "
01284                                            "current RTAB-Map version used (\"%s\"). New parameters (if there are some) will "
01285                                            "be ignored.",
01286                                            path.toStdString().c_str(),
01287                                            settings.value("Version", "").toString().toStdString().c_str(),
01288                                            RTABMAP_VERSION);
01289                         }
01290                 }
01291         }
01292 
01293         QStringList keys = settings.allKeys();
01294         // Get profile
01295         const rtabmap::ParametersMap & parameters = Parameters::getDefaultParameters();
01296         for(rtabmap::ParametersMap::const_iterator iter = parameters.begin(); iter!=parameters.end(); ++iter)
01297         {
01298                 QString key((*iter).first.c_str());
01299                 QString value = settings.value(key, "").toString();
01300                 if(!value.isEmpty())
01301                 {
01302                         if(key.toStdString().compare(Parameters::kRtabmapWorkingDirectory()) == 0)
01303                         {
01304                                 // The directory should exist if not the default one
01305                                 if(!QDir(value).exists() && value.compare(Parameters::defaultRtabmapWorkingDirectory().c_str()) != 0)
01306                                 {
01307                                         if(QDir(this->getWorkingDirectory().toStdString().c_str()).exists())
01308                                         {
01309                                                 UWARN("Reading config: Not existing working directory \"%s\". Keeping old one (\"%s\").",
01310                                                         value.toStdString().c_str(),
01311                                                         this->getWorkingDirectory().toStdString().c_str());
01312                                                 value = this->getWorkingDirectory();
01313                                         }
01314                                         else
01315                                         {
01316                                                 UWARN("Reading config: Not existing working directory \"%s\". Using default one (\"%s\").",
01317                                                         value.toStdString().c_str(),
01318                                                         (*iter).second.c_str());
01319                                                 value = (*iter).second.c_str();
01320                                         }
01321                                 }
01322                         }
01323                         this->setParameter(key.toStdString(), value.toStdString());
01324                 }
01325                 else
01326                 {
01327                         UDEBUG("key.toStdString()=%s", key.toStdString().c_str());
01328                         // Use the default value if the key doesn't exist yet
01329                         this->setParameter(key.toStdString(), (*iter).second);
01330 
01331                         // Add information about the working directory if not in the config file
01332                         if(key.toStdString().compare(Parameters::kRtabmapWorkingDirectory()) == 0)
01333                         {
01334                                 if(!_initialized)
01335                                 {
01336                                         QMessageBox::information(this,
01337                                                         tr("Working directory"),
01338                                                         tr("RTAB-Map needs a working directory to put the database.\n\n"
01339                                                            "By default, the directory \"%1\" is used.\n\n"
01340                                                            "The working directory can be changed any time in the "
01341                                                            "preferences menu.").arg(
01342                                                                            Parameters::defaultRtabmapWorkingDirectory().c_str()));
01343                                 }
01344                         }
01345                 }
01346         }
01347         settings.endGroup(); // Core
01348         return true;
01349 }
01350 
01351 bool PreferencesDialog::saveConfigTo()
01352 {
01353         QString path = QFileDialog::getSaveFileName(this, tr("Save settings..."), this->getWorkingDirectory()+QDir::separator()+"config.ini", "*.ini");
01354         if(!path.isEmpty())
01355         {
01356                 writeGuiSettings(path);
01357                 writeCameraSettings(path);
01358                 writeCoreSettings(path);
01359                 return true;
01360         }
01361         return false;
01362 }
01363 
01364 void PreferencesDialog::resetConfig()
01365 {
01366         int button = QMessageBox::warning(this,
01367                         tr("Reset settings..."),
01368                         tr("This will reset all settings. Restore all settings to default without saving them first?"),
01369                            QMessageBox::Cancel | QMessageBox::Yes | QMessageBox::Save,
01370                            QMessageBox::Cancel);
01371         if(button == QMessageBox::Yes ||
01372            (button == QMessageBox::Save && saveConfigTo()))
01373         {
01374                 this->resetSettings(-1);
01375         }
01376 }
01377 
01378 void PreferencesDialog::writeSettings(const QString & filePath)
01379 {
01380         writeGuiSettings(filePath);
01381         writeCameraSettings(filePath);
01382         writeCoreSettings(filePath);
01383 
01384         UDEBUG("_obsoletePanels=%d parameters=%d", (int)_obsoletePanels, (int)_parameters.size());
01385 
01386         if(_parameters.size())
01387         {
01388                 emit settingsChanged(_parameters);
01389         }
01390 
01391         if(_obsoletePanels)
01392         {
01393                 emit settingsChanged(_obsoletePanels);
01394         }
01395 
01396         _parameters.clear();
01397         _obsoletePanels = kPanelDummy;
01398 }
01399 
01400 void PreferencesDialog::writeGuiSettings(const QString & filePath) const
01401 {
01402         QString path = getIniFilePath();
01403         if(!filePath.isEmpty())
01404         {
01405                 path = filePath;
01406         }
01407         QSettings settings(path, QSettings::IniFormat);
01408         settings.beginGroup("Gui");
01409 
01410         settings.beginGroup("General");
01411         settings.setValue("imagesKept", _ui->general_checkBox_imagesKept->isChecked());
01412         settings.setValue("loggerLevel", _ui->comboBox_loggerLevel->currentIndex());
01413         settings.setValue("loggerEventLevel", _ui->comboBox_loggerEventLevel->currentIndex());
01414         settings.setValue("loggerPauseLevel", _ui->comboBox_loggerPauseLevel->currentIndex());
01415         settings.setValue("loggerType", _ui->comboBox_loggerType->currentIndex());
01416         settings.setValue("loggerPrintTime", _ui->checkBox_logger_printTime->isChecked());
01417         settings.setValue("verticalLayoutUsed", _ui->checkBox_verticalLayoutUsed->isChecked());
01418         settings.setValue("imageRejectedShown", _ui->checkBox_imageRejectedShown->isChecked());
01419         settings.setValue("imageHighestHypShown", _ui->checkBox_imageHighestHypShown->isChecked());
01420         settings.setValue("beep", _ui->checkBox_beep->isChecked());
01421         settings.setValue("notifyNewGlobalPath", _ui->checkBox_notifyWhenNewGlobalPathIsReceived->isChecked());
01422         settings.setValue("odomQualityThr", _ui->spinBox_odomQualityWarnThr->value());
01423         settings.setValue("posteriorGraphView", _ui->checkBox_posteriorGraphView->isChecked());
01424 
01425         for(int i=0; i<2; ++i)
01426         {
01427                 settings.setValue(QString("showClouds%1").arg(i), _3dRenderingShowClouds[i]->isChecked());
01428                 settings.setValue(QString("voxelSize%1").arg(i), _3dRenderingVoxelSize[i]->value());
01429                 settings.setValue(QString("decimation%1").arg(i), _3dRenderingDecimation[i]->value());
01430                 settings.setValue(QString("maxDepth%1").arg(i), _3dRenderingMaxDepth[i]->value());
01431                 settings.setValue(QString("showScans%1").arg(i), _3dRenderingShowScans[i]->isChecked());
01432 
01433                 settings.setValue(QString("opacity%1").arg(i), _3dRenderingOpacity[i]->value());
01434                 settings.setValue(QString("ptSize%1").arg(i), _3dRenderingPtSize[i]->value());
01435                 settings.setValue(QString("opacityScan%1").arg(i), _3dRenderingOpacityScan[i]->value());
01436                 settings.setValue(QString("ptSizeScan%1").arg(i), _3dRenderingPtSizeScan[i]->value());
01437         }
01438         settings.setValue("showGraphs", _ui->checkBox_showGraphs->isChecked());
01439 
01440         settings.setValue("meshing", _ui->checkBox_meshing->isChecked());
01441         settings.setValue("meshGP3Radius", _ui->doubleSpinBox_gp3Radius->value());
01442         settings.setValue("meshNormalKSearch", _ui->spinBox_normalKSearch->value());
01443         settings.setValue("meshSmoothing", _ui->checkBox_mls->isChecked());
01444         settings.setValue("meshSmoothingRadius", _ui->doubleSpinBox_mlsRadius->value());
01445 
01446         settings.setValue("cloudFiltering", _ui->groupBox_poseFiltering->isChecked());
01447         settings.setValue("cloudFilteringRadius", _ui->doubleSpinBox_cloudFilterRadius->value());
01448         settings.setValue("cloudFilteringAngle", _ui->doubleSpinBox_cloudFilterAngle->value());
01449 
01450         settings.setValue("gridMapShown", _ui->checkBox_map_shown->isChecked());
01451         settings.setValue("gridMapResolution", _ui->doubleSpinBox_map_resolution->value());
01452         settings.setValue("gridMapOccupancyFrom3DCloud", _ui->checkBox_map_occupancyFrom3DCloud->isChecked());
01453         settings.setValue("gridMapEroded", _ui->checkBox_map_erode->isChecked());
01454         settings.setValue("gridMapOpacity", _ui->doubleSpinBox_map_opacity->value());
01455         settings.endGroup(); // General
01456 
01457         settings.endGroup(); // rtabmap
01458 }
01459 
01460 void PreferencesDialog::writeCameraSettings(const QString & filePath) const
01461 {
01462         QString path = getIniFilePath();
01463         if(!filePath.isEmpty())
01464         {
01465                 path = filePath;
01466         }
01467         QSettings settings(path, QSettings::IniFormat);
01468         settings.beginGroup("Camera");
01469         settings.setValue("imageUsed",          _ui->groupBox_sourceImage->isChecked());
01470         settings.setValue("imgRate",            _ui->general_doubleSpinBox_imgRate->value());
01471         settings.setValue("mirroring",      _ui->source_mirroring->isChecked());
01472         settings.setValue("type",                       _ui->source_comboBox_image_type->currentIndex());
01473         settings.setValue("imgWidth",           _ui->source_spinBox_imgWidth->value());
01474         settings.setValue("imgHeight",          _ui->source_spinBox_imgheight->value());
01475         //usbDevice group
01476         settings.beginGroup("usbDevice");
01477         settings.setValue("id",                         _ui->source_usbDevice_spinBox_id->value());
01478         settings.endGroup(); //usbDevice
01479         //images group
01480         settings.beginGroup("images");
01481         settings.setValue("path",                       _ui->source_images_lineEdit_path->text());
01482         settings.setValue("startPos",           _ui->source_images_spinBox_startPos->value());
01483         settings.setValue("refreshDir",         _ui->source_images_refreshDir->isChecked());
01484         settings.endGroup(); //images
01485         //video group
01486         settings.beginGroup("video");
01487         settings.setValue("path",                       _ui->source_video_lineEdit_path->text());
01488         settings.endGroup(); //video
01489 
01490         settings.endGroup(); // Camera
01491 
01492         settings.beginGroup("Database");
01493         settings.setValue("databaseUsed",       _ui->groupBox_sourceDatabase->isChecked());
01494         settings.setValue("path",                       _ui->source_database_lineEdit_path->text());
01495         settings.setValue("ignoreOdometry", _ui->source_checkBox_ignoreOdometry->isChecked());
01496         settings.setValue("ignoreGoalDelay", _ui->source_checkBox_ignoreGoalDelay->isChecked());
01497         settings.setValue("startPos",       _ui->source_spinBox_databaseStartPos->value());
01498         settings.setValue("useDatabaseStamps", _ui->source_checkBox_useDbStamps->isChecked());
01499         settings.endGroup();
01500 
01501         settings.beginGroup("Openni");
01502         settings.setValue("openniUsed",         _ui->groupBox_sourceOpenni->isChecked());
01503         settings.setValue("cameraRGBDType",     _ui->comboBox_cameraRGBD->currentIndex());
01504         settings.setValue("openni2AutoWhiteBalance", _ui->openni2_autoWhiteBalance->isChecked());
01505         settings.setValue("openni2AutoExposure",        _ui->openni2_autoExposure->isChecked());
01506         settings.setValue("openni2Exposure",            _ui->openni2_exposure->value());
01507         settings.setValue("openni2Gain",                        _ui->openni2_gain->value());
01508         settings.setValue("openni2Mirroring", _ui->openni2_mirroring->isChecked());
01509         settings.setValue("freenect2Format", _ui->comboBox_freenect2Format->currentIndex());
01510         settings.setValue("rgbdColorOnly", _ui->checkbox_rgbd_colorOnly->isChecked());
01511         settings.setValue("device",             _ui->lineEdit_openniDevice->text());
01512         settings.setValue("localTransform", _ui->lineEdit_openniLocalTransform->text());
01513         _calibrationDialog->saveSettings(settings, "CalibrationDialog");
01514         settings.endGroup(); // Openni
01515 }
01516 
01517 void PreferencesDialog::writeCoreSettings(const QString & filePath) const
01518 {
01519         QString path = getIniFilePath();
01520         if(!filePath.isEmpty())
01521         {
01522                 path = filePath;
01523         }
01524         QSettings settings(path, QSettings::IniFormat);
01525         settings.beginGroup("Core");
01526 
01527         // save current RTAB-Map version
01528         settings.setValue("Version", QString(RTABMAP_VERSION));
01529 
01530         const rtabmap::ParametersMap & parameters = Parameters::getDefaultParameters();
01531         for(rtabmap::ParametersMap::const_iterator iter=parameters.begin(); iter!=parameters.end(); ++iter)
01532         {
01533                 QObject * obj = _ui->stackedWidget->findChild<QObject*>((*iter).first.c_str());
01534                 if(obj)
01535                 {
01536                         QSpinBox * spin = qobject_cast<QSpinBox *>(obj);
01537                         QDoubleSpinBox * doubleSpin = qobject_cast<QDoubleSpinBox *>(obj);
01538                         QComboBox * combo = qobject_cast<QComboBox *>(obj);
01539                         QCheckBox * check = qobject_cast<QCheckBox *>(obj);
01540                         QRadioButton * radio = qobject_cast<QRadioButton *>(obj);
01541                         QLineEdit * lineEdit = qobject_cast<QLineEdit *>(obj);
01542                         QGroupBox * groupBox = qobject_cast<QGroupBox *>(obj);
01543                         if(spin)
01544                         {
01545                                 settings.setValue(obj->objectName(), spin->value());
01546                         }
01547                         else if(doubleSpin)
01548                         {
01549                                 settings.setValue(obj->objectName(), doubleSpin->value());
01550                         }
01551                         else if(combo)
01552                         {
01553                                 settings.setValue(obj->objectName(), combo->currentIndex());
01554                         }
01555                         else if(check)
01556                         {
01557                                 settings.setValue(obj->objectName(), uBool2Str(check->isChecked()).c_str());
01558                         }
01559                         else if(radio)
01560                         {
01561                                 settings.setValue(obj->objectName(), uBool2Str(radio->isChecked()).c_str());
01562                         }
01563                         else if(lineEdit)
01564                         {
01565                                 settings.setValue(obj->objectName(), lineEdit->text());
01566                         }
01567                         else if(groupBox)
01568                         {
01569                                 settings.setValue(obj->objectName(), uBool2Str(groupBox->isChecked()).c_str());
01570                         }
01571                         else
01572                         {
01573                                 ULOGGER_WARN("QObject called %s can't be cast to a supported widget", (*iter).first.c_str());
01574                         }
01575                 }
01576                 else
01577                 {
01578                         ULOGGER_WARN("Can't find the related QObject for parameter %s", (*iter).first.c_str());
01579                 }
01580         }
01581         settings.endGroup(); // Core
01582 }
01583 
01584 bool PreferencesDialog::validateForm()
01585 {
01586         if(RTABMAP_NONFREE == 0)
01587         {
01588                 // verify that SURF/SIFT cannot be selected if not built with OpenCV nonfree module
01589                 // BOW dictionary type
01590                 if(_ui->comboBox_detector_strategy->currentIndex() <= 1)
01591                 {
01592                         QMessageBox::warning(this, tr("Parameter warning"),
01593                                         tr("Selected feature type (SURF/SIFT) is not available. RTAB-Map is not built "
01594                                            "with the nonfree module from OpenCV. ORB is set instead for the bag-of-words dictionary."));
01595                         _ui->comboBox_detector_strategy->setCurrentIndex(Feature2D::kFeatureOrb);
01596                 }
01597                 // BOW Reextract features type
01598                 if(_ui->reextract_type->currentIndex() <= 1)
01599                 {
01600                         QMessageBox::warning(this, tr("Parameter warning"),
01601                                         tr("Selected feature type (SURF/SIFT) is not available. RTAB-Map is not built "
01602                                            "with the nonfree module from OpenCV. Fast/Brief is set instead for the re-extraction "
01603                                            "of features on loop closure."));
01604                         _ui->reextract_type->setCurrentIndex(Feature2D::kFeatureFastBrief);
01605                 }
01606                 // odom type
01607                 if(_ui->odom_type->currentIndex() <= 1)
01608                 {
01609                         QMessageBox::warning(this, tr("Parameter warning"),
01610                                         tr("Selected feature type (SURF/SIFT) is not available. RTAB-Map is not built "
01611                                            "with the nonfree module from OpenCV. GFTT/Brief is set instead for odometry."));
01612                         _ui->odom_type->setCurrentIndex(Feature2D::kFeatureGfttBrief);
01613                 }
01614         }
01615 
01616         // optimization strategy
01617         if(!graph::G2OOptimizer::available())
01618         {
01619                 if(_ui->graphOptimization_type->currentIndex() > 0)
01620                 {
01621                         QMessageBox::warning(this, tr("Parameter warning"),
01622                                         tr("Selected graph optimization strategy (g2o) is not available. RTAB-Map is not built "
01623                                            "with g2o. TORO is set instead for graph optimization strategy."));
01624                         _ui->graphOptimization_type->setCurrentIndex(graph::Optimizer::kTypeTORO);
01625                 }
01626         }
01627 
01628         //verify binary features and nearest neighbor
01629         // BOW dictionary type
01630         if(_ui->comboBox_dictionary_strategy->currentIndex() == VWDictionary::kNNFlannLSH && _ui->comboBox_detector_strategy->currentIndex() <= 1)
01631         {
01632                 QMessageBox::warning(this, tr("Parameter warning"),
01633                                 tr("With the selected feature type (SURF or SIFT), parameter \"Visual word->Nearest Neighbor\" "
01634                                    "cannot be LSH (used for binary descriptor). KD-tree is set instead for the bag-of-words dictionary."));
01635                 _ui->comboBox_dictionary_strategy->setCurrentIndex(VWDictionary::kNNFlannKdTree);
01636         }
01637         else if(_ui->comboBox_dictionary_strategy->currentIndex() == VWDictionary::kNNFlannKdTree && _ui->comboBox_detector_strategy->currentIndex() >1)
01638         {
01639                 QMessageBox::warning(this, tr("Parameter warning"),
01640                                 tr("With the selected feature type (ORB, FAST, FREAK or BRIEF), parameter \"Visual word->Nearest Neighbor\" "
01641                                    "cannot be KD-Tree (used for float descriptor). BruteForce matching is set instead for the bag-of-words dictionary."));
01642                 _ui->comboBox_dictionary_strategy->setCurrentIndex(VWDictionary::kNNBruteForce);
01643         }
01644 
01645         // BOW Reextract features type
01646         if(_ui->reextract_nn->currentIndex() == VWDictionary::kNNFlannLSH && _ui->reextract_type->currentIndex() <= 1)
01647         {
01648                 QMessageBox::warning(this, tr("Parameter warning"),
01649                                 tr("With the selected feature type (SURF or SIFT), parameter \"Visual word->Nearest Neighbor\" "
01650                                    "cannot be LSH (used for binary descriptor). KD-tree is set instead for the re-extraction "
01651                                            "of features on loop closure."));
01652                 _ui->reextract_nn->setCurrentIndex(VWDictionary::kNNFlannKdTree);
01653         }
01654         else if(_ui->reextract_nn->currentIndex() == VWDictionary::kNNFlannKdTree && _ui->reextract_type->currentIndex() >1)
01655         {
01656                 QMessageBox::warning(this, tr("Parameter warning"),
01657                                 tr("With the selected feature type (ORB, FAST, FREAK or BRIEF), parameter \"Visual word->Nearest Neighbor\" "
01658                                    "cannot be KD-Tree (used for float descriptor). BruteForce matching is set instead for the re-extraction "
01659                                            "of features on loop closure."));
01660                 _ui->reextract_nn->setCurrentIndex(VWDictionary::kNNBruteForce);
01661         }
01662 
01663         // odom type
01664         if(_ui->odom_bin_nn->currentIndex() == VWDictionary::kNNFlannLSH && _ui->odom_type->currentIndex() <= 1)
01665         {
01666                 QMessageBox::warning(this, tr("Parameter warning"),
01667                                 tr("With the selected feature type (SURF or SIFT), parameter \"Odometry->Nearest Neighbor\" "
01668                                    "cannot be LSH (used for binary descriptor). KD-tree is set instead for odometry."));
01669                 _ui->odom_bin_nn->setCurrentIndex(VWDictionary::kNNFlannKdTree);
01670         }
01671         else if(_ui->odom_bin_nn->currentIndex() == VWDictionary::kNNFlannKdTree && _ui->odom_type->currentIndex() >1)
01672         {
01673                 QMessageBox::warning(this, tr("Parameter warning"),
01674                                 tr("With the selected feature type (ORB, FAST, FREAK or BRIEF), parameter \"Odometry->Nearest Neighbor\" "
01675                                    "cannot be KD-Tree (used for float descriptor). BruteForce matching is set instead for odometry."));
01676                 _ui->odom_bin_nn->setCurrentIndex(VWDictionary::kNNBruteForce);
01677         }
01678 
01679         return true;
01680 }
01681 
01682 QString PreferencesDialog::getParamMessage()
01683 {
01684         return tr("Reading parameters from the configuration file...");
01685 }
01686 
01687 void PreferencesDialog::showEvent ( QShowEvent * event )
01688 {
01689         if(_monitoringState)
01690         {
01691                 // In monitoring state, you cannot change remote paths
01692                 _ui->lineEdit_workingDirectory->setEnabled(false);
01693                 _ui->toolButton_workingDirectory->setEnabled(false);
01694                 _ui->label_workingDirectory->setEnabled(false);
01695 
01696                 _ui->lineEdit_dictionaryPath->setEnabled(false);
01697                 _ui->toolButton_dictionaryPath->setEnabled(false);
01698                 _ui->label_dictionaryPath->setEnabled(false);
01699 
01700                 _ui->groupBox_source0->setEnabled(false);
01701                 _ui->groupBox_odometry1->setEnabled(false);
01702 
01703                 this->setWindowTitle(tr("Preferences [Monitoring mode]"));
01704         }
01705         else
01706         {
01707                 _ui->lineEdit_workingDirectory->setEnabled(true);
01708                 _ui->toolButton_workingDirectory->setEnabled(true);
01709                 _ui->label_workingDirectory->setEnabled(true);
01710 
01711                 _ui->lineEdit_dictionaryPath->setEnabled(true);
01712                 _ui->toolButton_dictionaryPath->setEnabled(true);
01713                 _ui->label_dictionaryPath->setEnabled(true);
01714 
01715                 _ui->groupBox_source0->setEnabled(true);
01716                 _ui->groupBox_odometry1->setEnabled(true);
01717 
01718                 this->setWindowTitle(tr("Preferences"));
01719         }
01720         this->readSettingsBegin();
01721 }
01722 
01723 void PreferencesDialog::readSettingsBegin()
01724 {
01725         _progressDialog->setLabelText(this->getParamMessage());
01726         _progressDialog->show();
01727 
01728         // this will let the MainThread to display the progress dialog before reading the parameters...
01729         QTimer::singleShot(10, this, SLOT(readSettingsEnd()));
01730 }
01731 
01732 void PreferencesDialog::readSettingsEnd()
01733 {
01734         QApplication::processEvents();
01735 
01736         this->readSettings(getTmpIniFilePath());
01737 
01738         _progressDialog->setValue(1);
01739         if(this->isVisible())
01740         {
01741                 _progressDialog->setLabelText(tr("Setup dialog..."));
01742 
01743                 this->updatePredictionPlot();
01744                 this->setupKpRoiPanel();
01745         }
01746 
01747         _progressDialog->setValue(2); // this will make closing...
01748 }
01749 
01750 void PreferencesDialog::saveWindowGeometry(const QWidget * window)
01751 {
01752         if(!window->objectName().isNull() && !window->isMaximized())
01753         {
01754                 QSettings settings(getIniFilePath(), QSettings::IniFormat);
01755                 settings.beginGroup("Gui");
01756                 settings.beginGroup(window->objectName());
01757                 settings.setValue("geometry", window->saveGeometry());
01758                 settings.endGroup(); // "windowName"
01759                 settings.endGroup(); // rtabmap
01760         }
01761 }
01762 
01763 void PreferencesDialog::loadWindowGeometry(QWidget * window)
01764 {
01765         if(!window->objectName().isNull())
01766         {
01767                 QByteArray bytes;
01768                 QSettings settings(getIniFilePath(), QSettings::IniFormat);
01769                 settings.beginGroup("Gui");
01770                 settings.beginGroup(window->objectName());
01771                 bytes = settings.value("geometry", QByteArray()).toByteArray();
01772                 if(!bytes.isEmpty())
01773                 {
01774                         window->restoreGeometry(bytes);
01775                 }
01776                 settings.endGroup(); // "windowName"
01777                 settings.endGroup(); // rtabmap
01778         }
01779 }
01780 
01781 void PreferencesDialog::saveMainWindowState(const QMainWindow * mainWindow)
01782 {
01783         if(!mainWindow->objectName().isNull())
01784         {
01785                 saveWindowGeometry(mainWindow);
01786 
01787                 QSettings settings(getIniFilePath(), QSettings::IniFormat);
01788                 settings.beginGroup("Gui");
01789                 settings.beginGroup(mainWindow->objectName());
01790                 settings.setValue("state", mainWindow->saveState());
01791                 settings.setValue("maximized", mainWindow->isMaximized());
01792                 settings.endGroup(); // "MainWindow"
01793                 settings.endGroup(); // rtabmap
01794         }
01795 }
01796 
01797 void PreferencesDialog::loadMainWindowState(QMainWindow * mainWindow,  bool & maximized)
01798 {
01799         if(!mainWindow->objectName().isNull())
01800         {
01801                 loadWindowGeometry(mainWindow);
01802 
01803                 QByteArray bytes;
01804                 QSettings settings(getIniFilePath(), QSettings::IniFormat);
01805                 settings.beginGroup("Gui");
01806                 settings.beginGroup(mainWindow->objectName());
01807                 bytes = settings.value("state", QByteArray()).toByteArray();
01808                 if(!bytes.isEmpty())
01809                 {
01810                         mainWindow->restoreState(bytes);
01811                 }
01812                 maximized = settings.value("maximized", false).toBool();
01813                 settings.endGroup(); // "MainWindow"
01814                 settings.endGroup(); // rtabmap
01815         }
01816 }
01817 
01818 void PreferencesDialog::saveWidgetState(const QWidget * widget)
01819 {
01820         if(!widget->objectName().isNull())
01821         {
01822                 QSettings settings(getIniFilePath(), QSettings::IniFormat);
01823                 settings.beginGroup("Gui");
01824                 settings.beginGroup(widget->objectName());
01825 
01826                 const CloudViewer * cloudViewer = qobject_cast<const CloudViewer*>(widget);
01827                 const ImageView * imageView = qobject_cast<const ImageView*>(widget);
01828                 const ExportCloudsDialog * exportCloudsDialog = qobject_cast<const ExportCloudsDialog*>(widget);
01829                 const PostProcessingDialog * postProcessingDialog = qobject_cast<const PostProcessingDialog *>(widget);
01830                 const GraphViewer * graphViewer = qobject_cast<const GraphViewer *>(widget);
01831                 const CalibrationDialog * calibrationDialog = qobject_cast<const CalibrationDialog *>(widget);
01832 
01833                 if(cloudViewer)
01834                 {
01835                         cloudViewer->saveSettings(settings);
01836                 }
01837                 else if(imageView)
01838                 {
01839                         imageView->saveSettings(settings);
01840                 }
01841                 else if(exportCloudsDialog)
01842                 {
01843                         exportCloudsDialog->saveSettings(settings);
01844                 }
01845                 else if(postProcessingDialog)
01846                 {
01847                         postProcessingDialog->saveSettings(settings);
01848                 }
01849                 else if(graphViewer)
01850                 {
01851                         graphViewer->saveSettings(settings);
01852                 }
01853                 else if(calibrationDialog)
01854                 {
01855                         calibrationDialog->saveSettings(settings);
01856                 }
01857                 else
01858                 {
01859                         UERROR("Widget \"%s\" cannot be exported in config file.", widget->objectName().toStdString().c_str());
01860                 }
01861 
01862                 settings.endGroup(); // "name"
01863                 settings.endGroup(); // Gui
01864         }
01865 }
01866 
01867 void PreferencesDialog::loadWidgetState(QWidget * widget)
01868 {
01869         if(!widget->objectName().isNull())
01870         {
01871                 QByteArray bytes;
01872                 QSettings settings(getIniFilePath(), QSettings::IniFormat);
01873                 settings.beginGroup("Gui");
01874                 settings.beginGroup(widget->objectName());
01875 
01876                 CloudViewer * cloudViewer = qobject_cast<CloudViewer*>(widget);
01877                 ImageView * imageView = qobject_cast<ImageView*>(widget);
01878                 ExportCloudsDialog * exportCloudsDialog = qobject_cast<ExportCloudsDialog*>(widget);
01879                 PostProcessingDialog * postProcessingDialog = qobject_cast<PostProcessingDialog *>(widget);
01880                 GraphViewer * graphViewer = qobject_cast<GraphViewer *>(widget);
01881                 CalibrationDialog * calibrationDialog = qobject_cast<CalibrationDialog *>(widget);
01882 
01883                 if(cloudViewer)
01884                 {
01885                         cloudViewer->loadSettings(settings);
01886                 }
01887                 else if(imageView)
01888                 {
01889                         imageView->loadSettings(settings);
01890                 }
01891                 else if(exportCloudsDialog)
01892                 {
01893                         exportCloudsDialog->loadSettings(settings);
01894                 }
01895                 else if(postProcessingDialog)
01896                 {
01897                         postProcessingDialog->loadSettings(settings);
01898                 }
01899                 else if(graphViewer)
01900                 {
01901                         graphViewer->loadSettings(settings);
01902                 }
01903                 else if(calibrationDialog)
01904                 {
01905                         calibrationDialog->loadSettings(settings);
01906                 }
01907                 else
01908                 {
01909                         UERROR("Widget \"%s\" cannot be loaded from config file.", widget->objectName().toStdString().c_str());
01910                 }
01911 
01912                 settings.endGroup(); //"name"
01913                 settings.endGroup(); // Gui
01914         }
01915 }
01916 
01917 
01918 void PreferencesDialog::saveCustomConfig(const QString & section, const QString & key, const QString & value)
01919 {
01920         QSettings settings(getIniFilePath(), QSettings::IniFormat);
01921         settings.beginGroup("Gui");
01922         settings.beginGroup(section);
01923         settings.setValue(key, value);
01924         settings.endGroup(); // "section"
01925         settings.endGroup(); // rtabmap
01926 }
01927 
01928 QString PreferencesDialog::loadCustomConfig(const QString & section, const QString & key)
01929 {
01930         QString value;
01931         QSettings settings(getIniFilePath(), QSettings::IniFormat);
01932         settings.beginGroup("Gui");
01933         settings.beginGroup(section);
01934         value = settings.value(key, QString()).toString();
01935         settings.endGroup(); // "section"
01936         settings.endGroup(); // rtabmap
01937         return value;
01938 }
01939 
01940 void PreferencesDialog::selectSourceImage(Src src)
01941 {
01942         ULOGGER_DEBUG("");
01943 
01944         bool fromPrefDialog = false;
01945         //bool modified = false;
01946         if(src == kSrcUndef)
01947         {
01948                 fromPrefDialog = true;
01949                 if(_ui->source_comboBox_image_type->currentIndex() == 1)
01950                 {
01951                         src = kSrcImages;
01952                 }
01953                 else if(_ui->source_comboBox_image_type->currentIndex() == 2)
01954                 {
01955                         src = kSrcVideo;
01956                 }
01957                 else
01958                 {
01959                         src = kSrcUsbDevice;
01960                 }
01961         }
01962 
01963         if(!fromPrefDialog)
01964         {
01965                 if(_ui->general_checkBox_activateRGBD->isChecked())
01966                 {
01967                         int button = QMessageBox::information(this,
01968                                         tr("Desactivate RGB-D SLAM?"),
01969                                         tr("You've selected source input as images only and RGB-D SLAM mode is activated. "
01970                                            "RGB-D SLAM cannot work with images only so do you want to desactivate it?"),
01971                                         QMessageBox::Yes | QMessageBox::No);
01972                         if(button & QMessageBox::Yes)
01973                         {
01974                                 _ui->general_checkBox_activateRGBD->setChecked(false);
01975                         }
01976                 }
01977         }
01978 
01979         if(src == kSrcImages)
01980         {
01981                 QString path = QFileDialog::getExistingDirectory(this, QString(), _ui->source_images_lineEdit_path->text());
01982                 QDir dir(path);
01983                 if(!path.isEmpty() && dir.exists())
01984                 {
01985                         QStringList filters;
01986                         filters << "*.jpg" << "*.ppm" << "*.bmp" << "*.png" << "*.pnm" << "*.tiff";
01987                         dir.setNameFilters(filters);
01988                         QFileInfoList files = dir.entryInfoList();
01989                         if(!files.empty())
01990                         {
01991                                 _ui->source_comboBox_image_type->setCurrentIndex(1);
01992                                 _ui->source_images_lineEdit_path->setText(path);
01993                                 _ui->source_images_spinBox_startPos->setValue(1);
01994                                 _ui->source_images_refreshDir->setChecked(false);
01995                                 _ui->groupBox_sourceImage->setChecked(true);
01996                         }
01997                         else
01998                         {
01999                                 QMessageBox::information(this,
02000                                                                                    tr("RTAB-Map"),
02001                                                                                    tr("Images must be one of these formats: ") + filters.join(" "));
02002                         }
02003                 }
02004         }
02005         else if(src == kSrcVideo)
02006         {
02007                 QString path = QFileDialog::getOpenFileName(this, tr("Select file"), _ui->source_video_lineEdit_path->text(), tr("Videos (*.avi *.mpg *.mp4)"));
02008                 QFile file(path);
02009                 if(!path.isEmpty() && file.exists())
02010                 {
02011                         _ui->source_comboBox_image_type->setCurrentIndex(2);
02012                         _ui->source_video_lineEdit_path->setText(path);
02013                         _ui->groupBox_sourceImage->setChecked(true);
02014                 }
02015         }
02016         else // kSrcUsbDevice
02017         {
02018                 _ui->source_comboBox_image_type->setCurrentIndex(0);
02019                 _ui->groupBox_sourceImage->setChecked(true);
02020         }
02021 
02022         if(_ui->groupBox_sourceImage->isChecked())
02023         {
02024                 _ui->groupBox_sourceDatabase->setChecked(false);
02025                 _ui->groupBox_sourceOpenni->setChecked(false);
02026         }
02027 
02028         if(!fromPrefDialog)
02029         {
02030                 // Even if there is no change, MainWindow should be notified
02031                 makeObsoleteSourcePanel();
02032 
02033                 if(validateForm())
02034                 {
02035                         this->writeSettings(getTmpIniFilePath());
02036                 }
02037                 else
02038                 {
02039                         this->readSettingsBegin();
02040                 }
02041         }
02042 }
02043 
02044 void PreferencesDialog::selectSourceDatabase(bool user)
02045 {
02046         ULOGGER_DEBUG("");
02047 
02048         QString dir = _ui->source_database_lineEdit_path->text();
02049         if(dir.isEmpty())
02050         {
02051                 dir = getWorkingDirectory();
02052         }
02053         QStringList paths = QFileDialog::getOpenFileNames(this, tr("Select file"), dir, tr("RTAB-Map database files (*.db)"));
02054         if(paths.size())
02055         {
02056                 int r = QMessageBox::question(this, tr("Odometry in database..."), tr("Use odometry saved in database (if some saved)?"), QMessageBox::Yes | QMessageBox::No, QMessageBox::Yes);
02057 
02058                 _ui->groupBox_sourceDatabase->setChecked(true);
02059                 _ui->source_checkBox_ignoreOdometry->setChecked(r != QMessageBox::Yes);
02060                 _ui->source_checkBox_ignoreGoalDelay->setChecked(false);
02061                 _ui->source_database_lineEdit_path->setText(paths.size()==1?paths.front():paths.join(";"));
02062                 _ui->source_spinBox_databaseStartPos->setValue(0);
02063                 _ui->source_checkBox_useDbStamps->setChecked(false);
02064         }
02065 
02066         if(_ui->groupBox_sourceDatabase->isChecked())
02067         {
02068                 _ui->groupBox_sourceImage->setChecked(false);
02069                 _ui->groupBox_sourceOpenni->setChecked(false);
02070         }
02071 
02072         if(user)
02073         {
02074                 // Even if there is no change, MainWindow should be notified
02075                 makeObsoleteSourcePanel();
02076 
02077                 if(validateForm())
02078                 {
02079                         this->writeSettings(getTmpIniFilePath());
02080                 }
02081                 else
02082                 {
02083                         this->readSettingsBegin();
02084                 }
02085         }
02086 }
02087 
02088 void PreferencesDialog::selectSourceRGBD(Src src)
02089 {
02090         ULOGGER_DEBUG("");
02091 
02092         if(!_ui->general_checkBox_activateRGBD->isChecked())
02093         {
02094                 int button = QMessageBox::information(this,
02095                                 tr("Activate RGB-D SLAM?"),
02096                                 tr("You've selected RGB-D camera as source input, "
02097                                    "would you want to activate RGB-D SLAM mode?"),
02098                                 QMessageBox::Yes | QMessageBox::No, QMessageBox::Yes);
02099                 if(button & QMessageBox::Yes)
02100                 {
02101                         _ui->general_checkBox_activateRGBD->setChecked(true);
02102                 }
02103         }
02104 
02105         _ui->groupBox_sourceOpenni->setChecked(true);
02106         _ui->comboBox_cameraRGBD->setCurrentIndex(src - kSrcOpenNI_PCL);
02107 
02108         if(_ui->groupBox_sourceOpenni->isChecked())
02109         {
02110                 _ui->groupBox_sourceImage->setChecked(false);
02111                 _ui->groupBox_sourceDatabase->setChecked(false);
02112         }
02113 
02114         if(validateForm())
02115         {
02116                 // Even if there is no change, MainWindow should be notified
02117                 makeObsoleteSourcePanel();
02118 
02119                 this->writeSettings(getTmpIniFilePath());
02120         }
02121         else
02122         {
02123                 this->readSettingsBegin();
02124         }
02125 }
02126 
02127 void PreferencesDialog::openDatabaseViewer()
02128 {
02129         DatabaseViewer * viewer = new DatabaseViewer(this);
02130         viewer->setWindowModality(Qt::WindowModal);
02131         viewer->setAttribute(Qt::WA_DeleteOnClose, true);
02132         viewer->showCloseButton();
02133         if(viewer->openDatabase(_ui->source_database_lineEdit_path->text()))
02134         {
02135                 viewer->show();
02136         }
02137         else
02138         {
02139                 delete viewer;
02140         }
02141 }
02142 
02143 void PreferencesDialog::setParameter(const std::string & key, const std::string & value)
02144 {
02145         UDEBUG("%s=%s", key.c_str(), value.c_str());
02146         QWidget * obj = _ui->stackedWidget->findChild<QWidget*>(key.c_str());
02147         if(obj)
02148         {
02149                 QSpinBox * spin = qobject_cast<QSpinBox *>(obj);
02150                 QDoubleSpinBox * doubleSpin = qobject_cast<QDoubleSpinBox *>(obj);
02151                 QComboBox * combo = qobject_cast<QComboBox *>(obj);
02152                 QCheckBox * check = qobject_cast<QCheckBox *>(obj);
02153                 QRadioButton * radio = qobject_cast<QRadioButton *>(obj);
02154                 QLineEdit * lineEdit = qobject_cast<QLineEdit *>(obj);
02155                 QGroupBox * groupBox = qobject_cast<QGroupBox *>(obj);
02156                 bool ok;
02157                 if(spin)
02158                 {
02159                         spin->setValue(QString(value.c_str()).toInt(&ok));
02160                         if(!ok)
02161                         {
02162                                 UERROR("Conversion failed from \"%s\" for parameter %s", value.c_str(), key.c_str());
02163                         }
02164                 }
02165                 else if(doubleSpin)
02166                 {
02167                         doubleSpin->setValue(QString(value.c_str()).toDouble(&ok));
02168                         if(!ok)
02169                         {
02170                                 UERROR("Conversion failed from \"%s\" for parameter %s", value.c_str(), key.c_str());
02171                         }
02172                 }
02173                 else if(combo)
02174                 {
02175                         int valueInt = QString(value.c_str()).toInt(&ok);
02176                         if(!ok)
02177                         {
02178                                 UERROR("Conversion failed from \"%s\" for parameter %s", value.c_str(), key.c_str());
02179                         }
02180                         else
02181                         {
02182                                 if(RTABMAP_NONFREE == 0)
02183                                 {
02184                                         if(valueInt <= 1 &&
02185                                                         (combo->objectName().toStdString().compare(Parameters::kKpDetectorStrategy()) == 0 ||
02186                                                         combo->objectName().toStdString().compare(Parameters::kLccReextractFeatureType()) == 0 ||
02187                                                         combo->objectName().toStdString().compare(Parameters::kOdomFeatureType()) == 0))
02188                                         {
02189                                                 UWARN("Trying to set \"%s\" to SIFT/SURF but RTAB-Map isn't built "
02190                                                           "with the nonfree module from OpenCV. Keeping default combo value: %s.",
02191                                                           combo->objectName().toStdString().c_str(),
02192                                                           combo->currentText().toStdString().c_str());
02193                                                 ok = false;
02194                                         }
02195                                         else if(valueInt==1 &&
02196                                                         (combo->objectName().toStdString().compare(Parameters::kKpNNStrategy()) == 0 ||
02197                                                         combo->objectName().toStdString().compare(Parameters::kLccReextractNNType()) == 0 ||
02198                                                         combo->objectName().toStdString().compare(Parameters::kOdomBowNNType()) == 0))
02199 
02200                                         {
02201                                                 UWARN("Trying to set \"%s\" to KdTree but RTAB-Map isn't built "
02202                                                           "with the nonfree module from OpenCV and kdTree cannot be used "
02203                                                           "with binary descriptors. Keeping default combo value: %s.",
02204                                                           combo->objectName().toStdString().c_str(),
02205                                                           combo->currentText().toStdString().c_str());
02206                                                 ok = false;
02207                                         }
02208                                 }
02209                                 if(!graph::G2OOptimizer::available())
02210                                 {
02211                                         if(valueInt==1 && combo->objectName().toStdString().compare(Parameters::kRGBDOptimizeStrategy()) == 0)
02212                                         {
02213                                                 UWARN("Trying to set \"%s\" to g2o but RTAB-Map isn't built "
02214                                                           "with g2o. Keeping default combo value: %s.",
02215                                                           combo->objectName().toStdString().c_str(),
02216                                                           combo->currentText().toStdString().c_str());
02217                                                 ok = false;
02218                                         }
02219                                 }
02220                                 if(ok)
02221                                 {
02222                                         combo->setCurrentIndex(valueInt);
02223                                 }
02224                         }
02225 
02226                 }
02227                 else if(check)
02228                 {
02229                         check->setChecked(uStr2Bool(value.c_str()));
02230                 }
02231                 else if(radio)
02232                 {
02233                         radio->setChecked(uStr2Bool(value.c_str()));
02234                 }
02235                 else if(lineEdit)
02236                 {
02237                         lineEdit->setText(value.c_str());
02238                 }
02239                 else if(groupBox)
02240                 {
02241                         groupBox->setChecked(uStr2Bool(value.c_str()));
02242                 }
02243                 else
02244                 {
02245                         ULOGGER_WARN("QObject called %s can't be cast to a supported widget", key.c_str());
02246                 }
02247         }
02248         else
02249         {
02250                 ULOGGER_WARN("Can't find the related QObject for parameter %s", key.c_str());
02251         }
02252 }
02253 
02254 void PreferencesDialog::addParameter(int value)
02255 {
02256         if(sender())
02257         {
02258                 this->addParameter(sender(), value);
02259         }
02260         else
02261         {
02262                 ULOGGER_ERROR("This slot must be triggered by a signal, not a direct call...");
02263         }
02264 }
02265 
02266 void PreferencesDialog::addParameter(bool value)
02267 {
02268         if(sender())
02269         {
02270                 this->addParameter(sender(), value);
02271         }
02272         else
02273         {
02274                 ULOGGER_ERROR("This slot must be triggered by a signal, not a direct call...");
02275         }
02276 }
02277 
02278 void PreferencesDialog::addParameter(double value)
02279 {
02280         if(sender())
02281         {
02282                 this->addParameter(sender(), value);
02283         }
02284         else
02285         {
02286                 ULOGGER_ERROR("This slot must be triggered by a signal, not a direct call...");
02287         }
02288 }
02289 
02290 void PreferencesDialog::addParameter(const QString & value)
02291 {
02292         if(sender())
02293         {
02294                 this->addParameter(sender(), value);
02295         }
02296         else
02297         {
02298                 ULOGGER_ERROR("This slot must be triggered by a signal, not a direct call...");
02299         }
02300 }
02301 
02302 void PreferencesDialog::addParameter(const QObject * object, int value)
02303 {
02304         if(object)
02305         {
02306                 // Make sure the value is inserted, check if the same key already exists
02307                 rtabmap::ParametersMap::iterator iter = _parameters.find(object->objectName().toStdString());
02308                 if(iter != _parameters.end())
02309                 {
02310                         _parameters.erase(iter);
02311                 }
02312 
02313                 const QComboBox * comboBox = qobject_cast<const QComboBox*>(object);
02314                 const QSpinBox * spinbox = qobject_cast<const QSpinBox*>(object);
02315                 if(comboBox || spinbox)
02316                 {
02317                         if(comboBox)
02318                         {
02319                                 // Add related panels to parameters
02320                                 if(comboBox == _ui->comboBox_vh_strategy)
02321                                 {
02322                                         if(value == 0) // 0 none
02323                                         {
02324                                                 // No panel related...
02325                                         }
02326                                         else if(value == 1) // 2 epipolar
02327                                         {
02328                                                 this->addParameters(_ui->groupBox_vh_epipolar2);
02329                                         }
02330                                 }
02331                                 else if(comboBox == _ui->comboBox_detector_strategy ||
02332                                                 comboBox == _ui->odom_type ||
02333                                                 comboBox == _ui->reextract_type)
02334                                 {
02335                                         if(value == 0) //  surf
02336                                         {
02337                                                 this->addParameters(_ui->groupBox_detector_surf2);
02338                                         }
02339                                         else if(value == 1) //  sift
02340                                         {
02341                                                 this->addParameters(_ui->groupBox_detector_sift2);
02342                                         }
02343                                         else if(value == 2) //  orb
02344                                         {
02345                                                 this->addParameters(_ui->groupBox_detector_orb2);
02346                                         }
02347                                         else if(value == 3) //  fast+freak
02348                                         {
02349                                                 this->addParameters(_ui->groupBox_detector_fast2);
02350                                                 this->addParameters(_ui->groupBox_detector_freak2);
02351                                         }
02352                                         else if(value == 4) //  fast+brief
02353                                         {
02354                                                 this->addParameters(_ui->groupBox_detector_fast2);
02355                                                 this->addParameters(_ui->groupBox_detector_brief2);
02356                                         }
02357                                         else if(value == 5) //  gftt+freak
02358                                         {
02359                                                 this->addParameters(_ui->groupBox_detector_gftt2);
02360                                                 this->addParameters(_ui->groupBox_detector_freak2);
02361                                         }
02362                                         else if(value == 6) //  gftt+brief
02363                                         {
02364                                                 this->addParameters(_ui->groupBox_detector_gftt2);
02365                                                 this->addParameters(_ui->groupBox_detector_brief2);
02366                                         }
02367                                         else if(value == 7) //  brisk
02368                                         {
02369                                                 this->addParameters(_ui->groupBox_detector_brisk2);
02370                                         }
02371                                 }
02372                                 else if(comboBox == _ui->globalDetection_icpType)
02373                                 {
02374                                         if(value == 1) // 1 icp3
02375                                         {
02376                                                 this->addParameters(_ui->groupBox_loopClosure_icp3);
02377                                         }
02378                                         else if(value == 2) // 2 icp2
02379                                         {
02380                                                 this->addParameters(_ui->groupBox_loopClosure_icp2);
02381                                         }
02382                                 }
02383                         }
02384                         // Add parameter
02385                         _parameters.insert(rtabmap::ParametersPair(object->objectName().toStdString(), QString::number(value).toStdString()));
02386                 }
02387                 else
02388                 {
02389                         UWARN("Undefined object \"%s\"", object->objectName().toStdString().c_str());
02390                 }
02391 
02392         }
02393         else
02394         {
02395                 ULOGGER_ERROR("Object is null");
02396         }
02397 }
02398 
02399 void PreferencesDialog::addParameter(const QObject * object, bool value)
02400 {
02401         if(object)
02402         {
02403                 // Make sure the value is inserted, check if the same key already exists
02404                 rtabmap::ParametersMap::iterator iter = _parameters.find(object->objectName().toStdString());
02405                 if(iter != _parameters.end())
02406                 {
02407                         _parameters.erase(iter);
02408                 }
02409 
02410                 const QCheckBox * checkbox = qobject_cast<const QCheckBox*>(object);
02411                 const QRadioButton * radio = qobject_cast<const QRadioButton*>(object);
02412                 const QGroupBox * groupBox = qobject_cast<const QGroupBox*>(object);
02413                 if(checkbox || radio || groupBox)
02414                 {
02415                         // Add parameter
02416                         _parameters.insert(rtabmap::ParametersPair(object->objectName().toStdString(), uBool2Str(value)));
02417 
02418                         // RGBD panel
02419                         if(value && checkbox == _ui->general_checkBox_activateRGBD)
02420                         {
02421                                 // add all RGBD parameters!
02422                                 this->addParameters(_ui->groupBox_slam_update);
02423                                 this->addParameters(_ui->groupBox_graphOptimization);
02424                                 this->addParameters(_ui->groupBox_localDetection_time);
02425                                 this->addParameters(_ui->groupBox_localDetection_space);
02426                                 this->addParameters(_ui->groupBox_visualTransform2);
02427                         }
02428 
02429                         if(groupBox)
02430                         {
02431                                 // RGBD panel
02432                                 if(value && groupBox == _ui->groupBox_localDetection_time)
02433                                 {
02434                                         this->addParameters(_ui->groupBox_visualTransform2);
02435                                 }
02436                                 if(value && groupBox == _ui->groupBox_localDetection_space)
02437                                 {
02438                                         this->addParameters(_ui->groupBox_loopClosure_icp2);
02439                                 }
02440 
02441                                 this->addParameters(groupBox);
02442                         }
02443                 }
02444                 else
02445                 {
02446                         UWARN("Undefined object \"%s\"", object->objectName().toStdString().c_str());
02447                 }
02448 
02449         }
02450         else
02451         {
02452                 ULOGGER_ERROR("Object is null");
02453         }
02454 }
02455 
02456 void PreferencesDialog::addParameter(const QObject * object, double value)
02457 {
02458         if(object)
02459         {
02460                 // Make sure the value is inserted, check if the same key already exists
02461                 rtabmap::ParametersMap::iterator iter = _parameters.find(object->objectName().toStdString());
02462                 if(iter != _parameters.end())
02463                 {
02464                         _parameters.erase(iter);
02465                 }
02466                 _parameters.insert(rtabmap::ParametersPair(object->objectName().toStdString(), QString::number(value).toStdString()));
02467                 //ULOGGER_DEBUG("PreferencesDialog::addParameter(object, double) Added [\"%s\",\"%s\"]", object->objectName().toStdString().c_str(), QString::number(value).toStdString().c_str());
02468         }
02469         else
02470         {
02471                 ULOGGER_ERROR("Object is null");
02472         }
02473 }
02474 
02475 void PreferencesDialog::addParameter(const QObject * object, const QString & value)
02476 {
02477         if(object)
02478         {
02479                 // Make sure the value is inserted, check if the same key already exists
02480                 rtabmap::ParametersMap::iterator iter = _parameters.find(object->objectName().toStdString());
02481                 if(iter != _parameters.end())
02482                 {
02483                         _parameters.erase(iter);
02484                 }
02485                 _parameters.insert(rtabmap::ParametersPair(object->objectName().toStdString(), value.toStdString()));
02486                 //ULOGGER_DEBUG("PreferencesDialog::addParameter(object, QString) Added [\"%s\",\"%s\"]", object->objectName().toStdString().c_str(), QString::number(value).toStdString().c_str());
02487         }
02488         else
02489         {
02490                 ULOGGER_ERROR("Object is null");
02491         }
02492 }
02493 
02494 void PreferencesDialog::addParameters(const QObjectList & children)
02495 {
02496         //ULOGGER_DEBUG("PreferencesDialog::addParameters(QGroupBox) box %s has %d children", box->objectName().toStdString().c_str(), children.size());
02497         for(int i=0; i<children.size(); ++i)
02498         {
02499                 const QSpinBox * spin = qobject_cast<const QSpinBox *>(children[i]);
02500                 const QDoubleSpinBox * doubleSpin = qobject_cast<const QDoubleSpinBox *>(children[i]);
02501                 const QComboBox * combo = qobject_cast<const QComboBox *>(children[i]);
02502                 const QCheckBox * check = qobject_cast<const QCheckBox *>(children[i]);
02503                 const QRadioButton * radio = qobject_cast<const QRadioButton *>(children[i]);
02504                 const QLineEdit * lineEdit = qobject_cast<const QLineEdit *>(children[i]);
02505                 const QGroupBox * groupBox = qobject_cast<const QGroupBox *>(children[i]);
02506                 const QStackedWidget * stackedWidget = qobject_cast<const QStackedWidget *>(children[i]);
02507                 if(spin)
02508                 {
02509                         this->addParameter(spin, spin->value());
02510                 }
02511                 else if(doubleSpin)
02512                 {
02513                         this->addParameter(doubleSpin, doubleSpin->value());
02514                 }
02515                 else if(combo)
02516                 {
02517                         this->addParameter(combo, combo->currentIndex());
02518                 }
02519                 else if(check)
02520                 {
02521                         this->addParameter(check, check->isChecked());
02522                 }
02523                 else if(radio)
02524                 {
02525                         this->addParameter(radio, radio->isChecked());
02526                 }
02527                 else if(lineEdit)
02528                 {
02529                         this->addParameter(lineEdit, lineEdit->text());
02530                 }
02531                 else if(groupBox)
02532                 {
02533                         if(groupBox->isCheckable())
02534                         {
02535                                 this->addParameter(groupBox, groupBox->isChecked());
02536                         }
02537                         else
02538                         {
02539                                 this->addParameters(groupBox);
02540                         }
02541                 }
02542                 else if(stackedWidget)
02543                 {
02544                         this->addParameters(stackedWidget);
02545                 }
02546         }
02547 }
02548 
02549 void PreferencesDialog::addParameters(const QStackedWidget * stackedWidget)
02550 {
02551         if(stackedWidget)
02552         {
02553                 for(int i=0; i<stackedWidget->count(); ++i)
02554                 {
02555                         const QObjectList & children = stackedWidget->widget(i)->children();
02556                         addParameters(children);
02557                 }
02558         }
02559 }
02560 
02561 void PreferencesDialog::addParameters(const QGroupBox * box)
02562 {
02563         if(box)
02564         {
02565                 const QObjectList & children = box->children();
02566                 addParameters(children);
02567         }
02568 }
02569 
02570 void PreferencesDialog::updateBasicParameter()
02571 {
02572         // This method is used to update basic/advanced referred parameters, see above editingFinished()
02573 
02574         // basic to advanced (advanced to basic must be done by connecting signal valueChanged())
02575         if(sender() == _ui->general_doubleSpinBox_timeThr_2)
02576         {
02577                 _ui->general_doubleSpinBox_timeThr->setValue(_ui->general_doubleSpinBox_timeThr_2->value());
02578         }
02579         else if(sender() == _ui->general_doubleSpinBox_hardThr_2)
02580         {
02581                 _ui->general_doubleSpinBox_hardThr->setValue(_ui->general_doubleSpinBox_hardThr_2->value());
02582         }
02583         else if(sender() == _ui->general_doubleSpinBox_detectionRate_2)
02584         {
02585                 _ui->general_doubleSpinBox_detectionRate->setValue(_ui->general_doubleSpinBox_detectionRate_2->value());
02586         }
02587         else if(sender() == _ui->general_spinBox_imagesBufferSize_2)
02588         {
02589                 _ui->general_spinBox_imagesBufferSize->setValue(_ui->general_spinBox_imagesBufferSize_2->value());
02590         }
02591         else if(sender() == _ui->general_spinBox_maxStMemSize_2)
02592         {
02593                 _ui->general_spinBox_maxStMemSize->setValue(_ui->general_spinBox_maxStMemSize_2->value());
02594         }
02595         else if(sender() == _ui->groupBox_publishing)
02596         {
02597                 _ui->general_checkBox_publishStats_2->setChecked(_ui->groupBox_publishing->isChecked());
02598         }
02599         else if(sender() == _ui->general_checkBox_publishStats_2)
02600         {
02601                 _ui->groupBox_publishing->setChecked(_ui->general_checkBox_publishStats_2->isChecked());
02602         }
02603         else if(sender() == _ui->doubleSpinBox_similarityThreshold_2)
02604         {
02605                 _ui->doubleSpinBox_similarityThreshold->setValue(_ui->doubleSpinBox_similarityThreshold_2->value());
02606         }
02607         else if(sender() == _ui->general_checkBox_activateRGBD)
02608         {
02609                 _ui->general_checkBox_activateRGBD_2->setChecked(_ui->general_checkBox_activateRGBD->isChecked());
02610         }
02611         else if(sender() == _ui->general_checkBox_activateRGBD_2)
02612         {
02613                 _ui->general_checkBox_activateRGBD->setChecked(_ui->general_checkBox_activateRGBD_2->isChecked());
02614         }
02615         else if(sender() == _ui->general_checkBox_SLAM_mode)
02616         {
02617                 _ui->general_checkBox_SLAM_mode_2->setChecked(_ui->general_checkBox_SLAM_mode->isChecked());
02618         }
02619         else if(sender() == _ui->general_checkBox_SLAM_mode_2)
02620         {
02621                 _ui->general_checkBox_SLAM_mode->setChecked(_ui->general_checkBox_SLAM_mode_2->isChecked());
02622         }
02623         else
02624         {
02625                 //update all values (only those using editingFinished signal)
02626                 _ui->general_doubleSpinBox_timeThr->setValue(_ui->general_doubleSpinBox_timeThr_2->value());
02627                 _ui->general_doubleSpinBox_hardThr->setValue(_ui->general_doubleSpinBox_hardThr_2->value());
02628                 _ui->general_doubleSpinBox_detectionRate->setValue(_ui->general_doubleSpinBox_detectionRate_2->value());
02629                 _ui->general_spinBox_imagesBufferSize->setValue(_ui->general_spinBox_imagesBufferSize_2->value());
02630                 _ui->general_spinBox_maxStMemSize->setValue(_ui->general_spinBox_maxStMemSize_2->value());
02631                 _ui->doubleSpinBox_similarityThreshold->setValue(_ui->doubleSpinBox_similarityThreshold_2->value());
02632         }
02633 }
02634 
02635 void PreferencesDialog::makeObsoleteGeneralPanel()
02636 {
02637         ULOGGER_DEBUG("");
02638         _obsoletePanels = _obsoletePanels | kPanelGeneral;
02639 }
02640 
02641 void PreferencesDialog::makeObsoleteCloudRenderingPanel()
02642 {
02643         ULOGGER_DEBUG("");
02644         _obsoletePanels = _obsoletePanels | kPanelCloudRendering;
02645 }
02646 
02647 void PreferencesDialog::makeObsoleteLoggingPanel()
02648 {
02649         ULOGGER_DEBUG("");
02650         _obsoletePanels = _obsoletePanels | kPanelLogging;
02651 }
02652 
02653 void PreferencesDialog::makeObsoleteSourcePanel()
02654 {
02655         if(sender() == _ui->groupBox_sourceDatabase && _ui->groupBox_sourceDatabase->isChecked())
02656         {
02657                 _ui->groupBox_sourceImage->setChecked(false);
02658                 _ui->groupBox_sourceOpenni->setChecked(false);
02659         }
02660         else if(sender() == _ui->groupBox_sourceImage && _ui->groupBox_sourceImage->isChecked())
02661         {
02662                 _ui->groupBox_sourceDatabase->setChecked(false);
02663                 _ui->groupBox_sourceOpenni->setChecked(false);
02664         }
02665         else if(sender() == _ui->groupBox_sourceOpenni && _ui->groupBox_sourceOpenni->isChecked())
02666         {
02667                 _ui->groupBox_sourceImage->setChecked(false);
02668                 _ui->groupBox_sourceDatabase->setChecked(false);
02669         }
02670         ULOGGER_DEBUG("");
02671         _obsoletePanels = _obsoletePanels | kPanelSource;
02672 }
02673 
02674 rtabmap::ParametersMap PreferencesDialog::getAllParameters()
02675 {
02676         rtabmap::ParametersMap result;
02677         rtabmap::ParametersMap tmpParameters = _parameters;
02678         _parameters.clear();
02679 
02680         QList<QGroupBox*> boxes = this->getGroupBoxes();
02681         for(int i=0; i<boxes.size(); ++i)
02682         {
02683                 this->addParameters(boxes.at(i));
02684         }
02685 
02686         result = _parameters;
02687         _parameters = tmpParameters;
02688         return result;
02689 }
02690 
02691 QList<QGroupBox*> PreferencesDialog::getGroupBoxes()
02692 {
02693         QList<QGroupBox*> boxes;
02694         for(int i=0; i<_ui->stackedWidget->count(); ++i)
02695         {
02696                 QGroupBox * gb = 0;
02697                 const QObjectList & children = _ui->stackedWidget->widget(i)->children();
02698                 for(int j=0; j<children.size(); ++j)
02699                 {
02700                         if((gb = qobject_cast<QGroupBox *>(children.at(j))))
02701                         {
02702                                 //ULOGGER_DEBUG("PreferencesDialog::setupTreeView() index(%d) Added %s, box name=%s", i, gb->title().toStdString().c_str(), gb->objectName().toStdString().c_str());
02703                                 break;
02704                         }
02705                 }
02706                 if(gb)
02707                 {
02708                         boxes.append(gb);
02709                 }
02710                 else
02711                 {
02712                         ULOGGER_ERROR("A QGroupBox must be included in the first level of children in stacked widget, index=%d", i);
02713                 }
02714         }
02715         return boxes;
02716 }
02717 
02718 void PreferencesDialog::updatePredictionPlot()
02719 {
02720         QStringList values = _ui->lineEdit_bayes_predictionLC->text().simplified().split(' ');
02721         if(values.size() < 2)
02722         {
02723                 UERROR("Error parsing prediction (must have at least 2 items) : %s",
02724                                 _ui->lineEdit_bayes_predictionLC->text().toStdString().c_str());
02725                 return;
02726         }
02727         QVector<float> dataX((values.size()-2)*2 + 1);
02728         QVector<float> dataY((values.size()-2)*2 + 1);
02729         double value;
02730         double sum = 0;
02731         int lvl = 1;
02732         bool ok = false;
02733         bool error = false;
02734         int loopClosureIndex = (dataX.size()-1)/2;
02735         for(int i=0; i<values.size(); ++i)
02736         {
02737                 value = values.at(i).toDouble(&ok);
02738                 if(!ok)
02739                 {
02740                         UERROR("Error parsing prediction : \"%s\"", values.at(i).toStdString().c_str());
02741                         error = true;
02742                 }
02743                 sum+=value;
02744                 if(i==0)
02745                 {
02746                         //do nothing
02747                 }
02748                 else if(i == 1)
02749                 {
02750                         dataY[loopClosureIndex] = value;
02751                         dataX[loopClosureIndex] = 0;
02752                 }
02753                 else
02754                 {
02755                         dataY[loopClosureIndex-lvl] = value;
02756                         dataX[loopClosureIndex-lvl] = -lvl;
02757                         dataY[loopClosureIndex+lvl] = value;
02758                         dataX[loopClosureIndex+lvl] = lvl;
02759                         ++lvl;
02760                 }
02761         }
02762 
02763         _ui->label_prediction_sum->setNum(sum);
02764         if(error)
02765         {
02766                 _ui->label_prediction_sum->setText(QString("<font color=#FF0000>") + _ui->label_prediction_sum->text() + "</font>");
02767         }
02768         else if(sum == 1.0)
02769         {
02770                 _ui->label_prediction_sum->setText(QString("<font color=#00FF00>") + _ui->label_prediction_sum->text() + "</font>");
02771         }
02772         else if(sum > 1.0)
02773         {
02774                 _ui->label_prediction_sum->setText(QString("<font color=#FFa500>") + _ui->label_prediction_sum->text() + "</font>");
02775         }
02776         else
02777         {
02778                 _ui->label_prediction_sum->setText(QString("<font color=#000000>") + _ui->label_prediction_sum->text() + "</font>");
02779         }
02780 
02781         _ui->predictionPlot->removeCurves();
02782         _ui->predictionPlot->addCurve(new UPlotCurve("Prediction", dataX, dataY, _ui->predictionPlot));
02783 }
02784 
02785 void PreferencesDialog::setupKpRoiPanel()
02786 {
02787         QStringList strings = _ui->lineEdit_kp_roi->text().split(' ');
02788         if(strings.size()!=4)
02789         {
02790                 UERROR("ROI must have 4 values (%s)", _ui->lineEdit_kp_roi->text().toStdString().c_str());
02791                 return;
02792         }
02793         _ui->doubleSpinBox_kp_roi0->setValue(strings[0].toDouble()*100.0);
02794         _ui->doubleSpinBox_kp_roi1->setValue(strings[1].toDouble()*100.0);
02795         _ui->doubleSpinBox_kp_roi2->setValue(strings[2].toDouble()*100.0);
02796         _ui->doubleSpinBox_kp_roi3->setValue(strings[3].toDouble()*100.0);
02797 }
02798 
02799 void PreferencesDialog::updateKpROI()
02800 {
02801         QStringList strings;
02802         strings.append(QString::number(_ui->doubleSpinBox_kp_roi0->value()/100.0));
02803         strings.append(QString::number(_ui->doubleSpinBox_kp_roi1->value()/100.0));
02804         strings.append(QString::number(_ui->doubleSpinBox_kp_roi2->value()/100.0));
02805         strings.append(QString::number(_ui->doubleSpinBox_kp_roi3->value()/100.0));
02806         _ui->lineEdit_kp_roi->setText(strings.join(" "));
02807 }
02808 
02809 void PreferencesDialog::changeWorkingDirectory()
02810 {
02811         QString directory = QFileDialog::getExistingDirectory(this, tr("Working directory"), _ui->lineEdit_workingDirectory->text());
02812         if(!directory.isEmpty())
02813         {
02814                 ULOGGER_DEBUG("New working directory = %s", directory.toStdString().c_str());
02815                 _ui->lineEdit_workingDirectory->setText(directory);
02816         }
02817 }
02818 
02819 void PreferencesDialog::changeDictionaryPath()
02820 {
02821         QString path;
02822         if(_ui->lineEdit_dictionaryPath->text().isEmpty())
02823         {
02824                 path = QFileDialog::getOpenFileName(this, tr("Dictionary"), this->getWorkingDirectory());
02825         }
02826         else
02827         {
02828                 path = QFileDialog::getOpenFileName(this, tr("Dictionary"), _ui->lineEdit_dictionaryPath->text());
02829         }
02830         if(!path.isEmpty())
02831         {
02832                 _ui->lineEdit_dictionaryPath->setText(path);
02833         }
02834 }
02835 
02836 void PreferencesDialog::updateRGBDCameraGroupBoxVisibility()
02837 {
02838         _ui->groupBox_openni2->setVisible(_ui->comboBox_cameraRGBD->currentIndex() == kSrcOpenNI2-kSrcOpenNI_PCL);
02839         _ui->groupBox_freenect2->setVisible(_ui->comboBox_cameraRGBD->currentIndex() == kSrcFreenect2-kSrcOpenNI_PCL);
02840 }
02841 
02842 /*** GETTERS ***/
02843 //General
02844 int PreferencesDialog::getGeneralLoggerLevel() const
02845 {
02846         return _ui->comboBox_loggerLevel->currentIndex();
02847 }
02848 int PreferencesDialog::getGeneralLoggerEventLevel() const
02849 {
02850         return _ui->comboBox_loggerEventLevel->currentIndex();
02851 }
02852 int PreferencesDialog::getGeneralLoggerPauseLevel() const
02853 {
02854         return _ui->comboBox_loggerPauseLevel->currentIndex();
02855 }
02856 int PreferencesDialog::getGeneralLoggerType() const
02857 {
02858         return _ui->comboBox_loggerType->currentIndex();
02859 }
02860 bool PreferencesDialog::getGeneralLoggerPrintTime() const
02861 {
02862         return _ui->checkBox_logger_printTime->isChecked();
02863 }
02864 bool PreferencesDialog::isVerticalLayoutUsed() const
02865 {
02866         return _ui->checkBox_verticalLayoutUsed->isChecked();
02867 }
02868 bool PreferencesDialog::imageRejectedShown() const
02869 {
02870         return _ui->checkBox_imageRejectedShown->isChecked();
02871 }
02872 bool PreferencesDialog::imageHighestHypShown() const
02873 {
02874         return _ui->checkBox_imageHighestHypShown->isChecked();
02875 }
02876 bool PreferencesDialog::beepOnPause() const
02877 {
02878         return _ui->checkBox_beep->isChecked();
02879 }
02880 bool PreferencesDialog::notifyWhenNewGlobalPathIsReceived() const
02881 {
02882         return _ui->checkBox_notifyWhenNewGlobalPathIsReceived->isChecked();
02883 }
02884 int PreferencesDialog::getOdomQualityWarnThr() const
02885 {
02886         return _ui->spinBox_odomQualityWarnThr->value();
02887 }
02888 bool PreferencesDialog::isPosteriorGraphView() const
02889 {
02890         return _ui->checkBox_posteriorGraphView->isChecked();
02891 }
02892 
02893 bool PreferencesDialog::isCloudsShown(int index) const
02894 {
02895         UASSERT(index >= 0 && index <= 1);
02896         return _3dRenderingShowClouds[index]->isChecked();
02897 }
02898 bool PreferencesDialog::isGraphsShown() const
02899 {
02900         return _ui->checkBox_showGraphs->isChecked();
02901 }
02902 bool PreferencesDialog::isCloudMeshing() const
02903 {
02904         return _ui->checkBox_meshing->isChecked();
02905 }
02906 double PreferencesDialog::getCloudVoxelSize(int index) const
02907 {
02908         UASSERT(index >= 0 && index <= 1);
02909         return _3dRenderingVoxelSize[index]->value();
02910 }
02911 int PreferencesDialog::getCloudDecimation(int index) const
02912 {
02913         UASSERT(index >= 0 && index <= 1);
02914         return _3dRenderingDecimation[index]->value();
02915 }
02916 double PreferencesDialog::getCloudMaxDepth(int index) const
02917 {
02918         UASSERT(index >= 0 && index <= 1);
02919         return _3dRenderingMaxDepth[index]->value();
02920 }
02921 double PreferencesDialog::getCloudOpacity(int index) const
02922 {
02923         UASSERT(index >= 0 && index <= 1);
02924         return _3dRenderingOpacity[index]->value();
02925 }
02926 int PreferencesDialog::getCloudPointSize(int index) const
02927 {
02928         UASSERT(index >= 0 && index <= 1);
02929         return _3dRenderingPtSize[index]->value();
02930 }
02931 
02932 bool PreferencesDialog::isScansShown(int index) const
02933 {
02934         UASSERT(index >= 0 && index <= 1);
02935         return _3dRenderingShowScans[index]->isChecked();
02936 }
02937 double PreferencesDialog::getScanOpacity(int index) const
02938 {
02939         UASSERT(index >= 0 && index <= 1);
02940         return _3dRenderingOpacityScan[index]->value();
02941 }
02942 int PreferencesDialog::getScanPointSize(int index) const
02943 {
02944         UASSERT(index >= 0 && index <= 1);
02945         return _3dRenderingPtSizeScan[index]->value();
02946 }
02947 int PreferencesDialog::getMeshNormalKSearch() const
02948 {
02949         return _ui->spinBox_normalKSearch->value();
02950 }
02951 double PreferencesDialog::getMeshGP3Radius() const
02952 {
02953         return _ui->doubleSpinBox_gp3Radius->value();
02954 }
02955 bool PreferencesDialog::getMeshSmoothing() const
02956 {
02957         return _ui->checkBox_mls->isChecked();
02958 }
02959 double PreferencesDialog::getMeshSmoothingRadius() const
02960 {
02961         return _ui->doubleSpinBox_mlsRadius->value();
02962 }
02963 bool PreferencesDialog::isCloudFiltering() const
02964 {
02965         return _ui->groupBox_poseFiltering->isChecked();
02966 }
02967 double PreferencesDialog::getCloudFilteringRadius() const
02968 {
02969         return _ui->doubleSpinBox_cloudFilterRadius->value();
02970 }
02971 double PreferencesDialog::getCloudFilteringAngle() const
02972 {
02973         return _ui->doubleSpinBox_cloudFilterAngle->value();
02974 }
02975 bool PreferencesDialog::getGridMapShown() const
02976 {
02977         return _ui->checkBox_map_shown->isChecked();
02978 }
02979 double PreferencesDialog::getGridMapResolution() const
02980 {
02981         return _ui->doubleSpinBox_map_resolution->value();
02982 }
02983 bool PreferencesDialog::isGridMapFrom3DCloud() const
02984 {
02985         return _ui->checkBox_map_occupancyFrom3DCloud->isChecked();
02986 }
02987 bool PreferencesDialog::isGridMapEroded() const
02988 {
02989         return _ui->checkBox_map_erode->isChecked();
02990 }
02991 double PreferencesDialog::getGridMapOpacity() const
02992 {
02993         return _ui->doubleSpinBox_map_opacity->value();
02994 }
02995 
02996 
02997 // Source
02998 double PreferencesDialog::getGeneralInputRate() const
02999 {
03000         return _ui->general_doubleSpinBox_imgRate->value();
03001 }
03002 bool PreferencesDialog::isSourceMirroring() const
03003 {
03004         return _ui->source_mirroring->isChecked();
03005 }
03006 bool PreferencesDialog::isSourceImageUsed() const
03007 {
03008         return _ui->groupBox_sourceImage->isChecked();
03009 }
03010 bool PreferencesDialog::isSourceDatabaseUsed() const
03011 {
03012         return _ui->groupBox_sourceDatabase->isChecked();
03013 }
03014 bool PreferencesDialog::isSourceRGBDUsed() const
03015 {
03016         return _ui->groupBox_sourceOpenni->isChecked();
03017 }
03018 
03019 
03020 PreferencesDialog::Src PreferencesDialog::getSourceImageType() const
03021 {
03022         if(_ui->source_comboBox_image_type->currentIndex() == 1)
03023         {
03024                 return kSrcImages;
03025         }
03026         else if(_ui->source_comboBox_image_type->currentIndex() == 2)
03027         {
03028                 return kSrcVideo;
03029         }
03030         else
03031         {
03032                 return kSrcUsbDevice;
03033         }
03034 }
03035 QString PreferencesDialog::getSourceImageTypeStr() const
03036 {
03037         return _ui->source_comboBox_image_type->currentText();
03038 }
03039 int PreferencesDialog::getSourceWidth() const
03040 {
03041         return _ui->source_spinBox_imgWidth->value();
03042 }
03043 int PreferencesDialog::getSourceHeight() const
03044 {
03045         return _ui->source_spinBox_imgheight->value();
03046 }
03047 QString PreferencesDialog::getSourceImagesPath() const
03048 {
03049         return _ui->source_images_lineEdit_path->text();
03050 }
03051 int PreferencesDialog::getSourceImagesStartPos() const
03052 {
03053         return _ui->source_images_spinBox_startPos->value();
03054 }
03055 bool PreferencesDialog::getSourceImagesRefreshDir() const
03056 {
03057         return _ui->source_images_refreshDir->isChecked();
03058 }
03059 QString PreferencesDialog::getSourceVideoPath() const
03060 {
03061         return _ui->source_video_lineEdit_path->text();
03062 }
03063 int PreferencesDialog::getSourceUsbDeviceId() const
03064 {
03065         return _ui->source_usbDevice_spinBox_id->value();
03066 }
03067 QString PreferencesDialog::getSourceDatabasePath() const
03068 {
03069         return _ui->source_database_lineEdit_path->text();
03070 }
03071 bool PreferencesDialog::getSourceDatabaseOdometryIgnored() const
03072 {
03073         return _ui->source_checkBox_ignoreOdometry->isChecked();
03074 }
03075 bool PreferencesDialog::getSourceDatabaseGoalDelayIgnored() const
03076 {
03077         return _ui->source_checkBox_ignoreGoalDelay->isChecked();
03078 }
03079 int PreferencesDialog::getSourceDatabaseStartPos() const
03080 {
03081         return _ui->source_spinBox_databaseStartPos->value();
03082 }
03083 bool PreferencesDialog::getSourceDatabaseStampsUsed() const
03084 {
03085         return _ui->source_checkBox_useDbStamps->isChecked();
03086 }
03087 
03088 PreferencesDialog::Src PreferencesDialog::getSourceRGBD() const
03089 {
03090         return (PreferencesDialog::Src)(_ui->comboBox_cameraRGBD->currentIndex()+kSrcOpenNI_PCL);
03091 }
03092 bool PreferencesDialog::getSourceOpenni2AutoWhiteBalance() const
03093 {
03094         return _ui->openni2_autoWhiteBalance->isChecked();
03095 }
03096 bool PreferencesDialog::getSourceOpenni2AutoExposure() const
03097 {
03098         return _ui->openni2_autoExposure->isChecked();
03099 }
03100 int PreferencesDialog::getSourceOpenni2Exposure() const
03101 {
03102         return _ui->openni2_exposure->value();
03103 }
03104 int PreferencesDialog::getSourceOpenni2Gain() const
03105 {
03106         return _ui->openni2_gain->value();
03107 }
03108 bool PreferencesDialog::getSourceOpenni2Mirroring() const
03109 {
03110         return _ui->openni2_mirroring->isChecked();
03111 }
03112 int PreferencesDialog::getSourceFreenect2Format() const
03113 {
03114         return _ui->comboBox_freenect2Format->currentIndex();
03115 }
03116 
03117 bool PreferencesDialog::isSourceRGBDColorOnly() const
03118 {
03119         return _ui->checkbox_rgbd_colorOnly->isChecked();
03120 }
03121 QString PreferencesDialog::getSourceOpenniDevice() const
03122 {
03123         return _ui->lineEdit_openniDevice->text();
03124 }
03125 Transform PreferencesDialog::getSourceOpenniLocalTransform() const
03126 {
03127         Transform t = Transform::getIdentity();
03128         QString str = _ui->lineEdit_openniLocalTransform->text();
03129         str.replace("PI_2", QString::number(3.141592/2.0));
03130         QStringList list = str.split(' ');
03131         if(list.size() != 6)
03132         {
03133                 UERROR("Local transform is wrong! must have 6 items (%s)", str.toStdString().c_str());
03134         }
03135         else
03136         {
03137                 std::vector<float> numbers(6);
03138                 bool ok = false;
03139                 for(int i=0; i<list.size(); ++i)
03140                 {
03141                         numbers[i] = list.at(i).toDouble(&ok);
03142                         if(!ok)
03143                         {
03144                                 UERROR("Parsing local transform failed! \"%s\" not recognized (%s)",
03145                                                 list.at(i).toStdString().c_str(), str.toStdString().c_str());
03146                                 break;
03147                         }
03148                 }
03149                 if(ok)
03150                 {
03151                         t = Transform(numbers[0], numbers[1], numbers[2], numbers[3], numbers[4], numbers[5]);
03152                 }
03153         }
03154         return t;
03155 }
03156 
03157 CameraRGBD * PreferencesDialog::createCameraRGBD(bool forCalibration)
03158 {
03159         if(this->getSourceRGBD() == PreferencesDialog::kSrcOpenNI_PCL)
03160         {
03161                 if(forCalibration)
03162                 {
03163                         QMessageBox::warning(this, tr("Calibration"),
03164                                         tr("RTAB-Map calibration for \"OpenNI\" driver is not yet supported. "
03165                                             "Factory calibration loaded from OpenNI is used."), QMessageBox::Ok);
03166                         return 0;
03167                 }
03168                 else
03169                 {
03170                         return new CameraOpenni(
03171                                         this->getSourceOpenniDevice().toStdString(),
03172                                         this->getGeneralInputRate(),
03173                                         this->getSourceOpenniLocalTransform());
03174                 }
03175         }
03176         else if(this->getSourceRGBD() == PreferencesDialog::kSrcOpenNI2)
03177         {
03178                 if(forCalibration)
03179         {
03180                 QMessageBox::warning(this, tr("Calibration"),
03181                                 tr("RTAB-Map calibration for \"OpenNI2\" driver is not yet supported. "
03182                                         "Factory calibration loaded from OpenNI2 is used."), QMessageBox::Ok);
03183                 return 0;
03184         }
03185                 else
03186                 {
03187                         return new CameraOpenNI2(
03188                                         this->getSourceOpenniDevice().toStdString(),
03189                                         this->getGeneralInputRate(),
03190                                         this->getSourceOpenniLocalTransform());
03191                 }
03192         }
03193         else if(this->getSourceRGBD() == PreferencesDialog::kSrcFreenect)
03194         {
03195                 if(forCalibration)
03196                 {
03197                         QMessageBox::warning(this, tr("Calibration"),
03198                                         tr("RTAB-Map calibration for \"Freenect\" driver is not yet supported. "
03199                                                 "Factory calibration loaded from Freenect is used."), QMessageBox::Ok);
03200                         return 0;
03201                 }
03202                 else
03203                 {
03204                         return new CameraFreenect(
03205                                         this->getSourceOpenniDevice().isEmpty()?0:atoi(this->getSourceOpenniDevice().toStdString().c_str()),
03206                                         this->getGeneralInputRate(),
03207                                         this->getSourceOpenniLocalTransform());
03208                 }
03209         }
03210         else if(this->getSourceRGBD() == PreferencesDialog::kSrcOpenNI_CV ||
03211                         this->getSourceRGBD() == PreferencesDialog::kSrcOpenNI_CV_ASUS)
03212         {
03213                 if(forCalibration)
03214                 {
03215                         QMessageBox::warning(this, tr("Calibration"),
03216                                         tr("RTAB-Map calibration for \"OpenNI\" driver is not yet supported. "
03217                                                 "Factory calibration loaded from OpenNI is used."), QMessageBox::Ok);
03218                         return 0;
03219                 }
03220                 else
03221                 {
03222                         return new CameraOpenNICV(
03223                                         this->getSourceRGBD() == PreferencesDialog::kSrcOpenNI_CV_ASUS,
03224                                         this->getGeneralInputRate(),
03225                                         this->getSourceOpenniLocalTransform());
03226                 }
03227         }
03228         else if(this->getSourceRGBD() == kSrcFreenect2)
03229         {
03230                 return new CameraFreenect2(
03231                         this->getSourceOpenniDevice().isEmpty()?0:atoi(this->getSourceOpenniDevice().toStdString().c_str()),
03232                         forCalibration?CameraFreenect2::kTypeRGBIR:(CameraFreenect2::Type)getSourceFreenect2Format(),
03233                         this->getGeneralInputRate(),
03234                         this->getSourceOpenniLocalTransform());
03235         }
03236         else if(this->getSourceRGBD() == kSrcStereoDC1394)
03237         {
03238                 return new CameraStereoDC1394(
03239                         this->getGeneralInputRate(),
03240                         this->getSourceOpenniLocalTransform());
03241         }
03242         else if(this->getSourceRGBD() == kSrcStereoFlyCapture2)
03243         {
03244                 return new CameraStereoFlyCapture2(
03245                         this->getGeneralInputRate(),
03246                         this->getSourceOpenniLocalTransform());
03247         }
03248         else
03249         {
03250                 UFATAL("RGBD Source type undefined!");
03251         }
03252         return 0;
03253 }
03254 
03255 bool PreferencesDialog::isStatisticsPublished() const
03256 {
03257         return _ui->groupBox_publishing->isChecked();
03258 }
03259 double PreferencesDialog::getLoopThr() const
03260 {
03261         return _ui->general_doubleSpinBox_hardThr->value();
03262 }
03263 double PreferencesDialog::getVpThr() const
03264 {
03265         return _ui->general_doubleSpinBox_vp->value();
03266 }
03267 int PreferencesDialog::getOdomStrategy() const
03268 {
03269         return _ui->odom_strategy->currentIndex();
03270 }
03271 
03272 QString PreferencesDialog::getCameraInfoDir() const
03273 {
03274         return (this->getWorkingDirectory().isEmpty()?".":this->getWorkingDirectory())+"/camera_info";
03275 }
03276 
03277 bool PreferencesDialog::isImagesKept() const
03278 {
03279         return _ui->general_checkBox_imagesKept->isChecked();
03280 }
03281 float PreferencesDialog::getTimeLimit() const
03282 {
03283         return _ui->general_doubleSpinBox_timeThr->value();
03284 }
03285 float PreferencesDialog::getDetectionRate() const
03286 {
03287         return _ui->general_doubleSpinBox_detectionRate->value();
03288 }
03289 bool PreferencesDialog::isSLAMMode() const
03290 {
03291         return _ui->general_checkBox_SLAM_mode->isChecked();
03292 }
03293 
03294 /*** SETTERS ***/
03295 void PreferencesDialog::setInputRate(double value)
03296 {
03297         ULOGGER_DEBUG("imgRate=%2.2f", value);
03298         if(_ui->general_doubleSpinBox_imgRate->value() != value)
03299         {
03300                 _ui->general_doubleSpinBox_imgRate->setValue(value);
03301                 if(validateForm())
03302                 {
03303                         this->writeSettings(getTmpIniFilePath());
03304                 }
03305                 else
03306                 {
03307                         this->readSettingsBegin();
03308                 }
03309         }
03310 }
03311 
03312 void PreferencesDialog::setDetectionRate(double value)
03313 {
03314         ULOGGER_DEBUG("detectionRate=%2.2f", value);
03315         if(_ui->general_doubleSpinBox_detectionRate->value() != value)
03316         {
03317                 _ui->general_doubleSpinBox_detectionRate->setValue(value);
03318                 if(validateForm())
03319                 {
03320                         this->writeSettings(getTmpIniFilePath());
03321                 }
03322                 else
03323                 {
03324                         this->readSettingsBegin();
03325                 }
03326         }
03327 }
03328 
03329 void PreferencesDialog::setTimeLimit(float value)
03330 {
03331         ULOGGER_DEBUG("timeLimit=%fs", value);
03332         if(_ui->general_doubleSpinBox_timeThr->value() != value)
03333         {
03334                 _ui->general_doubleSpinBox_timeThr->setValue(value);
03335                 if(validateForm())
03336                 {
03337                         this->writeSettings(getTmpIniFilePath());
03338                 }
03339                 else
03340                 {
03341                         this->readSettingsBegin();
03342                 }
03343         }
03344 }
03345 
03346 void PreferencesDialog::setSLAMMode(bool enabled)
03347 {
03348         ULOGGER_DEBUG("slam mode=%s", enabled?"true":"false");
03349         if(_ui->general_checkBox_SLAM_mode->isChecked() != enabled)
03350         {
03351                 _ui->general_checkBox_SLAM_mode->setChecked(enabled);
03352                 if(validateForm())
03353                 {
03354                         this->writeSettings(getTmpIniFilePath());
03355                 }
03356                 else
03357                 {
03358                         this->readSettingsBegin();
03359                 }
03360         }
03361 }
03362 
03363 void PreferencesDialog::testOdometry()
03364 {
03365         testOdometry(_ui->odom_type->currentIndex());
03366 }
03367 
03368 void PreferencesDialog::testOdometry(int type)
03369 {
03370         CameraRGBD * camera = this->createCameraRGBD();
03371 
03372         if(camera == 0 || !camera->init(this->getCameraInfoDir().toStdString()))
03373         {
03374                 QMessageBox::warning(this,
03375                            tr("RTAB-Map"),
03376                            tr("RGBD camera initialization failed!"));
03377                 if(camera)
03378                 {
03379                         delete camera;
03380                 }
03381                 return;
03382         }
03383         else if(dynamic_cast<CameraOpenNI2*>(camera) != 0)
03384         {
03385                 ((CameraOpenNI2*)camera)->setAutoWhiteBalance(getSourceOpenni2AutoWhiteBalance());
03386                 ((CameraOpenNI2*)camera)->setAutoExposure(getSourceOpenni2AutoExposure());
03387                 ((CameraOpenNI2*)camera)->setMirroring(getSourceOpenni2Mirroring());
03388                 if(CameraOpenNI2::exposureGainAvailable())
03389                 {
03390                         ((CameraOpenNI2*)camera)->setExposure(getSourceOpenni2Exposure());
03391                         ((CameraOpenNI2*)camera)->setGain(getSourceOpenni2Gain());
03392                 }
03393         }
03394         camera->setMirroringEnabled(isSourceMirroring());
03395         camera->setColorOnly(isSourceRGBDColorOnly());
03396 
03397         ParametersMap parameters = this->getAllParameters();
03398         Odometry * odometry;
03399         if(this->getOdomStrategy() == 1)
03400         {
03401                 odometry = new OdometryOpticalFlow(parameters);
03402         }
03403         else if(this->getOdomStrategy() == 2)
03404         {
03405                 odometry = new OdometryMono(parameters);
03406         }
03407         else
03408         {
03409                 odometry = new OdometryBOW(parameters);
03410         }
03411 
03412         OdometryThread odomThread(odometry); // take ownership of odometry
03413         odomThread.registerToEventsManager();
03414 
03415         OdometryViewer * odomViewer = new OdometryViewer(10,
03416                                         _ui->spinBox_decimation_odom->value(),
03417                                         _ui->doubleSpinBox_voxelSize_odom->value(),
03418                                         this->getOdomQualityWarnThr(),
03419                                         this);
03420         odomViewer->setWindowTitle(tr("Odometry viewer"));
03421         odomViewer->resize(1280, 480+QPushButton().minimumHeight());
03422         odomViewer->registerToEventsManager();
03423 
03424         CameraThread cameraThread(camera); // take ownership of camera
03425         UEventsManager::createPipe(&cameraThread, &odomThread, "CameraEvent");
03426         UEventsManager::createPipe(&odomThread, odomViewer, "OdometryEvent");
03427 
03428         odomThread.start();
03429         cameraThread.start();
03430 
03431         odomViewer->exec();
03432         delete odomViewer;
03433 
03434         cameraThread.join(true);
03435         odomThread.join(true);
03436 }
03437 
03438 void PreferencesDialog::testRGBDCamera()
03439 {
03440         CameraRGBD * camera = this->createCameraRGBD();
03441         if(camera == 0 || !camera->init(this->getCameraInfoDir().toStdString()))
03442         {
03443                 QMessageBox::warning(this,
03444                            tr("RTAB-Map"),
03445                            tr("RGBD camera initialization failed!"));
03446                 if(camera)
03447                 {
03448                         delete camera;
03449                 }
03450                 return;
03451         }
03452         else if(dynamic_cast<CameraOpenNI2*>(camera) != 0)
03453         {
03454                 ((CameraOpenNI2*)camera)->setAutoWhiteBalance(getSourceOpenni2AutoWhiteBalance());
03455                 ((CameraOpenNI2*)camera)->setAutoExposure(getSourceOpenni2AutoExposure());
03456                 ((CameraOpenNI2*)camera)->setMirroring(getSourceOpenni2Mirroring());
03457                 if(CameraOpenNI2::exposureGainAvailable())
03458                 {
03459                         ((CameraOpenNI2*)camera)->setExposure(getSourceOpenni2Exposure());
03460                         ((CameraOpenNI2*)camera)->setGain(getSourceOpenni2Gain());
03461                 }
03462         }
03463         camera->setMirroringEnabled(isSourceMirroring());
03464 
03465         // Create DataRecorder without init it, just to show images...
03466         CameraViewer * window = new CameraViewer(this);
03467         window->setWindowTitle(tr("RGBD camera viewer"));
03468         window->resize(1280, 480+QPushButton().minimumHeight());
03469         window->registerToEventsManager();
03470 
03471         CameraThread cameraThread(camera);
03472         UEventsManager::createPipe(&cameraThread, window, "CameraEvent");
03473 
03474         cameraThread.start();
03475         window->exec();
03476         delete window;
03477         cameraThread.join(true);
03478 }
03479 
03480 void PreferencesDialog::calibrate()
03481 {
03482         CameraRGBD * camera = this->createCameraRGBD(true);
03483         if(camera == 0 || !camera->init("")) // don't set calibration folder to use raw images
03484         {
03485                 if(camera != 0)
03486                 {
03487                         QMessageBox::warning(this,
03488                                    tr("RTAB-Map"),
03489                                    tr("RGBD camera initialization failed!"));
03490                 }
03491                 //else already warned
03492 
03493                 if(camera)
03494                 {
03495                         delete camera;
03496                 }
03497                 return;
03498         }
03499         else if(dynamic_cast<CameraOpenNI2*>(camera) != 0)
03500         {
03501                 ((CameraOpenNI2*)camera)->setAutoWhiteBalance(getSourceOpenni2AutoWhiteBalance());
03502                 ((CameraOpenNI2*)camera)->setAutoExposure(getSourceOpenni2AutoExposure());
03503                 ((CameraOpenNI2*)camera)->setMirroring(getSourceOpenni2Mirroring());
03504                 if(CameraOpenNI2::exposureGainAvailable())
03505                 {
03506                         ((CameraOpenNI2*)camera)->setExposure(getSourceOpenni2Exposure());
03507                         ((CameraOpenNI2*)camera)->setGain(getSourceOpenni2Gain());
03508                 }
03509         }
03510         camera->setMirroringEnabled(isSourceMirroring());
03511 
03512 
03513         if(!this->getCameraInfoDir().isEmpty())
03514         {
03515                 QDir dir(this->getCameraInfoDir());
03516                 if (!dir.exists())
03517                 {
03518                         UINFO("Creating camera_info directory: \"%s\"", this->getCameraInfoDir().toStdString().c_str());
03519                         if(!dir.mkpath(this->getCameraInfoDir()))
03520                         {
03521                                 UWARN("Could create camera_info directory: \"%s\"", this->getCameraInfoDir().toStdString().c_str());
03522                         }
03523                 }
03524         }
03525         _calibrationDialog->setStereoMode(true);
03526         _calibrationDialog->setSwitchedImages(dynamic_cast<CameraFreenect2*>(camera) != 0);
03527         _calibrationDialog->setSavingDirectory(this->getCameraInfoDir());
03528         _calibrationDialog->registerToEventsManager();
03529 
03530         CameraThread cameraThread(camera);
03531         UEventsManager::createPipe(&cameraThread, _calibrationDialog, "CameraEvent");
03532 
03533         cameraThread.start();
03534 
03535         _calibrationDialog->exec();
03536         _calibrationDialog->unregisterFromEventsManager();
03537 
03538         cameraThread.join(true);
03539 }
03540 
03541 }


rtabmap
Author(s): Mathieu Labbe
autogenerated on Fri Aug 28 2015 12:51:32