00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028 #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 <QInputDialog>
00039 #include <QMessageBox>
00040 #include <QtGui/QStandardItemModel>
00041 #include <QMainWindow>
00042 #include <QProgressDialog>
00043 #include <QScrollBar>
00044 #include <QStatusBar>
00045 #include <QtGui/QCloseEvent>
00046
00047 #include "ui_preferencesDialog.h"
00048
00049 #include "rtabmap/core/Version.h"
00050 #include "rtabmap/core/Rtabmap.h"
00051 #include "rtabmap/core/Parameters.h"
00052 #include "rtabmap/core/Odometry.h"
00053 #include "rtabmap/core/OdometryThread.h"
00054 #include "rtabmap/core/CameraRGBD.h"
00055 #include "rtabmap/core/CameraThread.h"
00056 #include "rtabmap/core/CameraRGB.h"
00057 #include "rtabmap/core/CameraStereo.h"
00058 #include "rtabmap/core/Memory.h"
00059 #include "rtabmap/core/VWDictionary.h"
00060 #include "rtabmap/core/Optimizer.h"
00061 #include "rtabmap/core/OptimizerG2O.h"
00062 #include "rtabmap/core/DBReader.h"
00063
00064 #include "rtabmap/gui/LoopClosureViewer.h"
00065 #include "rtabmap/gui/CameraViewer.h"
00066 #include "rtabmap/gui/CloudViewer.h"
00067 #include "rtabmap/gui/ImageView.h"
00068 #include "rtabmap/gui/GraphViewer.h"
00069 #include "ExportCloudsDialog.h"
00070 #include "ExportScansDialog.h"
00071 #include "PostProcessingDialog.h"
00072 #include "CreateSimpleCalibrationDialog.h"
00073
00074 #include <rtabmap/utilite/ULogger.h>
00075 #include <rtabmap/utilite/UConversion.h>
00076 #include <rtabmap/utilite/UStl.h>
00077 #include <rtabmap/utilite/UEventsManager.h>
00078 #include "rtabmap/utilite/UPlot.h"
00079
00080 #include <opencv2/opencv_modules.hpp>
00081 #if CV_MAJOR_VERSION < 3
00082 #ifdef HAVE_OPENCV_GPU
00083 #include <opencv2/gpu/gpu.hpp>
00084 #endif
00085 #else
00086 #ifdef HAVE_OPENCV_CUDAFEATURES2D
00087 #include <opencv2/core/cuda.hpp>
00088 #endif
00089 #endif
00090
00091 using namespace rtabmap;
00092
00093 namespace rtabmap {
00094
00095 PreferencesDialog::PreferencesDialog(QWidget * parent) :
00096 QDialog(parent),
00097 _obsoletePanels(kPanelDummy),
00098 _ui(0),
00099 _indexModel(0),
00100 _initialized(false),
00101 _progressDialog(new QProgressDialog(this)),
00102 _calibrationDialog(new CalibrationDialog(false, ".", this)),
00103 _createCalibrationDialog(new CreateSimpleCalibrationDialog(".", "", this))
00104 {
00105 ULOGGER_DEBUG("");
00106 _calibrationDialog->setWindowFlags(Qt::Window);
00107 _calibrationDialog->setWindowTitle(tr("Calibration"));
00108
00109 _progressDialog->setWindowTitle(tr("Read parameters..."));
00110 _progressDialog->setMaximum(2);
00111 _progressDialog->setValue(2);
00112
00113 _ui = new Ui_preferencesDialog();
00114 _ui->setupUi(this);
00115
00116 bool haveCuda = false;
00117 #if CV_MAJOR_VERSION < 3
00118 #ifdef HAVE_OPENCV_GPU
00119 haveCuda = cv::gpu::getCudaEnabledDeviceCount() != 0;
00120 #endif
00121 #else
00122 #ifdef HAVE_OPENCV_CUDAFEATURES2D
00123 haveCuda = cv::cuda::getCudaEnabledDeviceCount() != 0;
00124 #endif
00125 #endif
00126 if(!haveCuda)
00127 {
00128 _ui->surf_checkBox_gpuVersion->setChecked(false);
00129 _ui->surf_checkBox_gpuVersion->setEnabled(false);
00130 _ui->label_surf_checkBox_gpuVersion->setEnabled(false);
00131 _ui->surf_doubleSpinBox_gpuKeypointsRatio->setEnabled(false);
00132 _ui->label_surf_checkBox_gpuKeypointsRatio->setEnabled(false);
00133
00134 _ui->fastGpu->setChecked(false);
00135 _ui->fastGpu->setEnabled(false);
00136 _ui->label_fastGPU->setEnabled(false);
00137 _ui->fastKeypointRatio->setEnabled(false);
00138 _ui->label_fastGPUKptRatio->setEnabled(false);
00139
00140 _ui->checkBox_ORBGpu->setChecked(false);
00141 _ui->checkBox_ORBGpu->setEnabled(false);
00142 _ui->label_orbGpu->setEnabled(false);
00143
00144
00145 _ui->comboBox_dictionary_strategy->removeItem(4);
00146 _ui->reextract_nn->removeItem(4);
00147 }
00148
00149 #if PCL_VERSION_COMPARE(<, 1, 7, 2)
00150 _ui->checkBox_map_shown->setChecked(false);
00151 _ui->checkBox_map_shown->setEnabled(false);
00152 _ui->label_map_shown->setText(_ui->label_map_shown->text() + " (Disabled, PCL >=1.7.2 required)");
00153 _ui->label_map_shown->setEnabled(false);
00154 #endif
00155
00156 #ifndef RTABMAP_OCTOMAP
00157 _ui->groupBox_octomap->setChecked(false);
00158 _ui->groupBox_octomap->setEnabled(false);
00159 #endif
00160
00161 #ifndef RTABMAP_NONFREE
00162 _ui->comboBox_detector_strategy->setItemData(0, 0, Qt::UserRole - 1);
00163 _ui->comboBox_detector_strategy->setItemData(1, 0, Qt::UserRole - 1);
00164 _ui->reextract_type->setItemData(0, 0, Qt::UserRole - 1);
00165 _ui->reextract_type->setItemData(1, 0, Qt::UserRole - 1);
00166
00167 _ui->comboBox_dictionary_strategy->setItemData(1, 0, Qt::UserRole - 1);
00168 _ui->reextract_nn->setItemData(1, 0, Qt::UserRole - 1);
00169
00170 #if CV_MAJOR_VERSION == 3
00171 _ui->comboBox_detector_strategy->setItemData(0, 0, Qt::UserRole - 1);
00172 _ui->comboBox_detector_strategy->setItemData(1, 0, Qt::UserRole - 1);
00173 _ui->comboBox_detector_strategy->setItemData(3, 0, Qt::UserRole - 1);
00174 _ui->comboBox_detector_strategy->setItemData(4, 0, Qt::UserRole - 1);
00175 _ui->comboBox_detector_strategy->setItemData(5, 0, Qt::UserRole - 1);
00176 _ui->comboBox_detector_strategy->setItemData(6, 0, Qt::UserRole - 1);
00177 _ui->reextract_type->setItemData(0, 0, Qt::UserRole - 1);
00178 _ui->reextract_type->setItemData(1, 0, Qt::UserRole - 1);
00179 _ui->reextract_type->setItemData(3, 0, Qt::UserRole - 1);
00180 _ui->reextract_type->setItemData(4, 0, Qt::UserRole - 1);
00181 _ui->reextract_type->setItemData(5, 0, Qt::UserRole - 1);
00182 _ui->reextract_type->setItemData(6, 0, Qt::UserRole - 1);
00183 #endif
00184 #endif
00185
00186 #if CV_MAJOR_VERSION == 3
00187 _ui->groupBox_fast_opencv2->setEnabled(false);
00188 #endif
00189
00190 _ui->comboBox_cameraImages_gtFormat->setItemData(4, 0, Qt::UserRole - 1);
00191 if(!Optimizer::isAvailable(Optimizer::kTypeG2O))
00192 {
00193 _ui->graphOptimization_type->setItemData(1, 0, Qt::UserRole - 1);
00194 }
00195 if(!OptimizerG2O::isCSparseAvailable())
00196 {
00197 _ui->comboBox_g2o_solver->setItemData(0, 0, Qt::UserRole - 1);
00198 }
00199 if(!OptimizerG2O::isCholmodAvailable())
00200 {
00201 _ui->comboBox_g2o_solver->setItemData(2, 0, Qt::UserRole - 1);
00202 }
00203 if(!Optimizer::isAvailable(Optimizer::kTypeTORO))
00204 {
00205 _ui->graphOptimization_type->setItemData(0, 0, Qt::UserRole - 1);
00206 }
00207 if(!Optimizer::isAvailable(Optimizer::kTypeGTSAM))
00208 {
00209 _ui->graphOptimization_type->setItemData(2, 0, Qt::UserRole - 1);
00210 }
00211 #ifdef RTABMAP_VERTIGO
00212 if(!Optimizer::isAvailable(Optimizer::kTypeG2O) && !Optimizer::isAvailable(Optimizer::kTypeGTSAM))
00213 #endif
00214 {
00215 _ui->graphOptimization_robust->setEnabled(false);
00216 }
00217 if(!CameraOpenni::available())
00218 {
00219 _ui->comboBox_cameraRGBD->setItemData(0, 0, Qt::UserRole - 1);
00220 }
00221 if(!CameraFreenect::available())
00222 {
00223 _ui->comboBox_cameraRGBD->setItemData(1, 0, Qt::UserRole - 1);
00224 }
00225 if(!CameraOpenNICV::available())
00226 {
00227 _ui->comboBox_cameraRGBD->setItemData(2, 0, Qt::UserRole - 1);
00228 _ui->comboBox_cameraRGBD->setItemData(3, 0, Qt::UserRole - 1);
00229 }
00230 if(!CameraOpenNI2::available())
00231 {
00232 _ui->comboBox_cameraRGBD->setItemData(4, 0, Qt::UserRole - 1);
00233 }
00234 if(!CameraFreenect2::available())
00235 {
00236 _ui->comboBox_cameraRGBD->setItemData(5, 0, Qt::UserRole - 1);
00237 }
00238 if(!CameraStereoDC1394::available())
00239 {
00240 _ui->comboBox_cameraStereo->setItemData(0, 0, Qt::UserRole - 1);
00241 }
00242 if(!CameraStereoFlyCapture2::available())
00243 {
00244 _ui->comboBox_cameraStereo->setItemData(1, 0, Qt::UserRole - 1);
00245 }
00246 if (!CameraStereoZed::available())
00247 {
00248 _ui->comboBox_cameraRGBD->setItemData(7, 0, Qt::UserRole - 1);
00249 _ui->comboBox_cameraStereo->setItemData(4, 0, Qt::UserRole - 1);
00250 }
00251 _ui->openni2_exposure->setEnabled(CameraOpenNI2::exposureGainAvailable());
00252 _ui->openni2_gain->setEnabled(CameraOpenNI2::exposureGainAvailable());
00253
00254
00255 connect(_ui->comboBox_sourceType, SIGNAL(currentIndexChanged(int)), this, SLOT(updateSourceGrpVisibility()));
00256 connect(_ui->comboBox_cameraRGBD, SIGNAL(currentIndexChanged(int)), this, SLOT(updateSourceGrpVisibility()));
00257 connect(_ui->source_comboBox_image_type, SIGNAL(currentIndexChanged(int)), this, SLOT(updateSourceGrpVisibility()));
00258 connect(_ui->comboBox_cameraStereo, SIGNAL(currentIndexChanged(int)), this, SLOT(updateSourceGrpVisibility()));
00259 this->resetSettings(_ui->groupBox_source0);
00260
00261 _ui->predictionPlot->showLegend(false);
00262
00263 QButtonGroup * buttonGroup = new QButtonGroup(this);
00264 buttonGroup->addButton(_ui->radioButton_basic);
00265 buttonGroup->addButton(_ui->radioButton_advanced);
00266
00267
00268 connect(_ui->buttonBox_global, SIGNAL(clicked(QAbstractButton *)), this, SLOT(closeDialog(QAbstractButton *)));
00269 connect(_ui->buttonBox_local, SIGNAL(clicked(QAbstractButton *)), this, SLOT(resetApply(QAbstractButton *)));
00270 connect(_ui->pushButton_loadConfig, SIGNAL(clicked()), this, SLOT(loadConfigFrom()));
00271 connect(_ui->pushButton_saveConfig, SIGNAL(clicked()), this, SLOT(saveConfigTo()));
00272 connect(_ui->pushButton_resetConfig, SIGNAL(clicked()), this, SLOT(resetConfig()));
00273 connect(_ui->radioButton_basic, SIGNAL(toggled(bool)), this, SLOT(setupTreeView()));
00274 connect(_ui->pushButton_testOdometry, SIGNAL(clicked()), this, SLOT(testOdometry()));
00275 connect(_ui->pushButton_test_camera, SIGNAL(clicked()), this, SLOT(testCamera()));
00276
00277
00278 connect(_ui->general_checkBox_imagesKept, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteGeneralPanel()));
00279 connect(_ui->general_checkBox_cloudsKept, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteGeneralPanel()));
00280 connect(_ui->checkBox_verticalLayoutUsed, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteGeneralPanel()));
00281 connect(_ui->checkBox_imageRejectedShown, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteGeneralPanel()));
00282 connect(_ui->checkBox_imageHighestHypShown, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteGeneralPanel()));
00283 connect(_ui->checkBox_beep, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteGeneralPanel()));
00284 connect(_ui->checkBox_stamps, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteGeneralPanel()));
00285 connect(_ui->checkBox_notifyWhenNewGlobalPathIsReceived, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteGeneralPanel()));
00286 connect(_ui->spinBox_odomQualityWarnThr, SIGNAL(valueChanged(int)), this, SLOT(makeObsoleteGeneralPanel()));
00287 connect(_ui->checkBox_posteriorGraphView, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteGeneralPanel()));
00288
00289
00290 _3dRenderingShowClouds.resize(2);
00291 _3dRenderingShowClouds[0] = _ui->checkBox_showClouds;
00292 _3dRenderingShowClouds[1] = _ui->checkBox_showOdomClouds;
00293
00294 _3dRenderingDecimation.resize(2);
00295 _3dRenderingDecimation[0] = _ui->spinBox_decimation;
00296 _3dRenderingDecimation[1] = _ui->spinBox_decimation_odom;
00297
00298 _3dRenderingMaxDepth.resize(2);
00299 _3dRenderingMaxDepth[0] = _ui->doubleSpinBox_maxDepth;
00300 _3dRenderingMaxDepth[1] = _ui->doubleSpinBox_maxDepth_odom;
00301
00302 _3dRenderingMinDepth.resize(2);
00303 _3dRenderingMinDepth[0] = _ui->doubleSpinBox_minDepth;
00304 _3dRenderingMinDepth[1] = _ui->doubleSpinBox_minDepth_odom;
00305
00306 _3dRenderingOpacity.resize(2);
00307 _3dRenderingOpacity[0] = _ui->doubleSpinBox_opacity;
00308 _3dRenderingOpacity[1] = _ui->doubleSpinBox_opacity_odom;
00309
00310 _3dRenderingPtSize.resize(2);
00311 _3dRenderingPtSize[0] = _ui->spinBox_ptsize;
00312 _3dRenderingPtSize[1] = _ui->spinBox_ptsize_odom;
00313
00314 _3dRenderingShowScans.resize(2);
00315 _3dRenderingShowScans[0] = _ui->checkBox_showScans;
00316 _3dRenderingShowScans[1] = _ui->checkBox_showOdomScans;
00317
00318 _3dRenderingDownsamplingScan.resize(2);
00319 _3dRenderingDownsamplingScan[0] = _ui->spinBox_downsamplingScan;
00320 _3dRenderingDownsamplingScan[1] = _ui->spinBox_downsamplingScan_odom;
00321
00322 _3dRenderingVoxelSizeScan.resize(2);
00323 _3dRenderingVoxelSizeScan[0] = _ui->doubleSpinBox_voxelSizeScan;
00324 _3dRenderingVoxelSizeScan[1] = _ui->doubleSpinBox_voxelSizeScan_odom;
00325
00326 _3dRenderingOpacityScan.resize(2);
00327 _3dRenderingOpacityScan[0] = _ui->doubleSpinBox_opacity_scan;
00328 _3dRenderingOpacityScan[1] = _ui->doubleSpinBox_opacity_odom_scan;
00329
00330 _3dRenderingPtSizeScan.resize(2);
00331 _3dRenderingPtSizeScan[0] = _ui->spinBox_ptsize_scan;
00332 _3dRenderingPtSizeScan[1] = _ui->spinBox_ptsize_odom_scan;
00333
00334 _3dRenderingShowFeatures.resize(2);
00335 _3dRenderingShowFeatures[0] = _ui->checkBox_showFeatures;
00336 _3dRenderingShowFeatures[1] = _ui->checkBox_showOdomFeatures;
00337
00338 _3dRenderingPtSizeFeatures.resize(2);
00339 _3dRenderingPtSizeFeatures[0] = _ui->spinBox_ptsize_features;
00340 _3dRenderingPtSizeFeatures[1] = _ui->spinBox_ptsize_odom_features;
00341
00342 for(int i=0; i<2; ++i)
00343 {
00344 connect(_3dRenderingShowClouds[i], SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteCloudRenderingPanel()));
00345 connect(_3dRenderingDecimation[i], SIGNAL(valueChanged(int)), this, SLOT(makeObsoleteCloudRenderingPanel()));
00346 connect(_3dRenderingMaxDepth[i], SIGNAL(valueChanged(double)), this, SLOT(makeObsoleteCloudRenderingPanel()));
00347 connect(_3dRenderingMinDepth[i], SIGNAL(valueChanged(double)), this, SLOT(makeObsoleteCloudRenderingPanel()));
00348 connect(_3dRenderingShowScans[i], SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteCloudRenderingPanel()));
00349 connect(_3dRenderingShowFeatures[i], SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteCloudRenderingPanel()));
00350
00351 connect(_3dRenderingDownsamplingScan[i], SIGNAL(valueChanged(int)), this, SLOT(makeObsoleteCloudRenderingPanel()));
00352 connect(_3dRenderingVoxelSizeScan[i], SIGNAL(valueChanged(double)), this, SLOT(makeObsoleteCloudRenderingPanel()));
00353 connect(_3dRenderingOpacity[i], SIGNAL(valueChanged(double)), this, SLOT(makeObsoleteCloudRenderingPanel()));
00354 connect(_3dRenderingPtSize[i], SIGNAL(valueChanged(int)), this, SLOT(makeObsoleteCloudRenderingPanel()));
00355 connect(_3dRenderingOpacityScan[i], SIGNAL(valueChanged(double)), this, SLOT(makeObsoleteCloudRenderingPanel()));
00356 connect(_3dRenderingPtSizeScan[i], SIGNAL(valueChanged(int)), this, SLOT(makeObsoleteCloudRenderingPanel()));
00357 connect(_3dRenderingPtSizeFeatures[i], SIGNAL(valueChanged(int)), this, SLOT(makeObsoleteCloudRenderingPanel()));
00358 }
00359 connect(_ui->doubleSpinBox_voxel, SIGNAL(valueChanged(double)), this, SLOT(makeObsoleteCloudRenderingPanel()));
00360 connect(_ui->doubleSpinBox_noiseRadius, SIGNAL(valueChanged(double)), this, SLOT(makeObsoleteCloudRenderingPanel()));
00361 connect(_ui->spinBox_noiseMinNeighbors, SIGNAL(valueChanged(int)), this, SLOT(makeObsoleteCloudRenderingPanel()));
00362
00363 connect(_ui->checkBox_showGraphs, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteCloudRenderingPanel()));
00364 connect(_ui->checkBox_showLabels, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteCloudRenderingPanel()));
00365
00366 connect(_ui->radioButton_noFiltering, SIGNAL(toggled(bool)), this, SLOT(makeObsoleteCloudRenderingPanel()));
00367 connect(_ui->radioButton_nodeFiltering, SIGNAL(toggled(bool)), this, SLOT(makeObsoleteCloudRenderingPanel()));
00368 connect(_ui->radioButton_subtractFiltering, SIGNAL(toggled(bool)), this, SLOT(makeObsoleteCloudRenderingPanel()));
00369 connect(_ui->doubleSpinBox_cloudFilterRadius, SIGNAL(valueChanged(double)), this, SLOT(makeObsoleteCloudRenderingPanel()));
00370 connect(_ui->doubleSpinBox_cloudFilterAngle, SIGNAL(valueChanged(double)), this, SLOT(makeObsoleteCloudRenderingPanel()));
00371 connect(_ui->spinBox_subtractFilteringMinPts, SIGNAL(valueChanged(int)), this, SLOT(makeObsoleteCloudRenderingPanel()));
00372 connect(_ui->doubleSpinBox_subtractFilteringRadius, SIGNAL(valueChanged(double)), this, SLOT(makeObsoleteCloudRenderingPanel()));
00373 connect(_ui->doubleSpinBox_subtractFilteringAngle, SIGNAL(valueChanged(double)), this, SLOT(makeObsoleteCloudRenderingPanel()));
00374 connect(_ui->spinBox_normalKSearch, SIGNAL(valueChanged(int)), this, SLOT(makeObsoleteCloudRenderingPanel()));
00375
00376 connect(_ui->checkBox_map_shown, SIGNAL(clicked(bool)), this, SLOT(makeObsoleteCloudRenderingPanel()));
00377 connect(_ui->doubleSpinBox_map_resolution, SIGNAL(valueChanged(double)), this, SLOT(makeObsoleteCloudRenderingPanel()));
00378 connect(_ui->doubleSpinBox_map_opacity, SIGNAL(valueChanged(double)), this, SLOT(makeObsoleteCloudRenderingPanel()));
00379 connect(_ui->checkBox_map_erode, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteCloudRenderingPanel()));
00380 connect(_ui->groupBox_map_occupancyFrom3DCloud, SIGNAL(toggled(bool)), this, SLOT(makeObsoleteCloudRenderingPanel()));
00381 connect(_ui->checkBox_projMapFrame, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteCloudRenderingPanel()));
00382 connect(_ui->doubleSpinBox_projMaxGroundAngle, SIGNAL(valueChanged(double)), this, SLOT(makeObsoleteCloudRenderingPanel()));
00383 connect(_ui->doubleSpinBox_projMaxGroundHeight, SIGNAL(valueChanged(double)), this, SLOT(makeObsoleteCloudRenderingPanel()));
00384 connect(_ui->spinBox_projMinClusterSize, SIGNAL(valueChanged(int)), this, SLOT(makeObsoleteCloudRenderingPanel()));
00385 connect(_ui->doubleSpinBox_projMaxObstaclesHeight, SIGNAL(valueChanged(double)), this, SLOT(makeObsoleteCloudRenderingPanel()));
00386 connect(_ui->checkBox_projFlatObstaclesDetected, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteCloudRenderingPanel()));
00387
00388 connect(_ui->groupBox_octomap, SIGNAL(toggled(bool)), this, SLOT(makeObsoleteCloudRenderingPanel()));
00389 connect(_ui->spinBox_octomap_treeDepth, SIGNAL(valueChanged(int)), this, SLOT(makeObsoleteCloudRenderingPanel()));
00390 connect(_ui->checkBox_octomap_groundObstacle, SIGNAL(clicked(bool)), this, SLOT(makeObsoleteCloudRenderingPanel()));
00391
00392 connect(_ui->groupBox_organized, SIGNAL(toggled(bool)), this, SLOT(makeObsoleteCloudRenderingPanel()));
00393 connect(_ui->doubleSpinBox_mesh_angleTolerance, SIGNAL(valueChanged(double)), this, SLOT(makeObsoleteCloudRenderingPanel()));
00394 connect(_ui->checkBox_mesh_quad, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteCloudRenderingPanel()));
00395 connect(_ui->spinBox_mesh_triangleSize, SIGNAL(valueChanged(int)), this, SLOT(makeObsoleteCloudRenderingPanel()));
00396
00397
00398 connect(_ui->comboBox_loggerLevel, SIGNAL(currentIndexChanged(int)), this, SLOT(makeObsoleteLoggingPanel()));
00399 connect(_ui->comboBox_loggerEventLevel, SIGNAL(currentIndexChanged(int)), this, SLOT(makeObsoleteLoggingPanel()));
00400 connect(_ui->comboBox_loggerPauseLevel, SIGNAL(currentIndexChanged(int)), this, SLOT(makeObsoleteLoggingPanel()));
00401 connect(_ui->checkBox_logger_printTime, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteLoggingPanel()));
00402 connect(_ui->checkBox_logger_printThreadId, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteLoggingPanel()));
00403 connect(_ui->comboBox_loggerType, SIGNAL(currentIndexChanged(int)), this, SLOT(makeObsoleteLoggingPanel()));
00404
00405
00406 connect(_ui->general_doubleSpinBox_imgRate, SIGNAL(valueChanged(double)), this, SLOT(makeObsoleteSourcePanel()));
00407 connect(_ui->source_mirroring, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
00408 connect(_ui->toolButton_source_path_calibration, SIGNAL(clicked()), this, SLOT(selectCalibrationPath()));
00409 connect(_ui->lineEdit_calibrationFile, SIGNAL(textChanged(const QString &)), this, SLOT(makeObsoleteSourcePanel()));
00410 _ui->stackedWidget_src->setCurrentIndex(_ui->comboBox_sourceType->currentIndex());
00411 connect(_ui->comboBox_sourceType, SIGNAL(currentIndexChanged(int)), _ui->stackedWidget_src, SLOT(setCurrentIndex(int)));
00412 connect(_ui->comboBox_sourceType, SIGNAL(currentIndexChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
00413 connect(_ui->lineEdit_sourceDevice, SIGNAL(textChanged(const QString &)), this, SLOT(makeObsoleteSourcePanel()));
00414 connect(_ui->lineEdit_sourceLocalTransform, SIGNAL(textChanged(const QString &)), this, SLOT(makeObsoleteSourcePanel()));
00415
00416
00417 _ui->stackedWidget_image->setCurrentIndex(_ui->source_comboBox_image_type->currentIndex());
00418 connect(_ui->source_comboBox_image_type, SIGNAL(currentIndexChanged(int)), _ui->stackedWidget_image, SLOT(setCurrentIndex(int)));
00419 connect(_ui->source_comboBox_image_type, SIGNAL(currentIndexChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
00420
00421 connect(_ui->source_images_toolButton_selectSource, SIGNAL(clicked()), this, SLOT(selectSourceImagesPath()));
00422 connect(_ui->source_images_lineEdit_path, SIGNAL(textChanged(const QString &)), this, SLOT(makeObsoleteSourcePanel()));
00423 connect(_ui->source_images_spinBox_startPos, SIGNAL(valueChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
00424 connect(_ui->source_images_refreshDir, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
00425 connect(_ui->checkBox_rgbImages_rectify, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
00426 connect(_ui->comboBox_cameraImages_bayerMode, SIGNAL(currentIndexChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
00427
00428 connect(_ui->source_video_toolButton_selectSource, SIGNAL(clicked()), this, SLOT(selectSourceVideoPath()));
00429 connect(_ui->source_video_lineEdit_path, SIGNAL(textChanged(const QString &)), this, SLOT(makeObsoleteSourcePanel()));
00430 connect(_ui->checkBox_rgbVideo_rectify, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
00431
00432 connect(_ui->source_database_toolButton_selectSource, SIGNAL(clicked()), this, SLOT(selectSourceDatabase()));
00433 connect(_ui->toolButton_dbViewer, SIGNAL(clicked()), this, SLOT(openDatabaseViewer()));
00434 connect(_ui->groupBox_sourceDatabase, SIGNAL(toggled(bool)), this, SLOT(makeObsoleteSourcePanel()));
00435 connect(_ui->source_database_lineEdit_path, SIGNAL(textChanged(const QString &)), this, SLOT(makeObsoleteSourcePanel()));
00436 connect(_ui->source_checkBox_ignoreOdometry, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
00437 connect(_ui->source_checkBox_ignoreGoalDelay, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
00438 connect(_ui->source_checkBox_ignoreGoals, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
00439 connect(_ui->source_spinBox_databaseStartPos, SIGNAL(valueChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
00440 connect(_ui->source_checkBox_useDbStamps, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
00441 connect(_ui->source_spinBox_database_cameraIndex, SIGNAL(valueChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
00442
00443
00444 _ui->stackedWidget_rgbd->setCurrentIndex(_ui->comboBox_cameraRGBD->currentIndex());
00445 connect(_ui->comboBox_cameraRGBD, SIGNAL(currentIndexChanged(int)), _ui->stackedWidget_rgbd, SLOT(setCurrentIndex(int)));
00446 connect(_ui->comboBox_cameraRGBD, SIGNAL(currentIndexChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
00447 _ui->stackedWidget_stereo->setCurrentIndex(_ui->comboBox_cameraStereo->currentIndex());
00448 connect(_ui->comboBox_cameraStereo, SIGNAL(currentIndexChanged(int)), _ui->stackedWidget_stereo, SLOT(setCurrentIndex(int)));
00449 connect(_ui->comboBox_cameraStereo, SIGNAL(currentIndexChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
00450 connect(_ui->openni2_autoWhiteBalance, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
00451 connect(_ui->openni2_autoExposure, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
00452 connect(_ui->openni2_exposure, SIGNAL(valueChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
00453 connect(_ui->openni2_gain, SIGNAL(valueChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
00454 connect(_ui->openni2_mirroring, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
00455 connect(_ui->openni2_stampsIdsUsed, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
00456 connect(_ui->comboBox_freenect2Format, SIGNAL(currentIndexChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
00457 connect(_ui->doubleSpinBox_freenect2MinDepth, SIGNAL(valueChanged(double)), this, SLOT(makeObsoleteSourcePanel()));
00458 connect(_ui->doubleSpinBox_freenect2MaxDepth, SIGNAL(valueChanged(double)), this, SLOT(makeObsoleteSourcePanel()));
00459 connect(_ui->checkBox_freenect2BilateralFiltering, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
00460 connect(_ui->checkBox_freenect2EdgeAwareFiltering, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
00461 connect(_ui->checkBox_freenect2NoiseFiltering, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
00462
00463 connect(_ui->toolButton_cameraImages_timestamps, SIGNAL(clicked()), this, SLOT(selectSourceImagesStamps()));
00464 connect(_ui->lineEdit_cameraImages_timestamps, SIGNAL(textChanged(const QString &)), this, SLOT(makeObsoleteSourcePanel()));
00465 connect(_ui->toolButton_cameraRGBDImages_path_rgb, SIGNAL(clicked()), this, SLOT(selectSourceRGBDImagesPathRGB()));
00466 connect(_ui->toolButton_cameraRGBDImages_path_depth, SIGNAL(clicked()), this, SLOT(selectSourceRGBDImagesPathDepth()));
00467 connect(_ui->toolButton_cameraImages_path_scans, SIGNAL(clicked()), this, SLOT(selectSourceImagesPathScans()));
00468 connect(_ui->toolButton_cameraImages_gt, SIGNAL(clicked()), this, SLOT(selectSourceImagesPathGt()));
00469 connect(_ui->lineEdit_cameraRGBDImages_path_rgb, SIGNAL(textChanged(const QString &)), this, SLOT(makeObsoleteSourcePanel()));
00470 connect(_ui->lineEdit_cameraRGBDImages_path_depth, SIGNAL(textChanged(const QString &)), this, SLOT(makeObsoleteSourcePanel()));
00471 connect(_ui->checkBox_cameraImages_timestamps, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
00472 connect(_ui->checkBox_cameraImages_syncTimeStamps, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
00473 connect(_ui->doubleSpinBox_cameraRGBDImages_scale, SIGNAL(valueChanged(double)), this, SLOT(makeObsoleteSourcePanel()));
00474 connect(_ui->lineEdit_cameraImages_path_scans, SIGNAL(textChanged(const QString &)), this, SLOT(makeObsoleteSourcePanel()));
00475 connect(_ui->lineEdit_cameraImages_laser_transform, SIGNAL(textChanged(const QString &)), this, SLOT(makeObsoleteSourcePanel()));
00476 connect(_ui->spinBox_cameraImages_max_scan_pts, SIGNAL(valueChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
00477 connect(_ui->spinBox_cameraImages_scanDownsampleStep, SIGNAL(valueChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
00478 connect(_ui->doubleSpinBox_cameraImages_scanVoxelSize, SIGNAL(valueChanged(double)), this, SLOT(makeObsoleteSourcePanel()));
00479 connect(_ui->lineEdit_cameraImages_gt, SIGNAL(textChanged(const QString &)), this, SLOT(makeObsoleteSourcePanel()));
00480 connect(_ui->comboBox_cameraImages_gtFormat, SIGNAL(currentIndexChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
00481 connect(_ui->groupBox_depthFromScan, SIGNAL(toggled(bool)), this, SLOT(makeObsoleteSourcePanel()));
00482 connect(_ui->groupBox_depthFromScan_fillHoles, SIGNAL(toggled(bool)), this, SLOT(makeObsoleteSourcePanel()));
00483 connect(_ui->radioButton_depthFromScan_vertical, SIGNAL(toggled(bool)), this, SLOT(makeObsoleteSourcePanel()));
00484 connect(_ui->radioButton_depthFromScan_horizontal, SIGNAL(toggled(bool)), this, SLOT(makeObsoleteSourcePanel()));
00485 connect(_ui->checkBox_depthFromScan_fillBorders, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
00486
00487 connect(_ui->toolButton_cameraStereoImages_path_left, SIGNAL(clicked()), this, SLOT(selectSourceStereoImagesPathLeft()));
00488 connect(_ui->toolButton_cameraStereoImages_path_right, SIGNAL(clicked()), this, SLOT(selectSourceStereoImagesPathRight()));
00489 connect(_ui->lineEdit_cameraStereoImages_path_left, SIGNAL(textChanged(const QString &)), this, SLOT(makeObsoleteSourcePanel()));
00490 connect(_ui->lineEdit_cameraStereoImages_path_right, SIGNAL(textChanged(const QString &)), this, SLOT(makeObsoleteSourcePanel()));
00491 connect(_ui->checkBox_stereoImages_rectify, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
00492
00493 connect(_ui->toolButton_cameraStereoVideo_path, SIGNAL(clicked()), this, SLOT(selectSourceStereoVideoPath()));
00494 connect(_ui->lineEdit_cameraStereoVideo_path, SIGNAL(textChanged(const QString &)), this, SLOT(makeObsoleteSourcePanel()));
00495 connect(_ui->checkBox_stereoVideo_rectify, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
00496
00497 connect(_ui->comboBox_stereoZed_resolution, SIGNAL(currentIndexChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
00498 connect(_ui->comboBox_stereoZed_quality, SIGNAL(currentIndexChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
00499 connect(_ui->comboBox_stereoZed_quality, SIGNAL(currentIndexChanged(int)), this, SLOT(updateStereoDisparityVisibility()));
00500 connect(_ui->comboBox_cameraStereo, SIGNAL(currentIndexChanged(int)), this, SLOT(updateStereoDisparityVisibility()));
00501 connect(_ui->comboBox_stereoZed_sensingMode, SIGNAL(currentIndexChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
00502 connect(_ui->spinBox_stereoZed_confidenceThr, SIGNAL(valueChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
00503 connect(_ui->checkbox_stereoZed_odom, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
00504 connect(_ui->toolButton_zedSvoPath, SIGNAL(clicked()), this, SLOT(selectSourceSvoPath()));
00505 connect(_ui->lineEdit_zedSvoPath, SIGNAL(textChanged(const QString &)), this, SLOT(makeObsoleteSourcePanel()));
00506
00507 connect(_ui->checkbox_rgbd_colorOnly, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
00508 connect(_ui->spinBox_source_imageDecimation, SIGNAL(valueChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
00509 connect(_ui->checkbox_stereo_depthGenerated, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
00510 connect(_ui->pushButton_calibrate, SIGNAL(clicked()), this, SLOT(calibrate()));
00511 connect(_ui->pushButton_calibrate_simple, SIGNAL(clicked()), this, SLOT(calibrateSimple()));
00512 connect(_ui->toolButton_openniOniPath, SIGNAL(clicked()), this, SLOT(selectSourceOniPath()));
00513 connect(_ui->toolButton_openni2OniPath, SIGNAL(clicked()), this, SLOT(selectSourceOni2Path()));
00514 connect(_ui->lineEdit_openniOniPath, SIGNAL(textChanged(const QString &)), this, SLOT(makeObsoleteSourcePanel()));
00515 connect(_ui->lineEdit_openni2OniPath, SIGNAL(textChanged(const QString &)), this, SLOT(makeObsoleteSourcePanel()));
00516
00517 connect(_ui->groupBox_scanFromDepth, SIGNAL(toggled(bool)), this, SLOT(makeObsoleteSourcePanel()));
00518 connect(_ui->spinBox_cameraScanFromDepth_decimation, SIGNAL(valueChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
00519 connect(_ui->doubleSpinBox_cameraSCanFromDepth_maxDepth, SIGNAL(valueChanged(double)), this, SLOT(makeObsoleteSourcePanel()));
00520 connect(_ui->doubleSpinBox_cameraImages_scanVoxelSize, SIGNAL(valueChanged(double)), this, SLOT(makeObsoleteSourcePanel()));
00521 connect(_ui->spinBox_cameraImages_scanNormalsK, SIGNAL(valueChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
00522
00523
00524 connect(_ui->general_doubleSpinBox_timeThr, SIGNAL(valueChanged(double)), _ui->general_doubleSpinBox_timeThr_2, SLOT(setValue(double)));
00525 connect(_ui->general_doubleSpinBox_hardThr, SIGNAL(valueChanged(double)), _ui->general_doubleSpinBox_hardThr_2, SLOT(setValue(double)));
00526 connect(_ui->doubleSpinBox_similarityThreshold, SIGNAL(valueChanged(double)), _ui->doubleSpinBox_similarityThreshold_2, SLOT(setValue(double)));
00527 connect(_ui->general_doubleSpinBox_detectionRate, SIGNAL(valueChanged(double)), _ui->general_doubleSpinBox_detectionRate_2, SLOT(setValue(double)));
00528 connect(_ui->general_spinBox_imagesBufferSize, SIGNAL(valueChanged(int)), _ui->general_spinBox_imagesBufferSize_2, SLOT(setValue(int)));
00529 connect(_ui->general_spinBox_maxStMemSize, SIGNAL(valueChanged(int)), _ui->general_spinBox_maxStMemSize_2, SLOT(setValue(int)));
00530
00531 connect(_ui->general_doubleSpinBox_timeThr_2, SIGNAL(editingFinished()), this, SLOT(updateBasicParameter()));
00532 connect(_ui->general_doubleSpinBox_hardThr_2, SIGNAL(editingFinished()), this, SLOT(updateBasicParameter()));
00533 connect(_ui->doubleSpinBox_similarityThreshold_2, SIGNAL(editingFinished()), this, SLOT(updateBasicParameter()));
00534 connect(_ui->general_doubleSpinBox_detectionRate_2, SIGNAL(editingFinished()), this, SLOT(updateBasicParameter()));
00535 connect(_ui->general_spinBox_imagesBufferSize_2, SIGNAL(editingFinished()), this, SLOT(updateBasicParameter()));
00536 connect(_ui->general_spinBox_maxStMemSize_2, SIGNAL(editingFinished()), this, SLOT(updateBasicParameter()));
00537 connect(_ui->groupBox_publishing, SIGNAL(toggled(bool)), this, SLOT(updateBasicParameter()));
00538 connect(_ui->general_checkBox_publishStats_2, SIGNAL(stateChanged(int)), this, SLOT(updateBasicParameter()));
00539 connect(_ui->general_checkBox_activateRGBD, SIGNAL(stateChanged(int)), this, SLOT(updateBasicParameter()));
00540 connect(_ui->general_checkBox_activateRGBD_2, SIGNAL(stateChanged(int)), this, SLOT(updateBasicParameter()));
00541 connect(_ui->general_checkBox_SLAM_mode, SIGNAL(stateChanged(int)), this, SLOT(updateBasicParameter()));
00542 connect(_ui->general_checkBox_SLAM_mode_2, SIGNAL(stateChanged(int)), this, SLOT(updateBasicParameter()));
00543
00544
00545
00546 _ui->groupBox_publishing->setObjectName(Parameters::kRtabmapPublishStats().c_str());
00547 _ui->general_checkBox_publishRawData->setObjectName(Parameters::kRtabmapPublishLastSignature().c_str());
00548 _ui->general_checkBox_publishPdf->setObjectName(Parameters::kRtabmapPublishPdf().c_str());
00549 _ui->general_checkBox_publishLikelihood->setObjectName(Parameters::kRtabmapPublishLikelihood().c_str());
00550 _ui->general_checkBox_statisticLogsBufferedInRAM->setObjectName(Parameters::kRtabmapStatisticLogsBufferedInRAM().c_str());
00551 _ui->groupBox_statistics->setObjectName(Parameters::kRtabmapStatisticLogged().c_str());
00552 _ui->general_checkBox_statisticLoggedHeaders->setObjectName(Parameters::kRtabmapStatisticLoggedHeaders().c_str());
00553 _ui->general_doubleSpinBox_timeThr->setObjectName(Parameters::kRtabmapTimeThr().c_str());
00554 _ui->general_spinBox_memoryThr->setObjectName(Parameters::kRtabmapMemoryThr().c_str());
00555 _ui->general_doubleSpinBox_detectionRate->setObjectName(Parameters::kRtabmapDetectionRate().c_str());
00556 _ui->general_spinBox_imagesBufferSize->setObjectName(Parameters::kRtabmapImageBufferSize().c_str());
00557 _ui->general_checkBox_createIntermediateNodes->setObjectName(Parameters::kRtabmapCreateIntermediateNodes().c_str());
00558 _ui->general_spinBox_maxRetrieved->setObjectName(Parameters::kRtabmapMaxRetrieved().c_str());
00559 _ui->general_checkBox_startNewMapOnLoopClosure->setObjectName(Parameters::kRtabmapStartNewMapOnLoopClosure().c_str());
00560 _ui->lineEdit_workingDirectory->setObjectName(Parameters::kRtabmapWorkingDirectory().c_str());
00561 connect(_ui->toolButton_workingDirectory, SIGNAL(clicked()), this, SLOT(changeWorkingDirectory()));
00562
00563
00564 _ui->general_checkBox_keepRawData->setObjectName(Parameters::kMemImageKept().c_str());
00565 _ui->general_checkBox_keepBinaryData->setObjectName(Parameters::kMemBinDataKept().c_str());
00566 _ui->general_checkBox_keepDescriptors->setObjectName(Parameters::kMemRawDescriptorsKept().c_str());
00567 _ui->general_checkBox_saveDepth16bits->setObjectName(Parameters::kMemSaveDepth16Format().c_str());
00568 _ui->general_checkBox_reduceGraph->setObjectName(Parameters::kMemReduceGraph().c_str());
00569 _ui->general_checkBox_keepNotLinkedNodes->setObjectName(Parameters::kMemNotLinkedNodesKept().c_str());
00570 _ui->general_spinBox_maxStMemSize->setObjectName(Parameters::kMemSTMSize().c_str());
00571 _ui->doubleSpinBox_similarityThreshold->setObjectName(Parameters::kMemRehearsalSimilarity().c_str());
00572 _ui->general_checkBox_SLAM_mode->setObjectName(Parameters::kMemIncrementalMemory().c_str());
00573 _ui->general_doubleSpinBox_recentWmRatio->setObjectName(Parameters::kMemRecentWmRatio().c_str());
00574 _ui->general_checkBox_transferSortingByWeightId->setObjectName(Parameters::kMemTransferSortingByWeightId().c_str());
00575 _ui->general_checkBox_RehearsalIdUpdatedToNewOne->setObjectName(Parameters::kMemRehearsalIdUpdatedToNewOne().c_str());
00576 _ui->general_checkBox_generateIds->setObjectName(Parameters::kMemGenerateIds().c_str());
00577 _ui->general_checkBox_badSignaturesIgnored->setObjectName(Parameters::kMemBadSignaturesIgnored().c_str());
00578 _ui->general_checkBox_createMapLabels->setObjectName(Parameters::kMemMapLabelsAdded().c_str());
00579 _ui->general_checkBox_initWMWithAllNodes->setObjectName(Parameters::kMemInitWMWithAllNodes().c_str());
00580 _ui->checkBox_localSpaceScanMatchingIDsSaved->setObjectName(Parameters::kRGBDScanMatchingIdsSavedInLinks().c_str());
00581 _ui->spinBox_imagePreDecimation->setObjectName(Parameters::kMemImagePreDecimation().c_str());
00582 _ui->spinBox_imagePostDecimation->setObjectName(Parameters::kMemImagePostDecimation().c_str());
00583 _ui->general_spinBox_laserScanDownsample->setObjectName(Parameters::kMemLaserScanDownsampleStepSize().c_str());
00584 _ui->checkBox_useOdomFeatures->setObjectName(Parameters::kMemUseOdomFeatures().c_str());
00585
00586
00587 _ui->checkBox_dbInMemory->setObjectName(Parameters::kDbSqlite3InMemory().c_str());
00588 _ui->spinBox_dbCacheSize->setObjectName(Parameters::kDbSqlite3CacheSize().c_str());
00589 _ui->comboBox_dbJournalMode->setObjectName(Parameters::kDbSqlite3JournalMode().c_str());
00590 _ui->comboBox_dbSynchronous->setObjectName(Parameters::kDbSqlite3Synchronous().c_str());
00591 _ui->comboBox_dbTempStore->setObjectName(Parameters::kDbSqlite3TempStore().c_str());
00592
00593
00594 _ui->general_doubleSpinBox_hardThr->setObjectName(Parameters::kRtabmapLoopThr().c_str());
00595 _ui->general_doubleSpinBox_loopRatio->setObjectName(Parameters::kRtabmapLoopRatio().c_str());
00596
00597
00598 _ui->general_doubleSpinBox_vp->setObjectName(Parameters::kBayesVirtualPlacePriorThr().c_str());
00599 _ui->lineEdit_bayes_predictionLC->setObjectName(Parameters::kBayesPredictionLC().c_str());
00600 _ui->checkBox_bayes_fullPredictionUpdate->setObjectName(Parameters::kBayesFullPredictionUpdate().c_str());
00601 connect(_ui->lineEdit_bayes_predictionLC, SIGNAL(textChanged(const QString &)), this, SLOT(updatePredictionPlot()));
00602
00603
00604 _ui->comboBox_dictionary_strategy->setObjectName(Parameters::kKpNNStrategy().c_str());
00605 _ui->checkBox_dictionary_incremental->setObjectName(Parameters::kKpIncrementalDictionary().c_str());
00606 _ui->checkBox_kp_incrementalFlann->setObjectName(Parameters::kKpIncrementalFlann().c_str());
00607 _ui->comboBox_detector_strategy->setObjectName(Parameters::kKpDetectorStrategy().c_str());
00608 _ui->surf_doubleSpinBox_nndrRatio->setObjectName(Parameters::kKpNndrRatio().c_str());
00609 _ui->surf_doubleSpinBox_maxDepth->setObjectName(Parameters::kKpMaxDepth().c_str());
00610 _ui->surf_doubleSpinBox_minDepth->setObjectName(Parameters::kKpMinDepth().c_str());
00611 _ui->surf_spinBox_wordsPerImageTarget->setObjectName(Parameters::kKpMaxFeatures().c_str());
00612 _ui->surf_doubleSpinBox_ratioBadSign->setObjectName(Parameters::kKpBadSignRatio().c_str());
00613 _ui->checkBox_kp_tfIdfLikelihoodUsed->setObjectName(Parameters::kKpTfIdfLikelihoodUsed().c_str());
00614 _ui->checkBox_kp_parallelized->setObjectName(Parameters::kKpParallelized().c_str());
00615 _ui->lineEdit_kp_roi->setObjectName(Parameters::kKpRoiRatios().c_str());
00616 _ui->lineEdit_dictionaryPath->setObjectName(Parameters::kKpDictionaryPath().c_str());
00617 connect(_ui->toolButton_dictionaryPath, SIGNAL(clicked()), this, SLOT(changeDictionaryPath()));
00618 _ui->checkBox_kp_newWordsComparedTogether->setObjectName(Parameters::kKpNewWordsComparedTogether().c_str());
00619 _ui->subpix_winSize_kp->setObjectName(Parameters::kKpSubPixWinSize().c_str());
00620 _ui->subpix_iterations_kp->setObjectName(Parameters::kKpSubPixIterations().c_str());
00621 _ui->subpix_eps_kp->setObjectName(Parameters::kKpSubPixEps().c_str());
00622
00623 _ui->subpix_winSize->setObjectName(Parameters::kKpSubPixWinSize().c_str());
00624 _ui->subpix_iterations->setObjectName(Parameters::kKpSubPixIterations().c_str());
00625 _ui->subpix_eps->setObjectName(Parameters::kKpSubPixEps().c_str());
00626
00627
00628 _ui->surf_doubleSpinBox_hessianThr->setObjectName(Parameters::kSURFHessianThreshold().c_str());
00629 _ui->surf_spinBox_octaves->setObjectName(Parameters::kSURFOctaves().c_str());
00630 _ui->surf_spinBox_octaveLayers->setObjectName(Parameters::kSURFOctaveLayers().c_str());
00631 _ui->checkBox_surfExtended->setObjectName(Parameters::kSURFExtended().c_str());
00632 _ui->surf_checkBox_upright->setObjectName(Parameters::kSURFUpright().c_str());
00633 _ui->surf_checkBox_gpuVersion->setObjectName(Parameters::kSURFGpuVersion().c_str());
00634 _ui->surf_doubleSpinBox_gpuKeypointsRatio->setObjectName(Parameters::kSURFGpuKeypointsRatio().c_str());
00635
00636
00637 _ui->sift_spinBox_nFeatures->setObjectName(Parameters::kSIFTNFeatures().c_str());
00638 _ui->sift_spinBox_nOctaveLayers->setObjectName(Parameters::kSIFTNOctaveLayers().c_str());
00639 _ui->sift_doubleSpinBox_contrastThr->setObjectName(Parameters::kSIFTContrastThreshold().c_str());
00640 _ui->sift_doubleSpinBox_edgeThr->setObjectName(Parameters::kSIFTEdgeThreshold().c_str());
00641 _ui->sift_doubleSpinBox_sigma->setObjectName(Parameters::kSIFTSigma().c_str());
00642
00643
00644 _ui->briefBytes->setObjectName(Parameters::kBRIEFBytes().c_str());
00645
00646
00647 _ui->fastSuppressNonMax->setObjectName(Parameters::kFASTNonmaxSuppression().c_str());
00648 _ui->fastThreshold->setObjectName(Parameters::kFASTThreshold().c_str());
00649 _ui->fastThresholdMin->setObjectName(Parameters::kFASTMinThreshold().c_str());
00650 _ui->fastThresholdMax->setObjectName(Parameters::kFASTMaxThreshold().c_str());
00651 _ui->fastGridRows->setObjectName(Parameters::kFASTGridRows().c_str());
00652 _ui->fastGridCols->setObjectName(Parameters::kFASTGridCols().c_str());
00653 _ui->fastGpu->setObjectName(Parameters::kFASTGpu().c_str());
00654 _ui->fastKeypointRatio->setObjectName(Parameters::kFASTGpuKeypointsRatio().c_str());
00655
00656
00657 _ui->doubleSpinBox_ORBScaleFactor->setObjectName(Parameters::kORBScaleFactor().c_str());
00658 _ui->spinBox_ORBNLevels->setObjectName(Parameters::kORBNLevels().c_str());
00659 _ui->spinBox_ORBEdgeThreshold->setObjectName(Parameters::kORBEdgeThreshold().c_str());
00660 _ui->spinBox_ORBFirstLevel->setObjectName(Parameters::kORBFirstLevel().c_str());
00661 _ui->spinBox_ORBWTA_K->setObjectName(Parameters::kORBWTA_K().c_str());
00662 _ui->spinBox_ORBScoreType->setObjectName(Parameters::kORBScoreType().c_str());
00663 _ui->spinBox_ORBPatchSize->setObjectName(Parameters::kORBPatchSize().c_str());
00664 _ui->checkBox_ORBGpu->setObjectName(Parameters::kORBGpu().c_str());
00665
00666
00667 _ui->checkBox_FREAKOrientationNormalized->setObjectName(Parameters::kFREAKOrientationNormalized().c_str());
00668 _ui->checkBox_FREAKScaleNormalized->setObjectName(Parameters::kFREAKScaleNormalized().c_str());
00669 _ui->doubleSpinBox_FREAKPatternScale->setObjectName(Parameters::kFREAKPatternScale().c_str());
00670 _ui->spinBox_FREAKNOctaves->setObjectName(Parameters::kFREAKNOctaves().c_str());
00671
00672
00673 _ui->doubleSpinBox_GFTT_qualityLevel->setObjectName(Parameters::kGFTTQualityLevel().c_str());
00674 _ui->doubleSpinBox_GFTT_minDistance->setObjectName(Parameters::kGFTTMinDistance().c_str());
00675 _ui->spinBox_GFTT_blockSize->setObjectName(Parameters::kGFTTBlockSize().c_str());
00676 _ui->checkBox_GFTT_useHarrisDetector->setObjectName(Parameters::kGFTTUseHarrisDetector().c_str());
00677 _ui->doubleSpinBox_GFTT_k->setObjectName(Parameters::kGFTTK().c_str());
00678
00679
00680 _ui->spinBox_BRISK_thresh->setObjectName(Parameters::kBRISKThresh().c_str());
00681 _ui->spinBox_BRISK_octaves->setObjectName(Parameters::kBRISKOctaves().c_str());
00682 _ui->doubleSpinBox_BRISK_patterScale->setObjectName(Parameters::kBRISKPatternScale().c_str());
00683
00684
00685 _ui->comboBox_vh_strategy->setObjectName(Parameters::kRtabmapVhStrategy().c_str());
00686 _ui->surf_spinBox_matchCountMinAccepted->setObjectName(Parameters::kVhEpMatchCountMin().c_str());
00687 _ui->surf_doubleSpinBox_ransacParam1->setObjectName(Parameters::kVhEpRansacParam1().c_str());
00688 _ui->surf_doubleSpinBox_ransacParam2->setObjectName(Parameters::kVhEpRansacParam2().c_str());
00689
00690
00691 _ui->general_checkBox_activateRGBD->setObjectName(Parameters::kRGBDEnabled().c_str());
00692 _ui->rgdb_linearUpdate->setObjectName(Parameters::kRGBDLinearUpdate().c_str());
00693 _ui->rgdb_angularUpdate->setObjectName(Parameters::kRGBDAngularUpdate().c_str());
00694 _ui->rgdb_rehearsalWeightIgnoredWhileMoving->setObjectName(Parameters::kMemRehearsalWeightIgnoredWhileMoving().c_str());
00695 _ui->rgdb_newMapOdomChange->setObjectName(Parameters::kRGBDNewMapOdomChangeDistance().c_str());
00696 _ui->odomScanHistory->setObjectName(Parameters::kRGBDNeighborLinkRefining().c_str());
00697 _ui->spinBox_maxLocalLocationsRetrieved->setObjectName(Parameters::kRGBDMaxLocalRetrieved().c_str());
00698
00699 _ui->graphOptimization_type->setObjectName(Parameters::kOptimizerStrategy().c_str());
00700 _ui->graphOptimization_slam2d->setObjectName(Parameters::kOptimizerSlam2D().c_str());
00701 _ui->graphOptimization_iterations->setObjectName(Parameters::kOptimizerIterations().c_str());
00702 _ui->graphOptimization_covarianceIgnored->setObjectName(Parameters::kOptimizerVarianceIgnored().c_str());
00703 _ui->graphOptimization_fromGraphEnd->setObjectName(Parameters::kRGBDOptimizeFromGraphEnd().c_str());
00704 _ui->graphOptimization_maxError->setObjectName(Parameters::kRGBDOptimizeMaxError().c_str());
00705 _ui->graphOptimization_stopEpsilon->setObjectName(Parameters::kOptimizerEpsilon().c_str());
00706 _ui->graphOptimization_robust->setObjectName(Parameters::kOptimizerRobust().c_str());
00707
00708 _ui->comboBox_g2o_solver->setObjectName(Parameters::kg2oSolver().c_str());
00709 _ui->comboBox_g2o_optimizer->setObjectName(Parameters::kg2oOptimizer().c_str());
00710 _ui->doubleSpinBox_g2o_variance->setObjectName(Parameters::kg2oPixelVariance().c_str());
00711
00712 _ui->graphPlan_goalReachedRadius->setObjectName(Parameters::kRGBDGoalReachedRadius().c_str());
00713 _ui->graphPlan_goalsSavedInUserData->setObjectName(Parameters::kRGBDGoalsSavedInUserData().c_str());
00714 _ui->graphPlan_stuckIterations->setObjectName(Parameters::kRGBDPlanStuckIterations().c_str());
00715 _ui->graphPlan_linearVelocity->setObjectName(Parameters::kRGBDPlanLinearVelocity().c_str());
00716 _ui->graphPlan_angularVelocity->setObjectName(Parameters::kRGBDPlanAngularVelocity().c_str());
00717
00718 _ui->groupBox_localDetection_time->setObjectName(Parameters::kRGBDProximityByTime().c_str());
00719 _ui->groupBox_localDetection_space->setObjectName(Parameters::kRGBDProximityBySpace().c_str());
00720 _ui->localDetection_radius->setObjectName(Parameters::kRGBDLocalRadius().c_str());
00721 _ui->localDetection_maxDiffID->setObjectName(Parameters::kRGBDProximityMaxGraphDepth().c_str());
00722 _ui->localDetection_pathFilteringRadius->setObjectName(Parameters::kRGBDProximityPathFilteringRadius().c_str());
00723 _ui->localDetection_angle->setObjectName(Parameters::kRGBDProximityAngle().c_str());
00724 _ui->checkBox_localSpacePathOdomPosesUsed->setObjectName(Parameters::kRGBDProximityPathRawPosesUsed().c_str());
00725 _ui->rgdb_localImmunizationRatio->setObjectName(Parameters::kRGBDLocalImmunizationRatio().c_str());
00726 _ui->loopClosure_reextract->setObjectName(Parameters::kRGBDLoopClosureReextractFeatures().c_str());
00727
00728
00729 _ui->loopClosure_bowVarianceFromInliersCount->setObjectName(Parameters::kRegVarianceFromInliersCount().c_str());
00730 _ui->comboBox_registrationStrategy->setObjectName(Parameters::kRegStrategy().c_str());
00731 _ui->loopClosure_bowForce2D->setObjectName(Parameters::kRegForce3DoF().c_str());
00732
00733
00734 _ui->loopClosure_bowMinInliers->setObjectName(Parameters::kVisMinInliers().c_str());
00735 _ui->loopClosure_bowInlierDistance->setObjectName(Parameters::kVisInlierDistance().c_str());
00736 _ui->loopClosure_bowIterations->setObjectName(Parameters::kVisIterations().c_str());
00737 _ui->loopClosure_bowRefineIterations->setObjectName(Parameters::kVisRefineIterations().c_str());
00738 _ui->loopClosure_estimationType->setObjectName(Parameters::kVisEstimationType().c_str());
00739 connect(_ui->loopClosure_estimationType, SIGNAL(currentIndexChanged(int)), _ui->stackedWidget_loopClosureEstimation, SLOT(setCurrentIndex(int)));
00740 _ui->stackedWidget_loopClosureEstimation->setCurrentIndex(Parameters::defaultVisEstimationType());
00741 _ui->loopClosure_forwardEst->setObjectName(Parameters::kVisForwardEstOnly().c_str());
00742 _ui->loopClosure_bowEpipolarGeometryVar->setObjectName(Parameters::kVisEpipolarGeometryVar().c_str());
00743 _ui->loopClosure_pnpReprojError->setObjectName(Parameters::kVisPnPReprojError().c_str());
00744 _ui->loopClosure_pnpFlags->setObjectName(Parameters::kVisPnPFlags().c_str());
00745 _ui->loopClosure_pnpRefineIterations->setObjectName(Parameters::kVisPnPRefineIterations().c_str());
00746 _ui->loopClosure_correspondencesType->setObjectName(Parameters::kVisCorType().c_str());
00747 connect(_ui->loopClosure_correspondencesType, SIGNAL(currentIndexChanged(int)), _ui->stackedWidget_loopClosureCorrespondences, SLOT(setCurrentIndex(int)));
00748 _ui->stackedWidget_loopClosureCorrespondences->setCurrentIndex(Parameters::defaultVisCorType());
00749 _ui->reextract_nn->setObjectName(Parameters::kVisCorNNType().c_str());
00750 _ui->reextract_nndrRatio->setObjectName(Parameters::kVisCorNNDR().c_str());
00751 _ui->spinBox_visCorGuessWinSize->setObjectName(Parameters::kVisCorGuessWinSize().c_str());
00752 _ui->reextract_type->setObjectName(Parameters::kVisFeatureType().c_str());
00753 _ui->reextract_maxFeatures->setObjectName(Parameters::kVisMaxFeatures().c_str());
00754 _ui->loopClosure_bowMaxDepth->setObjectName(Parameters::kVisMaxDepth().c_str());
00755 _ui->loopClosure_bowMinDepth->setObjectName(Parameters::kVisMinDepth().c_str());
00756 _ui->loopClosure_roi->setObjectName(Parameters::kVisRoiRatios().c_str());
00757 _ui->subpix_winSize->setObjectName(Parameters::kVisSubPixWinSize().c_str());
00758 _ui->subpix_iterations->setObjectName(Parameters::kVisSubPixIterations().c_str());
00759 _ui->subpix_eps->setObjectName(Parameters::kVisSubPixEps().c_str());
00760 _ui->odom_flow_winSize_2->setObjectName(Parameters::kVisCorFlowWinSize().c_str());
00761 _ui->odom_flow_maxLevel_2->setObjectName(Parameters::kVisCorFlowMaxLevel().c_str());
00762 _ui->odom_flow_iterations_2->setObjectName(Parameters::kVisCorFlowIterations().c_str());
00763 _ui->odom_flow_eps_2->setObjectName(Parameters::kVisCorFlowEps().c_str());
00764
00765
00766 _ui->globalDetection_icpMaxTranslation->setObjectName(Parameters::kIcpMaxTranslation().c_str());
00767 _ui->globalDetection_icpMaxRotation->setObjectName(Parameters::kIcpMaxRotation().c_str());
00768 _ui->loopClosure_icpVoxelSize->setObjectName(Parameters::kIcpVoxelSize().c_str());
00769 _ui->loopClosure_icpDownsamplingStep->setObjectName(Parameters::kIcpDownsamplingStep().c_str());
00770 _ui->loopClosure_icpMaxCorrespondenceDistance->setObjectName(Parameters::kIcpMaxCorrespondenceDistance().c_str());
00771 _ui->loopClosure_icpIterations->setObjectName(Parameters::kIcpIterations().c_str());
00772 _ui->loopClosure_icpEpsilon->setObjectName(Parameters::kIcpEpsilon().c_str());
00773 _ui->loopClosure_icpRatio->setObjectName(Parameters::kIcpCorrespondenceRatio().c_str());
00774 _ui->loopClosure_icpPointToPlane->setObjectName(Parameters::kIcpPointToPlane().c_str());
00775 _ui->loopClosure_icpPointToPlaneNormals->setObjectName(Parameters::kIcpPointToPlaneNormalNeighbors().c_str());
00776
00777
00778
00779 _ui->odom_strategy->setObjectName(Parameters::kOdomStrategy().c_str());
00780 connect(_ui->odom_strategy, SIGNAL(currentIndexChanged(int)), _ui->stackedWidget_odometryType, SLOT(setCurrentIndex(int)));
00781 _ui->odom_strategy->setCurrentIndex(Parameters::defaultOdomStrategy());
00782 _ui->odom_countdown->setObjectName(Parameters::kOdomResetCountdown().c_str());
00783 _ui->odom_holonomic->setObjectName(Parameters::kOdomHolonomic().c_str());
00784 _ui->odom_fillInfoData->setObjectName(Parameters::kOdomFillInfoData().c_str());
00785 _ui->odom_dataBufferSize->setObjectName(Parameters::kOdomImageBufferSize().c_str());
00786 _ui->odom_flow_keyframeThr->setObjectName(Parameters::kOdomKeyFrameThr().c_str());
00787 _ui->odom_flow_scanKeyframeThr->setObjectName(Parameters::kOdomScanKeyFrameThr().c_str());
00788 _ui->odom_flow_guessMotion->setObjectName(Parameters::kOdomGuessMotion().c_str());
00789 _ui->odom_imageDecimation->setObjectName(Parameters::kOdomImageDecimation().c_str());
00790 _ui->odom_alignWithGround->setObjectName(Parameters::kOdomAlignWithGround().c_str());
00791
00792
00793 _ui->odom_localHistory->setObjectName(Parameters::kOdomF2MMaxSize().c_str());
00794 _ui->spinBox_odom_f2m_maxNewFeatures->setObjectName(Parameters::kOdomF2MMaxNewFeatures().c_str());
00795 _ui->spinBox_odom_f2m_scanMaxSize->setObjectName(Parameters::kOdomF2MScanMaxSize().c_str());
00796 _ui->doubleSpinBox_odom_f2m_scanRadius->setObjectName(Parameters::kOdomF2MScanSubtractRadius().c_str());
00797 _ui->odom_fixedLocalMapPath->setObjectName(Parameters::kOdomF2MFixedMapPath().c_str());
00798 connect(_ui->toolButton_odomBowFixedLocalMap, SIGNAL(clicked()), this, SLOT(changeOdomBowFixedLocalMapPath()));
00799
00800
00801 _ui->doubleSpinBox_minFlow->setObjectName(Parameters::kOdomMonoInitMinFlow().c_str());
00802 _ui->doubleSpinBox_minInitTranslation->setObjectName(Parameters::kOdomMonoInitMinTranslation().c_str());
00803 _ui->doubleSpinBox_minTranslation->setObjectName(Parameters::kOdomMonoMinTranslation().c_str());
00804 _ui->doubleSpinBox_maxVariance->setObjectName(Parameters::kOdomMonoMaxVariance().c_str());
00805
00806
00807 _ui->odom_filteringStrategy->setObjectName(Parameters::kOdomFilteringStrategy().c_str());
00808 _ui->stackedWidget_odometryFiltering->setCurrentIndex(_ui->odom_filteringStrategy->currentIndex());
00809 connect(_ui->odom_filteringStrategy, SIGNAL(currentIndexChanged(int)), _ui->stackedWidget_odometryFiltering, SLOT(setCurrentIndex(int)));
00810 _ui->spinBox_particleSize->setObjectName(Parameters::kOdomParticleSize().c_str());
00811 _ui->doubleSpinBox_particleNoiseT->setObjectName(Parameters::kOdomParticleNoiseT().c_str());
00812 _ui->doubleSpinBox_particleLambdaT->setObjectName(Parameters::kOdomParticleLambdaT().c_str());
00813 _ui->doubleSpinBox_particleNoiseR->setObjectName(Parameters::kOdomParticleNoiseR().c_str());
00814 _ui->doubleSpinBox_particleLambdaR->setObjectName(Parameters::kOdomParticleLambdaR().c_str());
00815
00816
00817 _ui->doubleSpinBox_kalmanProcessNoise->setObjectName(Parameters::kOdomKalmanProcessNoise().c_str());
00818 _ui->doubleSpinBox_kalmanMeasurementNoise->setObjectName(Parameters::kOdomKalmanMeasurementNoise().c_str());
00819
00820
00821 _ui->stereo_winWidth->setObjectName(Parameters::kStereoWinWidth().c_str());
00822 _ui->stereo_winHeight->setObjectName(Parameters::kStereoWinHeight().c_str());
00823 _ui->stereo_maxLevel->setObjectName(Parameters::kStereoMaxLevel().c_str());
00824 _ui->stereo_iterations->setObjectName(Parameters::kStereoIterations().c_str());
00825 _ui->stereo_minDisparity->setObjectName(Parameters::kStereoMinDisparity().c_str());
00826 _ui->stereo_maxDisparity->setObjectName(Parameters::kStereoMaxDisparity().c_str());
00827 _ui->stereo_ssd->setObjectName(Parameters::kStereoSSD().c_str());
00828 _ui->stereo_flow_eps->setObjectName(Parameters::kStereoEps().c_str());
00829 _ui->stereo_opticalFlow->setObjectName(Parameters::kStereoOpticalFlow().c_str());
00830
00831
00832 _ui->stereobm_blockSize->setObjectName(Parameters::kStereoBMBlockSize().c_str());
00833 _ui->stereobm_minDisparity->setObjectName(Parameters::kStereoBMMinDisparity().c_str());
00834 _ui->stereobm_numDisparities->setObjectName(Parameters::kStereoBMNumDisparities().c_str());
00835 _ui->stereobm_preFilterCap->setObjectName(Parameters::kStereoBMPreFilterCap().c_str());
00836 _ui->stereobm_preFilterSize->setObjectName(Parameters::kStereoBMPreFilterSize().c_str());
00837 _ui->stereobm_speckleRange->setObjectName(Parameters::kStereoBMSpeckleRange().c_str());
00838 _ui->stereobm_speckleWinSize->setObjectName(Parameters::kStereoBMSpeckleWindowSize().c_str());
00839 _ui->stereobm_tetureThreshold->setObjectName(Parameters::kStereoBMTextureThreshold().c_str());
00840 _ui->stereobm_uniquessRatio->setObjectName(Parameters::kStereoBMUniquenessRatio().c_str());
00841
00842
00843 resetSettings(_ui->groupBox_generalSettingsGui0);
00844 resetSettings(_ui->groupBox_cloudRendering1);
00845 resetSettings(_ui->groupBox_filtering2);
00846 resetSettings(_ui->groupBox_gridMap2);
00847 resetSettings(_ui->groupBox_logging1);
00848 resetSettings(_ui->groupBox_source0);
00849
00850 setupSignals();
00851
00852 connect(_ui->doubleSpinBox_kp_roi0, SIGNAL(valueChanged(double)), this, SLOT(updateKpROI()));
00853 connect(_ui->doubleSpinBox_kp_roi1, SIGNAL(valueChanged(double)), this, SLOT(updateKpROI()));
00854 connect(_ui->doubleSpinBox_kp_roi2, SIGNAL(valueChanged(double)), this, SLOT(updateKpROI()));
00855 connect(_ui->doubleSpinBox_kp_roi3, SIGNAL(valueChanged(double)), this, SLOT(updateKpROI()));
00856 connect(_ui->graphOptimization_type, SIGNAL(currentIndexChanged(int)), this, SLOT(updateG2oVisibility()));
00857 connect(_ui->checkBox_useOdomFeatures, SIGNAL(toggled(bool)), this, SLOT(useOdomFeatures()));
00858
00859
00860
00861 _ui->stackedWidget->setCurrentIndex(0);
00862 this->setupTreeView();
00863
00864 _obsoletePanels = kPanelAll;
00865 }
00866
00867 PreferencesDialog::~PreferencesDialog() {
00868
00869 QFile::remove(getTmpIniFilePath());
00870 delete _ui;
00871 }
00872
00873 void PreferencesDialog::init()
00874 {
00875 UDEBUG("");
00876
00877 const ParametersMap & defaults = Parameters::getDefaultParameters();
00878 for(ParametersMap::const_iterator iter=defaults.begin(); iter!=defaults.end(); ++iter)
00879 {
00880 this->setParameter(iter->first, iter->second);
00881 }
00882
00883 this->readSettings();
00884 this->writeSettings(getTmpIniFilePath());
00885
00886 _initialized = true;
00887 }
00888
00889 void PreferencesDialog::setCurrentPanelToSource()
00890 {
00891 QList<QGroupBox*> boxes = this->getGroupBoxes();
00892 for(int i =0;i<boxes.size();++i)
00893 {
00894 if(boxes[i] == _ui->groupBox_source0)
00895 {
00896 _ui->stackedWidget->setCurrentIndex(i);
00897 _ui->treeView->setCurrentIndex(_indexModel->index(i-2, 0));
00898 break;
00899 }
00900 }
00901 }
00902
00903 void PreferencesDialog::saveSettings()
00904 {
00905 writeSettings();
00906 }
00907
00908 void PreferencesDialog::setupTreeView()
00909 {
00910 if(_indexModel)
00911 {
00912 _ui->treeView->setModel(0);
00913 delete _indexModel;
00914 }
00915 _indexModel = new QStandardItemModel(this);
00916
00917 QList<QGroupBox*> boxes = this->getGroupBoxes();
00918 if(_ui->radioButton_basic->isChecked())
00919 {
00920 boxes = boxes.mid(0,7);
00921 }
00922 else
00923 {
00924 boxes.removeAt(6);
00925 }
00926
00927 QStandardItem * parentItem = _indexModel->invisibleRootItem();
00928 int index = 0;
00929 this->parseModel(boxes, parentItem, 0, index);
00930 if(_ui->radioButton_advanced->isChecked() && index != _ui->stackedWidget->count()-1)
00931 {
00932 ULOGGER_ERROR("The tree model is not the same size of the stacked widgets...%d vs %d advanced stacks", index, _ui->stackedWidget->count()-1);
00933 }
00934 int currentIndex = _ui->stackedWidget->currentIndex();
00935 if(_ui->radioButton_basic->isChecked())
00936 {
00937 if(currentIndex >= 6)
00938 {
00939 _ui->stackedWidget->setCurrentIndex(6);
00940 currentIndex = 6;
00941 }
00942 }
00943 else
00944 {
00945 if(currentIndex == 6)
00946 {
00947 _ui->stackedWidget->setCurrentIndex(7);
00948 }
00949 }
00950 _ui->treeView->setModel(_indexModel);
00951 _ui->treeView->expandToDepth(1);
00952
00953
00954 connect(_ui->treeView->selectionModel(), SIGNAL(currentChanged(const QModelIndex &, const QModelIndex &)), this, SLOT(clicked(const QModelIndex &, const QModelIndex &)));
00955 }
00956
00957
00958 bool PreferencesDialog::parseModel(QList<QGroupBox*> & boxes, QStandardItem * parentItem, int currentLevel, int & absoluteIndex)
00959 {
00960 if(parentItem == 0)
00961 {
00962 ULOGGER_ERROR("Parent item is null !");
00963 return false;
00964 }
00965
00966 QStandardItem * currentItem = 0;
00967 while(absoluteIndex < boxes.size())
00968 {
00969 QString objectName = boxes.at(absoluteIndex)->objectName();
00970 QString title = boxes.at(absoluteIndex)->title();
00971 bool ok = false;
00972 int lvl = QString(objectName.at(objectName.size()-1)).toInt(&ok);
00973 if(!ok)
00974 {
00975 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());
00976 return false;
00977 }
00978
00979
00980 if(lvl == currentLevel)
00981 {
00982 QStandardItem * item = new QStandardItem(title);
00983 item->setData(absoluteIndex);
00984 currentItem = item;
00985
00986 parentItem->appendRow(item);
00987 ++absoluteIndex;
00988 }
00989 else if(lvl > currentLevel)
00990 {
00991 if(lvl>currentLevel+1)
00992 {
00993 ULOGGER_ERROR("Intermediary lvl doesn't exist, lvl %d to %d, indexes %d and %d", currentLevel, lvl, absoluteIndex-1, absoluteIndex);
00994 return false;
00995 }
00996 else
00997 {
00998 parseModel(boxes, currentItem, currentLevel+1, absoluteIndex);
00999 }
01000 }
01001 else
01002 {
01003 return false;
01004 }
01005 }
01006 return true;
01007 }
01008
01009 void PreferencesDialog::setupSignals()
01010 {
01011 const rtabmap::ParametersMap & parameters = Parameters::getDefaultParameters();
01012 for(rtabmap::ParametersMap::const_iterator iter=parameters.begin(); iter!=parameters.end(); ++iter)
01013 {
01014 QWidget * obj = _ui->stackedWidget->findChild<QWidget*>((*iter).first.c_str());
01015 if(obj)
01016 {
01017
01018 obj->setToolTip(tr("%1 (Default=\"%2\")").arg(iter->first.c_str()).arg(iter->second.c_str()));
01019
01020 QSpinBox * spin = qobject_cast<QSpinBox *>(obj);
01021 QDoubleSpinBox * doubleSpin = qobject_cast<QDoubleSpinBox *>(obj);
01022 QComboBox * combo = qobject_cast<QComboBox *>(obj);
01023 QCheckBox * check = qobject_cast<QCheckBox *>(obj);
01024 QRadioButton * radio = qobject_cast<QRadioButton *>(obj);
01025 QLineEdit * lineEdit = qobject_cast<QLineEdit *>(obj);
01026 QGroupBox * groupBox = qobject_cast<QGroupBox *>(obj);
01027 if(spin)
01028 {
01029 connect(spin, SIGNAL(valueChanged(int)), this, SLOT(addParameter(int)));
01030 }
01031 else if(doubleSpin)
01032 {
01033 connect(doubleSpin, SIGNAL(valueChanged(double)), this, SLOT(addParameter(double)));
01034 }
01035 else if(combo)
01036 {
01037 connect(combo, SIGNAL(currentIndexChanged(int)), this, SLOT(addParameter(int)));
01038 }
01039 else if(check)
01040 {
01041 connect(check, SIGNAL(toggled(bool)), this, SLOT(addParameter(bool)));
01042 }
01043 else if(radio)
01044 {
01045 connect(radio, SIGNAL(toggled(bool)), this, SLOT(addParameter(bool)));
01046 }
01047 else if(lineEdit)
01048 {
01049 connect(lineEdit, SIGNAL(textChanged(const QString &)), this, SLOT(addParameter(const QString &)));
01050 }
01051 else if(groupBox)
01052 {
01053 connect(groupBox, SIGNAL(clicked(bool)), this, SLOT(addParameter(bool)));
01054 }
01055 else
01056 {
01057 ULOGGER_WARN("QWidget called %s can't be cast to a supported widget", (*iter).first.c_str());
01058 }
01059 }
01060 else
01061 {
01062 ULOGGER_WARN("Can't find the related QWidget for parameter %s", (*iter).first.c_str());
01063 }
01064 }
01065 }
01066
01067 void PreferencesDialog::clicked(const QModelIndex & current, const QModelIndex & previous)
01068 {
01069 QStandardItem * item = _indexModel->itemFromIndex(current);
01070 if(item && item->isEnabled())
01071 {
01072 int index = item->data().toInt();
01073 if(_ui->radioButton_advanced->isChecked() && index >= 6)
01074 {
01075 ++index;
01076 }
01077 _ui->stackedWidget->setCurrentIndex(index);
01078 _ui->scrollArea->horizontalScrollBar()->setValue(0);
01079 _ui->scrollArea->verticalScrollBar()->setValue(0);
01080 }
01081 }
01082
01083 void PreferencesDialog::closeEvent(QCloseEvent *event)
01084 {
01085 UDEBUG("");
01086 _modifiedParameters.clear();
01087 _obsoletePanels = kPanelDummy;
01088 this->readGuiSettings(getTmpIniFilePath());
01089 this->readCameraSettings(getTmpIniFilePath());
01090 event->accept();
01091 }
01092
01093 void PreferencesDialog::closeDialog ( QAbstractButton * button )
01094 {
01095 UDEBUG("");
01096
01097 QDialogButtonBox::ButtonRole role = _ui->buttonBox_global->buttonRole(button);
01098 switch(role)
01099 {
01100 case QDialogButtonBox::RejectRole:
01101 _modifiedParameters.clear();
01102 _obsoletePanels = kPanelDummy;
01103 this->readGuiSettings(getTmpIniFilePath());
01104 this->readCameraSettings(getTmpIniFilePath());
01105 this->reject();
01106 break;
01107
01108 case QDialogButtonBox::AcceptRole:
01109 updateBasicParameter();
01110 if((_obsoletePanels & kPanelAll) || _modifiedParameters.size())
01111 {
01112 if(validateForm())
01113 {
01114 writeSettings(getTmpIniFilePath());
01115 this->accept();
01116 }
01117 }
01118 else
01119 {
01120 this->accept();
01121 }
01122 break;
01123
01124 default:
01125 break;
01126 }
01127 }
01128
01129 void PreferencesDialog::resetApply ( QAbstractButton * button )
01130 {
01131 QDialogButtonBox::ButtonRole role = _ui->buttonBox_local->buttonRole(button);
01132 switch(role)
01133 {
01134 case QDialogButtonBox::ApplyRole:
01135 updateBasicParameter();
01136 if(validateForm())
01137 {
01138 writeSettings(getTmpIniFilePath());
01139 }
01140 break;
01141
01142 case QDialogButtonBox::ResetRole:
01143 resetSettings(_ui->stackedWidget->currentIndex());
01144 break;
01145
01146 default:
01147 break;
01148 }
01149 }
01150
01151 void PreferencesDialog::resetSettings(QGroupBox * groupBox)
01152 {
01153 if(groupBox->objectName() == _ui->groupBox_generalSettingsGui0->objectName())
01154 {
01155 _ui->general_checkBox_imagesKept->setChecked(true);
01156 _ui->general_checkBox_cloudsKept->setChecked(true);
01157 _ui->checkBox_beep->setChecked(false);
01158 _ui->checkBox_stamps->setChecked(true);
01159 _ui->checkBox_notifyWhenNewGlobalPathIsReceived->setChecked(false);
01160 _ui->checkBox_verticalLayoutUsed->setChecked(true);
01161 _ui->checkBox_imageRejectedShown->setChecked(true);
01162 _ui->checkBox_imageHighestHypShown->setChecked(false);
01163 _ui->spinBox_odomQualityWarnThr->setValue(50);
01164 _ui->checkBox_posteriorGraphView->setChecked(true);
01165 }
01166 else if(groupBox->objectName() == _ui->groupBox_cloudRendering1->objectName())
01167 {
01168 for(int i=0; i<2; ++i)
01169 {
01170 _3dRenderingShowClouds[i]->setChecked(true);
01171 _3dRenderingDecimation[i]->setValue(4);
01172 _3dRenderingMaxDepth[i]->setValue(0.0);
01173 _3dRenderingMinDepth[i]->setValue(0.0);
01174 _3dRenderingShowScans[i]->setChecked(true);
01175 _3dRenderingShowFeatures[i]->setChecked(i==0?false:true);
01176
01177 _3dRenderingDownsamplingScan[i]->setValue(1);
01178 _3dRenderingVoxelSizeScan[i]->setValue(0.0);
01179 _3dRenderingOpacity[i]->setValue(i==0?1.0:0.75);
01180 _3dRenderingPtSize[i]->setValue(2);
01181 _3dRenderingOpacityScan[i]->setValue(i==0?1.0:0.5);
01182 _3dRenderingPtSizeScan[i]->setValue(2);
01183 _3dRenderingPtSizeFeatures[i]->setValue(3);
01184 }
01185 _ui->doubleSpinBox_voxel->setValue(0);
01186 _ui->doubleSpinBox_noiseRadius->setValue(0);
01187 _ui->spinBox_noiseMinNeighbors->setValue(5);
01188
01189 _ui->checkBox_showGraphs->setChecked(true);
01190 _ui->checkBox_showLabels->setChecked(false);
01191
01192 _ui->spinBox_normalKSearch->setValue(10);
01193
01194 _ui->doubleSpinBox_mesh_angleTolerance->setValue(15.0);
01195 #if PCL_VERSION_COMPARE(>=, 1, 7, 2)
01196 _ui->groupBox_organized->setChecked(false);
01197 _ui->checkBox_mesh_quad->setChecked(true);
01198 #else
01199 _ui->groupBox_organized->setChecked(false);
01200 _ui->checkBox_mesh_quad->setChecked(false);
01201 #endif
01202 _ui->spinBox_mesh_triangleSize->setValue(2);
01203 }
01204 else if(groupBox->objectName() == _ui->groupBox_filtering2->objectName())
01205 {
01206 _ui->radioButton_noFiltering->setChecked(true);
01207 _ui->radioButton_nodeFiltering->setChecked(false);
01208 _ui->radioButton_subtractFiltering->setChecked(false);
01209 _ui->doubleSpinBox_cloudFilterRadius->setValue(0.1);
01210 _ui->doubleSpinBox_cloudFilterAngle->setValue(30);
01211 _ui->spinBox_subtractFilteringMinPts->setValue(5);
01212 _ui->doubleSpinBox_subtractFilteringRadius->setValue(0.02);
01213 _ui->doubleSpinBox_subtractFilteringAngle->setValue(0);
01214 }
01215 else if(groupBox->objectName() == _ui->groupBox_gridMap2->objectName())
01216 {
01217 _ui->checkBox_map_shown->setChecked(false);
01218 _ui->doubleSpinBox_map_resolution->setValue(0.05);
01219 _ui->checkBox_map_erode->setChecked(false);
01220 _ui->doubleSpinBox_map_opacity->setValue(0.75);
01221 _ui->groupBox_map_occupancyFrom3DCloud->setChecked(false);
01222 _ui->checkBox_projMapFrame->setChecked(true);
01223 _ui->doubleSpinBox_projMaxGroundAngle->setValue(30);
01224 _ui->doubleSpinBox_projMaxGroundHeight->setValue(0);
01225 _ui->spinBox_projMinClusterSize->setValue(20);
01226 _ui->doubleSpinBox_projMaxObstaclesHeight->setValue(0);
01227 _ui->checkBox_projFlatObstaclesDetected->setChecked(true);
01228
01229 _ui->groupBox_octomap->setChecked(false);
01230 _ui->spinBox_octomap_treeDepth->setValue(16);
01231 _ui->checkBox_octomap_groundObstacle->setChecked(true);
01232 }
01233 else if(groupBox->objectName() == _ui->groupBox_logging1->objectName())
01234 {
01235 _ui->comboBox_loggerLevel->setCurrentIndex(2);
01236 _ui->comboBox_loggerEventLevel->setCurrentIndex(3);
01237 _ui->comboBox_loggerPauseLevel->setCurrentIndex(3);
01238 _ui->checkBox_logger_printTime->setChecked(true);
01239 _ui->checkBox_logger_printThreadId->setChecked(false);
01240 _ui->comboBox_loggerType->setCurrentIndex(1);
01241 }
01242 else if(groupBox->objectName() == _ui->groupBox_source0->objectName())
01243 {
01244 _ui->general_doubleSpinBox_imgRate->setValue(0.0);
01245 _ui->source_mirroring->setChecked(false);
01246 _ui->lineEdit_calibrationFile->clear();
01247 _ui->comboBox_sourceType->setCurrentIndex(kSrcRGBD);
01248 _ui->lineEdit_sourceDevice->setText("");
01249 _ui->lineEdit_sourceLocalTransform->setText("0 0 1 -1 0 0 0 -1 0");
01250
01251 _ui->source_comboBox_image_type->setCurrentIndex(kSrcUsbDevice-kSrcUsbDevice);
01252 _ui->source_images_spinBox_startPos->setValue(0);
01253 _ui->source_images_refreshDir->setChecked(false);
01254 _ui->checkBox_rgbImages_rectify->setChecked(false);
01255 _ui->comboBox_cameraImages_bayerMode->setCurrentIndex(0);
01256 _ui->checkBox_rgbVideo_rectify->setChecked(false);
01257
01258 _ui->source_checkBox_ignoreOdometry->setChecked(false);
01259 _ui->source_checkBox_ignoreGoalDelay->setChecked(true);
01260 _ui->source_checkBox_ignoreGoals->setChecked(true);
01261 _ui->source_spinBox_databaseStartPos->setValue(0);
01262 _ui->source_spinBox_database_cameraIndex->setValue(-1);
01263 _ui->source_checkBox_useDbStamps->setChecked(true);
01264
01265 #ifdef _WIN32
01266 _ui->comboBox_cameraRGBD->setCurrentIndex(kSrcOpenNI2-kSrcRGBD);
01267 #else
01268 if(CameraFreenect::available())
01269 {
01270 _ui->comboBox_cameraRGBD->setCurrentIndex(kSrcFreenect-kSrcRGBD);
01271 }
01272 else if(CameraOpenNI2::available())
01273 {
01274 _ui->comboBox_cameraRGBD->setCurrentIndex(kSrcOpenNI2-kSrcRGBD);
01275 }
01276 else
01277 {
01278 _ui->comboBox_cameraRGBD->setCurrentIndex(kSrcOpenNI_PCL-kSrcRGBD);
01279 }
01280 #endif
01281 if(CameraStereoDC1394::available())
01282 {
01283 _ui->comboBox_cameraStereo->setCurrentIndex(kSrcDC1394-kSrcStereo);
01284 }
01285 else if(CameraStereoFlyCapture2::available())
01286 {
01287 _ui->comboBox_cameraStereo->setCurrentIndex(kSrcFlyCapture2-kSrcStereo);
01288 }
01289 else
01290 {
01291 _ui->comboBox_cameraStereo->setCurrentIndex(kSrcStereoImages-kSrcStereo);
01292 }
01293
01294 _ui->checkbox_rgbd_colorOnly->setChecked(false);
01295 _ui->spinBox_source_imageDecimation->setValue(1);
01296 _ui->checkbox_stereo_depthGenerated->setChecked(false);
01297 _ui->openni2_autoWhiteBalance->setChecked(true);
01298 _ui->openni2_autoExposure->setChecked(true);
01299 _ui->openni2_exposure->setValue(0);
01300 _ui->openni2_gain->setValue(100);
01301 _ui->openni2_mirroring->setChecked(false);
01302 _ui->openni2_stampsIdsUsed->setChecked(false);
01303 _ui->comboBox_freenect2Format->setCurrentIndex(0);
01304 _ui->doubleSpinBox_freenect2MinDepth->setValue(0.3);
01305 _ui->doubleSpinBox_freenect2MaxDepth->setValue(12.0);
01306 _ui->checkBox_freenect2BilateralFiltering->setChecked(true);
01307 _ui->checkBox_freenect2EdgeAwareFiltering->setChecked(true);
01308 _ui->checkBox_freenect2NoiseFiltering->setChecked(true);
01309 _ui->lineEdit_openniOniPath->clear();
01310 _ui->lineEdit_openni2OniPath->clear();
01311 _ui->lineEdit_cameraRGBDImages_path_rgb->setText("");
01312 _ui->lineEdit_cameraRGBDImages_path_depth->setText("");
01313 _ui->doubleSpinBox_cameraRGBDImages_scale->setValue(1.0);
01314
01315 _ui->source_comboBox_image_type->setCurrentIndex(kSrcDC1394-kSrcDC1394);
01316 _ui->lineEdit_cameraStereoImages_path_left->setText("");
01317 _ui->lineEdit_cameraStereoImages_path_right->setText("");
01318 _ui->checkBox_stereoImages_rectify->setChecked(false);
01319 _ui->lineEdit_cameraStereoVideo_path->setText("");
01320 _ui->checkBox_stereoVideo_rectify->setChecked(false);
01321 _ui->comboBox_stereoZed_resolution->setCurrentIndex(2);
01322 _ui->comboBox_stereoZed_quality->setCurrentIndex(1);
01323 _ui->comboBox_stereoZed_sensingMode->setCurrentIndex(1);
01324 _ui->spinBox_stereoZed_confidenceThr->setValue(100);
01325 _ui->checkbox_stereoZed_odom->setChecked(false);
01326 _ui->lineEdit_zedSvoPath->clear();
01327
01328 _ui->checkBox_cameraImages_timestamps->setChecked(false);
01329 _ui->checkBox_cameraImages_syncTimeStamps->setChecked(true);
01330 _ui->lineEdit_cameraImages_timestamps->setText("");
01331 _ui->lineEdit_cameraImages_path_scans->setText("");
01332 _ui->lineEdit_cameraImages_laser_transform->setText("0 0 0 0 0 0");
01333 _ui->spinBox_cameraImages_max_scan_pts->setValue(0);
01334 _ui->spinBox_cameraImages_scanDownsampleStep->setValue(1);
01335 _ui->doubleSpinBox_cameraImages_scanVoxelSize->setValue(0.0f);
01336 _ui->lineEdit_cameraImages_gt->setText("");
01337 _ui->comboBox_cameraImages_gtFormat->setCurrentIndex(0);
01338
01339 _ui->groupBox_scanFromDepth->setChecked(false);
01340 _ui->spinBox_cameraScanFromDepth_decimation->setValue(8);
01341 _ui->doubleSpinBox_cameraSCanFromDepth_maxDepth->setValue(4.0);
01342 _ui->doubleSpinBox_cameraImages_scanVoxelSize->setValue(0.025f);
01343 _ui->spinBox_cameraImages_scanNormalsK->setValue(20);
01344
01345 _ui->groupBox_depthFromScan->setChecked(false);
01346 _ui->groupBox_depthFromScan_fillHoles->setChecked(true);
01347 _ui->radioButton_depthFromScan_vertical->setChecked(true);
01348 _ui->radioButton_depthFromScan_horizontal->setChecked(false);
01349 _ui->checkBox_depthFromScan_fillBorders->setChecked(false);
01350 }
01351 else if(groupBox->objectName() == _ui->groupBox_rtabmap_basic0->objectName())
01352 {
01353 _ui->general_doubleSpinBox_timeThr_2->setValue(Parameters::defaultRtabmapTimeThr());
01354 _ui->general_doubleSpinBox_hardThr_2->setValue(Parameters::defaultRtabmapLoopThr());
01355 _ui->doubleSpinBox_similarityThreshold_2->setValue(Parameters::defaultMemRehearsalSimilarity());
01356 _ui->general_spinBox_imagesBufferSize_2->setValue(Parameters::defaultRtabmapImageBufferSize());
01357 _ui->general_spinBox_maxStMemSize_2->setValue(Parameters::defaultMemSTMSize());
01358 _ui->general_checkBox_publishStats_2->setChecked(Parameters::defaultRtabmapPublishStats());
01359 _ui->general_checkBox_activateRGBD_2->setChecked(Parameters::defaultRGBDEnabled());
01360 _ui->general_checkBox_SLAM_mode_2->setChecked(Parameters::defaultMemIncrementalMemory());
01361 _ui->general_doubleSpinBox_detectionRate_2->setValue(Parameters::defaultRtabmapDetectionRate());
01362
01363 _ui->general_doubleSpinBox_timeThr->setValue(Parameters::defaultRtabmapTimeThr());
01364 _ui->general_doubleSpinBox_hardThr->setValue(Parameters::defaultRtabmapLoopThr());
01365 _ui->doubleSpinBox_similarityThreshold->setValue(Parameters::defaultMemRehearsalSimilarity());
01366 _ui->general_spinBox_imagesBufferSize->setValue(Parameters::defaultRtabmapImageBufferSize());
01367 _ui->general_spinBox_maxStMemSize->setValue(Parameters::defaultMemSTMSize());
01368 _ui->general_doubleSpinBox_detectionRate->setValue(Parameters::defaultRtabmapDetectionRate());
01369 }
01370 else
01371 {
01372 QObjectList children = groupBox->children();
01373 rtabmap::ParametersMap defaults = Parameters::getDefaultParameters();
01374 std::string key;
01375 for(int i=0; i<children.size(); ++i)
01376 {
01377 key = children.at(i)->objectName().toStdString();
01378 if(uContains(defaults, key))
01379 {
01380 if(key.compare(Parameters::kRtabmapWorkingDirectory().c_str()) == 0)
01381 {
01382 this->setParameter(key, Parameters::createDefaultWorkingDirectory());
01383 }
01384 else
01385 {
01386 this->setParameter(key, defaults.at(key));
01387 }
01388 if(qobject_cast<const QGroupBox*>(children.at(i)))
01389 {
01390 this->resetSettings((QGroupBox*)children.at(i));
01391 }
01392 }
01393 else if(qobject_cast<const QGroupBox*>(children.at(i)))
01394 {
01395 this->resetSettings((QGroupBox*)children.at(i));
01396 }
01397 else if(qobject_cast<const QStackedWidget*>(children.at(i)))
01398 {
01399 QStackedWidget * stackedWidget = (QStackedWidget*)children.at(i);
01400 for(int j=0; j<stackedWidget->count(); ++j)
01401 {
01402 const QObjectList & children2 = stackedWidget->widget(j)->children();
01403 for(int k=0; k<children2.size(); ++k)
01404 {
01405 if(qobject_cast<QGroupBox *>(children2.at(k)))
01406 {
01407 this->resetSettings((QGroupBox*)children2.at(k));
01408 }
01409 }
01410 }
01411 }
01412 }
01413
01414 if(groupBox->findChild<QLineEdit*>(_ui->lineEdit_kp_roi->objectName()))
01415 {
01416 this->setupKpRoiPanel();
01417 }
01418 }
01419 }
01420
01421 void PreferencesDialog::resetSettings(int panelNumber)
01422 {
01423 QList<QGroupBox*> boxes = this->getGroupBoxes();
01424 if(panelNumber >= 0 && panelNumber < boxes.size())
01425 {
01426 this->resetSettings(boxes.at(panelNumber));
01427 }
01428 else if(panelNumber == -1)
01429 {
01430 for(QList<QGroupBox*>::iterator iter = boxes.begin(); iter!=boxes.end(); ++iter)
01431 {
01432 this->resetSettings(*iter);
01433 }
01434 }
01435 else
01436 {
01437 ULOGGER_WARN("panel number and the number of stacked widget doesn't match");
01438 }
01439
01440 }
01441
01442 QString PreferencesDialog::getWorkingDirectory() const
01443 {
01444 return _ui->lineEdit_workingDirectory->text();
01445 }
01446
01447 QString PreferencesDialog::getIniFilePath() const
01448 {
01449 QString privatePath = QDir::homePath() + "/.rtabmap";
01450 if(!QDir(privatePath).exists())
01451 {
01452 QDir::home().mkdir(".rtabmap");
01453 }
01454 return privatePath + "/rtabmap.ini";
01455 }
01456
01457 QString PreferencesDialog::getTmpIniFilePath() const
01458 {
01459 return getIniFilePath()+".tmp";
01460 }
01461
01462 void PreferencesDialog::loadConfigFrom()
01463 {
01464 QString path = QFileDialog::getOpenFileName(this, tr("Load settings..."), this->getWorkingDirectory(), "*.ini");
01465 if(!path.isEmpty())
01466 {
01467 this->readSettings(path);
01468 }
01469 }
01470
01471 void PreferencesDialog::readSettings(const QString & filePath)
01472 {
01473 ULOGGER_DEBUG("%s", filePath.toStdString().c_str());
01474 readGuiSettings(filePath);
01475 readCameraSettings(filePath);
01476 if(!readCoreSettings(filePath))
01477 {
01478 _modifiedParameters.clear();
01479 _obsoletePanels = kPanelDummy;
01480
01481
01482 QStandardItem * parentItem = _indexModel->invisibleRootItem();
01483 if(parentItem)
01484 {
01485 for(int i=1; i<parentItem->rowCount(); ++i)
01486 {
01487 parentItem->child(i)->setEnabled(false);
01488 }
01489 }
01490 _ui->radioButton_basic->setEnabled(false);
01491 _ui->radioButton_advanced->setEnabled(false);
01492 }
01493 else
01494 {
01495
01496 QStandardItem * parentItem = _indexModel->invisibleRootItem();
01497 if(parentItem)
01498 {
01499 for(int i=0; i<parentItem->rowCount(); ++i)
01500 {
01501 parentItem->child(i)->setEnabled(true);
01502 }
01503 }
01504 _ui->radioButton_basic->setEnabled(true);
01505 _ui->radioButton_advanced->setEnabled(true);
01506 }
01507 }
01508
01509 void PreferencesDialog::readGuiSettings(const QString & filePath)
01510 {
01511 QString path = getIniFilePath();
01512 if(!filePath.isEmpty())
01513 {
01514 path = filePath;
01515 }
01516 QSettings settings(path, QSettings::IniFormat);
01517 settings.beginGroup("Gui");
01518 settings.beginGroup("General");
01519 _ui->general_checkBox_imagesKept->setChecked(settings.value("imagesKept", _ui->general_checkBox_imagesKept->isChecked()).toBool());
01520 _ui->general_checkBox_cloudsKept->setChecked(settings.value("cloudsKept", _ui->general_checkBox_cloudsKept->isChecked()).toBool());
01521 _ui->comboBox_loggerLevel->setCurrentIndex(settings.value("loggerLevel", _ui->comboBox_loggerLevel->currentIndex()).toInt());
01522 _ui->comboBox_loggerEventLevel->setCurrentIndex(settings.value("loggerEventLevel", _ui->comboBox_loggerEventLevel->currentIndex()).toInt());
01523 _ui->comboBox_loggerPauseLevel->setCurrentIndex(settings.value("loggerPauseLevel", _ui->comboBox_loggerPauseLevel->currentIndex()).toInt());
01524 _ui->comboBox_loggerType->setCurrentIndex(settings.value("loggerType", _ui->comboBox_loggerType->currentIndex()).toInt());
01525 _ui->checkBox_logger_printTime->setChecked(settings.value("loggerPrintTime", _ui->checkBox_logger_printTime->isChecked()).toBool());
01526 _ui->checkBox_logger_printThreadId->setChecked(settings.value("loggerPrintThreadId", _ui->checkBox_logger_printThreadId->isChecked()).toBool());
01527 _ui->checkBox_verticalLayoutUsed->setChecked(settings.value("verticalLayoutUsed", _ui->checkBox_verticalLayoutUsed->isChecked()).toBool());
01528 _ui->checkBox_imageRejectedShown->setChecked(settings.value("imageRejectedShown", _ui->checkBox_imageRejectedShown->isChecked()).toBool());
01529 _ui->checkBox_imageHighestHypShown->setChecked(settings.value("imageHighestHypShown", _ui->checkBox_imageHighestHypShown->isChecked()).toBool());
01530 _ui->checkBox_beep->setChecked(settings.value("beep", _ui->checkBox_beep->isChecked()).toBool());
01531 _ui->checkBox_stamps->setChecked(settings.value("figure_time", _ui->checkBox_stamps->isChecked()).toBool());
01532 _ui->checkBox_notifyWhenNewGlobalPathIsReceived->setChecked(settings.value("notifyNewGlobalPath", _ui->checkBox_notifyWhenNewGlobalPathIsReceived->isChecked()).toBool());
01533 _ui->spinBox_odomQualityWarnThr->setValue(settings.value("odomQualityThr", _ui->spinBox_odomQualityWarnThr->value()).toInt());
01534 _ui->checkBox_posteriorGraphView->setChecked(settings.value("posteriorGraphView", _ui->checkBox_posteriorGraphView->isChecked()).toBool());
01535
01536 for(int i=0; i<2; ++i)
01537 {
01538 _3dRenderingShowClouds[i]->setChecked(settings.value(QString("showClouds%1").arg(i), _3dRenderingShowClouds[i]->isChecked()).toBool());
01539 _3dRenderingDecimation[i]->setValue(settings.value(QString("decimation%1").arg(i), _3dRenderingDecimation[i]->value()).toInt());
01540 _3dRenderingMaxDepth[i]->setValue(settings.value(QString("maxDepth%1").arg(i), _3dRenderingMaxDepth[i]->value()).toDouble());
01541 _3dRenderingMinDepth[i]->setValue(settings.value(QString("minDepth%1").arg(i), _3dRenderingMinDepth[i]->value()).toDouble());
01542 _3dRenderingShowScans[i]->setChecked(settings.value(QString("showScans%1").arg(i), _3dRenderingShowScans[i]->isChecked()).toBool());
01543 _3dRenderingShowFeatures[i]->setChecked(settings.value(QString("showFeatures%1").arg(i), _3dRenderingShowFeatures[i]->isChecked()).toBool());
01544
01545 _3dRenderingDownsamplingScan[i]->setValue(settings.value(QString("downsamplingScan%1").arg(i), _3dRenderingDownsamplingScan[i]->value()).toInt());
01546 _3dRenderingVoxelSizeScan[i]->setValue(settings.value(QString("voxelSizeScan%1").arg(i), _3dRenderingVoxelSizeScan[i]->value()).toDouble());
01547 _3dRenderingOpacity[i]->setValue(settings.value(QString("opacity%1").arg(i), _3dRenderingOpacity[i]->value()).toDouble());
01548 _3dRenderingPtSize[i]->setValue(settings.value(QString("ptSize%1").arg(i), _3dRenderingPtSize[i]->value()).toInt());
01549 _3dRenderingOpacityScan[i]->setValue(settings.value(QString("opacityScan%1").arg(i), _3dRenderingOpacityScan[i]->value()).toDouble());
01550 _3dRenderingPtSizeScan[i]->setValue(settings.value(QString("ptSizeScan%1").arg(i), _3dRenderingPtSizeScan[i]->value()).toInt());
01551 _3dRenderingPtSizeFeatures[i]->setValue(settings.value(QString("ptSizeFeatures%1").arg(i), _3dRenderingPtSizeFeatures[i]->value()).toInt());
01552 }
01553 _ui->doubleSpinBox_voxel->setValue(settings.value("cloudVoxel", _ui->doubleSpinBox_voxel->value()).toDouble());
01554 _ui->doubleSpinBox_noiseRadius->setValue(settings.value("cloudNoiseRadius", _ui->doubleSpinBox_noiseRadius->value()).toDouble());
01555 _ui->spinBox_noiseMinNeighbors->setValue(settings.value("cloudNoiseMinNeighbors", _ui->spinBox_noiseMinNeighbors->value()).toInt());
01556
01557 _ui->checkBox_showGraphs->setChecked(settings.value("showGraphs", _ui->checkBox_showGraphs->isChecked()).toBool());
01558 _ui->checkBox_showLabels->setChecked(settings.value("showLabels", _ui->checkBox_showLabels->isChecked()).toBool());
01559
01560 _ui->radioButton_noFiltering->setChecked(settings.value("noFiltering", _ui->radioButton_noFiltering->isChecked()).toBool());
01561 _ui->radioButton_nodeFiltering->setChecked(settings.value("cloudFiltering", _ui->radioButton_nodeFiltering->isChecked()).toBool());
01562 _ui->doubleSpinBox_cloudFilterRadius->setValue(settings.value("cloudFilteringRadius", _ui->doubleSpinBox_cloudFilterRadius->value()).toDouble());
01563 _ui->doubleSpinBox_cloudFilterAngle->setValue(settings.value("cloudFilteringAngle", _ui->doubleSpinBox_cloudFilterAngle->value()).toDouble());
01564 _ui->radioButton_subtractFiltering->setChecked(settings.value("subtractFiltering", _ui->radioButton_subtractFiltering->isChecked()).toBool());
01565 _ui->spinBox_subtractFilteringMinPts->setValue(settings.value("subtractFilteringMinPts", _ui->spinBox_subtractFilteringMinPts->value()).toInt());
01566 _ui->doubleSpinBox_subtractFilteringRadius->setValue(settings.value("subtractFilteringRadius", _ui->doubleSpinBox_subtractFilteringRadius->value()).toDouble());
01567 _ui->doubleSpinBox_subtractFilteringAngle->setValue(settings.value("subtractFilteringAngle", _ui->doubleSpinBox_subtractFilteringAngle->value()).toDouble());
01568 _ui->spinBox_normalKSearch->setValue(settings.value("normalKSearch", _ui->spinBox_normalKSearch->value()).toInt());
01569
01570 _ui->checkBox_map_shown->setChecked(settings.value("gridMapShown", _ui->checkBox_map_shown->isChecked()).toBool());
01571 _ui->doubleSpinBox_map_resolution->setValue(settings.value("gridMapResolution", _ui->doubleSpinBox_map_resolution->value()).toDouble());
01572 _ui->checkBox_map_erode->setChecked(settings.value("gridMapEroded", _ui->checkBox_map_erode->isChecked()).toBool());
01573 _ui->doubleSpinBox_map_opacity->setValue(settings.value("gridMapOpacity", _ui->doubleSpinBox_map_opacity->value()).toDouble());
01574 _ui->groupBox_map_occupancyFrom3DCloud->setChecked(settings.value("gridMapOccupancyFrom3DCloud", _ui->groupBox_map_occupancyFrom3DCloud->isChecked()).toBool());
01575 _ui->checkBox_projMapFrame->setChecked(settings.value("projMapFrame", _ui->checkBox_projMapFrame->isChecked()).toBool());
01576 _ui->doubleSpinBox_projMaxGroundAngle->setValue(settings.value("projMaxGroundAngle", _ui->doubleSpinBox_projMaxGroundAngle->value()).toDouble());
01577 _ui->doubleSpinBox_projMaxGroundHeight->setValue(settings.value("projMaxGroundHeight", _ui->doubleSpinBox_projMaxGroundHeight->value()).toDouble());
01578 _ui->spinBox_projMinClusterSize->setValue(settings.value("projMinClusterSize", _ui->spinBox_projMinClusterSize->value()).toInt());
01579 _ui->doubleSpinBox_projMaxObstaclesHeight->setValue(settings.value("projMaxObstaclesHeight", _ui->doubleSpinBox_projMaxObstaclesHeight->value()).toDouble());
01580 _ui->checkBox_projFlatObstaclesDetected->setChecked(settings.value("projFlatObstaclesDetected", _ui->checkBox_projFlatObstaclesDetected->isChecked()).toBool());
01581
01582 _ui->groupBox_octomap->setChecked(settings.value("octomap", _ui->groupBox_octomap->isChecked()).toBool());
01583 _ui->spinBox_octomap_treeDepth->setValue(settings.value("octomap_depth", _ui->spinBox_octomap_treeDepth->value()).toInt());
01584 _ui->checkBox_octomap_groundObstacle->setChecked(settings.value("octomap_ground_is_obstacle", _ui->checkBox_octomap_groundObstacle->isChecked()).toBool());
01585
01586 _ui->groupBox_organized->setChecked(settings.value("meshing", _ui->groupBox_organized->isChecked()).toBool());
01587 _ui->doubleSpinBox_mesh_angleTolerance->setValue(settings.value("meshing_angle", _ui->doubleSpinBox_mesh_angleTolerance->value()).toDouble());
01588 _ui->checkBox_mesh_quad->setChecked(settings.value("meshing_quad", _ui->checkBox_mesh_quad->isChecked()).toBool());
01589 _ui->spinBox_mesh_triangleSize->setValue(settings.value("meshing_triangle_size", _ui->spinBox_mesh_triangleSize->value()).toInt());
01590
01591 settings.endGroup();
01592
01593 settings.endGroup();
01594 }
01595
01596 void PreferencesDialog::readCameraSettings(const QString & filePath)
01597 {
01598 QString path = getIniFilePath();
01599 if(!filePath.isEmpty())
01600 {
01601 path = filePath;
01602 }
01603 QSettings settings(path, QSettings::IniFormat);
01604
01605 settings.beginGroup("Camera");
01606 _ui->general_doubleSpinBox_imgRate->setValue(settings.value("imgRate", _ui->general_doubleSpinBox_imgRate->value()).toDouble());
01607 _ui->source_mirroring->setChecked(settings.value("mirroring", _ui->source_mirroring->isChecked()).toBool());
01608 _ui->lineEdit_calibrationFile->setText(settings.value("calibrationName", _ui->lineEdit_calibrationFile->text()).toString());
01609 _ui->comboBox_sourceType->setCurrentIndex(settings.value("type", _ui->comboBox_sourceType->currentIndex()).toInt());
01610 _ui->lineEdit_sourceDevice->setText(settings.value("device",_ui->lineEdit_sourceDevice->text()).toString());
01611 _ui->lineEdit_sourceLocalTransform->setText(settings.value("localTransform",_ui->lineEdit_sourceLocalTransform->text()).toString());
01612 _ui->spinBox_source_imageDecimation->setValue(settings.value("imageDecimation",_ui->spinBox_source_imageDecimation->value()).toInt());
01613
01614 settings.beginGroup("rgbd");
01615 _ui->comboBox_cameraRGBD->setCurrentIndex(settings.value("driver", _ui->comboBox_cameraRGBD->currentIndex()).toInt());
01616 _ui->checkbox_rgbd_colorOnly->setChecked(settings.value("rgbdColorOnly", _ui->checkbox_rgbd_colorOnly->isChecked()).toBool());
01617 settings.endGroup();
01618
01619 settings.beginGroup("stereo");
01620 _ui->comboBox_cameraStereo->setCurrentIndex(settings.value("driver", _ui->comboBox_cameraStereo->currentIndex()).toInt());
01621 _ui->checkbox_stereo_depthGenerated->setChecked(settings.value("depthGenerated", _ui->checkbox_stereo_depthGenerated->isChecked()).toBool());
01622 settings.endGroup();
01623
01624 settings.beginGroup("rgb");
01625 _ui->source_comboBox_image_type->setCurrentIndex(settings.value("driver", _ui->source_comboBox_image_type->currentIndex()).toInt());
01626 settings.endGroup();
01627
01628 settings.beginGroup("Openni");
01629 _ui->lineEdit_openniOniPath->setText(settings.value("oniPath", _ui->lineEdit_openniOniPath->text()).toString());
01630 settings.endGroup();
01631
01632 settings.beginGroup("Openni2");
01633 _ui->openni2_autoWhiteBalance->setChecked(settings.value("autoWhiteBalance", _ui->openni2_autoWhiteBalance->isChecked()).toBool());
01634 _ui->openni2_autoExposure->setChecked(settings.value("autoExposure", _ui->openni2_autoExposure->isChecked()).toBool());
01635 _ui->openni2_exposure->setValue(settings.value("exposure", _ui->openni2_exposure->value()).toInt());
01636 _ui->openni2_gain->setValue(settings.value("gain", _ui->openni2_gain->value()).toInt());
01637 _ui->openni2_mirroring->setChecked(settings.value("mirroring", _ui->openni2_mirroring->isChecked()).toBool());
01638 _ui->openni2_stampsIdsUsed->setChecked(settings.value("stampsIdsUsed", _ui->openni2_stampsIdsUsed->isChecked()).toBool());
01639 _ui->lineEdit_openni2OniPath->setText(settings.value("oniPath", _ui->lineEdit_openni2OniPath->text()).toString());
01640 settings.endGroup();
01641
01642 settings.beginGroup("Freenect2");
01643 _ui->comboBox_freenect2Format->setCurrentIndex(settings.value("format", _ui->comboBox_freenect2Format->currentIndex()).toInt());
01644 _ui->doubleSpinBox_freenect2MinDepth->setValue(settings.value("minDepth", _ui->doubleSpinBox_freenect2MinDepth->value()).toDouble());
01645 _ui->doubleSpinBox_freenect2MaxDepth->setValue(settings.value("maxDepth", _ui->doubleSpinBox_freenect2MaxDepth->value()).toDouble());
01646 _ui->checkBox_freenect2BilateralFiltering->setChecked(settings.value("bilateralFiltering", _ui->checkBox_freenect2BilateralFiltering->isChecked()).toBool());
01647 _ui->checkBox_freenect2EdgeAwareFiltering->setChecked(settings.value("edgeAwareFiltering", _ui->checkBox_freenect2EdgeAwareFiltering->isChecked()).toBool());
01648 _ui->checkBox_freenect2NoiseFiltering->setChecked(settings.value("noiseFiltering", _ui->checkBox_freenect2NoiseFiltering->isChecked()).toBool());
01649 settings.endGroup();
01650
01651 settings.beginGroup("RGBDImages");
01652 _ui->lineEdit_cameraRGBDImages_path_rgb->setText(settings.value("path_rgb", _ui->lineEdit_cameraRGBDImages_path_rgb->text()).toString());
01653 _ui->lineEdit_cameraRGBDImages_path_depth->setText(settings.value("path_depth", _ui->lineEdit_cameraRGBDImages_path_depth->text()).toString());
01654 _ui->doubleSpinBox_cameraRGBDImages_scale->setValue(settings.value("scale", _ui->doubleSpinBox_cameraRGBDImages_scale->value()).toDouble());
01655 settings.endGroup();
01656
01657 settings.beginGroup("StereoImages");
01658 _ui->lineEdit_cameraStereoImages_path_left->setText(settings.value("path_left", _ui->lineEdit_cameraStereoImages_path_left->text()).toString());
01659 _ui->lineEdit_cameraStereoImages_path_right->setText(settings.value("path_right", _ui->lineEdit_cameraStereoImages_path_right->text()).toString());
01660 _ui->checkBox_stereoImages_rectify->setChecked(settings.value("rectify",_ui->checkBox_stereoImages_rectify->isChecked()).toBool());
01661 settings.endGroup();
01662
01663 settings.beginGroup("StereoVideo");
01664 _ui->lineEdit_cameraStereoVideo_path->setText(settings.value("path", _ui->lineEdit_cameraStereoVideo_path->text()).toString());
01665 _ui->checkBox_stereoVideo_rectify->setChecked(settings.value("rectify",_ui->checkBox_stereoVideo_rectify->isChecked()).toBool());
01666 settings.endGroup();
01667
01668 settings.beginGroup("StereoZed");
01669 _ui->comboBox_stereoZed_resolution->setCurrentIndex(settings.value("resolution", _ui->comboBox_stereoZed_resolution->currentIndex()).toInt());
01670 _ui->comboBox_stereoZed_quality->setCurrentIndex(settings.value("quality", _ui->comboBox_stereoZed_quality->currentIndex()).toInt());
01671 _ui->comboBox_stereoZed_sensingMode->setCurrentIndex(settings.value("sensing_mode", _ui->comboBox_stereoZed_sensingMode->currentIndex()).toInt());
01672 _ui->spinBox_stereoZed_confidenceThr->setValue(settings.value("confidence_thr", _ui->spinBox_stereoZed_confidenceThr->value()).toInt());
01673 _ui->checkbox_stereoZed_odom->setChecked(settings.value("odom", _ui->checkbox_stereoZed_odom->isChecked()).toBool());
01674 _ui->lineEdit_zedSvoPath->setText(settings.value("svo_path", _ui->lineEdit_zedSvoPath->text()).toString());
01675 settings.endGroup();
01676
01677
01678 settings.beginGroup("Images");
01679 _ui->source_images_lineEdit_path->setText(settings.value("path", _ui->source_images_lineEdit_path->text()).toString());
01680 _ui->source_images_spinBox_startPos->setValue(settings.value("startPos",_ui->source_images_spinBox_startPos->value()).toInt());
01681 _ui->source_images_refreshDir->setChecked(settings.value("refreshDir",_ui->source_images_refreshDir->isChecked()).toBool());
01682 _ui->checkBox_rgbImages_rectify->setChecked(settings.value("rectify",_ui->checkBox_rgbImages_rectify->isChecked()).toBool());
01683 _ui->comboBox_cameraImages_bayerMode->setCurrentIndex(settings.value("bayerMode",_ui->comboBox_cameraImages_bayerMode->currentIndex()).toInt());
01684
01685 _ui->checkBox_cameraImages_timestamps->setChecked(settings.value("filenames_as_stamps",_ui->checkBox_cameraImages_timestamps->isChecked()).toBool());
01686 _ui->checkBox_cameraImages_syncTimeStamps->setChecked(settings.value("sync_stamps",_ui->checkBox_cameraImages_syncTimeStamps->isChecked()).toBool());
01687 _ui->lineEdit_cameraImages_timestamps->setText(settings.value("stamps", _ui->lineEdit_cameraImages_timestamps->text()).toString());
01688 _ui->lineEdit_cameraImages_path_scans->setText(settings.value("path_scans", _ui->lineEdit_cameraImages_path_scans->text()).toString());
01689 _ui->lineEdit_cameraImages_laser_transform->setText(settings.value("scan_transform", _ui->lineEdit_cameraImages_laser_transform->text()).toString());
01690 _ui->spinBox_cameraImages_max_scan_pts->setValue(settings.value("scan_max_pts", _ui->spinBox_cameraImages_max_scan_pts->value()).toInt());
01691 _ui->spinBox_cameraImages_scanDownsampleStep->setValue(settings.value("scan_downsample_step", _ui->spinBox_cameraImages_scanDownsampleStep->value()).toInt());
01692 _ui->doubleSpinBox_cameraImages_scanVoxelSize->setValue(settings.value("scan_voxel_size", _ui->doubleSpinBox_cameraImages_scanVoxelSize->value()).toDouble());
01693 _ui->lineEdit_cameraImages_gt->setText(settings.value("gt_path", _ui->lineEdit_cameraImages_gt->text()).toString());
01694 _ui->comboBox_cameraImages_gtFormat->setCurrentIndex(settings.value("gt_format", _ui->comboBox_cameraImages_gtFormat->currentIndex()).toInt());
01695 settings.endGroup();
01696
01697 settings.beginGroup("Video");
01698 _ui->source_video_lineEdit_path->setText(settings.value("path", _ui->source_video_lineEdit_path->text()).toString());
01699 _ui->checkBox_rgbVideo_rectify->setChecked(settings.value("rectify",_ui->checkBox_rgbVideo_rectify->isChecked()).toBool());
01700 settings.endGroup();
01701
01702 settings.beginGroup("ScanFromDepth");
01703 _ui->groupBox_scanFromDepth->setChecked(settings.value("enabled", _ui->groupBox_scanFromDepth->isChecked()).toBool());
01704 _ui->spinBox_cameraScanFromDepth_decimation->setValue(settings.value("decimation", _ui->spinBox_cameraScanFromDepth_decimation->value()).toInt());
01705 _ui->doubleSpinBox_cameraSCanFromDepth_maxDepth->setValue(settings.value("maxDepth", _ui->doubleSpinBox_cameraSCanFromDepth_maxDepth->value()).toDouble());
01706 _ui->doubleSpinBox_cameraImages_scanVoxelSize->setValue(settings.value("voxelSize", _ui->doubleSpinBox_cameraImages_scanVoxelSize->value()).toDouble());
01707 _ui->spinBox_cameraImages_scanNormalsK->setValue(settings.value("normalsK", _ui->spinBox_cameraImages_scanNormalsK->value()).toInt());
01708 settings.endGroup();
01709
01710 settings.beginGroup("DepthFromScan");
01711 _ui->groupBox_depthFromScan->setChecked(settings.value("depthFromScan", _ui->groupBox_depthFromScan->isChecked()).toBool());
01712 _ui->groupBox_depthFromScan_fillHoles->setChecked(settings.value("depthFromScanFillHoles", _ui->groupBox_depthFromScan_fillHoles->isChecked()).toBool());
01713 _ui->radioButton_depthFromScan_vertical->setChecked(settings.value("depthFromScanVertical", _ui->radioButton_depthFromScan_vertical->isChecked()).toBool());
01714 _ui->radioButton_depthFromScan_horizontal->setChecked(settings.value("depthFromScanHorizontal", _ui->radioButton_depthFromScan_horizontal->isChecked()).toBool());
01715 _ui->checkBox_depthFromScan_fillBorders->setChecked(settings.value("depthFromScanFillBorders", _ui->checkBox_depthFromScan_fillBorders->isChecked()).toBool());
01716 settings.endGroup();
01717
01718 settings.beginGroup("Database");
01719 _ui->source_database_lineEdit_path->setText(settings.value("path",_ui->source_database_lineEdit_path->text()).toString());
01720 _ui->source_checkBox_ignoreOdometry->setChecked(settings.value("ignoreOdometry", _ui->source_checkBox_ignoreOdometry->isChecked()).toBool());
01721 _ui->source_checkBox_ignoreGoalDelay->setChecked(settings.value("ignoreGoalDelay", _ui->source_checkBox_ignoreGoalDelay->isChecked()).toBool());
01722 _ui->source_checkBox_ignoreGoals->setChecked(settings.value("ignoreGoals", _ui->source_checkBox_ignoreGoals->isChecked()).toBool());
01723 _ui->source_spinBox_databaseStartPos->setValue(settings.value("startPos", _ui->source_spinBox_databaseStartPos->value()).toInt());
01724 _ui->source_spinBox_database_cameraIndex->setValue(settings.value("cameraIndex", _ui->source_spinBox_database_cameraIndex->value()).toInt());
01725 _ui->source_checkBox_useDbStamps->setChecked(settings.value("useDatabaseStamps", _ui->source_checkBox_useDbStamps->isChecked()).toBool());
01726 settings.endGroup();
01727
01728 settings.endGroup();
01729
01730 _calibrationDialog->loadSettings(settings, "CalibrationDialog");
01731
01732 }
01733
01734 bool PreferencesDialog::readCoreSettings(const QString & filePath)
01735 {
01736 QString path = getIniFilePath();
01737 if(!filePath.isEmpty())
01738 {
01739 path = filePath;
01740 }
01741
01742 UDEBUG("%s", path.toStdString().c_str());
01743
01744 if(!QFile::exists(path))
01745 {
01746 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));
01747 }
01748
01749 QSettings settings(path, QSettings::IniFormat);
01750
01751
01752 settings.beginGroup("Core");
01753
01754
01755 QStringList version = settings.value("Version", "").toString().split('.');
01756 if(version.size() == 3)
01757 {
01758 if(!RTABMAP_VERSION_COMPARE(version[0].toInt(), version[1].toInt(), version[2].toInt()))
01759 {
01760 if(path.contains(".rtabmap"))
01761 {
01762 UWARN("Version in the config file \"%s\" is more recent (\"%s\") than "
01763 "current RTAB-Map version used (\"%s\"). The config file will be upgraded "
01764 "to new version.",
01765 path.toStdString().c_str(),
01766 settings.value("Version", "").toString().toStdString().c_str(),
01767 RTABMAP_VERSION);
01768 }
01769 else
01770 {
01771 UERROR("Version in the config file \"%s\" is more recent (\"%s\") than "
01772 "current RTAB-Map version used (\"%s\"). New parameters (if there are some) will "
01773 "be ignored.",
01774 path.toStdString().c_str(),
01775 settings.value("Version", "").toString().toStdString().c_str(),
01776 RTABMAP_VERSION);
01777 }
01778 }
01779 }
01780
01781 QStringList keys = settings.allKeys();
01782
01783 const rtabmap::ParametersMap & parameters = Parameters::getDefaultParameters();
01784 for(rtabmap::ParametersMap::const_iterator iter = parameters.begin(); iter!=parameters.end(); ++iter)
01785 {
01786 QString key(iter->first.c_str());
01787 QString value = settings.value(key, "").toString();
01788 if(value.isEmpty())
01789 {
01790
01791 rtabmap::ParametersMap::const_iterator oldIter = Parameters::getBackwardCompatibilityMap().find(iter->first);
01792 if(oldIter!=Parameters::getBackwardCompatibilityMap().end())
01793 {
01794 value = settings.value(QString(oldIter->second.c_str()), "").toString();
01795 if(!value.isEmpty())
01796 {
01797 UWARN("Parameter migration from \"%s\" to \"%s\" (value=%s).",
01798 oldIter->second.c_str(), oldIter->first.c_str(), value.toStdString().c_str());
01799 }
01800 }
01801 }
01802
01803 if(!value.isEmpty())
01804 {
01805 if(key.toStdString().compare(Parameters::kRtabmapWorkingDirectory()) == 0)
01806 {
01807
01808 if(!QDir(value).exists() && value.compare(Parameters::createDefaultWorkingDirectory().c_str()) != 0)
01809 {
01810 if(QDir(this->getWorkingDirectory().toStdString().c_str()).exists())
01811 {
01812 UWARN("Reading config: Not existing working directory \"%s\". Keeping old one (\"%s\").",
01813 value.toStdString().c_str(),
01814 this->getWorkingDirectory().toStdString().c_str());
01815 value = this->getWorkingDirectory();
01816 }
01817 else
01818 {
01819 UWARN("Reading config: Not existing working directory \"%s\". Using default one (\"%s\").",
01820 value.toStdString().c_str(),
01821 (*iter).second.c_str());
01822 value = (*iter).second.c_str();
01823 }
01824 }
01825 }
01826 this->setParameter(key.toStdString(), value.toStdString());
01827 }
01828 else
01829 {
01830
01831 if(key.toStdString().compare(Parameters::kRtabmapWorkingDirectory()) == 0)
01832 {
01833 if(!_initialized)
01834 {
01835 QMessageBox::information(this,
01836 tr("Working directory"),
01837 tr("RTAB-Map needs a working directory to put the database.\n\n"
01838 "By default, the directory \"%1\" is used.\n\n"
01839 "The working directory can be changed any time in the "
01840 "preferences menu.").arg(
01841 Parameters::createDefaultWorkingDirectory().c_str()));
01842 }
01843 this->setParameter(key.toStdString(), Parameters::createDefaultWorkingDirectory());
01844 UDEBUG("key.toStdString()=%s", Parameters::createDefaultWorkingDirectory().c_str());
01845 }
01846 else
01847 {
01848
01849 this->setParameter(key.toStdString(), (*iter).second);
01850 UDEBUG("key.toStdString()=%s", key.toStdString().c_str());
01851 }
01852 }
01853 }
01854 settings.endGroup();
01855 return true;
01856 }
01857
01858 bool PreferencesDialog::saveConfigTo()
01859 {
01860 QString path = QFileDialog::getSaveFileName(this, tr("Save settings..."), this->getWorkingDirectory()+QDir::separator()+"config.ini", "*.ini");
01861 if(!path.isEmpty())
01862 {
01863 writeGuiSettings(path);
01864 writeCameraSettings(path);
01865 writeCoreSettings(path);
01866 return true;
01867 }
01868 return false;
01869 }
01870
01871 void PreferencesDialog::resetConfig()
01872 {
01873 int button = QMessageBox::warning(this,
01874 tr("Reset settings..."),
01875 tr("This will reset all settings. Restore all settings to default without saving them first?"),
01876 QMessageBox::Cancel | QMessageBox::Yes | QMessageBox::Save,
01877 QMessageBox::Cancel);
01878 if(button == QMessageBox::Yes ||
01879 (button == QMessageBox::Save && saveConfigTo()))
01880 {
01881 this->resetSettings(-1);
01882
01883 _calibrationDialog->resetSettings();
01884 }
01885 }
01886
01887 void PreferencesDialog::writeSettings(const QString & filePath)
01888 {
01889 writeGuiSettings(filePath);
01890 writeCameraSettings(filePath);
01891 writeCoreSettings(filePath);
01892
01893 UDEBUG("_obsoletePanels=%d modified parameters=%d", (int)_obsoletePanels, (int)_modifiedParameters.size());
01894
01895 if(_modifiedParameters.size())
01896 {
01897 emit settingsChanged(_modifiedParameters);
01898 }
01899
01900 if(_obsoletePanels)
01901 {
01902 emit settingsChanged(_obsoletePanels);
01903 }
01904
01905 for(ParametersMap::iterator iter = _modifiedParameters.begin(); iter!=_modifiedParameters.end(); ++iter)
01906 {
01907 if( _parameters.at(iter->first).compare(iter->second) != 0)
01908 {
01909 UINFO("modified %s = %s->%s", iter->first.c_str(), _parameters.at(iter->first).c_str(), iter->second.c_str());
01910 }
01911 }
01912
01913 uInsert(_parameters, _modifiedParameters);
01914 _modifiedParameters.clear();
01915 _obsoletePanels = kPanelDummy;
01916 }
01917
01918 void PreferencesDialog::writeGuiSettings(const QString & filePath) const
01919 {
01920 QString path = getIniFilePath();
01921 if(!filePath.isEmpty())
01922 {
01923 path = filePath;
01924 }
01925 QSettings settings(path, QSettings::IniFormat);
01926 settings.beginGroup("Gui");
01927
01928 settings.beginGroup("General");
01929 settings.remove("");
01930 settings.setValue("imagesKept", _ui->general_checkBox_imagesKept->isChecked());
01931 settings.setValue("cloudsKept", _ui->general_checkBox_cloudsKept->isChecked());
01932 settings.setValue("loggerLevel", _ui->comboBox_loggerLevel->currentIndex());
01933 settings.setValue("loggerEventLevel", _ui->comboBox_loggerEventLevel->currentIndex());
01934 settings.setValue("loggerPauseLevel", _ui->comboBox_loggerPauseLevel->currentIndex());
01935 settings.setValue("loggerType", _ui->comboBox_loggerType->currentIndex());
01936 settings.setValue("loggerPrintTime", _ui->checkBox_logger_printTime->isChecked());
01937 settings.setValue("loggerPrintThreadId", _ui->checkBox_logger_printThreadId->isChecked());
01938 settings.setValue("verticalLayoutUsed", _ui->checkBox_verticalLayoutUsed->isChecked());
01939 settings.setValue("imageRejectedShown", _ui->checkBox_imageRejectedShown->isChecked());
01940 settings.setValue("imageHighestHypShown", _ui->checkBox_imageHighestHypShown->isChecked());
01941 settings.setValue("beep", _ui->checkBox_beep->isChecked());
01942 settings.setValue("figure_time", _ui->checkBox_stamps->isChecked());
01943 settings.setValue("notifyNewGlobalPath", _ui->checkBox_notifyWhenNewGlobalPathIsReceived->isChecked());
01944 settings.setValue("odomQualityThr", _ui->spinBox_odomQualityWarnThr->value());
01945 settings.setValue("posteriorGraphView", _ui->checkBox_posteriorGraphView->isChecked());
01946
01947 for(int i=0; i<2; ++i)
01948 {
01949 settings.setValue(QString("showClouds%1").arg(i), _3dRenderingShowClouds[i]->isChecked());
01950 settings.setValue(QString("decimation%1").arg(i), _3dRenderingDecimation[i]->value());
01951 settings.setValue(QString("maxDepth%1").arg(i), _3dRenderingMaxDepth[i]->value());
01952 settings.setValue(QString("minDepth%1").arg(i), _3dRenderingMinDepth[i]->value());
01953 settings.setValue(QString("showScans%1").arg(i), _3dRenderingShowScans[i]->isChecked());
01954 settings.setValue(QString("showFeatures%1").arg(i), _3dRenderingShowFeatures[i]->isChecked());
01955
01956 settings.setValue(QString("downsamplingScan%1").arg(i), _3dRenderingDownsamplingScan[i]->value());
01957 settings.setValue(QString("voxelSizeScan%1").arg(i), _3dRenderingVoxelSizeScan[i]->value());
01958 settings.setValue(QString("opacity%1").arg(i), _3dRenderingOpacity[i]->value());
01959 settings.setValue(QString("ptSize%1").arg(i), _3dRenderingPtSize[i]->value());
01960 settings.setValue(QString("opacityScan%1").arg(i), _3dRenderingOpacityScan[i]->value());
01961 settings.setValue(QString("ptSizeScan%1").arg(i), _3dRenderingPtSizeScan[i]->value());
01962 settings.setValue(QString("ptSizeFeatures%1").arg(i), _3dRenderingPtSizeFeatures[i]->value());
01963 }
01964 settings.setValue("cloudVoxel", _ui->doubleSpinBox_voxel->value());
01965 settings.setValue("cloudNoiseRadius", _ui->doubleSpinBox_noiseRadius->value());
01966 settings.setValue("cloudNoiseMinNeighbors", _ui->spinBox_noiseMinNeighbors->value());
01967
01968 settings.setValue("showGraphs", _ui->checkBox_showGraphs->isChecked());
01969 settings.setValue("showLabels", _ui->checkBox_showLabels->isChecked());
01970
01971 settings.setValue("noFiltering", _ui->radioButton_noFiltering->isChecked());
01972 settings.setValue("cloudFiltering", _ui->radioButton_nodeFiltering->isChecked());
01973 settings.setValue("cloudFilteringRadius", _ui->doubleSpinBox_cloudFilterRadius->value());
01974 settings.setValue("cloudFilteringAngle", _ui->doubleSpinBox_cloudFilterAngle->value());
01975 settings.setValue("subtractFiltering", _ui->radioButton_subtractFiltering->isChecked());
01976 settings.setValue("subtractFilteringMinPts", _ui->spinBox_subtractFilteringMinPts->value());
01977 settings.setValue("subtractFilteringRadius", _ui->doubleSpinBox_subtractFilteringRadius->value());
01978 settings.setValue("subtractFilteringAngle", _ui->doubleSpinBox_subtractFilteringAngle->value());
01979 settings.setValue("normalKSearch", _ui->spinBox_normalKSearch->value());
01980
01981 settings.setValue("gridMapShown", _ui->checkBox_map_shown->isChecked());
01982 settings.setValue("gridMapResolution", _ui->doubleSpinBox_map_resolution->value());
01983 settings.setValue("gridMapEroded", _ui->checkBox_map_erode->isChecked());
01984 settings.setValue("gridMapOpacity", _ui->doubleSpinBox_map_opacity->value());
01985
01986 settings.setValue("gridMapOccupancyFrom3DCloud", _ui->groupBox_map_occupancyFrom3DCloud->isChecked());
01987 settings.setValue("projMapFrame", _ui->checkBox_projMapFrame->isChecked());
01988 settings.setValue("projMaxGroundAngle", _ui->doubleSpinBox_projMaxGroundAngle->value());
01989 settings.setValue("projMaxGroundHeight", _ui->doubleSpinBox_projMaxGroundHeight->value());
01990 settings.setValue("projMinClusterSize", _ui->spinBox_projMinClusterSize->value());
01991 settings.setValue("projMaxObstaclesHeight", _ui->doubleSpinBox_projMaxObstaclesHeight->value());
01992 settings.setValue("projFlatObstaclesDetected", _ui->checkBox_projFlatObstaclesDetected->isChecked());
01993
01994 settings.setValue("octomap", _ui->groupBox_octomap->isChecked());
01995 settings.setValue("octomap_depth", _ui->spinBox_octomap_treeDepth->value());
01996 settings.setValue("octomap_ground_is_obstacle", _ui->checkBox_octomap_groundObstacle->isChecked());
01997
01998 settings.setValue("meshing", _ui->groupBox_organized->isChecked());
01999 settings.setValue("meshing_angle", _ui->doubleSpinBox_mesh_angleTolerance->value());
02000 settings.setValue("meshing_quad", _ui->checkBox_mesh_quad->isChecked());
02001 settings.setValue("meshing_triangle_size", _ui->spinBox_mesh_triangleSize->value());
02002
02003 settings.endGroup();
02004
02005 settings.endGroup();
02006 }
02007
02008 void PreferencesDialog::writeCameraSettings(const QString & filePath) const
02009 {
02010 QString path = getIniFilePath();
02011 if(!filePath.isEmpty())
02012 {
02013 path = filePath;
02014 }
02015 QSettings settings(path, QSettings::IniFormat);
02016
02017 settings.beginGroup("Camera");
02018 settings.remove("");
02019 settings.setValue("imgRate", _ui->general_doubleSpinBox_imgRate->value());
02020 settings.setValue("mirroring", _ui->source_mirroring->isChecked());
02021 settings.setValue("calibrationName", _ui->lineEdit_calibrationFile->text());
02022 settings.setValue("type", _ui->comboBox_sourceType->currentIndex());
02023 settings.setValue("device", _ui->lineEdit_sourceDevice->text());
02024 settings.setValue("localTransform", _ui->lineEdit_sourceLocalTransform->text());
02025 settings.setValue("imageDecimation", _ui->spinBox_source_imageDecimation->value());
02026
02027 settings.beginGroup("rgbd");
02028 settings.setValue("driver", _ui->comboBox_cameraRGBD->currentIndex());
02029 settings.setValue("rgbdColorOnly", _ui->checkbox_rgbd_colorOnly->isChecked());
02030 settings.endGroup();
02031
02032 settings.beginGroup("stereo");
02033 settings.setValue("driver", _ui->comboBox_cameraStereo->currentIndex());
02034 settings.setValue("depthGenerated", _ui->checkbox_stereo_depthGenerated->isChecked());
02035 settings.endGroup();
02036
02037 settings.beginGroup("rgb");
02038 settings.setValue("driver", _ui->source_comboBox_image_type->currentIndex());
02039 settings.endGroup();
02040
02041 settings.beginGroup("Openni");
02042 settings.setValue("oniPath", _ui->lineEdit_openniOniPath->text());
02043 settings.endGroup();
02044
02045 settings.beginGroup("Openni2");
02046 settings.setValue("autoWhiteBalance", _ui->openni2_autoWhiteBalance->isChecked());
02047 settings.setValue("autoExposure", _ui->openni2_autoExposure->isChecked());
02048 settings.setValue("exposure", _ui->openni2_exposure->value());
02049 settings.setValue("gain", _ui->openni2_gain->value());
02050 settings.setValue("mirroring", _ui->openni2_mirroring->isChecked());
02051 settings.setValue("stampsIdsUsed", _ui->openni2_stampsIdsUsed->isChecked());
02052 settings.setValue("oniPath", _ui->lineEdit_openni2OniPath->text());
02053 settings.endGroup();
02054
02055 settings.beginGroup("Freenect2");
02056 settings.setValue("format", _ui->comboBox_freenect2Format->currentIndex());
02057 settings.setValue("minDepth", _ui->doubleSpinBox_freenect2MinDepth->value());
02058 settings.setValue("maxDepth", _ui->doubleSpinBox_freenect2MaxDepth->value());
02059 settings.setValue("bilateralFiltering", _ui->checkBox_freenect2BilateralFiltering->isChecked());
02060 settings.setValue("edgeAwareFiltering", _ui->checkBox_freenect2EdgeAwareFiltering->isChecked());
02061 settings.setValue("noiseFiltering", _ui->checkBox_freenect2NoiseFiltering->isChecked());
02062 settings.endGroup();
02063
02064 settings.beginGroup("RGBDImages");
02065 settings.setValue("path_rgb", _ui->lineEdit_cameraRGBDImages_path_rgb->text());
02066 settings.setValue("path_depth", _ui->lineEdit_cameraRGBDImages_path_depth->text());
02067 settings.setValue("scale", _ui->doubleSpinBox_cameraRGBDImages_scale->value());
02068 settings.endGroup();
02069
02070 settings.beginGroup("StereoImages");
02071 settings.setValue("path_left", _ui->lineEdit_cameraStereoImages_path_left->text());
02072 settings.setValue("path_right", _ui->lineEdit_cameraStereoImages_path_right->text());
02073 settings.setValue("rectify", _ui->checkBox_stereoImages_rectify->isChecked());
02074 settings.endGroup();
02075
02076 settings.beginGroup("StereoVideo");
02077 settings.setValue("path", _ui->lineEdit_cameraStereoVideo_path->text());
02078 settings.setValue("rectify", _ui->checkBox_stereoVideo_rectify->isChecked());
02079 settings.endGroup();
02080
02081 settings.beginGroup("StereoZed");
02082 settings.setValue("resolution", _ui->comboBox_stereoZed_resolution->currentIndex());
02083 settings.setValue("quality", _ui->comboBox_stereoZed_quality->currentIndex());
02084 settings.setValue("sensing_mode", _ui->comboBox_stereoZed_sensingMode->currentIndex());
02085 settings.setValue("confidence_thr", _ui->spinBox_stereoZed_confidenceThr->value());
02086 settings.setValue("odom", _ui->checkbox_stereoZed_odom->isChecked());
02087 settings.setValue("svo_path", _ui->lineEdit_zedSvoPath->text());
02088 settings.endGroup();
02089
02090
02091
02092 settings.beginGroup("Images");
02093 settings.setValue("path", _ui->source_images_lineEdit_path->text());
02094 settings.setValue("startPos", _ui->source_images_spinBox_startPos->value());
02095 settings.setValue("refreshDir", _ui->source_images_refreshDir->isChecked());
02096 settings.setValue("rectify", _ui->checkBox_rgbImages_rectify->isChecked());
02097 settings.setValue("bayerMode", _ui->comboBox_cameraImages_bayerMode->currentIndex());
02098 settings.setValue("filenames_as_stamps", _ui->checkBox_cameraImages_timestamps->isChecked());
02099 settings.setValue("sync_stamps", _ui->checkBox_cameraImages_syncTimeStamps->isChecked());
02100 settings.setValue("stamps", _ui->lineEdit_cameraImages_timestamps->text());
02101 settings.setValue("path_scans", _ui->lineEdit_cameraImages_path_scans->text());
02102 settings.setValue("scan_transform", _ui->lineEdit_cameraImages_laser_transform->text());
02103 settings.setValue("scan_max_pts", _ui->spinBox_cameraImages_max_scan_pts->value());
02104 settings.setValue("scan_downsample_step", _ui->spinBox_cameraImages_scanDownsampleStep->value());
02105 settings.setValue("scan_voxel_size", _ui->doubleSpinBox_cameraImages_scanVoxelSize->value());
02106 settings.setValue("gt_path", _ui->lineEdit_cameraImages_gt->text());
02107 settings.setValue("gt_format", _ui->comboBox_cameraImages_gtFormat->currentIndex());
02108 settings.endGroup();
02109
02110 settings.beginGroup("Video");
02111 settings.setValue("path", _ui->source_video_lineEdit_path->text());
02112 settings.setValue("rectify", _ui->checkBox_rgbVideo_rectify->isChecked());
02113 settings.endGroup();
02114
02115 settings.beginGroup("ScanFromDepth");
02116 settings.setValue("enabled", _ui->groupBox_scanFromDepth->isChecked());
02117 settings.setValue("decimation", _ui->spinBox_cameraScanFromDepth_decimation->value());
02118 settings.setValue("maxDepth", _ui->doubleSpinBox_cameraSCanFromDepth_maxDepth->value());
02119 settings.setValue("voxelSize", _ui->doubleSpinBox_cameraImages_scanVoxelSize->value());
02120 settings.setValue("normalsK", _ui->spinBox_cameraImages_scanNormalsK->value());
02121 settings.endGroup();
02122
02123 settings.beginGroup("DepthFromScan");
02124 settings.setValue("depthFromScan", _ui->groupBox_depthFromScan->isChecked());
02125 settings.setValue("depthFromScanFillHoles", _ui->groupBox_depthFromScan_fillHoles->isChecked());
02126 settings.setValue("depthFromScanVertical", _ui->radioButton_depthFromScan_vertical->isChecked());
02127 settings.setValue("depthFromScanHorizontal", _ui->radioButton_depthFromScan_horizontal->isChecked());
02128 settings.setValue("depthFromScanFillBorders", _ui->checkBox_depthFromScan_fillBorders->isChecked());
02129 settings.endGroup();
02130
02131 settings.beginGroup("Database");
02132 settings.setValue("path", _ui->source_database_lineEdit_path->text());
02133 settings.setValue("ignoreOdometry", _ui->source_checkBox_ignoreOdometry->isChecked());
02134 settings.setValue("ignoreGoalDelay", _ui->source_checkBox_ignoreGoalDelay->isChecked());
02135 settings.setValue("ignoreGoals", _ui->source_checkBox_ignoreGoals->isChecked());
02136 settings.setValue("startPos", _ui->source_spinBox_databaseStartPos->value());
02137 settings.setValue("cameraIndex", _ui->source_spinBox_database_cameraIndex->value());
02138 settings.setValue("useDatabaseStamps", _ui->source_checkBox_useDbStamps->isChecked());
02139 settings.endGroup();
02140
02141 settings.endGroup();
02142
02143 _calibrationDialog->saveSettings(settings, "CalibrationDialog");
02144 }
02145
02146 void PreferencesDialog::writeCoreSettings(const QString & filePath) const
02147 {
02148 QString path = getIniFilePath();
02149 if(!filePath.isEmpty())
02150 {
02151 path = filePath;
02152 }
02153 QSettings settings(path, QSettings::IniFormat);
02154 settings.beginGroup("Core");
02155 settings.remove("");
02156
02157
02158 settings.setValue("Version", QString(RTABMAP_VERSION));
02159
02160 const rtabmap::ParametersMap & parameters = Parameters::getDefaultParameters();
02161 for(rtabmap::ParametersMap::const_iterator iter=parameters.begin(); iter!=parameters.end(); ++iter)
02162 {
02163 QObject * obj = _ui->stackedWidget->findChild<QObject*>((*iter).first.c_str());
02164 if(obj)
02165 {
02166 QSpinBox * spin = qobject_cast<QSpinBox *>(obj);
02167 QDoubleSpinBox * doubleSpin = qobject_cast<QDoubleSpinBox *>(obj);
02168 QComboBox * combo = qobject_cast<QComboBox *>(obj);
02169 QCheckBox * check = qobject_cast<QCheckBox *>(obj);
02170 QRadioButton * radio = qobject_cast<QRadioButton *>(obj);
02171 QLineEdit * lineEdit = qobject_cast<QLineEdit *>(obj);
02172 QGroupBox * groupBox = qobject_cast<QGroupBox *>(obj);
02173 if(spin)
02174 {
02175 settings.setValue(obj->objectName(), spin->value());
02176 }
02177 else if(doubleSpin)
02178 {
02179 settings.setValue(obj->objectName(), doubleSpin->value());
02180 }
02181 else if(combo)
02182 {
02183 settings.setValue(obj->objectName(), combo->currentIndex());
02184 }
02185 else if(check)
02186 {
02187 settings.setValue(obj->objectName(), uBool2Str(check->isChecked()).c_str());
02188 }
02189 else if(radio)
02190 {
02191 settings.setValue(obj->objectName(), uBool2Str(radio->isChecked()).c_str());
02192 }
02193 else if(lineEdit)
02194 {
02195 settings.setValue(obj->objectName(), lineEdit->text());
02196 }
02197 else if(groupBox)
02198 {
02199 settings.setValue(obj->objectName(), uBool2Str(groupBox->isChecked()).c_str());
02200 }
02201 else
02202 {
02203 ULOGGER_WARN("QObject called %s can't be cast to a supported widget", (*iter).first.c_str());
02204 }
02205 }
02206 else
02207 {
02208 ULOGGER_WARN("Can't find the related QObject for parameter %s", (*iter).first.c_str());
02209 }
02210 }
02211 settings.endGroup();
02212 }
02213
02214 bool PreferencesDialog::validateForm()
02215 {
02216 #ifndef RTABMAP_NONFREE
02217
02218
02219 if(_ui->comboBox_detector_strategy->currentIndex() <= 1)
02220 {
02221 QMessageBox::warning(this, tr("Parameter warning"),
02222 tr("Selected feature type (SURF/SIFT) is not available. RTAB-Map is not built "
02223 "with the nonfree module from OpenCV. ORB is set instead for the bag-of-words dictionary."));
02224 _ui->comboBox_detector_strategy->setCurrentIndex(Feature2D::kFeatureOrb);
02225 }
02226
02227 if(_ui->reextract_type->currentIndex() <= 1)
02228 {
02229 QMessageBox::warning(this, tr("Parameter warning"),
02230 tr("Selected feature type (SURF/SIFT) is not available. RTAB-Map is not built "
02231 "with the nonfree module from OpenCV. Fast/Brief is set instead for the re-extraction "
02232 "of features on loop closure."));
02233 _ui->reextract_type->setCurrentIndex(Feature2D::kFeatureFastBrief);
02234 }
02235 #endif
02236
02237
02238 if(_ui->graphOptimization_type->currentIndex() == 0 && !Optimizer::isAvailable(Optimizer::kTypeTORO))
02239 {
02240 if(Optimizer::isAvailable(Optimizer::kTypeGTSAM))
02241 {
02242 QMessageBox::warning(this, tr("Parameter warning"),
02243 tr("Selected graph optimization strategy (TORO) is not available. RTAB-Map is not built "
02244 "with TORO. GTSAM is set instead for graph optimization strategy."));
02245 _ui->graphOptimization_type->setCurrentIndex(Optimizer::kTypeGTSAM);
02246 }
02247 else if(Optimizer::isAvailable(Optimizer::kTypeG2O))
02248 {
02249 QMessageBox::warning(this, tr("Parameter warning"),
02250 tr("Selected graph optimization strategy (TORO) is not available. RTAB-Map is not built "
02251 "with TORO. g2o is set instead for graph optimization strategy."));
02252 _ui->graphOptimization_type->setCurrentIndex(Optimizer::kTypeG2O);
02253 }
02254 }
02255 if(_ui->graphOptimization_type->currentIndex() == 1 && !Optimizer::isAvailable(Optimizer::kTypeG2O))
02256 {
02257 if(Optimizer::isAvailable(Optimizer::kTypeGTSAM))
02258 {
02259 QMessageBox::warning(this, tr("Parameter warning"),
02260 tr("Selected graph optimization strategy (g2o) is not available. RTAB-Map is not built "
02261 "with g2o. GTSAM is set instead for graph optimization strategy."));
02262 _ui->graphOptimization_type->setCurrentIndex(Optimizer::kTypeGTSAM);
02263 }
02264 else if(Optimizer::isAvailable(Optimizer::kTypeTORO))
02265 {
02266 QMessageBox::warning(this, tr("Parameter warning"),
02267 tr("Selected graph optimization strategy (g2o) is not available. RTAB-Map is not built "
02268 "with g2o. TORO is set instead for graph optimization strategy."));
02269 _ui->graphOptimization_type->setCurrentIndex(Optimizer::kTypeTORO);
02270 }
02271 }
02272 if(_ui->graphOptimization_type->currentIndex() == 2 && !Optimizer::isAvailable(Optimizer::kTypeGTSAM))
02273 {
02274 if(Optimizer::isAvailable(Optimizer::kTypeG2O))
02275 {
02276 QMessageBox::warning(this, tr("Parameter warning"),
02277 tr("Selected graph optimization strategy (GTSAM) is not available. RTAB-Map is not built "
02278 "with GTSAM. g2o is set instead for graph optimization strategy."));
02279 _ui->graphOptimization_type->setCurrentIndex(Optimizer::kTypeG2O);
02280 }
02281 else if(Optimizer::isAvailable(Optimizer::kTypeTORO))
02282 {
02283 QMessageBox::warning(this, tr("Parameter warning"),
02284 tr("Selected graph optimization strategy (GTSAM) is not available. RTAB-Map is not built "
02285 "with GTSAM. TORO is set instead for graph optimization strategy."));
02286 _ui->graphOptimization_type->setCurrentIndex(Optimizer::kTypeTORO);
02287 }
02288 }
02289
02290
02291 if(_ui->graphOptimization_robust->isChecked() && _ui->graphOptimization_maxError->value()>0.0)
02292 {
02293 QMessageBox::warning(this, tr("Parameter warning"),
02294 tr("Robust graph optimization and maximum optimization error threshold cannot be "
02295 "both used at the same time. Disabling robust optimization."));
02296 _ui->graphOptimization_robust->setChecked(false);
02297 }
02298
02299
02300
02301 if(_ui->comboBox_dictionary_strategy->currentIndex() == VWDictionary::kNNFlannLSH && _ui->comboBox_detector_strategy->currentIndex() <= 1)
02302 {
02303 QMessageBox::warning(this, tr("Parameter warning"),
02304 tr("With the selected feature type (SURF or SIFT), parameter \"Visual word->Nearest Neighbor\" "
02305 "cannot be LSH (used for binary descriptor). KD-tree is set instead for the bag-of-words dictionary."));
02306 _ui->comboBox_dictionary_strategy->setCurrentIndex(VWDictionary::kNNFlannKdTree);
02307 }
02308
02309
02310 if(_ui->reextract_nn->currentIndex() == VWDictionary::kNNFlannLSH && _ui->reextract_type->currentIndex() <= 1)
02311 {
02312 QMessageBox::warning(this, tr("Parameter warning"),
02313 tr("With the selected feature type (SURF or SIFT), parameter \"Visual word->Nearest Neighbor\" "
02314 "cannot be LSH (used for binary descriptor). KD-tree is set instead for the re-extraction "
02315 "of features on loop closure."));
02316 _ui->reextract_nn->setCurrentIndex(VWDictionary::kNNFlannKdTree);
02317 }
02318
02319 if(_ui->doubleSpinBox_freenect2MinDepth->value() >= _ui->doubleSpinBox_freenect2MaxDepth->value())
02320 {
02321 QMessageBox::warning(this, tr("Parameter warning"),
02322 tr("Freenect2 minimum depth (%1 m) should be lower than maximum depth (%2 m). Setting maximum depth to %3 m.")
02323 .arg(_ui->doubleSpinBox_freenect2MinDepth->value())
02324 .arg(_ui->doubleSpinBox_freenect2MaxDepth->value())
02325 .arg(_ui->doubleSpinBox_freenect2MaxDepth->value()+1));
02326 _ui->doubleSpinBox_freenect2MaxDepth->setValue(_ui->doubleSpinBox_freenect2MaxDepth->value()+1);
02327 }
02328
02329 if(_ui->surf_doubleSpinBox_maxDepth->value() > 0.0 &&
02330 _ui->surf_doubleSpinBox_minDepth->value() >= _ui->surf_doubleSpinBox_maxDepth->value())
02331 {
02332 QMessageBox::warning(this, tr("Parameter warning"),
02333 tr("Visual word minimum depth (%1 m) should be lower than maximum depth (%2 m). Setting maximum depth to %3 m.")
02334 .arg(_ui->surf_doubleSpinBox_minDepth->value())
02335 .arg(_ui->surf_doubleSpinBox_maxDepth->value())
02336 .arg(_ui->surf_doubleSpinBox_maxDepth->value()+1));
02337 _ui->doubleSpinBox_freenect2MinDepth->setValue(0);
02338 }
02339
02340 if(_ui->loopClosure_bowMaxDepth->value() > 0.0 &&
02341 _ui->loopClosure_bowMinDepth->value() >= _ui->loopClosure_bowMaxDepth->value())
02342 {
02343 QMessageBox::warning(this, tr("Parameter warning"),
02344 tr("Visual registration word minimum depth (%1 m) should be lower than maximum depth (%2 m). Setting maximum depth to %3 m.")
02345 .arg(_ui->loopClosure_bowMinDepth->value())
02346 .arg(_ui->loopClosure_bowMaxDepth->value())
02347 .arg(_ui->loopClosure_bowMaxDepth->value()+1));
02348 _ui->loopClosure_bowMinDepth->setValue(0);
02349 }
02350
02351 if(_ui->fastThresholdMax->value() < _ui->fastThresholdMin->value())
02352 {
02353 QMessageBox::warning(this, tr("Parameter warning"),
02354 tr("FAST minimum threshold cannot be lower than maximum threshold. Setting minimum to 1."));
02355 _ui->fastThresholdMin->setValue(1);
02356 }
02357 if(_ui->fastThreshold->value() > _ui->fastThresholdMax->value())
02358 {
02359 QMessageBox::warning(this, tr("Parameter warning"),
02360 tr("FAST threshold cannot be higher than maximum threshold. Maximum value set to current threshold."));
02361 _ui->fastThresholdMax->setValue(_ui->fastThreshold->value());
02362 }
02363 if(_ui->fastThreshold->value() < _ui->fastThresholdMin->value())
02364 {
02365 QMessageBox::warning(this, tr("Parameter warning"),
02366 tr("FAST threshold cannot be lower than minimum threshold. Minimum value set to current threshold."));
02367 _ui->fastThresholdMin->setValue(_ui->fastThreshold->value());
02368 }
02369
02370 return true;
02371 }
02372
02373 QString PreferencesDialog::getParamMessage()
02374 {
02375 return tr("Reading parameters from the configuration file...");
02376 }
02377
02378 void PreferencesDialog::showEvent ( QShowEvent * event )
02379 {
02380 if(_monitoringState)
02381 {
02382
02383 _ui->lineEdit_dictionaryPath->setEnabled(false);
02384 _ui->toolButton_dictionaryPath->setEnabled(false);
02385 _ui->label_dictionaryPath->setEnabled(false);
02386
02387 _ui->groupBox_source0->setEnabled(false);
02388 _ui->groupBox_odometry1->setEnabled(false);
02389
02390 _ui->checkBox_useOdomFeatures->setChecked(false);
02391 _ui->checkBox_useOdomFeatures->setEnabled(false);
02392
02393 this->setWindowTitle(tr("Preferences [Monitoring mode]"));
02394 }
02395 else
02396 {
02397 _ui->lineEdit_dictionaryPath->setEnabled(true);
02398 _ui->toolButton_dictionaryPath->setEnabled(true);
02399 _ui->label_dictionaryPath->setEnabled(true);
02400
02401 _ui->groupBox_source0->setEnabled(true);
02402 _ui->groupBox_odometry1->setEnabled(true);
02403
02404 _ui->checkBox_useOdomFeatures->setEnabled(true);
02405
02406 this->setWindowTitle(tr("Preferences"));
02407 }
02408 this->readSettingsBegin();
02409 }
02410
02411 void PreferencesDialog::readSettingsBegin()
02412 {
02413 _progressDialog->setLabelText(this->getParamMessage());
02414 _progressDialog->show();
02415
02416
02417 QTimer::singleShot(10, this, SLOT(readSettingsEnd()));
02418 }
02419
02420 void PreferencesDialog::readSettingsEnd()
02421 {
02422 QApplication::processEvents();
02423
02424 this->readSettings(getTmpIniFilePath());
02425
02426 _progressDialog->setValue(1);
02427 if(this->isVisible())
02428 {
02429 _progressDialog->setLabelText(tr("Setup dialog..."));
02430
02431 this->updatePredictionPlot();
02432 this->setupKpRoiPanel();
02433 }
02434
02435 _progressDialog->setValue(2);
02436 }
02437
02438 void PreferencesDialog::saveWindowGeometry(const QWidget * window)
02439 {
02440 if(!window->objectName().isNull() && !window->isMaximized())
02441 {
02442 QSettings settings(getIniFilePath(), QSettings::IniFormat);
02443 settings.beginGroup("Gui");
02444 settings.beginGroup(window->objectName());
02445 settings.setValue("geometry", window->saveGeometry());
02446 settings.endGroup();
02447 settings.endGroup();
02448 }
02449 }
02450
02451 void PreferencesDialog::loadWindowGeometry(QWidget * window)
02452 {
02453 if(!window->objectName().isNull())
02454 {
02455 QByteArray bytes;
02456 QSettings settings(getIniFilePath(), QSettings::IniFormat);
02457 settings.beginGroup("Gui");
02458 settings.beginGroup(window->objectName());
02459 bytes = settings.value("geometry", QByteArray()).toByteArray();
02460 if(!bytes.isEmpty())
02461 {
02462 window->restoreGeometry(bytes);
02463 }
02464 settings.endGroup();
02465 settings.endGroup();
02466 }
02467 }
02468
02469 void PreferencesDialog::saveMainWindowState(const QMainWindow * mainWindow)
02470 {
02471 if(!mainWindow->objectName().isNull())
02472 {
02473 saveWindowGeometry(mainWindow);
02474
02475 QSettings settings(getIniFilePath(), QSettings::IniFormat);
02476 settings.beginGroup("Gui");
02477 settings.beginGroup(mainWindow->objectName());
02478 settings.setValue("state", mainWindow->saveState());
02479 settings.setValue("maximized", mainWindow->isMaximized());
02480 settings.setValue("status_bar", mainWindow->statusBar()->isVisible());
02481 settings.endGroup();
02482 settings.endGroup();
02483 }
02484 }
02485
02486 void PreferencesDialog::loadMainWindowState(QMainWindow * mainWindow, bool & maximized, bool & statusBarShown)
02487 {
02488 if(!mainWindow->objectName().isNull())
02489 {
02490 loadWindowGeometry(mainWindow);
02491
02492 QByteArray bytes;
02493 QSettings settings(getIniFilePath(), QSettings::IniFormat);
02494 settings.beginGroup("Gui");
02495 settings.beginGroup(mainWindow->objectName());
02496 bytes = settings.value("state", QByteArray()).toByteArray();
02497 if(!bytes.isEmpty())
02498 {
02499 mainWindow->restoreState(bytes);
02500 }
02501 maximized = settings.value("maximized", false).toBool();
02502 statusBarShown = settings.value("status_bar", false).toBool();
02503 mainWindow->statusBar()->setVisible(statusBarShown);
02504 settings.endGroup();
02505 settings.endGroup();
02506 }
02507 }
02508
02509 void PreferencesDialog::saveWidgetState(const QWidget * widget)
02510 {
02511 if(!widget->objectName().isNull())
02512 {
02513 QSettings settings(getIniFilePath(), QSettings::IniFormat);
02514 settings.beginGroup("Gui");
02515 settings.beginGroup(widget->objectName());
02516
02517 const CloudViewer * cloudViewer = qobject_cast<const CloudViewer*>(widget);
02518 const ImageView * imageView = qobject_cast<const ImageView*>(widget);
02519 const ExportCloudsDialog * exportCloudsDialog = qobject_cast<const ExportCloudsDialog*>(widget);
02520 const ExportScansDialog * exportScansDialog = qobject_cast<const ExportScansDialog*>(widget);
02521 const PostProcessingDialog * postProcessingDialog = qobject_cast<const PostProcessingDialog *>(widget);
02522 const GraphViewer * graphViewer = qobject_cast<const GraphViewer *>(widget);
02523 const CalibrationDialog * calibrationDialog = qobject_cast<const CalibrationDialog *>(widget);
02524
02525 if(cloudViewer)
02526 {
02527 cloudViewer->saveSettings(settings);
02528 }
02529 else if(imageView)
02530 {
02531 imageView->saveSettings(settings);
02532 }
02533 else if(exportCloudsDialog)
02534 {
02535 exportCloudsDialog->saveSettings(settings);
02536 }
02537 else if(exportScansDialog)
02538 {
02539 exportScansDialog->saveSettings(settings);
02540 }
02541 else if(postProcessingDialog)
02542 {
02543 postProcessingDialog->saveSettings(settings);
02544 }
02545 else if(graphViewer)
02546 {
02547 graphViewer->saveSettings(settings);
02548 }
02549 else if(calibrationDialog)
02550 {
02551 calibrationDialog->saveSettings(settings);
02552 }
02553 else
02554 {
02555 UERROR("Widget \"%s\" cannot be exported in config file.", widget->objectName().toStdString().c_str());
02556 }
02557
02558 settings.endGroup();
02559 settings.endGroup();
02560 }
02561 }
02562
02563 void PreferencesDialog::loadWidgetState(QWidget * widget)
02564 {
02565 if(!widget->objectName().isNull())
02566 {
02567 QByteArray bytes;
02568 QSettings settings(getIniFilePath(), QSettings::IniFormat);
02569 settings.beginGroup("Gui");
02570 settings.beginGroup(widget->objectName());
02571
02572 CloudViewer * cloudViewer = qobject_cast<CloudViewer*>(widget);
02573 ImageView * imageView = qobject_cast<ImageView*>(widget);
02574 ExportCloudsDialog * exportCloudsDialog = qobject_cast<ExportCloudsDialog*>(widget);
02575 ExportScansDialog * exportScansDialog = qobject_cast<ExportScansDialog*>(widget);
02576 PostProcessingDialog * postProcessingDialog = qobject_cast<PostProcessingDialog *>(widget);
02577 GraphViewer * graphViewer = qobject_cast<GraphViewer *>(widget);
02578 CalibrationDialog * calibrationDialog = qobject_cast<CalibrationDialog *>(widget);
02579
02580 if(cloudViewer)
02581 {
02582 cloudViewer->loadSettings(settings);
02583 }
02584 else if(imageView)
02585 {
02586 imageView->loadSettings(settings);
02587 }
02588 else if(exportCloudsDialog)
02589 {
02590 exportCloudsDialog->loadSettings(settings);
02591 }
02592 else if(exportScansDialog)
02593 {
02594 exportScansDialog->loadSettings(settings);
02595 }
02596 else if(postProcessingDialog)
02597 {
02598 postProcessingDialog->loadSettings(settings);
02599 }
02600 else if(graphViewer)
02601 {
02602 graphViewer->loadSettings(settings);
02603 }
02604 else if(calibrationDialog)
02605 {
02606 calibrationDialog->loadSettings(settings);
02607 }
02608 else
02609 {
02610 UERROR("Widget \"%s\" cannot be loaded from config file.", widget->objectName().toStdString().c_str());
02611 }
02612
02613 settings.endGroup();
02614 settings.endGroup();
02615 }
02616 }
02617
02618
02619 void PreferencesDialog::saveCustomConfig(const QString & section, const QString & key, const QString & value)
02620 {
02621 QSettings settings(getIniFilePath(), QSettings::IniFormat);
02622 settings.beginGroup("Gui");
02623 settings.beginGroup(section);
02624 settings.setValue(key, value);
02625 settings.endGroup();
02626 settings.endGroup();
02627 }
02628
02629 QString PreferencesDialog::loadCustomConfig(const QString & section, const QString & key)
02630 {
02631 QString value;
02632 QSettings settings(getIniFilePath(), QSettings::IniFormat);
02633 settings.beginGroup("Gui");
02634 settings.beginGroup(section);
02635 value = settings.value(key, QString()).toString();
02636 settings.endGroup();
02637 settings.endGroup();
02638 return value;
02639 }
02640
02641 rtabmap::ParametersMap PreferencesDialog::getAllParameters() const
02642 {
02643 UASSERT_MSG(_parameters.size() == Parameters::getDefaultParameters().size(),
02644 uFormat("%d vs %d (Is PreferencesDialog::init() called?)", (int)_parameters.size(), (int)Parameters::getDefaultParameters().size()).c_str());
02645
02646 ParametersMap parameters = _parameters;
02647 uInsert(parameters, _modifiedParameters);
02648
02649 return parameters;
02650 }
02651
02652 void PreferencesDialog::updateParameters(const ParametersMap & parameters)
02653 {
02654 if(parameters.size())
02655 {
02656 for(rtabmap::ParametersMap::const_iterator iter = parameters.begin(); iter!=parameters.end(); ++iter)
02657 {
02658 this->setParameter(iter->first, iter->second);
02659 }
02660 if(!this->isVisible())
02661 {
02662 this->writeSettings(getTmpIniFilePath());
02663 }
02664 }
02665 }
02666
02667 void PreferencesDialog::selectSourceDriver(Src src)
02668 {
02669 if(src >= kSrcRGBD && src<kSrcStereo)
02670 {
02671 _ui->comboBox_sourceType->setCurrentIndex(0);
02672 _ui->comboBox_cameraRGBD->setCurrentIndex(src - kSrcRGBD);
02673 if(src == kSrcOpenNI_PCL)
02674 {
02675 _ui->lineEdit_openniOniPath->clear();
02676 }
02677 else if(src == kSrcOpenNI2)
02678 {
02679 _ui->lineEdit_openni2OniPath->clear();
02680 }
02681 }
02682 else if(src >= kSrcStereo && src<kSrcRGB)
02683 {
02684 _ui->comboBox_sourceType->setCurrentIndex(1);
02685 _ui->comboBox_cameraStereo->setCurrentIndex(src - kSrcStereo);
02686 }
02687 else if(src >= kSrcRGB && src<kSrcDatabase)
02688 {
02689 _ui->comboBox_sourceType->setCurrentIndex(2);
02690 _ui->source_comboBox_image_type->setCurrentIndex(src - kSrcRGB);
02691 }
02692 else if(src >= kSrcDatabase)
02693 {
02694 _ui->comboBox_sourceType->setCurrentIndex(3);
02695 }
02696
02697 if(validateForm())
02698 {
02699
02700 makeObsoleteSourcePanel();
02701
02702 this->writeSettings(getTmpIniFilePath());
02703 }
02704 else
02705 {
02706 this->readSettingsBegin();
02707 }
02708 }
02709
02710 void PreferencesDialog::selectSourceDatabase()
02711 {
02712 QString dir = _ui->source_database_lineEdit_path->text();
02713 if(dir.isEmpty())
02714 {
02715 dir = getWorkingDirectory();
02716 }
02717 QStringList paths = QFileDialog::getOpenFileNames(this, tr("Select file"), dir, tr("RTAB-Map database files (*.db)"));
02718 if(paths.size())
02719 {
02720 int r = QMessageBox::question(this, tr("Odometry in database..."), tr("Use odometry saved in database (if some saved)?"), QMessageBox::Yes | QMessageBox::No, QMessageBox::Yes);
02721 _ui->source_checkBox_ignoreOdometry->setChecked(r != QMessageBox::Yes);
02722 _ui->source_database_lineEdit_path->setText(paths.size()==1?paths.front():paths.join(";"));
02723 _ui->source_spinBox_databaseStartPos->setValue(0);
02724 _ui->source_spinBox_database_cameraIndex->setValue(-1);
02725 _ui->source_checkBox_useDbStamps->setChecked(true);
02726 }
02727 }
02728
02729 void PreferencesDialog::openDatabaseViewer()
02730 {
02731 DatabaseViewer * viewer = new DatabaseViewer(getIniFilePath(), this);
02732 viewer->setWindowModality(Qt::WindowModal);
02733 viewer->setAttribute(Qt::WA_DeleteOnClose, true);
02734 viewer->showCloseButton();
02735 if(viewer->openDatabase(_ui->source_database_lineEdit_path->text()))
02736 {
02737 viewer->show();
02738 }
02739 else
02740 {
02741 delete viewer;
02742 }
02743 }
02744
02745 void PreferencesDialog::selectCalibrationPath()
02746 {
02747 QString dir = _ui->lineEdit_calibrationFile->text();
02748 if(dir.isEmpty())
02749 {
02750 dir = getWorkingDirectory()+"/camera_info";
02751 }
02752 else if(!dir.contains('.'))
02753 {
02754 dir = getWorkingDirectory()+"/camera_info/"+dir;
02755 }
02756 QString path = QFileDialog::getOpenFileName(this, tr("Select file"), dir, tr("Calibration file (*.yaml)"));
02757 if(path.size())
02758 {
02759 _ui->lineEdit_calibrationFile->setText(path);
02760 }
02761 }
02762
02763 void PreferencesDialog::selectSourceImagesStamps()
02764 {
02765 QString dir = _ui->lineEdit_cameraImages_timestamps->text();
02766 if(dir.isEmpty())
02767 {
02768 dir = getWorkingDirectory();
02769 }
02770 QString path = QFileDialog::getOpenFileName(this, tr("Select file"), dir, tr("Timestamps file (*.txt)"));
02771 if(path.size())
02772 {
02773 _ui->lineEdit_cameraImages_timestamps->setText(path);
02774 }
02775 }
02776
02777 void PreferencesDialog::selectSourceRGBDImagesPathRGB()
02778 {
02779 QString dir = _ui->lineEdit_cameraRGBDImages_path_rgb->text();
02780 if(dir.isEmpty())
02781 {
02782 dir = getWorkingDirectory();
02783 }
02784 QString path = QFileDialog::getExistingDirectory(this, tr("Select RGB images directory"), dir);
02785 if(path.size())
02786 {
02787 _ui->lineEdit_cameraRGBDImages_path_rgb->setText(path);
02788 }
02789 }
02790
02791
02792 void PreferencesDialog::selectSourceImagesPathScans()
02793 {
02794 QString dir = _ui->lineEdit_cameraImages_path_scans->text();
02795 if(dir.isEmpty())
02796 {
02797 dir = getWorkingDirectory();
02798 }
02799 QString path = QFileDialog::getExistingDirectory(this, tr("Select scans directory"), dir);
02800 if(path.size())
02801 {
02802 _ui->lineEdit_cameraImages_path_scans->setText(path);
02803 }
02804 }
02805
02806 void PreferencesDialog::selectSourceRGBDImagesPathDepth()
02807 {
02808 QString dir = _ui->lineEdit_cameraRGBDImages_path_depth->text();
02809 if(dir.isEmpty())
02810 {
02811 dir = getWorkingDirectory();
02812 }
02813 QString path = QFileDialog::getExistingDirectory(this, tr("Select depth images directory"), dir);
02814 if(path.size())
02815 {
02816 _ui->lineEdit_cameraRGBDImages_path_depth->setText(path);
02817 }
02818 }
02819
02820 void PreferencesDialog::selectSourceImagesPathGt()
02821 {
02822 QString dir = _ui->lineEdit_cameraImages_gt->text();
02823 if(dir.isEmpty())
02824 {
02825 dir = getWorkingDirectory();
02826 }
02827 QString path = QFileDialog::getOpenFileName(this, tr("Select file"), dir, tr("Ground Truth (*.txt *.log *.toro *.g2o)"));
02828 if(path.size())
02829 {
02830 QStringList list;
02831 for(int i=0; i<_ui->comboBox_cameraImages_gtFormat->count(); ++i)
02832 {
02833 list.push_back(_ui->comboBox_cameraImages_gtFormat->itemText(i));
02834 }
02835 QString item = QInputDialog::getItem(this, tr("Ground Truth Format"), tr("Format:"), list, 0, false);
02836 if(!item.isEmpty())
02837 {
02838 _ui->lineEdit_cameraImages_gt->setText(path);
02839 _ui->comboBox_cameraImages_gtFormat->setCurrentIndex(_ui->comboBox_cameraImages_gtFormat->findText(item));
02840 }
02841 }
02842 }
02843
02844 void PreferencesDialog::selectSourceStereoImagesPathLeft()
02845 {
02846 QString dir = _ui->lineEdit_cameraStereoImages_path_left->text();
02847 if(dir.isEmpty())
02848 {
02849 dir = getWorkingDirectory();
02850 }
02851 QString path = QFileDialog::getExistingDirectory(this, tr("Select left images directory"), dir);
02852 if(path.size())
02853 {
02854 _ui->lineEdit_cameraStereoImages_path_left->setText(path);
02855 }
02856 }
02857
02858 void PreferencesDialog::selectSourceStereoImagesPathRight()
02859 {
02860 QString dir = _ui->lineEdit_cameraStereoImages_path_right->text();
02861 if(dir.isEmpty())
02862 {
02863 dir = getWorkingDirectory();
02864 }
02865 QString path = QFileDialog::getExistingDirectory(this, tr("Select right images directory"), dir);
02866 if(path.size())
02867 {
02868 _ui->lineEdit_cameraStereoImages_path_right->setText(path);
02869 }
02870 }
02871
02872 void PreferencesDialog::selectSourceImagesPath()
02873 {
02874 QString dir = _ui->source_images_lineEdit_path->text();
02875 if(dir.isEmpty())
02876 {
02877 dir = getWorkingDirectory();
02878 }
02879 QString path = QFileDialog::getExistingDirectory(this, tr("Select images directory"), _ui->source_images_lineEdit_path->text());
02880 if(!path.isEmpty())
02881 {
02882 _ui->source_images_lineEdit_path->setText(path);
02883 _ui->source_images_spinBox_startPos->setValue(0);
02884 }
02885 }
02886
02887 void PreferencesDialog::selectSourceVideoPath()
02888 {
02889 QString dir = _ui->source_video_lineEdit_path->text();
02890 if(dir.isEmpty())
02891 {
02892 dir = getWorkingDirectory();
02893 }
02894 QString path = QFileDialog::getOpenFileName(this, tr("Select file"), _ui->source_video_lineEdit_path->text(), tr("Videos (*.avi *.mpg *.mp4)"));
02895 if(!path.isEmpty())
02896 {
02897 _ui->source_video_lineEdit_path->setText(path);
02898 }
02899 }
02900
02901 void PreferencesDialog::selectSourceStereoVideoPath()
02902 {
02903 QString dir = _ui->lineEdit_cameraStereoVideo_path->text();
02904 if(dir.isEmpty())
02905 {
02906 dir = getWorkingDirectory();
02907 }
02908 QString path = QFileDialog::getOpenFileName(this, tr("Select file"), _ui->lineEdit_cameraStereoVideo_path->text(), tr("Videos (*.avi *.mpg *.mp4)"));
02909 if(!path.isEmpty())
02910 {
02911 _ui->lineEdit_cameraStereoVideo_path->setText(path);
02912 }
02913 }
02914
02915 void PreferencesDialog::selectSourceOniPath()
02916 {
02917 QString dir = _ui->lineEdit_openniOniPath->text();
02918 if(dir.isEmpty())
02919 {
02920 dir = getWorkingDirectory();
02921 }
02922 QString path = QFileDialog::getOpenFileName(this, tr("Select file"), _ui->lineEdit_openniOniPath->text(), tr("OpenNI (*.oni)"));
02923 if(!path.isEmpty())
02924 {
02925 _ui->lineEdit_openniOniPath->setText(path);
02926 }
02927 }
02928
02929 void PreferencesDialog::selectSourceOni2Path()
02930 {
02931 QString dir = _ui->lineEdit_openni2OniPath->text();
02932 if(dir.isEmpty())
02933 {
02934 dir = getWorkingDirectory();
02935 }
02936 QString path = QFileDialog::getOpenFileName(this, tr("Select file"), _ui->lineEdit_openni2OniPath->text(), tr("OpenNI (*.oni)"));
02937 if(!path.isEmpty())
02938 {
02939 _ui->lineEdit_openni2OniPath->setText(path);
02940 }
02941 }
02942
02943 void PreferencesDialog::selectSourceSvoPath()
02944 {
02945 QString dir = _ui->lineEdit_zedSvoPath->text();
02946 if(dir.isEmpty())
02947 {
02948 dir = getWorkingDirectory();
02949 }
02950 QString path = QFileDialog::getOpenFileName(this, tr("Select file"), _ui->lineEdit_zedSvoPath->text(), tr("ZED (*.svo)"));
02951 if(!path.isEmpty())
02952 {
02953 _ui->lineEdit_zedSvoPath->setText(path);
02954 }
02955 }
02956
02957 void PreferencesDialog::setParameter(const std::string & key, const std::string & value)
02958 {
02959 UDEBUG("%s=%s", key.c_str(), value.c_str());
02960 QWidget * obj = _ui->stackedWidget->findChild<QWidget*>(key.c_str());
02961 if(obj)
02962 {
02963 uInsert(_parameters, ParametersPair(key, value));
02964
02965 QSpinBox * spin = qobject_cast<QSpinBox *>(obj);
02966 QDoubleSpinBox * doubleSpin = qobject_cast<QDoubleSpinBox *>(obj);
02967 QComboBox * combo = qobject_cast<QComboBox *>(obj);
02968 QCheckBox * check = qobject_cast<QCheckBox *>(obj);
02969 QRadioButton * radio = qobject_cast<QRadioButton *>(obj);
02970 QLineEdit * lineEdit = qobject_cast<QLineEdit *>(obj);
02971 QGroupBox * groupBox = qobject_cast<QGroupBox *>(obj);
02972 bool ok;
02973 if(spin)
02974 {
02975 spin->setValue(QString(value.c_str()).toInt(&ok));
02976 if(!ok)
02977 {
02978 UERROR("Conversion failed from \"%s\" for parameter %s", value.c_str(), key.c_str());
02979 }
02980 }
02981 else if(doubleSpin)
02982 {
02983 doubleSpin->setValue(QString(value.c_str()).toDouble(&ok));
02984 if(!ok)
02985 {
02986 UERROR("Conversion failed from \"%s\" for parameter %s", value.c_str(), key.c_str());
02987 }
02988 }
02989 else if(combo)
02990 {
02991 int valueInt = QString(value.c_str()).toInt(&ok);
02992 if(!ok)
02993 {
02994 UERROR("Conversion failed from \"%s\" for parameter %s", value.c_str(), key.c_str());
02995 }
02996 else
02997 {
02998 #ifndef RTABMAP_NONFREE
02999 if(valueInt <= 1 &&
03000 (combo->objectName().toStdString().compare(Parameters::kKpDetectorStrategy()) == 0 ||
03001 combo->objectName().toStdString().compare(Parameters::kVisFeatureType()) == 0))
03002 {
03003 UWARN("Trying to set \"%s\" to SIFT/SURF but RTAB-Map isn't built "
03004 "with the nonfree module from OpenCV. Keeping default combo value: %s.",
03005 combo->objectName().toStdString().c_str(),
03006 combo->currentText().toStdString().c_str());
03007 ok = false;
03008 }
03009 #endif
03010 if(!Optimizer::isAvailable(Optimizer::kTypeG2O))
03011 {
03012 if(valueInt==1 && combo->objectName().toStdString().compare(Parameters::kOptimizerStrategy()) == 0)
03013 {
03014 UWARN("Trying to set \"%s\" to g2o but RTAB-Map isn't built "
03015 "with g2o. Keeping default combo value: %s.",
03016 combo->objectName().toStdString().c_str(),
03017 combo->currentText().toStdString().c_str());
03018 ok = false;
03019 }
03020 }
03021 if(!Optimizer::isAvailable(Optimizer::kTypeGTSAM))
03022 {
03023 if(valueInt==2 && combo->objectName().toStdString().compare(Parameters::kOptimizerStrategy()) == 0)
03024 {
03025 UWARN("Trying to set \"%s\" to GTSAM but RTAB-Map isn't built "
03026 "with GTSAM. Keeping default combo value: %s.",
03027 combo->objectName().toStdString().c_str(),
03028 combo->currentText().toStdString().c_str());
03029 ok = false;
03030 }
03031 }
03032 if(ok)
03033 {
03034 combo->setCurrentIndex(valueInt);
03035 }
03036 }
03037
03038 }
03039 else if(check)
03040 {
03041 _ui->checkBox_useOdomFeatures->blockSignals(true);
03042 check->setChecked(uStr2Bool(value.c_str()));
03043 _ui->checkBox_useOdomFeatures->blockSignals(false);
03044 }
03045 else if(radio)
03046 {
03047 radio->setChecked(uStr2Bool(value.c_str()));
03048 }
03049 else if(lineEdit)
03050 {
03051 lineEdit->setText(value.c_str());
03052 }
03053 else if(groupBox)
03054 {
03055 groupBox->setChecked(uStr2Bool(value.c_str()));
03056 }
03057 else
03058 {
03059 ULOGGER_WARN("QObject called %s can't be cast to a supported widget", key.c_str());
03060 }
03061 }
03062 else
03063 {
03064 ULOGGER_WARN("Can't find the related QObject for parameter %s", key.c_str());
03065 }
03066 }
03067
03068 void PreferencesDialog::addParameter(int value)
03069 {
03070 if(sender())
03071 {
03072 this->addParameter(sender(), value);
03073 }
03074 else
03075 {
03076 ULOGGER_ERROR("This slot must be triggered by a signal, not a direct call...");
03077 }
03078 }
03079
03080 void PreferencesDialog::addParameter(bool value)
03081 {
03082 if(sender())
03083 {
03084 this->addParameter(sender(), value);
03085 }
03086 else
03087 {
03088 ULOGGER_ERROR("This slot must be triggered by a signal, not a direct call...");
03089 }
03090 }
03091
03092 void PreferencesDialog::addParameter(double value)
03093 {
03094 if(sender())
03095 {
03096 this->addParameter(sender(), value);
03097 }
03098 else
03099 {
03100 ULOGGER_ERROR("This slot must be triggered by a signal, not a direct call...");
03101 }
03102 }
03103
03104 void PreferencesDialog::addParameter(const QString & value)
03105 {
03106 if(sender())
03107 {
03108 this->addParameter(sender(), value);
03109 }
03110 else
03111 {
03112 ULOGGER_ERROR("This slot must be triggered by a signal, not a direct call...");
03113 }
03114 }
03115
03116 void PreferencesDialog::addParameter(const QObject * object, int value)
03117 {
03118 if(object)
03119 {
03120 const QComboBox * comboBox = qobject_cast<const QComboBox*>(object);
03121 const QSpinBox * spinbox = qobject_cast<const QSpinBox*>(object);
03122 if(comboBox || spinbox)
03123 {
03124
03125 UDEBUG("modify param %s=%s", object->objectName().toStdString().c_str(), uNumber2Str(value).c_str());
03126 uInsert(_modifiedParameters, rtabmap::ParametersPair(object->objectName().toStdString(), QString::number(value).toStdString()));
03127 }
03128 else
03129 {
03130 UWARN("Undefined object \"%s\"", object->objectName().toStdString().c_str());
03131 }
03132
03133 }
03134 else
03135 {
03136 ULOGGER_ERROR("Object is null");
03137 }
03138 }
03139
03140 void PreferencesDialog::addParameter(const QObject * object, bool value)
03141 {
03142 if(object)
03143 {
03144 const QCheckBox * checkbox = qobject_cast<const QCheckBox*>(object);
03145 const QRadioButton * radio = qobject_cast<const QRadioButton*>(object);
03146 const QGroupBox * groupBox = qobject_cast<const QGroupBox*>(object);
03147 if(checkbox || radio || groupBox)
03148 {
03149
03150 UDEBUG("modify param %s=%s", object->objectName().toStdString().c_str(), uBool2Str(value).c_str());
03151 uInsert(_modifiedParameters, rtabmap::ParametersPair(object->objectName().toStdString(), uBool2Str(value)));
03152 }
03153 else
03154 {
03155 UWARN("Undefined object \"%s\"", object->objectName().toStdString().c_str());
03156 }
03157
03158 }
03159 else
03160 {
03161 ULOGGER_ERROR("Object is null");
03162 }
03163 }
03164
03165 void PreferencesDialog::addParameter(const QObject * object, double value)
03166 {
03167 if(object)
03168 {
03169 UDEBUG("modify param %s=%f", object->objectName().toStdString().c_str(), value);
03170 uInsert(_modifiedParameters, rtabmap::ParametersPair(object->objectName().toStdString(), QString::number(value).toStdString()));
03171 }
03172 else
03173 {
03174 ULOGGER_ERROR("Object is null");
03175 }
03176 }
03177
03178 void PreferencesDialog::addParameter(const QObject * object, const QString & value)
03179 {
03180 if(object)
03181 {
03182 UDEBUG("modify param %s=%s", object->objectName().toStdString().c_str(), value.toStdString().c_str());
03183 uInsert(_modifiedParameters, rtabmap::ParametersPair(object->objectName().toStdString(), value.toStdString()));
03184 }
03185 else
03186 {
03187 ULOGGER_ERROR("Object is null");
03188 }
03189 }
03190
03191 void PreferencesDialog::addParameters(const QObjectList & children)
03192 {
03193
03194 for(int i=0; i<children.size(); ++i)
03195 {
03196 const QSpinBox * spin = qobject_cast<const QSpinBox *>(children[i]);
03197 const QDoubleSpinBox * doubleSpin = qobject_cast<const QDoubleSpinBox *>(children[i]);
03198 const QComboBox * combo = qobject_cast<const QComboBox *>(children[i]);
03199 const QCheckBox * check = qobject_cast<const QCheckBox *>(children[i]);
03200 const QRadioButton * radio = qobject_cast<const QRadioButton *>(children[i]);
03201 const QLineEdit * lineEdit = qobject_cast<const QLineEdit *>(children[i]);
03202 const QGroupBox * groupBox = qobject_cast<const QGroupBox *>(children[i]);
03203 const QStackedWidget * stackedWidget = qobject_cast<const QStackedWidget *>(children[i]);
03204 if(spin)
03205 {
03206 this->addParameter(spin, spin->value());
03207 }
03208 else if(doubleSpin)
03209 {
03210 this->addParameter(doubleSpin, doubleSpin->value());
03211 }
03212 else if(combo)
03213 {
03214 this->addParameter(combo, combo->currentIndex());
03215 }
03216 else if(check)
03217 {
03218 this->addParameter(check, check->isChecked());
03219 }
03220 else if(radio)
03221 {
03222 this->addParameter(radio, radio->isChecked());
03223 }
03224 else if(lineEdit)
03225 {
03226 this->addParameter(lineEdit, lineEdit->text());
03227 }
03228 else if(groupBox)
03229 {
03230 if(groupBox->isCheckable())
03231 {
03232 this->addParameter(groupBox, groupBox->isChecked());
03233 }
03234 else
03235 {
03236 this->addParameters(groupBox);
03237 }
03238 }
03239 else if(stackedWidget)
03240 {
03241 this->addParameters(stackedWidget);
03242 }
03243 }
03244 }
03245
03246 void PreferencesDialog::addParameters(const QStackedWidget * stackedWidget, int panel)
03247 {
03248 if(stackedWidget)
03249 {
03250 if(panel == -1)
03251 {
03252 for(int i=0; i<stackedWidget->count(); ++i)
03253 {
03254 const QObjectList & children = stackedWidget->widget(i)->children();
03255 addParameters(children);
03256 }
03257 }
03258 else
03259 {
03260 UASSERT(panel<stackedWidget->count());
03261 const QObjectList & children = stackedWidget->widget(panel)->children();
03262 addParameters(children);
03263 }
03264 }
03265 }
03266
03267 void PreferencesDialog::addParameters(const QGroupBox * box)
03268 {
03269 if(box)
03270 {
03271 const QObjectList & children = box->children();
03272 addParameters(children);
03273 }
03274 }
03275
03276 void PreferencesDialog::updateBasicParameter()
03277 {
03278
03279
03280
03281 if(sender() == _ui->general_doubleSpinBox_timeThr_2)
03282 {
03283 _ui->general_doubleSpinBox_timeThr->setValue(_ui->general_doubleSpinBox_timeThr_2->value());
03284 }
03285 else if(sender() == _ui->general_doubleSpinBox_hardThr_2)
03286 {
03287 _ui->general_doubleSpinBox_hardThr->setValue(_ui->general_doubleSpinBox_hardThr_2->value());
03288 }
03289 else if(sender() == _ui->general_doubleSpinBox_detectionRate_2)
03290 {
03291 _ui->general_doubleSpinBox_detectionRate->setValue(_ui->general_doubleSpinBox_detectionRate_2->value());
03292 }
03293 else if(sender() == _ui->general_spinBox_imagesBufferSize_2)
03294 {
03295 _ui->general_spinBox_imagesBufferSize->setValue(_ui->general_spinBox_imagesBufferSize_2->value());
03296 }
03297 else if(sender() == _ui->general_spinBox_maxStMemSize_2)
03298 {
03299 _ui->general_spinBox_maxStMemSize->setValue(_ui->general_spinBox_maxStMemSize_2->value());
03300 }
03301 else if(sender() == _ui->groupBox_publishing)
03302 {
03303 _ui->general_checkBox_publishStats_2->setChecked(_ui->groupBox_publishing->isChecked());
03304 }
03305 else if(sender() == _ui->general_checkBox_publishStats_2)
03306 {
03307 _ui->groupBox_publishing->setChecked(_ui->general_checkBox_publishStats_2->isChecked());
03308 }
03309 else if(sender() == _ui->doubleSpinBox_similarityThreshold_2)
03310 {
03311 _ui->doubleSpinBox_similarityThreshold->setValue(_ui->doubleSpinBox_similarityThreshold_2->value());
03312 }
03313 else if(sender() == _ui->general_checkBox_activateRGBD)
03314 {
03315 _ui->general_checkBox_activateRGBD_2->setChecked(_ui->general_checkBox_activateRGBD->isChecked());
03316 }
03317 else if(sender() == _ui->general_checkBox_activateRGBD_2)
03318 {
03319 _ui->general_checkBox_activateRGBD->setChecked(_ui->general_checkBox_activateRGBD_2->isChecked());
03320 }
03321 else if(sender() == _ui->general_checkBox_SLAM_mode)
03322 {
03323 _ui->general_checkBox_SLAM_mode_2->setChecked(_ui->general_checkBox_SLAM_mode->isChecked());
03324 }
03325 else if(sender() == _ui->general_checkBox_SLAM_mode_2)
03326 {
03327 _ui->general_checkBox_SLAM_mode->setChecked(_ui->general_checkBox_SLAM_mode_2->isChecked());
03328 }
03329 else
03330 {
03331
03332 _ui->general_doubleSpinBox_timeThr->setValue(_ui->general_doubleSpinBox_timeThr_2->value());
03333 _ui->general_doubleSpinBox_hardThr->setValue(_ui->general_doubleSpinBox_hardThr_2->value());
03334 _ui->general_doubleSpinBox_detectionRate->setValue(_ui->general_doubleSpinBox_detectionRate_2->value());
03335 _ui->general_spinBox_imagesBufferSize->setValue(_ui->general_spinBox_imagesBufferSize_2->value());
03336 _ui->general_spinBox_maxStMemSize->setValue(_ui->general_spinBox_maxStMemSize_2->value());
03337 _ui->doubleSpinBox_similarityThreshold->setValue(_ui->doubleSpinBox_similarityThreshold_2->value());
03338 }
03339 }
03340
03341 void PreferencesDialog::makeObsoleteGeneralPanel()
03342 {
03343 ULOGGER_DEBUG("");
03344 _obsoletePanels = _obsoletePanels | kPanelGeneral;
03345 }
03346
03347 void PreferencesDialog::makeObsoleteCloudRenderingPanel()
03348 {
03349 ULOGGER_DEBUG("");
03350 _obsoletePanels = _obsoletePanels | kPanelCloudRendering;
03351 }
03352
03353 void PreferencesDialog::makeObsoleteLoggingPanel()
03354 {
03355 ULOGGER_DEBUG("");
03356 _obsoletePanels = _obsoletePanels | kPanelLogging;
03357 }
03358
03359 void PreferencesDialog::makeObsoleteSourcePanel()
03360 {
03361 _obsoletePanels = _obsoletePanels | kPanelSource;
03362 }
03363
03364 QList<QGroupBox*> PreferencesDialog::getGroupBoxes()
03365 {
03366 QList<QGroupBox*> boxes;
03367 for(int i=0; i<_ui->stackedWidget->count(); ++i)
03368 {
03369 QGroupBox * gb = 0;
03370 const QObjectList & children = _ui->stackedWidget->widget(i)->children();
03371 for(int j=0; j<children.size(); ++j)
03372 {
03373 if((gb = qobject_cast<QGroupBox *>(children.at(j))))
03374 {
03375
03376 break;
03377 }
03378 }
03379 if(gb)
03380 {
03381 boxes.append(gb);
03382 }
03383 else
03384 {
03385 ULOGGER_ERROR("A QGroupBox must be included in the first level of children in stacked widget, index=%d", i);
03386 }
03387 }
03388 return boxes;
03389 }
03390
03391 void PreferencesDialog::updatePredictionPlot()
03392 {
03393 QStringList values = _ui->lineEdit_bayes_predictionLC->text().simplified().split(' ');
03394 if(values.size() < 2)
03395 {
03396 UERROR("Error parsing prediction (must have at least 2 items) : %s",
03397 _ui->lineEdit_bayes_predictionLC->text().toStdString().c_str());
03398 return;
03399 }
03400 QVector<float> dataX((values.size()-2)*2 + 1);
03401 QVector<float> dataY((values.size()-2)*2 + 1);
03402 double value;
03403 double sum = 0;
03404 int lvl = 1;
03405 bool ok = false;
03406 bool error = false;
03407 int loopClosureIndex = (dataX.size()-1)/2;
03408 for(int i=0; i<values.size(); ++i)
03409 {
03410 value = values.at(i).toDouble(&ok);
03411 if(!ok)
03412 {
03413 UERROR("Error parsing prediction : \"%s\"", values.at(i).toStdString().c_str());
03414 error = true;
03415 }
03416 sum+=value;
03417 if(i==0)
03418 {
03419
03420 }
03421 else if(i == 1)
03422 {
03423 dataY[loopClosureIndex] = value;
03424 dataX[loopClosureIndex] = 0;
03425 }
03426 else
03427 {
03428 dataY[loopClosureIndex-lvl] = value;
03429 dataX[loopClosureIndex-lvl] = -lvl;
03430 dataY[loopClosureIndex+lvl] = value;
03431 dataX[loopClosureIndex+lvl] = lvl;
03432 ++lvl;
03433 }
03434 }
03435
03436 _ui->label_prediction_sum->setNum(sum);
03437 if(error)
03438 {
03439 _ui->label_prediction_sum->setText(QString("<font color=#FF0000>") + _ui->label_prediction_sum->text() + "</font>");
03440 }
03441 else if(sum == 1.0)
03442 {
03443 _ui->label_prediction_sum->setText(QString("<font color=#00FF00>") + _ui->label_prediction_sum->text() + "</font>");
03444 }
03445 else if(sum > 1.0)
03446 {
03447 _ui->label_prediction_sum->setText(QString("<font color=#FFa500>") + _ui->label_prediction_sum->text() + "</font>");
03448 }
03449 else
03450 {
03451 _ui->label_prediction_sum->setText(QString("<font color=#000000>") + _ui->label_prediction_sum->text() + "</font>");
03452 }
03453
03454 _ui->predictionPlot->removeCurves();
03455 _ui->predictionPlot->addCurve(new UPlotCurve("Prediction", dataX, dataY, _ui->predictionPlot));
03456 }
03457
03458 void PreferencesDialog::setupKpRoiPanel()
03459 {
03460 QStringList strings = _ui->lineEdit_kp_roi->text().split(' ');
03461 if(strings.size()!=4)
03462 {
03463 UERROR("ROI must have 4 values (%s)", _ui->lineEdit_kp_roi->text().toStdString().c_str());
03464 return;
03465 }
03466 _ui->doubleSpinBox_kp_roi0->setValue(strings[0].toDouble()*100.0);
03467 _ui->doubleSpinBox_kp_roi1->setValue(strings[1].toDouble()*100.0);
03468 _ui->doubleSpinBox_kp_roi2->setValue(strings[2].toDouble()*100.0);
03469 _ui->doubleSpinBox_kp_roi3->setValue(strings[3].toDouble()*100.0);
03470 }
03471
03472 void PreferencesDialog::updateKpROI()
03473 {
03474 QStringList strings;
03475 strings.append(QString::number(_ui->doubleSpinBox_kp_roi0->value()/100.0));
03476 strings.append(QString::number(_ui->doubleSpinBox_kp_roi1->value()/100.0));
03477 strings.append(QString::number(_ui->doubleSpinBox_kp_roi2->value()/100.0));
03478 strings.append(QString::number(_ui->doubleSpinBox_kp_roi3->value()/100.0));
03479 _ui->lineEdit_kp_roi->setText(strings.join(" "));
03480 }
03481
03482 void PreferencesDialog::updateG2oVisibility()
03483 {
03484 _ui->groupBox_g2o->setVisible(_ui->graphOptimization_type->currentIndex() == 1);
03485 }
03486
03487 void PreferencesDialog::updateStereoDisparityVisibility()
03488 {
03489 Src driver = this->getSourceDriver();
03490 _ui->checkbox_stereo_depthGenerated->setVisible(
03491 driver != PreferencesDialog::kSrcStereoZed ||
03492 _ui->comboBox_stereoZed_quality->currentIndex() == 0);
03493 _ui->label_stereo_depthGenerated->setVisible(
03494 driver != PreferencesDialog::kSrcStereoZed ||
03495 _ui->comboBox_stereoZed_quality->currentIndex() == 0);
03496 }
03497
03498 void PreferencesDialog::useOdomFeatures()
03499 {
03500 if(this->isVisible() && _ui->checkBox_useOdomFeatures->isChecked())
03501 {
03502 int r = QMessageBox::question(this, tr("Using odometry features for vocabulary..."),
03503 tr("Do you want to match vocabulary feature parameters "
03504 "with corresponding ones used for odometry?"), QMessageBox::Yes | QMessageBox::No, QMessageBox::Yes);
03505
03506 if(r == QMessageBox::Yes)
03507 {
03508 _ui->comboBox_detector_strategy->setCurrentIndex(_ui->reextract_type->currentIndex());
03509 _ui->surf_doubleSpinBox_maxDepth->setValue(_ui->loopClosure_bowMaxDepth->value());
03510 _ui->surf_doubleSpinBox_minDepth->setValue(_ui->loopClosure_bowMinDepth->value());
03511 _ui->surf_spinBox_wordsPerImageTarget->setValue(_ui->reextract_maxFeatures->value());
03512 _ui->lineEdit_kp_roi->setText(_ui->loopClosure_roi->text());
03513 _ui->subpix_winSize_kp->setValue(_ui->subpix_winSize->value());
03514 _ui->subpix_iterations_kp->setValue(_ui->subpix_iterations->value());
03515 _ui->subpix_eps_kp->setValue(_ui->subpix_eps->value());
03516 }
03517 }
03518 }
03519
03520 void PreferencesDialog::changeWorkingDirectory()
03521 {
03522 QString directory = QFileDialog::getExistingDirectory(this, tr("Working directory"), _ui->lineEdit_workingDirectory->text());
03523 if(!directory.isEmpty())
03524 {
03525 ULOGGER_DEBUG("New working directory = %s", directory.toStdString().c_str());
03526 _ui->lineEdit_workingDirectory->setText(directory);
03527 }
03528 }
03529
03530 void PreferencesDialog::changeDictionaryPath()
03531 {
03532 QString path;
03533 if(_ui->lineEdit_dictionaryPath->text().isEmpty())
03534 {
03535 path = QFileDialog::getOpenFileName(this, tr("Dictionary"), this->getWorkingDirectory());
03536 }
03537 else
03538 {
03539 path = QFileDialog::getOpenFileName(this, tr("Dictionary"), _ui->lineEdit_dictionaryPath->text());
03540 }
03541 if(!path.isEmpty())
03542 {
03543 _ui->lineEdit_dictionaryPath->setText(path);
03544 }
03545 }
03546
03547 void PreferencesDialog::changeOdomBowFixedLocalMapPath()
03548 {
03549 QString path;
03550 if(_ui->odom_fixedLocalMapPath->text().isEmpty())
03551 {
03552 path = QFileDialog::getOpenFileName(this, tr("Database"), this->getWorkingDirectory(), tr("RTAB-Map database files (*.db)"));
03553 }
03554 else
03555 {
03556 path = QFileDialog::getOpenFileName(this, tr("Database"), _ui->odom_fixedLocalMapPath->text(), tr("RTAB-Map database files (*.db)"));
03557 }
03558 if(!path.isEmpty())
03559 {
03560 _ui->odom_fixedLocalMapPath->setText(path);
03561 }
03562 }
03563
03564 void PreferencesDialog::updateSourceGrpVisibility()
03565 {
03566 _ui->groupBox_sourceRGBD->setVisible(_ui->comboBox_sourceType->currentIndex() == 0);
03567 _ui->groupBox_sourceStereo->setVisible(_ui->comboBox_sourceType->currentIndex() == 1);
03568 _ui->groupBox_sourceRGB->setVisible(_ui->comboBox_sourceType->currentIndex() == 2);
03569 _ui->groupBox_sourceDatabase->setVisible(_ui->comboBox_sourceType->currentIndex() == 3);
03570
03571 _ui->groupBox_scanFromDepth->setVisible(_ui->comboBox_sourceType->currentIndex() <= 1 || _ui->comboBox_sourceType->currentIndex() == 3);
03572
03573 _ui->stackedWidget_rgbd->setVisible(_ui->comboBox_sourceType->currentIndex() == 0 &&
03574 (_ui->comboBox_cameraRGBD->currentIndex() == kSrcOpenNI2-kSrcRGBD ||
03575 _ui->comboBox_cameraRGBD->currentIndex() == kSrcFreenect2-kSrcRGBD ||
03576 _ui->comboBox_cameraRGBD->currentIndex() == kSrcRGBDImages-kSrcRGBD ||
03577 _ui->comboBox_cameraRGBD->currentIndex() == kSrcOpenNI_PCL-kSrcRGBD));
03578 _ui->groupBox_openni2->setVisible(_ui->comboBox_sourceType->currentIndex() == 0 && _ui->comboBox_cameraRGBD->currentIndex() == kSrcOpenNI2-kSrcRGBD);
03579 _ui->groupBox_freenect2->setVisible(_ui->comboBox_sourceType->currentIndex() == 0 && _ui->comboBox_cameraRGBD->currentIndex() == kSrcFreenect2-kSrcRGBD);
03580 _ui->groupBox_cameraRGBDImages->setVisible(_ui->comboBox_sourceType->currentIndex() == 0 && _ui->comboBox_cameraRGBD->currentIndex() == kSrcRGBDImages-kSrcRGBD);
03581 _ui->groupBox_openni->setVisible(_ui->comboBox_sourceType->currentIndex() == 0 && _ui->comboBox_cameraRGBD->currentIndex() == kSrcOpenNI_PCL-kSrcRGBD);
03582
03583 _ui->stackedWidget_stereo->setVisible(_ui->comboBox_sourceType->currentIndex() == 1 &&
03584 (_ui->comboBox_cameraStereo->currentIndex() == kSrcStereoVideo-kSrcStereo ||
03585 _ui->comboBox_cameraStereo->currentIndex() == kSrcStereoImages-kSrcStereo ||
03586 _ui->comboBox_cameraStereo->currentIndex() == kSrcStereoZed - kSrcStereo));
03587 _ui->groupBox_cameraStereoImages->setVisible(_ui->comboBox_sourceType->currentIndex() == 1 && _ui->comboBox_cameraStereo->currentIndex() == kSrcStereoImages-kSrcStereo);
03588 _ui->groupBox_cameraStereoVideo->setVisible(_ui->comboBox_sourceType->currentIndex() == 1 && _ui->comboBox_cameraStereo->currentIndex() == kSrcStereoVideo - kSrcStereo);
03589 _ui->groupBox_cameraStereoZed->setVisible(_ui->comboBox_sourceType->currentIndex() == 1 && _ui->comboBox_cameraStereo->currentIndex() == kSrcStereoZed - kSrcStereo);
03590
03591 _ui->stackedWidget_image->setVisible(_ui->comboBox_sourceType->currentIndex() == 2 && (_ui->source_comboBox_image_type->currentIndex() == kSrcImages-kSrcRGB || _ui->source_comboBox_image_type->currentIndex() == kSrcVideo-kSrcRGB));
03592 _ui->source_groupBox_images->setVisible(_ui->comboBox_sourceType->currentIndex() == 2 && _ui->source_comboBox_image_type->currentIndex() == kSrcImages-kSrcRGB);
03593 _ui->source_groupBox_video->setVisible(_ui->comboBox_sourceType->currentIndex() == 2 && _ui->source_comboBox_image_type->currentIndex() == kSrcVideo-kSrcRGB);
03594
03595 _ui->groupBox_sourceImages_optional->setVisible(
03596 (_ui->comboBox_sourceType->currentIndex() == 0 && _ui->comboBox_cameraRGBD->currentIndex() == kSrcRGBDImages-kSrcRGBD) ||
03597 (_ui->comboBox_sourceType->currentIndex() == 1 && _ui->comboBox_cameraStereo->currentIndex() == kSrcStereoImages-kSrcStereo) ||
03598 (_ui->comboBox_sourceType->currentIndex() == 2 && _ui->source_comboBox_image_type->currentIndex() == kSrcImages-kSrcRGB));
03599
03600
03601
03602 _ui->groupBox_depthFromScan->setVisible(_ui->comboBox_sourceType->currentIndex() == 2 && _ui->source_comboBox_image_type->currentIndex() == kSrcImages-kSrcRGB);
03603 }
03604
03605
03606
03607 int PreferencesDialog::getGeneralLoggerLevel() const
03608 {
03609 return _ui->comboBox_loggerLevel->currentIndex();
03610 }
03611 int PreferencesDialog::getGeneralLoggerEventLevel() const
03612 {
03613 return _ui->comboBox_loggerEventLevel->currentIndex();
03614 }
03615 int PreferencesDialog::getGeneralLoggerPauseLevel() const
03616 {
03617 return _ui->comboBox_loggerPauseLevel->currentIndex();
03618 }
03619 int PreferencesDialog::getGeneralLoggerType() const
03620 {
03621 return _ui->comboBox_loggerType->currentIndex();
03622 }
03623 bool PreferencesDialog::getGeneralLoggerPrintTime() const
03624 {
03625 return _ui->checkBox_logger_printTime->isChecked();
03626 }
03627 bool PreferencesDialog::getGeneralLoggerPrintThreadId() const
03628 {
03629 return _ui->checkBox_logger_printThreadId->isChecked();
03630 }
03631 bool PreferencesDialog::isVerticalLayoutUsed() const
03632 {
03633 return _ui->checkBox_verticalLayoutUsed->isChecked();
03634 }
03635 bool PreferencesDialog::imageRejectedShown() const
03636 {
03637 return _ui->checkBox_imageRejectedShown->isChecked();
03638 }
03639 bool PreferencesDialog::imageHighestHypShown() const
03640 {
03641 return _ui->checkBox_imageHighestHypShown->isChecked();
03642 }
03643 bool PreferencesDialog::beepOnPause() const
03644 {
03645 return _ui->checkBox_beep->isChecked();
03646 }
03647 bool PreferencesDialog::isTimeUsedInFigures() const
03648 {
03649 return _ui->checkBox_stamps->isChecked();
03650 }
03651 bool PreferencesDialog::notifyWhenNewGlobalPathIsReceived() const
03652 {
03653 return _ui->checkBox_notifyWhenNewGlobalPathIsReceived->isChecked();
03654 }
03655 int PreferencesDialog::getOdomQualityWarnThr() const
03656 {
03657 return _ui->spinBox_odomQualityWarnThr->value();
03658 }
03659 bool PreferencesDialog::isPosteriorGraphView() const
03660 {
03661 return _ui->checkBox_posteriorGraphView->isChecked();
03662 }
03663
03664 bool PreferencesDialog::isCloudsShown(int index) const
03665 {
03666 UASSERT(index >= 0 && index <= 1);
03667 return _3dRenderingShowClouds[index]->isChecked();
03668 }
03669 bool PreferencesDialog::isOctomapShown() const
03670 {
03671 #ifdef RTABMAP_OCTOMAP
03672 return _ui->groupBox_octomap->isChecked();
03673 #endif
03674 return false;
03675 }
03676 int PreferencesDialog::getOctomapTreeDepth() const
03677 {
03678 return _ui->spinBox_octomap_treeDepth->value();
03679 }
03680 bool PreferencesDialog::isOctomapGroundAnObstacle() const
03681 {
03682 return _ui->checkBox_octomap_groundObstacle->isChecked();
03683 }
03684
03685 double PreferencesDialog::getMapVoxel() const
03686 {
03687 return _ui->doubleSpinBox_voxel->value();
03688 }
03689 double PreferencesDialog::getMapNoiseRadius() const
03690 {
03691 return _ui->doubleSpinBox_noiseRadius->value();
03692 }
03693 int PreferencesDialog::getMapNoiseMinNeighbors() const
03694 {
03695 return _ui->spinBox_noiseMinNeighbors->value();
03696 }
03697
03698 bool PreferencesDialog::isGraphsShown() const
03699 {
03700 return _ui->checkBox_showGraphs->isChecked();
03701 }
03702 bool PreferencesDialog::isLabelsShown() const
03703 {
03704 return _ui->checkBox_showLabels->isChecked();
03705 }
03706 bool PreferencesDialog::isCloudMeshing() const
03707 {
03708 return _ui->groupBox_organized->isChecked();
03709 }
03710 double PreferencesDialog::getCloudMeshingAngle() const
03711 {
03712 return _ui->doubleSpinBox_mesh_angleTolerance->value()*M_PI/180.0;
03713 }
03714 bool PreferencesDialog::isCloudMeshingQuad() const
03715 {
03716 return _ui->checkBox_mesh_quad->isChecked();
03717 }
03718 int PreferencesDialog::getCloudMeshingTriangleSize()
03719 {
03720 return _ui->spinBox_mesh_triangleSize->value();
03721 }
03722 int PreferencesDialog::getCloudDecimation(int index) const
03723 {
03724 UASSERT(index >= 0 && index <= 1);
03725 return _3dRenderingDecimation[index]->value();
03726 }
03727 double PreferencesDialog::getCloudMaxDepth(int index) const
03728 {
03729 UASSERT(index >= 0 && index <= 1);
03730 return _3dRenderingMaxDepth[index]->value();
03731 }
03732 double PreferencesDialog::getCloudMinDepth(int index) const
03733 {
03734 UASSERT(index >= 0 && index <= 1);
03735 return _3dRenderingMinDepth[index]->value();
03736 }
03737 double PreferencesDialog::getCloudOpacity(int index) const
03738 {
03739 UASSERT(index >= 0 && index <= 1);
03740 return _3dRenderingOpacity[index]->value();
03741 }
03742 int PreferencesDialog::getCloudPointSize(int index) const
03743 {
03744 UASSERT(index >= 0 && index <= 1);
03745 return _3dRenderingPtSize[index]->value();
03746 }
03747
03748 bool PreferencesDialog::isScansShown(int index) const
03749 {
03750 UASSERT(index >= 0 && index <= 1);
03751 return _3dRenderingShowScans[index]->isChecked();
03752 }
03753 int PreferencesDialog::getDownsamplingStepScan(int index) const
03754 {
03755 UASSERT(index >= 0 && index <= 1);
03756 return _3dRenderingDownsamplingScan[index]->value();
03757 }
03758 double PreferencesDialog::getCloudVoxelSizeScan(int index) const
03759 {
03760 UASSERT(index >= 0 && index <= 1);
03761 return _3dRenderingVoxelSizeScan[index]->value();
03762 }
03763 double PreferencesDialog::getScanOpacity(int index) const
03764 {
03765 UASSERT(index >= 0 && index <= 1);
03766 return _3dRenderingOpacityScan[index]->value();
03767 }
03768 int PreferencesDialog::getScanPointSize(int index) const
03769 {
03770 UASSERT(index >= 0 && index <= 1);
03771 return _3dRenderingPtSizeScan[index]->value();
03772 }
03773
03774 bool PreferencesDialog::isFeaturesShown(int index) const
03775 {
03776 UASSERT(index >= 0 && index <= 1);
03777 return _3dRenderingShowFeatures[index]->isChecked();
03778 }
03779 int PreferencesDialog::getFeaturesPointSize(int index) const
03780 {
03781 UASSERT(index >= 0 && index <= 1);
03782 return _3dRenderingPtSizeFeatures[index]->value();
03783 }
03784
03785 bool PreferencesDialog::isCloudFiltering() const
03786 {
03787 return _ui->radioButton_nodeFiltering->isChecked();
03788 }
03789 bool PreferencesDialog::isSubtractFiltering() const
03790 {
03791 return _ui->radioButton_subtractFiltering->isChecked();
03792 }
03793 double PreferencesDialog::getCloudFilteringRadius() const
03794 {
03795 return _ui->doubleSpinBox_cloudFilterRadius->value();
03796 }
03797 double PreferencesDialog::getCloudFilteringAngle() const
03798 {
03799 return _ui->doubleSpinBox_cloudFilterAngle->value();
03800 }
03801 int PreferencesDialog::getSubtractFilteringMinPts() const
03802 {
03803 return _ui->spinBox_subtractFilteringMinPts->value();
03804 }
03805 double PreferencesDialog::getSubtractFilteringRadius() const
03806 {
03807 return _ui->doubleSpinBox_subtractFilteringRadius->value();
03808 }
03809 double PreferencesDialog::getSubtractFilteringAngle() const
03810 {
03811 return _ui->doubleSpinBox_subtractFilteringAngle->value()*M_PI/180.0;
03812 }
03813 int PreferencesDialog::getNormalKSearch() const
03814 {
03815 return _ui->spinBox_normalKSearch->value();
03816 }
03817 bool PreferencesDialog::getGridMapShown() const
03818 {
03819 return _ui->checkBox_map_shown->isChecked();
03820 }
03821 double PreferencesDialog::getGridMapResolution() const
03822 {
03823 return _ui->doubleSpinBox_map_resolution->value();
03824 }
03825 bool PreferencesDialog::isGridMapEroded() const
03826 {
03827 return _ui->checkBox_map_erode->isChecked();
03828 }
03829 bool PreferencesDialog::isGridMapFrom3DCloud() const
03830 {
03831 return _ui->groupBox_map_occupancyFrom3DCloud->isChecked();
03832 }
03833 bool PreferencesDialog::projMapFrame() const
03834 {
03835 return _ui->checkBox_projMapFrame->isChecked();
03836 }
03837 double PreferencesDialog::projMaxGroundAngle() const
03838 {
03839 return _ui->doubleSpinBox_projMaxGroundAngle->value()*M_PI/180.0;
03840 }
03841 double PreferencesDialog::projMaxGroundHeight() const
03842 {
03843 return _ui->doubleSpinBox_projMaxGroundHeight->value();
03844 }
03845 int PreferencesDialog::projMinClusterSize() const
03846 {
03847 return _ui->spinBox_projMinClusterSize->value();
03848 }
03849 double PreferencesDialog::projMaxObstaclesHeight() const
03850 {
03851 return _ui->doubleSpinBox_projMaxObstaclesHeight->value();
03852 }
03853 bool PreferencesDialog::projFlatObstaclesDetected() const
03854 {
03855 return _ui->checkBox_projFlatObstaclesDetected->isChecked();
03856 }
03857 double PreferencesDialog::getGridMapOpacity() const
03858 {
03859 return _ui->doubleSpinBox_map_opacity->value();
03860 }
03861
03862
03863
03864 double PreferencesDialog::getGeneralInputRate() const
03865 {
03866 return _ui->general_doubleSpinBox_imgRate->value();
03867 }
03868 bool PreferencesDialog::isSourceMirroring() const
03869 {
03870 return _ui->source_mirroring->isChecked();
03871 }
03872 PreferencesDialog::Src PreferencesDialog::getSourceType() const
03873 {
03874 int index = _ui->comboBox_sourceType->currentIndex();
03875 if(index == 0)
03876 {
03877 return kSrcRGBD;
03878 }
03879 else if(index == 1)
03880 {
03881 return kSrcStereo;
03882 }
03883 else if(index == 2)
03884 {
03885 return kSrcRGB;
03886 }
03887 else if(index == 3)
03888 {
03889 return kSrcDatabase;
03890 }
03891 return kSrcUndef;
03892 }
03893 PreferencesDialog::Src PreferencesDialog::getSourceDriver() const
03894 {
03895 PreferencesDialog::Src type = getSourceType();
03896 if(type==kSrcRGBD)
03897 {
03898 return (PreferencesDialog::Src)(_ui->comboBox_cameraRGBD->currentIndex()+kSrcRGBD);
03899 }
03900 else if(type==kSrcStereo)
03901 {
03902 return (PreferencesDialog::Src)(_ui->comboBox_cameraStereo->currentIndex()+kSrcStereo);
03903 }
03904 else if(type==kSrcRGB)
03905 {
03906 return (PreferencesDialog::Src)(_ui->source_comboBox_image_type->currentIndex()+kSrcRGB);
03907 }
03908 else if(type==kSrcDatabase)
03909 {
03910 return kSrcDatabase;
03911 }
03912 return kSrcUndef;
03913 }
03914 QString PreferencesDialog::getSourceDriverStr() const
03915 {
03916 PreferencesDialog::Src type = getSourceType();
03917 if(type==kSrcRGBD)
03918 {
03919 return _ui->comboBox_cameraRGBD->currentText();
03920 }
03921 else if(type==kSrcStereo)
03922 {
03923 return _ui->comboBox_cameraStereo->currentText();
03924 }
03925 else if(type==kSrcRGB)
03926 {
03927 return _ui->source_comboBox_image_type->currentText();
03928 }
03929 else if(type==kSrcDatabase)
03930 {
03931 return "Database";
03932 }
03933 return "";
03934 }
03935
03936 QString PreferencesDialog::getSourceDevice() const
03937 {
03938 return _ui->lineEdit_sourceDevice->text();
03939 }
03940
03941 Transform PreferencesDialog::getSourceLocalTransform() const
03942 {
03943 Transform t = Transform::fromString(_ui->lineEdit_sourceLocalTransform->text().replace("PI_2", QString::number(3.141592/2.0)).toStdString());
03944 if(t.isNull())
03945 {
03946 return Transform::getIdentity();
03947 }
03948 return t;
03949 }
03950
03951 Transform PreferencesDialog::getLaserLocalTransform() const
03952 {
03953 Transform t = Transform::fromString(_ui->lineEdit_cameraImages_laser_transform->text().replace("PI_2", QString::number(3.141592/2.0)).toStdString());
03954 if(t.isNull())
03955 {
03956 return Transform::getIdentity();
03957 }
03958 return t;
03959 }
03960
03961 bool PreferencesDialog::getSourceDatabaseStampsUsed() const
03962 {
03963 return _ui->source_checkBox_useDbStamps->isChecked();
03964 }
03965 bool PreferencesDialog::isSourceRGBDColorOnly() const
03966 {
03967 return _ui->checkbox_rgbd_colorOnly->isChecked();
03968 }
03969 int PreferencesDialog::getSourceImageDecimation() const
03970 {
03971 return _ui->spinBox_source_imageDecimation->value();
03972 }
03973 bool PreferencesDialog::isSourceStereoDepthGenerated() const
03974 {
03975 return _ui->checkbox_stereo_depthGenerated->isChecked();
03976 }
03977 bool PreferencesDialog::isSourceScanFromDepth() const
03978 {
03979 return _ui->groupBox_scanFromDepth->isChecked();
03980 }
03981 int PreferencesDialog::getSourceScanFromDepthDecimation() const
03982 {
03983 return _ui->spinBox_cameraScanFromDepth_decimation->value();
03984 }
03985 double PreferencesDialog::getSourceScanFromDepthMaxDepth() const
03986 {
03987 return _ui->doubleSpinBox_cameraSCanFromDepth_maxDepth->value();
03988 }
03989 double PreferencesDialog::getSourceScanVoxelSize() const
03990 {
03991 return _ui->doubleSpinBox_cameraImages_scanVoxelSize->value();
03992 }
03993 int PreferencesDialog::getSourceScanNormalsK() const
03994 {
03995 return _ui->spinBox_cameraImages_scanNormalsK->value();
03996 }
03997
03998 Camera * PreferencesDialog::createCamera(bool useRawImages)
03999 {
04000 Src driver = this->getSourceDriver();
04001 Camera * camera = 0;
04002 if(driver == PreferencesDialog::kSrcOpenNI_PCL)
04003 {
04004 if(useRawImages)
04005 {
04006 QMessageBox::warning(this, tr("Calibration"),
04007 tr("Using raw images for \"OpenNI\" driver is not yet supported. "
04008 "Factory calibration loaded from OpenNI is used."), QMessageBox::Ok);
04009 return 0;
04010 }
04011 else
04012 {
04013 camera = new CameraOpenni(
04014 _ui->lineEdit_openniOniPath->text().isEmpty()?this->getSourceDevice().toStdString():_ui->lineEdit_openniOniPath->text().toStdString(),
04015 this->getGeneralInputRate(),
04016 this->getSourceLocalTransform());
04017 }
04018 }
04019 else if(driver == PreferencesDialog::kSrcOpenNI2)
04020 {
04021 if(useRawImages)
04022 {
04023 QMessageBox::warning(this, tr("Calibration"),
04024 tr("Using raw images for \"OpenNI2\" driver is not yet supported. "
04025 "Factory calibration loaded from OpenNI2 is used."), QMessageBox::Ok);
04026 return 0;
04027 }
04028 else
04029 {
04030 camera = new CameraOpenNI2(
04031 _ui->lineEdit_openni2OniPath->text().isEmpty()?this->getSourceDevice().toStdString():_ui->lineEdit_openni2OniPath->text().toStdString(),
04032 this->getGeneralInputRate(),
04033 this->getSourceLocalTransform());
04034 }
04035 }
04036 else if(driver == PreferencesDialog::kSrcFreenect)
04037 {
04038 if(useRawImages)
04039 {
04040 QMessageBox::warning(this, tr("Calibration"),
04041 tr("Using raw images for \"Freenect\" driver is not yet supported. "
04042 "Factory calibration loaded from Freenect is used."), QMessageBox::Ok);
04043 return 0;
04044 }
04045 else
04046 {
04047 camera = new CameraFreenect(
04048 this->getSourceDevice().isEmpty()?0:atoi(this->getSourceDevice().toStdString().c_str()),
04049 this->getGeneralInputRate(),
04050 this->getSourceLocalTransform());
04051 }
04052 }
04053 else if(driver == PreferencesDialog::kSrcOpenNI_CV ||
04054 driver == PreferencesDialog::kSrcOpenNI_CV_ASUS)
04055 {
04056 if(useRawImages)
04057 {
04058 QMessageBox::warning(this, tr("Calibration"),
04059 tr("Using raw images for \"OpenNI\" driver is not yet supported. "
04060 "Factory calibration loaded from OpenNI is used."), QMessageBox::Ok);
04061 return 0;
04062 }
04063 else
04064 {
04065 camera = new CameraOpenNICV(
04066 driver == PreferencesDialog::kSrcOpenNI_CV_ASUS,
04067 this->getGeneralInputRate(),
04068 this->getSourceLocalTransform());
04069 }
04070 }
04071 else if(driver == kSrcFreenect2)
04072 {
04073 camera = new CameraFreenect2(
04074 this->getSourceDevice().isEmpty()?0:atoi(this->getSourceDevice().toStdString().c_str()),
04075 useRawImages?CameraFreenect2::kTypeColorIR:(CameraFreenect2::Type)_ui->comboBox_freenect2Format->currentIndex(),
04076 this->getGeneralInputRate(),
04077 this->getSourceLocalTransform(),
04078 _ui->doubleSpinBox_freenect2MinDepth->value(),
04079 _ui->doubleSpinBox_freenect2MaxDepth->value(),
04080 _ui->checkBox_freenect2BilateralFiltering->isChecked(),
04081 _ui->checkBox_freenect2EdgeAwareFiltering->isChecked(),
04082 _ui->checkBox_freenect2NoiseFiltering->isChecked());
04083 }
04084 else if(driver == kSrcRGBDImages)
04085 {
04086 camera = new CameraRGBDImages(
04087 _ui->lineEdit_cameraRGBDImages_path_rgb->text().append(QDir::separator()).toStdString(),
04088 _ui->lineEdit_cameraRGBDImages_path_depth->text().append(QDir::separator()).toStdString(),
04089 _ui->doubleSpinBox_cameraRGBDImages_scale->value(),
04090 this->getGeneralInputRate(),
04091 this->getSourceLocalTransform());
04092 ((CameraRGBDImages*)camera)->setBayerMode(_ui->comboBox_cameraImages_bayerMode->currentIndex()-1);
04093 ((CameraRGBDImages*)camera)->setGroundTruthPath(_ui->lineEdit_cameraImages_gt->text().toStdString(), _ui->comboBox_cameraImages_gtFormat->currentIndex());
04094 ((CameraRGBDImages*)camera)->setScanPath(
04095 _ui->lineEdit_cameraImages_path_scans->text().isEmpty()?"":_ui->lineEdit_cameraImages_path_scans->text().append(QDir::separator()).toStdString(),
04096 _ui->spinBox_cameraImages_max_scan_pts->value(),
04097 _ui->spinBox_cameraImages_scanDownsampleStep->value(),
04098 _ui->doubleSpinBox_cameraImages_scanVoxelSize->value(),
04099 _ui->spinBox_cameraImages_scanNormalsK->value(),
04100 this->getLaserLocalTransform());
04101 ((CameraRGBDImages*)camera)->setTimestamps(
04102 _ui->checkBox_cameraImages_timestamps->isChecked(),
04103 _ui->lineEdit_cameraImages_timestamps->text().toStdString(),
04104 _ui->checkBox_cameraImages_syncTimeStamps->isChecked());
04105 }
04106 else if(driver == kSrcDC1394)
04107 {
04108 camera = new CameraStereoDC1394(
04109 this->getGeneralInputRate(),
04110 this->getSourceLocalTransform());
04111 }
04112 else if(driver == kSrcFlyCapture2)
04113 {
04114 if(useRawImages)
04115 {
04116 QMessageBox::warning(this, tr("Calibration"),
04117 tr("Using raw images for \"FlyCapture2\" driver is not yet supported. "
04118 "Factory calibration loaded from FlyCapture2 is used."), QMessageBox::Ok);
04119 return 0;
04120 }
04121 else
04122 {
04123 camera = new CameraStereoFlyCapture2(
04124 this->getGeneralInputRate(),
04125 this->getSourceLocalTransform());
04126 }
04127 }
04128 else if(driver == kSrcStereoImages)
04129 {
04130 camera = new CameraStereoImages(
04131 _ui->lineEdit_cameraStereoImages_path_left->text().append(QDir::separator()).toStdString(),
04132 _ui->lineEdit_cameraStereoImages_path_right->text().append(QDir::separator()).toStdString(),
04133 _ui->checkBox_stereoImages_rectify->isChecked() && !useRawImages,
04134 this->getGeneralInputRate(),
04135 this->getSourceLocalTransform());
04136 ((CameraStereoImages*)camera)->setBayerMode(_ui->comboBox_cameraImages_bayerMode->currentIndex()-1);
04137 ((CameraStereoImages*)camera)->setGroundTruthPath(_ui->lineEdit_cameraImages_gt->text().toStdString(), _ui->comboBox_cameraImages_gtFormat->currentIndex());
04138 ((CameraStereoImages*)camera)->setScanPath(
04139 _ui->lineEdit_cameraImages_path_scans->text().isEmpty()?"":_ui->lineEdit_cameraImages_path_scans->text().append(QDir::separator()).toStdString(),
04140 _ui->spinBox_cameraImages_max_scan_pts->value(),
04141 _ui->spinBox_cameraImages_scanDownsampleStep->value(),
04142 _ui->doubleSpinBox_cameraImages_scanVoxelSize->value(),
04143 _ui->spinBox_cameraImages_scanNormalsK->value(),
04144 this->getLaserLocalTransform());
04145 ((CameraStereoImages*)camera)->setTimestamps(
04146 _ui->checkBox_cameraImages_timestamps->isChecked(),
04147 _ui->lineEdit_cameraImages_timestamps->text().toStdString(),
04148 _ui->checkBox_cameraImages_syncTimeStamps->isChecked());
04149 }
04150 else if (driver == kSrcStereoUsb)
04151 {
04152 camera = new CameraStereoVideo(
04153 this->getSourceDevice().isEmpty() ? 0 : atoi(this->getSourceDevice().toStdString().c_str()),
04154 !useRawImages,
04155 this->getGeneralInputRate(),
04156 this->getSourceLocalTransform());
04157 }
04158 else if(driver == kSrcStereoVideo)
04159 {
04160 camera = new CameraStereoVideo(
04161 _ui->lineEdit_cameraStereoVideo_path->text().toStdString(),
04162 _ui->checkBox_stereoVideo_rectify->isChecked() && !useRawImages,
04163 this->getGeneralInputRate(),
04164 this->getSourceLocalTransform());
04165 }
04166 else if (driver == kSrcStereoZed)
04167 {
04168 if(!_ui->lineEdit_zedSvoPath->text().isEmpty())
04169 {
04170 camera = new CameraStereoZed(
04171 _ui->lineEdit_zedSvoPath->text().toStdString(),
04172 _ui->comboBox_stereoZed_quality->currentIndex(),
04173 _ui->comboBox_stereoZed_sensingMode->currentIndex(),
04174 _ui->spinBox_stereoZed_confidenceThr->value(),
04175 _ui->checkbox_stereoZed_odom->isChecked(),
04176 this->getGeneralInputRate(),
04177 this->getSourceLocalTransform());
04178 }
04179 else
04180 {
04181 camera = new CameraStereoZed(
04182 this->getSourceDevice().isEmpty()?0:atoi(this->getSourceDevice().toStdString().c_str()),
04183 _ui->comboBox_stereoZed_resolution->currentIndex(),
04184 _ui->comboBox_stereoZed_quality->currentIndex(),
04185 _ui->comboBox_stereoZed_sensingMode->currentIndex(),
04186 _ui->spinBox_stereoZed_confidenceThr->value(),
04187 _ui->checkbox_stereoZed_odom->isChecked(),
04188 this->getGeneralInputRate(),
04189 this->getSourceLocalTransform());
04190 }
04191 }
04192 else if(driver == kSrcUsbDevice)
04193 {
04194 camera = new CameraVideo(
04195 this->getSourceDevice().isEmpty()?0:atoi(this->getSourceDevice().toStdString().c_str()),
04196 !useRawImages,
04197 this->getGeneralInputRate(),
04198 this->getSourceLocalTransform());
04199 }
04200 else if(driver == kSrcVideo)
04201 {
04202 camera = new CameraVideo(
04203 _ui->source_video_lineEdit_path->text().toStdString(),
04204 _ui->checkBox_rgbVideo_rectify->isChecked() && !useRawImages,
04205 this->getGeneralInputRate(),
04206 this->getSourceLocalTransform());
04207 }
04208 else if(driver == kSrcImages)
04209 {
04210 camera = new CameraImages(
04211 _ui->source_images_lineEdit_path->text().toStdString(),
04212 this->getGeneralInputRate(),
04213 this->getSourceLocalTransform());
04214
04215 ((CameraImages*)camera)->setStartIndex(_ui->source_images_spinBox_startPos->value());
04216 ((CameraImages*)camera)->setDirRefreshed(_ui->source_images_refreshDir->isChecked());
04217 ((CameraImages*)camera)->setImagesRectified(_ui->checkBox_rgbImages_rectify->isChecked() && !useRawImages);
04218
04219 ((CameraImages*)camera)->setBayerMode(_ui->comboBox_cameraImages_bayerMode->currentIndex()-1);
04220 ((CameraImages*)camera)->setGroundTruthPath(
04221 _ui->lineEdit_cameraImages_gt->text().toStdString(),
04222 _ui->comboBox_cameraImages_gtFormat->currentIndex());
04223 ((CameraImages*)camera)->setScanPath(
04224 _ui->lineEdit_cameraImages_path_scans->text().isEmpty()?"":_ui->lineEdit_cameraImages_path_scans->text().append(QDir::separator()).toStdString(),
04225 _ui->spinBox_cameraImages_max_scan_pts->value(),
04226 _ui->spinBox_cameraImages_scanDownsampleStep->value(),
04227 _ui->doubleSpinBox_cameraImages_scanVoxelSize->value(),
04228 _ui->spinBox_cameraImages_scanNormalsK->value(),
04229 this->getLaserLocalTransform());
04230 ((CameraImages*)camera)->setDepthFromScan(
04231 _ui->groupBox_depthFromScan->isChecked(),
04232 !_ui->groupBox_depthFromScan_fillHoles->isChecked()?0:_ui->radioButton_depthFromScan_vertical->isChecked()?1:-1,
04233 _ui->checkBox_depthFromScan_fillBorders->isChecked());
04234 ((CameraImages*)camera)->setTimestamps(
04235 _ui->checkBox_cameraImages_timestamps->isChecked(),
04236 _ui->lineEdit_cameraImages_timestamps->text().toStdString(),
04237 _ui->checkBox_cameraImages_syncTimeStamps->isChecked());
04238 }
04239 else if(driver == kSrcDatabase)
04240 {
04241 camera = new DBReader(_ui->source_database_lineEdit_path->text().toStdString(),
04242 _ui->source_checkBox_useDbStamps->isChecked()?-1:this->getGeneralInputRate(),
04243 _ui->source_checkBox_ignoreOdometry->isChecked(),
04244 _ui->source_checkBox_ignoreGoalDelay->isChecked(),
04245 _ui->source_checkBox_ignoreGoals->isChecked(),
04246 _ui->source_spinBox_databaseStartPos->value(),
04247 _ui->source_spinBox_database_cameraIndex->value());
04248 }
04249 else
04250 {
04251 UFATAL("Source driver undefined (%d)!", driver);
04252 }
04253
04254 if(camera)
04255 {
04256
04257 QString dir = this->getCameraInfoDir();
04258 QString calibrationFile = _ui->lineEdit_calibrationFile->text();
04259 if(!(driver >= kSrcRGB && driver <= kSrcVideo))
04260 {
04261 calibrationFile.remove("_left.yaml").remove("_right.yaml").remove("_pose.yaml");
04262 }
04263 QString name = QFileInfo(calibrationFile.remove(".yaml")).baseName();
04264 if(!_ui->lineEdit_calibrationFile->text().isEmpty())
04265 {
04266 QDir d = QFileInfo(_ui->lineEdit_calibrationFile->text()).dir();
04267 if(!_ui->lineEdit_calibrationFile->text().remove(QFileInfo(_ui->lineEdit_calibrationFile->text()).baseName()).isEmpty())
04268 {
04269 dir = d.absolutePath();
04270 }
04271 }
04272
04273 if(!camera->init(useRawImages?"":dir.toStdString(), name.toStdString()))
04274 {
04275 UWARN("init camera failed... ");
04276 QMessageBox::warning(this,
04277 tr("RTAB-Map"),
04278 tr("Camera initialization failed..."));
04279 delete camera;
04280 camera = 0;
04281 }
04282 else
04283 {
04284
04285 if(driver == kSrcOpenNI2)
04286 {
04287 ((CameraOpenNI2*)camera)->setAutoWhiteBalance(_ui->openni2_autoWhiteBalance->isChecked());
04288 ((CameraOpenNI2*)camera)->setAutoExposure(_ui->openni2_autoExposure->isChecked());
04289 ((CameraOpenNI2*)camera)->setMirroring(_ui->openni2_mirroring->isChecked());
04290 ((CameraOpenNI2*)camera)->setOpenNI2StampsAndIDsUsed(_ui->openni2_stampsIdsUsed->isChecked());
04291 if(CameraOpenNI2::exposureGainAvailable())
04292 {
04293 ((CameraOpenNI2*)camera)->setExposure(_ui->openni2_exposure->value());
04294 ((CameraOpenNI2*)camera)->setGain(_ui->openni2_gain->value());
04295 }
04296 }
04297 }
04298 }
04299
04300 return camera;
04301 }
04302
04303 bool PreferencesDialog::isStatisticsPublished() const
04304 {
04305 return _ui->groupBox_publishing->isChecked();
04306 }
04307 double PreferencesDialog::getLoopThr() const
04308 {
04309 return _ui->general_doubleSpinBox_hardThr->value();
04310 }
04311 double PreferencesDialog::getVpThr() const
04312 {
04313 return _ui->general_doubleSpinBox_vp->value();
04314 }
04315 double PreferencesDialog::getSimThr() const
04316 {
04317 return _ui->doubleSpinBox_similarityThreshold->value();
04318 }
04319 int PreferencesDialog::getOdomStrategy() const
04320 {
04321 return _ui->odom_strategy->currentIndex();
04322 }
04323 int PreferencesDialog::getOdomBufferSize() const
04324 {
04325 return _ui->odom_dataBufferSize->value();
04326 }
04327 bool PreferencesDialog::getRegVarianceFromInliersCount() const
04328 {
04329 return _ui->loopClosure_bowVarianceFromInliersCount->isChecked();
04330 }
04331
04332 QString PreferencesDialog::getCameraInfoDir() const
04333 {
04334 return (this->getWorkingDirectory().isEmpty()?".":this->getWorkingDirectory())+"/camera_info";
04335 }
04336
04337 bool PreferencesDialog::isImagesKept() const
04338 {
04339 return _ui->general_checkBox_imagesKept->isChecked();
04340 }
04341 bool PreferencesDialog::isCloudsKept() const
04342 {
04343 return _ui->general_checkBox_cloudsKept->isChecked();
04344 }
04345 float PreferencesDialog::getTimeLimit() const
04346 {
04347 return _ui->general_doubleSpinBox_timeThr->value();
04348 }
04349 float PreferencesDialog::getDetectionRate() const
04350 {
04351 return _ui->general_doubleSpinBox_detectionRate->value();
04352 }
04353 bool PreferencesDialog::isSLAMMode() const
04354 {
04355 return _ui->general_checkBox_SLAM_mode->isChecked();
04356 }
04357 bool PreferencesDialog::isRGBDMode() const
04358 {
04359 return _ui->general_checkBox_activateRGBD->isChecked();
04360 }
04361
04362
04363 void PreferencesDialog::setInputRate(double value)
04364 {
04365 ULOGGER_DEBUG("imgRate=%2.2f", value);
04366 if(_ui->general_doubleSpinBox_imgRate->value() != value)
04367 {
04368 _ui->general_doubleSpinBox_imgRate->setValue(value);
04369 if(validateForm())
04370 {
04371 this->writeSettings(getTmpIniFilePath());
04372 }
04373 else
04374 {
04375 this->readSettingsBegin();
04376 }
04377 }
04378 }
04379
04380 void PreferencesDialog::setDetectionRate(double value)
04381 {
04382 ULOGGER_DEBUG("detectionRate=%2.2f", value);
04383 if(_ui->general_doubleSpinBox_detectionRate->value() != value)
04384 {
04385 _ui->general_doubleSpinBox_detectionRate->setValue(value);
04386 if(validateForm())
04387 {
04388 this->writeSettings(getTmpIniFilePath());
04389 }
04390 else
04391 {
04392 this->readSettingsBegin();
04393 }
04394 }
04395 }
04396
04397 void PreferencesDialog::setTimeLimit(float value)
04398 {
04399 ULOGGER_DEBUG("timeLimit=%fs", value);
04400 if(_ui->general_doubleSpinBox_timeThr->value() != value)
04401 {
04402 _ui->general_doubleSpinBox_timeThr->setValue(value);
04403 if(validateForm())
04404 {
04405 this->writeSettings(getTmpIniFilePath());
04406 }
04407 else
04408 {
04409 this->readSettingsBegin();
04410 }
04411 }
04412 }
04413
04414 void PreferencesDialog::setSLAMMode(bool enabled)
04415 {
04416 ULOGGER_DEBUG("slam mode=%s", enabled?"true":"false");
04417 if(_ui->general_checkBox_SLAM_mode->isChecked() != enabled)
04418 {
04419 _ui->general_checkBox_SLAM_mode->setChecked(enabled);
04420 if(validateForm())
04421 {
04422 this->writeSettings(getTmpIniFilePath());
04423 }
04424 else
04425 {
04426 this->readSettingsBegin();
04427 }
04428 }
04429 }
04430
04431 void PreferencesDialog::testOdometry()
04432 {
04433 Camera * camera = this->createCamera();
04434 if(!camera)
04435 {
04436 return;
04437 }
04438
04439 ParametersMap parameters = this->getAllParameters();
04440 Odometry * odometry = Odometry::create(parameters);
04441
04442 OdometryThread odomThread(
04443 odometry,
04444 _ui->odom_dataBufferSize->value());
04445 odomThread.registerToEventsManager();
04446
04447 OdometryViewer * odomViewer = new OdometryViewer(10,
04448 _ui->spinBox_decimation_odom->value(),
04449 0.0f,
04450 _ui->doubleSpinBox_maxDepth_odom->value(),
04451 this->getOdomQualityWarnThr(),
04452 this,
04453 this->getAllParameters());
04454 odomViewer->setWindowTitle(tr("Odometry viewer"));
04455 odomViewer->resize(1280, 480+QPushButton().minimumHeight());
04456 odomViewer->registerToEventsManager();
04457
04458 CameraThread cameraThread(camera, this->getAllParameters());
04459 cameraThread.setMirroringEnabled(isSourceMirroring());
04460 cameraThread.setColorOnly(_ui->checkbox_rgbd_colorOnly->isChecked());
04461 cameraThread.setImageDecimation(_ui->spinBox_source_imageDecimation->value());
04462 cameraThread.setStereoToDepth(_ui->checkbox_stereo_depthGenerated->isChecked());
04463 cameraThread.setScanFromDepth(
04464 _ui->groupBox_scanFromDepth->isChecked(),
04465 _ui->spinBox_cameraScanFromDepth_decimation->value(),
04466 _ui->doubleSpinBox_cameraSCanFromDepth_maxDepth->value(),
04467 _ui->doubleSpinBox_cameraImages_scanVoxelSize->value(),
04468 _ui->spinBox_cameraImages_scanNormalsK->value());
04469 UEventsManager::createPipe(&cameraThread, &odomThread, "CameraEvent");
04470 UEventsManager::createPipe(&odomThread, odomViewer, "OdometryEvent");
04471 UEventsManager::createPipe(odomViewer, &odomThread, "OdometryResetEvent");
04472
04473 odomThread.start();
04474 cameraThread.start();
04475
04476 odomViewer->exec();
04477 delete odomViewer;
04478
04479 cameraThread.join(true);
04480 odomThread.join(true);
04481 }
04482
04483 void PreferencesDialog::testCamera()
04484 {
04485 CameraViewer * window = new CameraViewer(this, this->getAllParameters());
04486 window->setWindowTitle(tr("Camera viewer"));
04487 window->resize(1280, 480+QPushButton().minimumHeight());
04488 window->registerToEventsManager();
04489
04490 Camera * camera = this->createCamera();
04491 if(camera)
04492 {
04493 CameraThread cameraThread(camera, this->getAllParameters());
04494 cameraThread.setMirroringEnabled(isSourceMirroring());
04495 cameraThread.setColorOnly(_ui->checkbox_rgbd_colorOnly->isChecked());
04496 cameraThread.setImageDecimation(_ui->spinBox_source_imageDecimation->value());
04497 cameraThread.setStereoToDepth(_ui->checkbox_stereo_depthGenerated->isChecked());
04498 cameraThread.setScanFromDepth(
04499 _ui->groupBox_scanFromDepth->isChecked(),
04500 _ui->spinBox_cameraScanFromDepth_decimation->value(),
04501 _ui->doubleSpinBox_cameraSCanFromDepth_maxDepth->value(),
04502 _ui->doubleSpinBox_cameraImages_scanVoxelSize->value(),
04503 _ui->spinBox_cameraImages_scanNormalsK->value());
04504 UEventsManager::createPipe(&cameraThread, window, "CameraEvent");
04505
04506 cameraThread.start();
04507 window->exec();
04508 delete window;
04509 cameraThread.join(true);
04510 }
04511 else
04512 {
04513 delete window;
04514 }
04515 }
04516
04517 void PreferencesDialog::calibrate()
04518 {
04519 if(this->getSourceType() == kSrcDatabase)
04520 {
04521 QMessageBox::warning(this,
04522 tr("Calibration"),
04523 tr("Cannot calibrate database source!"));
04524 return;
04525 }
04526 Camera * camera = this->createCamera(true);
04527 if(!camera)
04528 {
04529 return;
04530 }
04531
04532 if(!this->getCameraInfoDir().isEmpty())
04533 {
04534 QDir dir(this->getCameraInfoDir());
04535 if (!dir.exists())
04536 {
04537 UINFO("Creating camera_info directory: \"%s\"", this->getCameraInfoDir().toStdString().c_str());
04538 if(!dir.mkpath(this->getCameraInfoDir()))
04539 {
04540 UWARN("Could create camera_info directory: \"%s\"", this->getCameraInfoDir().toStdString().c_str());
04541 }
04542 }
04543 }
04544 _calibrationDialog->setStereoMode(this->getSourceType() != kSrcRGB);
04545 _calibrationDialog->setSwitchedImages(dynamic_cast<CameraFreenect2*>(camera) != 0);
04546 _calibrationDialog->setSavingDirectory(this->getCameraInfoDir());
04547 _calibrationDialog->registerToEventsManager();
04548
04549 CameraThread cameraThread(camera, this->getAllParameters());
04550 UEventsManager::createPipe(&cameraThread, _calibrationDialog, "CameraEvent");
04551
04552 cameraThread.start();
04553
04554 _calibrationDialog->exec();
04555 _calibrationDialog->unregisterFromEventsManager();
04556
04557 cameraThread.join(true);
04558 }
04559
04560 void PreferencesDialog::calibrateSimple()
04561 {
04562 _createCalibrationDialog->setCameraInfoDir(this->getCameraInfoDir());
04563 if(_createCalibrationDialog->exec() == QMessageBox::Accepted)
04564 {
04565 _ui->lineEdit_calibrationFile->setText(_createCalibrationDialog->cameraName());
04566 }
04567 }
04568
04569 }
04570