PreferencesDialog.cpp
Go to the documentation of this file.
1 /*
2 Copyright (c) 2010-2016, Mathieu Labbe - IntRoLab - Universite de Sherbrooke
3 All rights reserved.
4 
5 Redistribution and use in source and binary forms, with or without
6 modification, are permitted provided that the following conditions are met:
7  * Redistributions of source code must retain the above copyright
8  notice, this list of conditions and the following disclaimer.
9  * Redistributions in binary form must reproduce the above copyright
10  notice, this list of conditions and the following disclaimer in the
11  documentation and/or other materials provided with the distribution.
12  * Neither the name of the Universite de Sherbrooke nor the
13  names of its contributors may be used to endorse or promote products
14  derived from this software without specific prior written permission.
15 
16 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
17 ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
18 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
19 DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY
20 DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
21 (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
22 LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
23 ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
24 (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
25 SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
26 */
27 
32 
33 #include <QtCore/QSettings>
34 #include <QtCore/QDir>
35 #include <QtCore/QTimer>
36 #include <QUrl>
37 
38 #include <QButtonGroup>
39 #include <QFileDialog>
40 #include <QInputDialog>
41 #include <QMessageBox>
42 #include <QtGui/QStandardItemModel>
43 #include <QMainWindow>
44 #include <QProgressDialog>
45 #include <QScrollBar>
46 #include <QStatusBar>
47 #include <QDesktopServices>
48 #include <QtGui/QCloseEvent>
49 
50 #include "ui_preferencesDialog.h"
51 
52 #include "rtabmap/core/Version.h"
54 #include "rtabmap/core/Odometry.h"
58 #include "rtabmap/core/CameraRGB.h"
60 #include "rtabmap/core/IMUThread.h"
61 #include "rtabmap/core/Memory.h"
63 #include "rtabmap/core/Optimizer.h"
65 #include "rtabmap/core/DBReader.h"
67 
71 #include "rtabmap/gui/ImageView.h"
78 
81 #include <rtabmap/utilite/UStl.h>
83 #include "rtabmap/utilite/UPlot.h"
84 
85 #include <opencv2/opencv_modules.hpp>
86 #if CV_MAJOR_VERSION < 3
87 #ifdef HAVE_OPENCV_GPU
88  #include <opencv2/gpu/gpu.hpp>
89 #endif
90 #else
91 #ifdef HAVE_OPENCV_CUDAFEATURES2D
92  #include <opencv2/core/cuda.hpp>
93 #endif
94 #endif
95 
96 using namespace rtabmap;
97 
98 namespace rtabmap {
99 
101  QDialog(parent),
102  _obsoletePanels(kPanelDummy),
103  _ui(0),
104  _indexModel(0),
105  _initialized(false),
106  _progressDialog(new QProgressDialog(this)),
107  _calibrationDialog(new CalibrationDialog(false, ".", false, this)),
108  _createCalibrationDialog(new CreateSimpleCalibrationDialog(".", "", this))
109 {
110  ULOGGER_DEBUG("");
111  _calibrationDialog->setWindowFlags(Qt::Window);
112  _calibrationDialog->setWindowTitle(tr("Calibration"));
113 
114  _progressDialog->setWindowTitle(tr("Read parameters..."));
115  _progressDialog->setMaximum(2);
116  _progressDialog->setValue(2);
117 
118  _ui = new Ui_preferencesDialog();
119  _ui->setupUi(this);
120 
121  bool haveCuda = false;
122 #if CV_MAJOR_VERSION < 3
123 #ifdef HAVE_OPENCV_GPU
124  haveCuda = cv::gpu::getCudaEnabledDeviceCount() != 0;
125 #endif
126 #else
127 #ifdef HAVE_OPENCV_CUDAFEATURES2D
128  haveCuda = cv::cuda::getCudaEnabledDeviceCount() != 0;
129 #endif
130 #endif
131  if(!haveCuda)
132  {
133  _ui->surf_checkBox_gpuVersion->setChecked(false);
134  _ui->surf_checkBox_gpuVersion->setEnabled(false);
135  _ui->label_surf_checkBox_gpuVersion->setEnabled(false);
136  _ui->surf_doubleSpinBox_gpuKeypointsRatio->setEnabled(false);
137  _ui->label_surf_checkBox_gpuKeypointsRatio->setEnabled(false);
138 
139  _ui->fastGpu->setChecked(false);
140  _ui->fastGpu->setEnabled(false);
141  _ui->label_fastGPU->setEnabled(false);
142  _ui->fastKeypointRatio->setEnabled(false);
143  _ui->label_fastGPUKptRatio->setEnabled(false);
144 
145  _ui->checkBox_ORBGpu->setChecked(false);
146  _ui->checkBox_ORBGpu->setEnabled(false);
147  _ui->label_orbGpu->setEnabled(false);
148 
149  // remove BruteForceGPU option
150  _ui->comboBox_dictionary_strategy->removeItem(4);
151  _ui->reextract_nn->removeItem(4);
152  }
153 
154 #ifndef RTABMAP_OCTOMAP
155  _ui->groupBox_octomap->setChecked(false);
156  _ui->groupBox_octomap->setEnabled(false);
157 #endif
158 
159 #ifndef RTABMAP_REALSENSE_SLAM
160  _ui->checkbox_realsenseOdom->setChecked(false);
161  _ui->checkbox_realsenseOdom->setEnabled(false);
162  _ui->label_realsenseOdom->setEnabled(false);
163 #endif
164 
165 #ifndef RTABMAP_FOVIS
166  _ui->odom_strategy->setItemData(2, 0, Qt::UserRole - 1);
167 #endif
168 #ifndef RTABMAP_VISO2
169  _ui->odom_strategy->setItemData(3, 0, Qt::UserRole - 1);
170 #endif
171 #ifndef RTABMAP_DVO
172  _ui->odom_strategy->setItemData(4, 0, Qt::UserRole - 1);
173 #endif
174 #ifndef RTABMAP_ORB_SLAM2
175  _ui->odom_strategy->setItemData(5, 0, Qt::UserRole - 1);
176 #endif
177 #ifndef RTABMAP_OKVIS
178  _ui->odom_strategy->setItemData(6, 0, Qt::UserRole - 1);
179 #endif
180 #ifndef RTABMAP_LOAM
181  _ui->odom_strategy->setItemData(7, 0, Qt::UserRole - 1);
182 #endif
183 #ifndef RTABMAP_MSCKF_VIO
184  _ui->odom_strategy->setItemData(8, 0, Qt::UserRole - 1);
185 #endif
186 
187 #ifndef RTABMAP_NONFREE
188  _ui->comboBox_detector_strategy->setItemData(0, 0, Qt::UserRole - 1);
189  _ui->comboBox_detector_strategy->setItemData(1, 0, Qt::UserRole - 1);
190  _ui->reextract_type->setItemData(0, 0, Qt::UserRole - 1);
191  _ui->reextract_type->setItemData(1, 0, Qt::UserRole - 1);
192 
193 #if CV_MAJOR_VERSION >= 3
194  _ui->comboBox_detector_strategy->setItemData(0, 0, Qt::UserRole - 1);
195  _ui->comboBox_detector_strategy->setItemData(1, 0, Qt::UserRole - 1);
196  _ui->comboBox_detector_strategy->setItemData(3, 0, Qt::UserRole - 1);
197  _ui->comboBox_detector_strategy->setItemData(4, 0, Qt::UserRole - 1);
198  _ui->comboBox_detector_strategy->setItemData(5, 0, Qt::UserRole - 1);
199  _ui->comboBox_detector_strategy->setItemData(6, 0, Qt::UserRole - 1);
200  _ui->reextract_type->setItemData(0, 0, Qt::UserRole - 1);
201  _ui->reextract_type->setItemData(1, 0, Qt::UserRole - 1);
202  _ui->reextract_type->setItemData(3, 0, Qt::UserRole - 1);
203  _ui->reextract_type->setItemData(4, 0, Qt::UserRole - 1);
204  _ui->reextract_type->setItemData(5, 0, Qt::UserRole - 1);
205  _ui->reextract_type->setItemData(6, 0, Qt::UserRole - 1);
206 #endif
207 #endif
208 
209 #if CV_MAJOR_VERSION >= 3
210  _ui->groupBox_fast_opencv2->setEnabled(false);
211 #else
212  _ui->comboBox_detector_strategy->setItemData(9, 0, Qt::UserRole - 1); // No KAZE
213  _ui->reextract_type->setItemData(9, 0, Qt::UserRole - 1); // No KAZE
214 #endif
215 
216  _ui->comboBox_cameraImages_odomFormat->setItemData(4, 0, Qt::UserRole - 1);
217  _ui->comboBox_cameraImages_gtFormat->setItemData(4, 0, Qt::UserRole - 1);
219  {
220  _ui->graphOptimization_type->setItemData(1, 0, Qt::UserRole - 1);
221  _ui->odom_f2m_bundleStrategy->setItemData(1, 0, Qt::UserRole - 1);
222  _ui->loopClosure_bundle->setItemData(1, 0, Qt::UserRole - 1);
223  _ui->groupBoxx_g2o->setEnabled(false);
224  }
225 #ifdef RTABMAP_ORB_SLAM2
226  else
227  {
228  // only graph optimization is disabled, g2o (from ORB_SLAM2) is valid only for SBA
229  _ui->graphOptimization_type->setItemData(1, 0, Qt::UserRole - 1);
230  }
231 #endif
233  {
234  _ui->comboBox_g2o_solver->setItemData(0, 0, Qt::UserRole - 1);
235  }
237  {
238  _ui->comboBox_g2o_solver->setItemData(2, 0, Qt::UserRole - 1);
239  }
241  {
242  _ui->graphOptimization_type->setItemData(0, 0, Qt::UserRole - 1);
243  }
245  {
246  _ui->graphOptimization_type->setItemData(2, 0, Qt::UserRole - 1);
247  }
249  {
250  _ui->odom_f2m_bundleStrategy->setItemData(2, 0, Qt::UserRole - 1);
251  _ui->loopClosure_bundle->setItemData(2, 0, Qt::UserRole - 1);
252  }
253 #ifdef RTABMAP_VERTIGO
255 #endif
256  {
257  _ui->graphOptimization_robust->setEnabled(false);
258  }
259 #ifndef RTABMAP_POINTMATCHER
260  _ui->groupBox_libpointmatcher->setEnabled(false);
261 #endif
263  {
264  _ui->comboBox_cameraRGBD->setItemData(kSrcOpenNI_PCL - kSrcRGBD, 0, Qt::UserRole - 1);
265  }
267  {
268  _ui->comboBox_cameraRGBD->setItemData(kSrcFreenect - kSrcRGBD, 0, Qt::UserRole - 1);
269  }
271  {
272  _ui->comboBox_cameraRGBD->setItemData(kSrcOpenNI_CV - kSrcRGBD, 0, Qt::UserRole - 1);
273  _ui->comboBox_cameraRGBD->setItemData(kSrcOpenNI_CV_ASUS - kSrcRGBD, 0, Qt::UserRole - 1);
274  }
276  {
277  _ui->comboBox_cameraRGBD->setItemData(kSrcOpenNI2 - kSrcRGBD, 0, Qt::UserRole - 1);
278  }
280  {
281  _ui->comboBox_cameraRGBD->setItemData(kSrcFreenect2 - kSrcRGBD, 0, Qt::UserRole - 1);
282  }
283  if (!CameraK4W2::available())
284  {
285  _ui->comboBox_cameraRGBD->setItemData(kSrcK4W2 - kSrcRGBD, 0, Qt::UserRole - 1);
286  }
288  {
289  _ui->comboBox_cameraRGBD->setItemData(kSrcRealSense - kSrcRGBD, 0, Qt::UserRole - 1);
290  }
292  {
293  _ui->comboBox_cameraRGBD->setItemData(kSrcRealSense2 - kSrcRGBD, 0, Qt::UserRole - 1);
294  }
296  {
297  _ui->comboBox_cameraStereo->setItemData(kSrcDC1394 - kSrcStereo, 0, Qt::UserRole - 1);
298  }
300  {
301  _ui->comboBox_cameraStereo->setItemData(kSrcFlyCapture2 - kSrcStereo, 0, Qt::UserRole - 1);
302  }
304  {
305  _ui->comboBox_cameraStereo->setItemData(kSrcStereoZed - kSrcStereo, 0, Qt::UserRole - 1);
306  }
307  _ui->openni2_exposure->setEnabled(CameraOpenNI2::exposureGainAvailable());
308  _ui->openni2_gain->setEnabled(CameraOpenNI2::exposureGainAvailable());
309 
310 #if PCL_VERSION_COMPARE(<, 1, 7, 2)
311  _ui->checkBox_showFrustums->setEnabled(false);
312  _ui->checkBox_showFrustums->setChecked(false);
313  _ui->checkBox_showOdomFrustums->setEnabled(false);
314  _ui->checkBox_showOdomFrustums->setChecked(false);
315 #endif
316 
317  // in case we change the ui, we should not forget to change stuff related to this parameter
318  UASSERT(_ui->odom_registration->count() == 4);
319 
320  // Default Driver
321  connect(_ui->comboBox_sourceType, SIGNAL(currentIndexChanged(int)), this, SLOT(updateSourceGrpVisibility()));
322  connect(_ui->comboBox_cameraRGBD, SIGNAL(currentIndexChanged(int)), this, SLOT(updateSourceGrpVisibility()));
323  connect(_ui->source_comboBox_image_type, SIGNAL(currentIndexChanged(int)), this, SLOT(updateSourceGrpVisibility()));
324  connect(_ui->comboBox_cameraStereo, SIGNAL(currentIndexChanged(int)), this, SLOT(updateSourceGrpVisibility()));
325  this->resetSettings(_ui->groupBox_source0);
326 
327  _ui->predictionPlot->showLegend(false);
328 
329  QButtonGroup * buttonGroup = new QButtonGroup(this);
330  buttonGroup->addButton(_ui->radioButton_basic);
331  buttonGroup->addButton(_ui->radioButton_advanced);
332 
333  // Connect
334  connect(_ui->buttonBox_global, SIGNAL(clicked(QAbstractButton *)), this, SLOT(closeDialog(QAbstractButton *)));
335  connect(_ui->buttonBox_local, SIGNAL(clicked(QAbstractButton *)), this, SLOT(resetApply(QAbstractButton *)));
336  connect(_ui->pushButton_loadConfig, SIGNAL(clicked()), this, SLOT(loadConfigFrom()));
337  connect(_ui->pushButton_saveConfig, SIGNAL(clicked()), this, SLOT(saveConfigTo()));
338  connect(_ui->pushButton_resetConfig, SIGNAL(clicked()), this, SLOT(resetConfig()));
339  connect(_ui->radioButton_basic, SIGNAL(toggled(bool)), this, SLOT(setupTreeView()));
340  connect(_ui->pushButton_testOdometry, SIGNAL(clicked()), this, SLOT(testOdometry()));
341  connect(_ui->pushButton_test_camera, SIGNAL(clicked()), this, SLOT(testCamera()));
342 
343  // General panel
344  connect(_ui->general_checkBox_imagesKept, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteGeneralPanel()));
345  connect(_ui->general_checkBox_cloudsKept, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteGeneralPanel()));
346  connect(_ui->checkBox_verticalLayoutUsed, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteGeneralPanel()));
347  connect(_ui->checkBox_imageRejectedShown, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteGeneralPanel()));
348  connect(_ui->checkBox_imageHighestHypShown, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteGeneralPanel()));
349  connect(_ui->checkBox_beep, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteGeneralPanel()));
350  connect(_ui->checkBox_stamps, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteGeneralPanel()));
351  connect(_ui->checkBox_cacheStatistics, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteGeneralPanel()));
352  connect(_ui->checkBox_notifyWhenNewGlobalPathIsReceived, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteGeneralPanel()));
353  connect(_ui->spinBox_odomQualityWarnThr, SIGNAL(valueChanged(int)), this, SLOT(makeObsoleteGeneralPanel()));
354  connect(_ui->checkBox_odom_onlyInliersShown, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteGeneralPanel()));
355  connect(_ui->radioButton_posteriorGraphView, SIGNAL(toggled(bool)), this, SLOT(makeObsoleteGeneralPanel()));
356  connect(_ui->radioButton_wordsGraphView, SIGNAL(toggled(bool)), this, SLOT(makeObsoleteGeneralPanel()));
357  connect(_ui->radioButton_localizationsGraphView, SIGNAL(toggled(bool)), this, SLOT(makeObsoleteGeneralPanel()));
358  connect(_ui->radioButton_nochangeGraphView, SIGNAL(toggled(bool)), this, SLOT(makeObsoleteGeneralPanel()));
359  connect(_ui->checkbox_odomDisabled, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteGeneralPanel()));
360  connect(_ui->odom_registration, SIGNAL(currentIndexChanged(int)), this, SLOT(makeObsoleteGeneralPanel()));
361  connect(_ui->checkbox_groundTruthAlign, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteGeneralPanel()));
362 
363  // Cloud rendering panel
364  _3dRenderingShowClouds.resize(2);
365  _3dRenderingShowClouds[0] = _ui->checkBox_showClouds;
366  _3dRenderingShowClouds[1] = _ui->checkBox_showOdomClouds;
367 
368  _3dRenderingDecimation.resize(2);
369  _3dRenderingDecimation[0] = _ui->spinBox_decimation;
370  _3dRenderingDecimation[1] = _ui->spinBox_decimation_odom;
371 
372  _3dRenderingMaxDepth.resize(2);
373  _3dRenderingMaxDepth[0] = _ui->doubleSpinBox_maxDepth;
374  _3dRenderingMaxDepth[1] = _ui->doubleSpinBox_maxDepth_odom;
375 
376  _3dRenderingMinDepth.resize(2);
377  _3dRenderingMinDepth[0] = _ui->doubleSpinBox_minDepth;
378  _3dRenderingMinDepth[1] = _ui->doubleSpinBox_minDepth_odom;
379 
380  _3dRenderingRoiRatios.resize(2);
381  _3dRenderingRoiRatios[0] = _ui->lineEdit_roiRatios;
382  _3dRenderingRoiRatios[1] = _ui->lineEdit_roiRatios_odom;
383 
384  _3dRenderingColorScheme.resize(2);
385  _3dRenderingColorScheme[0] = _ui->spinBox_colorScheme;
386  _3dRenderingColorScheme[1] = _ui->spinBox_colorScheme_odom;
387 
388  _3dRenderingOpacity.resize(2);
389  _3dRenderingOpacity[0] = _ui->doubleSpinBox_opacity;
390  _3dRenderingOpacity[1] = _ui->doubleSpinBox_opacity_odom;
391 
392  _3dRenderingPtSize.resize(2);
393  _3dRenderingPtSize[0] = _ui->spinBox_ptsize;
394  _3dRenderingPtSize[1] = _ui->spinBox_ptsize_odom;
395 
396  _3dRenderingShowScans.resize(2);
397  _3dRenderingShowScans[0] = _ui->checkBox_showScans;
398  _3dRenderingShowScans[1] = _ui->checkBox_showOdomScans;
399 
401  _3dRenderingDownsamplingScan[0] = _ui->spinBox_downsamplingScan;
402  _3dRenderingDownsamplingScan[1] = _ui->spinBox_downsamplingScan_odom;
403 
404  _3dRenderingMaxRange.resize(2);
405  _3dRenderingMaxRange[0] = _ui->doubleSpinBox_maxRange;
406  _3dRenderingMaxRange[1] = _ui->doubleSpinBox_maxRange_odom;
407 
408  _3dRenderingMinRange.resize(2);
409  _3dRenderingMinRange[0] = _ui->doubleSpinBox_minRange;
410  _3dRenderingMinRange[1] = _ui->doubleSpinBox_minRange_odom;
411 
412  _3dRenderingVoxelSizeScan.resize(2);
413  _3dRenderingVoxelSizeScan[0] = _ui->doubleSpinBox_voxelSizeScan;
414  _3dRenderingVoxelSizeScan[1] = _ui->doubleSpinBox_voxelSizeScan_odom;
415 
416  _3dRenderingColorSchemeScan.resize(2);
417  _3dRenderingColorSchemeScan[0] = _ui->spinBox_colorSchemeScan;
418  _3dRenderingColorSchemeScan[1] = _ui->spinBox_colorSchemeScan_odom;
419 
420  _3dRenderingOpacityScan.resize(2);
421  _3dRenderingOpacityScan[0] = _ui->doubleSpinBox_opacity_scan;
422  _3dRenderingOpacityScan[1] = _ui->doubleSpinBox_opacity_odom_scan;
423 
424  _3dRenderingPtSizeScan.resize(2);
425  _3dRenderingPtSizeScan[0] = _ui->spinBox_ptsize_scan;
426  _3dRenderingPtSizeScan[1] = _ui->spinBox_ptsize_odom_scan;
427 
428  _3dRenderingShowFeatures.resize(2);
429  _3dRenderingShowFeatures[0] = _ui->checkBox_showFeatures;
430  _3dRenderingShowFeatures[1] = _ui->checkBox_showOdomFeatures;
431 
432  _3dRenderingShowFrustums.resize(2);
433  _3dRenderingShowFrustums[0] = _ui->checkBox_showFrustums;
434  _3dRenderingShowFrustums[1] = _ui->checkBox_showOdomFrustums;
435 
436  _3dRenderingPtSizeFeatures.resize(2);
437  _3dRenderingPtSizeFeatures[0] = _ui->spinBox_ptsize_features;
438  _3dRenderingPtSizeFeatures[1] = _ui->spinBox_ptsize_odom_features;
439 
440  for(int i=0; i<2; ++i)
441  {
442  connect(_3dRenderingShowClouds[i], SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteCloudRenderingPanel()));
443  connect(_3dRenderingDecimation[i], SIGNAL(valueChanged(int)), this, SLOT(makeObsoleteCloudRenderingPanel()));
444  connect(_3dRenderingMaxDepth[i], SIGNAL(valueChanged(double)), this, SLOT(makeObsoleteCloudRenderingPanel()));
445  connect(_3dRenderingMinDepth[i], SIGNAL(valueChanged(double)), this, SLOT(makeObsoleteCloudRenderingPanel()));
446  connect(_3dRenderingRoiRatios[i], SIGNAL(textChanged(const QString &)), this, SLOT(makeObsoleteCloudRenderingPanel()));
447  connect(_3dRenderingShowScans[i], SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteCloudRenderingPanel()));
448  connect(_3dRenderingShowFeatures[i], SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteCloudRenderingPanel()));
449  connect(_3dRenderingShowFrustums[i], SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteCloudRenderingPanel()));
450 
451  connect(_3dRenderingDownsamplingScan[i], SIGNAL(valueChanged(int)), this, SLOT(makeObsoleteCloudRenderingPanel()));
452  connect(_3dRenderingMaxRange[i], SIGNAL(valueChanged(double)), this, SLOT(makeObsoleteCloudRenderingPanel()));
453  connect(_3dRenderingMinRange[i], SIGNAL(valueChanged(double)), this, SLOT(makeObsoleteCloudRenderingPanel()));
454  connect(_3dRenderingVoxelSizeScan[i], SIGNAL(valueChanged(double)), this, SLOT(makeObsoleteCloudRenderingPanel()));
455  connect(_3dRenderingColorScheme[i], SIGNAL(valueChanged(int)), this, SLOT(makeObsoleteCloudRenderingPanel()));
456  connect(_3dRenderingOpacity[i], SIGNAL(valueChanged(double)), this, SLOT(makeObsoleteCloudRenderingPanel()));
457  connect(_3dRenderingPtSize[i], SIGNAL(valueChanged(int)), this, SLOT(makeObsoleteCloudRenderingPanel()));
458  connect(_3dRenderingColorSchemeScan[i], SIGNAL(valueChanged(int)), this, SLOT(makeObsoleteCloudRenderingPanel()));
459  connect(_3dRenderingOpacityScan[i], SIGNAL(valueChanged(double)), this, SLOT(makeObsoleteCloudRenderingPanel()));
460  connect(_3dRenderingPtSizeScan[i], SIGNAL(valueChanged(int)), this, SLOT(makeObsoleteCloudRenderingPanel()));
461  connect(_3dRenderingPtSizeFeatures[i], SIGNAL(valueChanged(int)), this, SLOT(makeObsoleteCloudRenderingPanel()));
462  }
463  connect(_ui->doubleSpinBox_voxel, SIGNAL(valueChanged(double)), this, SLOT(makeObsoleteCloudRenderingPanel()));
464  connect(_ui->doubleSpinBox_noiseRadius, SIGNAL(valueChanged(double)), this, SLOT(makeObsoleteCloudRenderingPanel()));
465  connect(_ui->spinBox_noiseMinNeighbors, SIGNAL(valueChanged(int)), this, SLOT(makeObsoleteCloudRenderingPanel()));
466  connect(_ui->doubleSpinBox_ceilingFilterHeight, SIGNAL(valueChanged(double)), this, SLOT(makeObsoleteCloudRenderingPanel()));
467  connect(_ui->doubleSpinBox_floorFilterHeight, SIGNAL(valueChanged(double)), this, SLOT(makeObsoleteCloudRenderingPanel()));
468  connect(_ui->spinBox_normalKSearch, SIGNAL(valueChanged(int)), this, SLOT(makeObsoleteCloudRenderingPanel()));
469  connect(_ui->doubleSpinBox_normalRadiusSearch, SIGNAL(valueChanged(double)), this, SLOT(makeObsoleteCloudRenderingPanel()));
470  connect(_ui->doubleSpinBox_ceilingFilterHeight_scan, SIGNAL(valueChanged(double)), this, SLOT(makeObsoleteCloudRenderingPanel()));
471  connect(_ui->doubleSpinBox_floorFilterHeight_scan, SIGNAL(valueChanged(double)), this, SLOT(makeObsoleteCloudRenderingPanel()));
472  connect(_ui->spinBox_normalKSearch_scan, SIGNAL(valueChanged(int)), this, SLOT(makeObsoleteCloudRenderingPanel()));
473  connect(_ui->doubleSpinBox_normalRadiusSearch_scan, SIGNAL(valueChanged(double)), this, SLOT(makeObsoleteCloudRenderingPanel()));
474 
475  connect(_ui->checkBox_showGraphs, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteCloudRenderingPanel()));
476  connect(_ui->checkBox_showLabels, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteCloudRenderingPanel()));
477 
478  connect(_ui->radioButton_noFiltering, SIGNAL(toggled(bool)), this, SLOT(makeObsoleteCloudRenderingPanel()));
479  connect(_ui->radioButton_nodeFiltering, SIGNAL(toggled(bool)), this, SLOT(makeObsoleteCloudRenderingPanel()));
480  connect(_ui->radioButton_subtractFiltering, SIGNAL(toggled(bool)), this, SLOT(makeObsoleteCloudRenderingPanel()));
481  connect(_ui->doubleSpinBox_cloudFilterRadius, SIGNAL(valueChanged(double)), this, SLOT(makeObsoleteCloudRenderingPanel()));
482  connect(_ui->doubleSpinBox_cloudFilterAngle, SIGNAL(valueChanged(double)), this, SLOT(makeObsoleteCloudRenderingPanel()));
483  connect(_ui->spinBox_subtractFilteringMinPts, SIGNAL(valueChanged(int)), this, SLOT(makeObsoleteCloudRenderingPanel()));
484  connect(_ui->doubleSpinBox_subtractFilteringRadius, SIGNAL(valueChanged(double)), this, SLOT(makeObsoleteCloudRenderingPanel()));
485  connect(_ui->doubleSpinBox_subtractFilteringAngle, SIGNAL(valueChanged(double)), this, SLOT(makeObsoleteCloudRenderingPanel()));
486 
487  connect(_ui->checkBox_map_shown, SIGNAL(clicked(bool)), this, SLOT(makeObsoleteCloudRenderingPanel()));
488  connect(_ui->doubleSpinBox_map_opacity, SIGNAL(valueChanged(double)), this, SLOT(makeObsoleteCloudRenderingPanel()));
489 
490  connect(_ui->groupBox_octomap, SIGNAL(toggled(bool)), this, SLOT(makeObsoleteCloudRenderingPanel()));
491  connect(_ui->spinBox_octomap_treeDepth, SIGNAL(valueChanged(int)), this, SLOT(makeObsoleteCloudRenderingPanel()));
492  connect(_ui->checkBox_octomap_2dgrid, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteCloudRenderingPanel()));
493  connect(_ui->checkBox_octomap_show3dMap, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteCloudRenderingPanel()));
494  connect(_ui->comboBox_octomap_renderingType, SIGNAL(currentIndexChanged(int)), this, SLOT(makeObsoleteCloudRenderingPanel()));
495  connect(_ui->spinBox_octomap_pointSize, SIGNAL(valueChanged(int)), this, SLOT(makeObsoleteCloudRenderingPanel()));
496 
497  connect(_ui->groupBox_organized, SIGNAL(toggled(bool)), this, SLOT(makeObsoleteCloudRenderingPanel()));
498  connect(_ui->doubleSpinBox_mesh_angleTolerance, SIGNAL(valueChanged(double)), this, SLOT(makeObsoleteCloudRenderingPanel()));
499  connect(_ui->checkBox_mesh_quad, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteCloudRenderingPanel()));
500  connect(_ui->checkBox_mesh_texture, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteCloudRenderingPanel()));
501  connect(_ui->spinBox_mesh_triangleSize, SIGNAL(valueChanged(int)), this, SLOT(makeObsoleteCloudRenderingPanel()));
502 
503  //Logging panel
504  connect(_ui->comboBox_loggerLevel, SIGNAL(currentIndexChanged(int)), this, SLOT(makeObsoleteLoggingPanel()));
505  connect(_ui->comboBox_loggerEventLevel, SIGNAL(currentIndexChanged(int)), this, SLOT(makeObsoleteLoggingPanel()));
506  connect(_ui->comboBox_loggerPauseLevel, SIGNAL(currentIndexChanged(int)), this, SLOT(makeObsoleteLoggingPanel()));
507  connect(_ui->checkBox_logger_printTime, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteLoggingPanel()));
508  connect(_ui->checkBox_logger_printThreadId, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteLoggingPanel()));
509  connect(_ui->comboBox_loggerType, SIGNAL(currentIndexChanged(int)), this, SLOT(makeObsoleteLoggingPanel()));
510  _ui->comboBox_loggerFilter->SetDisplayText("Select:");
511  connect(_ui->comboBox_loggerFilter, SIGNAL(itemChanged()), this, SLOT(makeObsoleteLoggingPanel()));
512 
513  //Source panel
514  connect(_ui->general_doubleSpinBox_imgRate, SIGNAL(valueChanged(double)), this, SLOT(makeObsoleteSourcePanel()));
515  connect(_ui->general_doubleSpinBox_imgRate, SIGNAL(valueChanged(double)), _ui->doubleSpinBox_OdomORBSLAM2Fps, SLOT(setValue(double)));
516  connect(_ui->source_mirroring, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
517  connect(_ui->toolButton_source_path_calibration, SIGNAL(clicked()), this, SLOT(selectCalibrationPath()));
518  connect(_ui->lineEdit_calibrationFile, SIGNAL(textChanged(const QString &)), this, SLOT(makeObsoleteSourcePanel()));
519  _ui->stackedWidget_src->setCurrentIndex(_ui->comboBox_sourceType->currentIndex());
520  connect(_ui->comboBox_sourceType, SIGNAL(currentIndexChanged(int)), _ui->stackedWidget_src, SLOT(setCurrentIndex(int)));
521  connect(_ui->comboBox_sourceType, SIGNAL(currentIndexChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
522  connect(_ui->lineEdit_sourceDevice, SIGNAL(textChanged(const QString &)), this, SLOT(makeObsoleteSourcePanel()));
523  connect(_ui->lineEdit_sourceLocalTransform, SIGNAL(textChanged(const QString &)), this, SLOT(makeObsoleteSourcePanel()));
524 
525  //RGB source
526  _ui->stackedWidget_image->setCurrentIndex(_ui->source_comboBox_image_type->currentIndex());
527  connect(_ui->source_comboBox_image_type, SIGNAL(currentIndexChanged(int)), _ui->stackedWidget_image, SLOT(setCurrentIndex(int)));
528  connect(_ui->source_comboBox_image_type, SIGNAL(currentIndexChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
529  connect(_ui->checkBox_rgb_rectify, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
530  //images group
531  connect(_ui->source_images_toolButton_selectSource, SIGNAL(clicked()), this, SLOT(selectSourceImagesPath()));
532  connect(_ui->source_images_lineEdit_path, SIGNAL(textChanged(const QString &)), this, SLOT(makeObsoleteSourcePanel()));
533  connect(_ui->source_images_spinBox_startPos, SIGNAL(valueChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
534  connect(_ui->comboBox_cameraImages_bayerMode, SIGNAL(currentIndexChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
535  //video group
536  connect(_ui->source_video_toolButton_selectSource, SIGNAL(clicked()), this, SLOT(selectSourceVideoPath()));
537  connect(_ui->source_video_lineEdit_path, SIGNAL(textChanged(const QString &)), this, SLOT(makeObsoleteSourcePanel()));
538  //database group
539  connect(_ui->source_database_toolButton_selectSource, SIGNAL(clicked()), this, SLOT(selectSourceDatabase()));
540  connect(_ui->toolButton_dbViewer, SIGNAL(clicked()), this, SLOT(openDatabaseViewer()));
541  connect(_ui->groupBox_sourceDatabase, SIGNAL(toggled(bool)), this, SLOT(makeObsoleteSourcePanel()));
542  connect(_ui->source_database_lineEdit_path, SIGNAL(textChanged(const QString &)), this, SLOT(makeObsoleteSourcePanel()));
543  connect(_ui->source_checkBox_ignoreOdometry, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
544  connect(_ui->source_checkBox_ignoreGoalDelay, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
545  connect(_ui->source_checkBox_ignoreGoals, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
546  connect(_ui->source_spinBox_databaseStartPos, SIGNAL(valueChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
547  connect(_ui->source_checkBox_useDbStamps, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
548  connect(_ui->source_spinBox_database_cameraIndex, SIGNAL(valueChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
549 
550  //openni group
551  _ui->stackedWidget_rgbd->setCurrentIndex(_ui->comboBox_cameraRGBD->currentIndex());
552  connect(_ui->comboBox_cameraRGBD, SIGNAL(currentIndexChanged(int)), _ui->stackedWidget_rgbd, SLOT(setCurrentIndex(int)));
553  connect(_ui->comboBox_cameraRGBD, SIGNAL(currentIndexChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
554  _ui->stackedWidget_stereo->setCurrentIndex(_ui->comboBox_cameraStereo->currentIndex());
555  connect(_ui->comboBox_cameraStereo, SIGNAL(currentIndexChanged(int)), _ui->stackedWidget_stereo, SLOT(setCurrentIndex(int)));
556  connect(_ui->comboBox_cameraStereo, SIGNAL(currentIndexChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
557  connect(_ui->openni2_autoWhiteBalance, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
558  connect(_ui->openni2_autoExposure, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
559  connect(_ui->openni2_exposure, SIGNAL(valueChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
560  connect(_ui->openni2_gain, SIGNAL(valueChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
561  connect(_ui->openni2_mirroring, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
562  connect(_ui->openni2_stampsIdsUsed, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
563  connect(_ui->openni2_hshift, SIGNAL(valueChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
564  connect(_ui->openni2_vshift, SIGNAL(valueChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
565  connect(_ui->comboBox_freenect2Format, SIGNAL(currentIndexChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
566  connect(_ui->doubleSpinBox_freenect2MinDepth, SIGNAL(valueChanged(double)), this, SLOT(makeObsoleteSourcePanel()));
567  connect(_ui->doubleSpinBox_freenect2MaxDepth, SIGNAL(valueChanged(double)), this, SLOT(makeObsoleteSourcePanel()));
568  connect(_ui->checkBox_freenect2BilateralFiltering, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
569  connect(_ui->checkBox_freenect2EdgeAwareFiltering, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
570  connect(_ui->checkBox_freenect2NoiseFiltering, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
571  connect(_ui->lineEdit_freenect2Pipeline, SIGNAL(textChanged(const QString &)), this, SLOT(makeObsoleteSourcePanel()));
572  connect(_ui->comboBox_k4w2Format, SIGNAL(currentIndexChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
573  connect(_ui->comboBox_realsensePresetRGB, SIGNAL(currentIndexChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
574  connect(_ui->comboBox_realsensePresetDepth, SIGNAL(currentIndexChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
575  connect(_ui->checkbox_realsenseOdom, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
576  connect(_ui->checkbox_realsenseDepthScaledToRGBSize, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
577  connect(_ui->comboBox_realsenseRGBSource, SIGNAL(currentIndexChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
578  connect(_ui->checkbox_rs2_emitter, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
579  connect(_ui->checkbox_rs2_irDepth, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
580 
581  connect(_ui->toolButton_cameraImages_timestamps, SIGNAL(clicked()), this, SLOT(selectSourceImagesStamps()));
582  connect(_ui->lineEdit_cameraImages_timestamps, SIGNAL(textChanged(const QString &)), this, SLOT(makeObsoleteSourcePanel()));
583  connect(_ui->toolButton_cameraRGBDImages_path_rgb, SIGNAL(clicked()), this, SLOT(selectSourceRGBDImagesPathRGB()));
584  connect(_ui->toolButton_cameraRGBDImages_path_depth, SIGNAL(clicked()), this, SLOT(selectSourceRGBDImagesPathDepth()));
585  connect(_ui->toolButton_cameraImages_path_scans, SIGNAL(clicked()), this, SLOT(selectSourceImagesPathScans()));
586  connect(_ui->toolButton_cameraImages_path_imu, SIGNAL(clicked()), this, SLOT(selectSourceImagesPathIMU()));
587  connect(_ui->toolButton_cameraImages_odom, SIGNAL(clicked()), this, SLOT(selectSourceImagesPathOdom()));
588  connect(_ui->toolButton_cameraImages_gt, SIGNAL(clicked()), this, SLOT(selectSourceImagesPathGt()));
589  connect(_ui->lineEdit_cameraRGBDImages_path_rgb, SIGNAL(textChanged(const QString &)), this, SLOT(makeObsoleteSourcePanel()));
590  connect(_ui->lineEdit_cameraRGBDImages_path_depth, SIGNAL(textChanged(const QString &)), this, SLOT(makeObsoleteSourcePanel()));
591  connect(_ui->checkBox_cameraImages_timestamps, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
592  connect(_ui->checkBox_cameraImages_syncTimeStamps, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
593  connect(_ui->doubleSpinBox_cameraRGBDImages_scale, SIGNAL(valueChanged(double)), this, SLOT(makeObsoleteSourcePanel()));
594  connect(_ui->spinBox_cameraRGBDImages_startIndex, SIGNAL(valueChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
595  connect(_ui->lineEdit_cameraImages_path_scans, SIGNAL(textChanged(const QString &)), this, SLOT(makeObsoleteSourcePanel()));
596  connect(_ui->lineEdit_cameraImages_laser_transform, SIGNAL(textChanged(const QString &)), this, SLOT(makeObsoleteSourcePanel()));
597  connect(_ui->spinBox_cameraImages_max_scan_pts, SIGNAL(valueChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
598  connect(_ui->spinBox_cameraImages_scanDownsampleStep, SIGNAL(valueChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
599  connect(_ui->doubleSpinBox_cameraImages_scanVoxelSize, SIGNAL(valueChanged(double)), this, SLOT(makeObsoleteSourcePanel()));
600  connect(_ui->lineEdit_cameraImages_odom, SIGNAL(textChanged(const QString &)), this, SLOT(makeObsoleteSourcePanel()));
601  connect(_ui->comboBox_cameraImages_odomFormat, SIGNAL(currentIndexChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
602  connect(_ui->lineEdit_cameraImages_gt, SIGNAL(textChanged(const QString &)), this, SLOT(makeObsoleteSourcePanel()));
603  connect(_ui->comboBox_cameraImages_gtFormat, SIGNAL(currentIndexChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
604  connect(_ui->doubleSpinBox_maxPoseTimeDiff, SIGNAL(valueChanged(double)), this, SLOT(makeObsoleteSourcePanel()));
605  connect(_ui->lineEdit_cameraImages_path_imu, SIGNAL(textChanged(const QString &)), this, SLOT(makeObsoleteSourcePanel()));
606  connect(_ui->lineEdit_cameraImages_imu_transform, SIGNAL(textChanged(const QString &)), this, SLOT(makeObsoleteSourcePanel()));
607  connect(_ui->spinBox_cameraImages_max_imu_rate, SIGNAL(valueChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
608  connect(_ui->groupBox_depthFromScan, SIGNAL(toggled(bool)), this, SLOT(makeObsoleteSourcePanel()));
609  connect(_ui->groupBox_depthFromScan_fillHoles, SIGNAL(toggled(bool)), this, SLOT(makeObsoleteSourcePanel()));
610  connect(_ui->radioButton_depthFromScan_vertical, SIGNAL(toggled(bool)), this, SLOT(makeObsoleteSourcePanel()));
611  connect(_ui->radioButton_depthFromScan_horizontal, SIGNAL(toggled(bool)), this, SLOT(makeObsoleteSourcePanel()));
612  connect(_ui->checkBox_depthFromScan_fillBorders, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
613 
614  connect(_ui->toolButton_cameraStereoImages_path_left, SIGNAL(clicked()), this, SLOT(selectSourceStereoImagesPathLeft()));
615  connect(_ui->toolButton_cameraStereoImages_path_right, SIGNAL(clicked()), this, SLOT(selectSourceStereoImagesPathRight()));
616  connect(_ui->lineEdit_cameraStereoImages_path_left, SIGNAL(textChanged(const QString &)), this, SLOT(makeObsoleteSourcePanel()));
617  connect(_ui->lineEdit_cameraStereoImages_path_right, SIGNAL(textChanged(const QString &)), this, SLOT(makeObsoleteSourcePanel()));
618  connect(_ui->checkBox_stereo_rectify, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
619  connect(_ui->spinBox_cameraStereoImages_startIndex, SIGNAL(valueChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
620 
621  connect(_ui->toolButton_cameraStereoVideo_path, SIGNAL(clicked()), this, SLOT(selectSourceStereoVideoPath()));
622  connect(_ui->toolButton_cameraStereoVideo_path_2, SIGNAL(clicked()), this, SLOT(selectSourceStereoVideoPath2()));
623  connect(_ui->lineEdit_cameraStereoVideo_path, SIGNAL(textChanged(const QString &)), this, SLOT(makeObsoleteSourcePanel()));
624  connect(_ui->lineEdit_cameraStereoVideo_path_2, SIGNAL(textChanged(const QString &)), this, SLOT(makeObsoleteSourcePanel()));
625 
626  connect(_ui->spinBox_stereo_right_device, SIGNAL(valueChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
627 
628  connect(_ui->comboBox_stereoZed_resolution, SIGNAL(currentIndexChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
629  connect(_ui->comboBox_stereoZed_quality, SIGNAL(currentIndexChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
630  connect(_ui->comboBox_stereoZed_quality, SIGNAL(currentIndexChanged(int)), this, SLOT(updateStereoDisparityVisibility()));
631  connect(_ui->checkbox_stereoZed_selfCalibration, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
632  connect(_ui->comboBox_cameraStereo, SIGNAL(currentIndexChanged(int)), this, SLOT(updateStereoDisparityVisibility()));
633  connect(_ui->comboBox_stereoZed_sensingMode, SIGNAL(currentIndexChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
634  connect(_ui->spinBox_stereoZed_confidenceThr, SIGNAL(valueChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
635  connect(_ui->checkbox_stereoZed_odom, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
636  connect(_ui->toolButton_zedSvoPath, SIGNAL(clicked()), this, SLOT(selectSourceSvoPath()));
637  connect(_ui->lineEdit_zedSvoPath, SIGNAL(textChanged(const QString &)), this, SLOT(makeObsoleteSourcePanel()));
638 
639  connect(_ui->checkbox_rgbd_colorOnly, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
640  connect(_ui->spinBox_source_imageDecimation, SIGNAL(valueChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
641  connect(_ui->checkbox_stereo_depthGenerated, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
642  connect(_ui->checkBox_stereo_exposureCompensation, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
643  connect(_ui->pushButton_calibrate, SIGNAL(clicked()), this, SLOT(calibrate()));
644  connect(_ui->pushButton_calibrate_simple, SIGNAL(clicked()), this, SLOT(calibrateSimple()));
645  connect(_ui->toolButton_openniOniPath, SIGNAL(clicked()), this, SLOT(selectSourceOniPath()));
646  connect(_ui->toolButton_openni2OniPath, SIGNAL(clicked()), this, SLOT(selectSourceOni2Path()));
647  connect(_ui->toolButton_source_distortionModel, SIGNAL(clicked()), this, SLOT(selectSourceDistortionModel()));
648  connect(_ui->toolButton_distortionModel, SIGNAL(clicked()), this, SLOT(visualizeDistortionModel()));
649  connect(_ui->lineEdit_openniOniPath, SIGNAL(textChanged(const QString &)), this, SLOT(makeObsoleteSourcePanel()));
650  connect(_ui->lineEdit_openni2OniPath, SIGNAL(textChanged(const QString &)), this, SLOT(makeObsoleteSourcePanel()));
651  connect(_ui->lineEdit_source_distortionModel, SIGNAL(textChanged(const QString &)), this, SLOT(makeObsoleteSourcePanel()));
652  connect(_ui->groupBox_bilateral, SIGNAL(toggled(bool)), this, SLOT(makeObsoleteSourcePanel()));
653  connect(_ui->doubleSpinBox_bilateral_sigmaS, SIGNAL(valueChanged(double)), this, SLOT(makeObsoleteSourcePanel()));
654  connect(_ui->doubleSpinBox_bilateral_sigmaR, SIGNAL(valueChanged(double)), this, SLOT(makeObsoleteSourcePanel()));
655 
656  connect(_ui->groupBox_scanFromDepth, SIGNAL(toggled(bool)), this, SLOT(makeObsoleteSourcePanel()));
657  connect(_ui->spinBox_cameraScanFromDepth_decimation, SIGNAL(valueChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
658  connect(_ui->doubleSpinBox_cameraSCanFromDepth_maxDepth, SIGNAL(valueChanged(double)), this, SLOT(makeObsoleteSourcePanel()));
659  connect(_ui->doubleSpinBox_cameraImages_scanVoxelSize, SIGNAL(valueChanged(double)), this, SLOT(makeObsoleteSourcePanel()));
660  connect(_ui->spinBox_cameraImages_scanNormalsK, SIGNAL(valueChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
661  connect(_ui->doubleSpinBox_cameraImages_scanNormalsRadius, SIGNAL(valueChanged(double)), this, SLOT(makeObsoleteSourcePanel()));
662  connect(_ui->checkBox_cameraImages_scanForceGroundNormalsUp, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
663 
664 
665  //Rtabmap basic
666  connect(_ui->general_doubleSpinBox_timeThr, SIGNAL(valueChanged(double)), _ui->general_doubleSpinBox_timeThr_2, SLOT(setValue(double)));
667  connect(_ui->general_doubleSpinBox_hardThr, SIGNAL(valueChanged(double)), _ui->general_doubleSpinBox_hardThr_2, SLOT(setValue(double)));
668  connect(_ui->doubleSpinBox_similarityThreshold, SIGNAL(valueChanged(double)), _ui->doubleSpinBox_similarityThreshold_2, SLOT(setValue(double)));
669  connect(_ui->general_doubleSpinBox_detectionRate, SIGNAL(valueChanged(double)), _ui->general_doubleSpinBox_detectionRate_2, SLOT(setValue(double)));
670  connect(_ui->general_spinBox_imagesBufferSize, SIGNAL(valueChanged(int)), _ui->general_spinBox_imagesBufferSize_2, SLOT(setValue(int)));
671  connect(_ui->general_spinBox_maxStMemSize, SIGNAL(valueChanged(int)), _ui->general_spinBox_maxStMemSize_2, SLOT(setValue(int)));
672 
673  connect(_ui->general_doubleSpinBox_timeThr_2, SIGNAL(editingFinished()), this, SLOT(updateBasicParameter()));
674  connect(_ui->general_doubleSpinBox_hardThr_2, SIGNAL(editingFinished()), this, SLOT(updateBasicParameter()));
675  connect(_ui->doubleSpinBox_similarityThreshold_2, SIGNAL(editingFinished()), this, SLOT(updateBasicParameter()));
676  connect(_ui->general_doubleSpinBox_detectionRate_2, SIGNAL(editingFinished()), this, SLOT(updateBasicParameter()));
677  connect(_ui->general_spinBox_imagesBufferSize_2, SIGNAL(editingFinished()), this, SLOT(updateBasicParameter()));
678  connect(_ui->general_spinBox_maxStMemSize_2, SIGNAL(editingFinished()), this, SLOT(updateBasicParameter()));
679  connect(_ui->groupBox_publishing, SIGNAL(toggled(bool)), this, SLOT(updateBasicParameter()));
680  connect(_ui->general_checkBox_publishStats_2, SIGNAL(stateChanged(int)), this, SLOT(updateBasicParameter()));
681  connect(_ui->general_checkBox_activateRGBD, SIGNAL(stateChanged(int)), this, SLOT(updateBasicParameter()));
682  connect(_ui->general_checkBox_activateRGBD_2, SIGNAL(stateChanged(int)), this, SLOT(updateBasicParameter()));
683  connect(_ui->general_checkBox_SLAM_mode, SIGNAL(stateChanged(int)), this, SLOT(updateBasicParameter()));
684  connect(_ui->general_checkBox_SLAM_mode_2, SIGNAL(stateChanged(int)), this, SLOT(updateBasicParameter()));
685 
686  // Map objects name with the corresponding parameter key, needed for the addParameter() slots
687  //Rtabmap
688  _ui->groupBox_publishing->setObjectName(Parameters::kRtabmapPublishStats().c_str());
689  _ui->general_checkBox_publishRawData->setObjectName(Parameters::kRtabmapPublishLastSignature().c_str());
690  _ui->general_checkBox_publishPdf->setObjectName(Parameters::kRtabmapPublishPdf().c_str());
691  _ui->general_checkBox_publishLikelihood->setObjectName(Parameters::kRtabmapPublishLikelihood().c_str());
692  _ui->general_checkBox_publishRMSE->setObjectName(Parameters::kRtabmapComputeRMSE().c_str());
693  _ui->general_checkBox_saveWMState->setObjectName(Parameters::kRtabmapSaveWMState().c_str());
694  _ui->general_checkBox_publishRAM->setObjectName(Parameters::kRtabmapPublishRAMUsage().c_str());
695  _ui->general_checkBox_statisticLogsBufferedInRAM->setObjectName(Parameters::kRtabmapStatisticLogsBufferedInRAM().c_str());
696  _ui->groupBox_statistics->setObjectName(Parameters::kRtabmapStatisticLogged().c_str());
697  _ui->general_checkBox_statisticLoggedHeaders->setObjectName(Parameters::kRtabmapStatisticLoggedHeaders().c_str());
698  _ui->general_doubleSpinBox_timeThr->setObjectName(Parameters::kRtabmapTimeThr().c_str());
699  _ui->general_spinBox_memoryThr->setObjectName(Parameters::kRtabmapMemoryThr().c_str());
700  _ui->general_doubleSpinBox_detectionRate->setObjectName(Parameters::kRtabmapDetectionRate().c_str());
701  _ui->general_spinBox_imagesBufferSize->setObjectName(Parameters::kRtabmapImageBufferSize().c_str());
702  _ui->general_checkBox_createIntermediateNodes->setObjectName(Parameters::kRtabmapCreateIntermediateNodes().c_str());
703  _ui->general_spinBox_maxRetrieved->setObjectName(Parameters::kRtabmapMaxRetrieved().c_str());
704  _ui->general_checkBox_startNewMapOnLoopClosure->setObjectName(Parameters::kRtabmapStartNewMapOnLoopClosure().c_str());
705  _ui->general_checkBox_startNewMapOnGoodSignature->setObjectName(Parameters::kRtabmapStartNewMapOnGoodSignature().c_str());
706  _ui->general_checkBox_imagesAlreadyRectified->setObjectName(Parameters::kRtabmapImagesAlreadyRectified().c_str());
707  _ui->general_checkBox_rectifyOnlyFeatures->setObjectName(Parameters::kRtabmapRectifyOnlyFeatures().c_str());
708  _ui->lineEdit_workingDirectory->setObjectName(Parameters::kRtabmapWorkingDirectory().c_str());
709  connect(_ui->toolButton_workingDirectory, SIGNAL(clicked()), this, SLOT(changeWorkingDirectory()));
710 
711  // Memory
712  _ui->general_checkBox_keepRawData->setObjectName(Parameters::kMemImageKept().c_str());
713  _ui->general_checkBox_keepBinaryData->setObjectName(Parameters::kMemBinDataKept().c_str());
714  _ui->general_checkBox_saveIntermediateNodeData->setObjectName(Parameters::kMemIntermediateNodeDataKept().c_str());
715  _ui->general_checkBox_keepDescriptors->setObjectName(Parameters::kMemRawDescriptorsKept().c_str());
716  _ui->general_checkBox_saveDepth16bits->setObjectName(Parameters::kMemSaveDepth16Format().c_str());
717  _ui->general_checkBox_compressionParallelized->setObjectName(Parameters::kMemCompressionParallelized().c_str());
718  _ui->general_checkBox_reduceGraph->setObjectName(Parameters::kMemReduceGraph().c_str());
719  _ui->general_checkBox_keepNotLinkedNodes->setObjectName(Parameters::kMemNotLinkedNodesKept().c_str());
720  _ui->general_spinBox_maxStMemSize->setObjectName(Parameters::kMemSTMSize().c_str());
721  _ui->doubleSpinBox_similarityThreshold->setObjectName(Parameters::kMemRehearsalSimilarity().c_str());
722  _ui->general_checkBox_SLAM_mode->setObjectName(Parameters::kMemIncrementalMemory().c_str());
723  _ui->general_doubleSpinBox_recentWmRatio->setObjectName(Parameters::kMemRecentWmRatio().c_str());
724  _ui->general_checkBox_transferSortingByWeightId->setObjectName(Parameters::kMemTransferSortingByWeightId().c_str());
725  _ui->general_checkBox_RehearsalIdUpdatedToNewOne->setObjectName(Parameters::kMemRehearsalIdUpdatedToNewOne().c_str());
726  _ui->general_checkBox_generateIds->setObjectName(Parameters::kMemGenerateIds().c_str());
727  _ui->general_checkBox_badSignaturesIgnored->setObjectName(Parameters::kMemBadSignaturesIgnored().c_str());
728  _ui->general_checkBox_createMapLabels->setObjectName(Parameters::kMemMapLabelsAdded().c_str());
729  _ui->general_checkBox_initWMWithAllNodes->setObjectName(Parameters::kMemInitWMWithAllNodes().c_str());
730  _ui->checkBox_localSpaceScanMatchingIDsSaved->setObjectName(Parameters::kRGBDScanMatchingIdsSavedInLinks().c_str());
731  _ui->spinBox_imagePreDecimation->setObjectName(Parameters::kMemImagePreDecimation().c_str());
732  _ui->spinBox_imagePostDecimation->setObjectName(Parameters::kMemImagePostDecimation().c_str());
733  _ui->general_spinBox_laserScanDownsample->setObjectName(Parameters::kMemLaserScanDownsampleStepSize().c_str());
734  _ui->general_doubleSpinBox_laserScanVoxelSize->setObjectName(Parameters::kMemLaserScanVoxelSize().c_str());
735  _ui->general_spinBox_laserScanNormalK->setObjectName(Parameters::kMemLaserScanNormalK().c_str());
736  _ui->general_doubleSpinBox_laserScanNormalRadius->setObjectName(Parameters::kMemLaserScanNormalRadius().c_str());
737  _ui->checkBox_useOdomFeatures->setObjectName(Parameters::kMemUseOdomFeatures().c_str());
738  _ui->memCovOffDiagIgnored->setObjectName(Parameters::kMemCovOffDiagIgnored().c_str());
739 
740  // Database
741  _ui->checkBox_dbInMemory->setObjectName(Parameters::kDbSqlite3InMemory().c_str());
742  _ui->spinBox_dbCacheSize->setObjectName(Parameters::kDbSqlite3CacheSize().c_str());
743  _ui->comboBox_dbJournalMode->setObjectName(Parameters::kDbSqlite3JournalMode().c_str());
744  _ui->comboBox_dbSynchronous->setObjectName(Parameters::kDbSqlite3Synchronous().c_str());
745  _ui->comboBox_dbTempStore->setObjectName(Parameters::kDbSqlite3TempStore().c_str());
746 
747  // Create hypotheses
748  _ui->general_doubleSpinBox_hardThr->setObjectName(Parameters::kRtabmapLoopThr().c_str());
749  _ui->general_doubleSpinBox_loopRatio->setObjectName(Parameters::kRtabmapLoopRatio().c_str());
750 
751  //Bayes
752  _ui->general_doubleSpinBox_vp->setObjectName(Parameters::kBayesVirtualPlacePriorThr().c_str());
753  _ui->lineEdit_bayes_predictionLC->setObjectName(Parameters::kBayesPredictionLC().c_str());
754  _ui->checkBox_bayes_fullPredictionUpdate->setObjectName(Parameters::kBayesFullPredictionUpdate().c_str());
755  connect(_ui->lineEdit_bayes_predictionLC, SIGNAL(textChanged(const QString &)), this, SLOT(updatePredictionPlot()));
756 
757  //Keypoint-based
758  _ui->comboBox_dictionary_strategy->setObjectName(Parameters::kKpNNStrategy().c_str());
759  _ui->checkBox_dictionary_incremental->setObjectName(Parameters::kKpIncrementalDictionary().c_str());
760  _ui->checkBox_kp_incrementalFlann->setObjectName(Parameters::kKpIncrementalFlann().c_str());
761  _ui->surf_doubleSpinBox_rebalancingFactor->setObjectName(Parameters::kKpFlannRebalancingFactor().c_str());
762  _ui->comboBox_detector_strategy->setObjectName(Parameters::kKpDetectorStrategy().c_str());
763  _ui->surf_doubleSpinBox_nndrRatio->setObjectName(Parameters::kKpNndrRatio().c_str());
764  _ui->surf_doubleSpinBox_maxDepth->setObjectName(Parameters::kKpMaxDepth().c_str());
765  _ui->surf_doubleSpinBox_minDepth->setObjectName(Parameters::kKpMinDepth().c_str());
766  _ui->checkBox_memDepthAsMask->setObjectName(Parameters::kMemDepthAsMask().c_str());
767  _ui->surf_spinBox_wordsPerImageTarget->setObjectName(Parameters::kKpMaxFeatures().c_str());
768  _ui->spinBox_KPGridRows->setObjectName(Parameters::kKpGridRows().c_str());
769  _ui->spinBox_KPGridCols->setObjectName(Parameters::kKpGridCols().c_str());
770  _ui->surf_doubleSpinBox_ratioBadSign->setObjectName(Parameters::kKpBadSignRatio().c_str());
771  _ui->checkBox_kp_tfIdfLikelihoodUsed->setObjectName(Parameters::kKpTfIdfLikelihoodUsed().c_str());
772  _ui->checkBox_kp_parallelized->setObjectName(Parameters::kKpParallelized().c_str());
773  _ui->lineEdit_kp_roi->setObjectName(Parameters::kKpRoiRatios().c_str());
774  _ui->lineEdit_dictionaryPath->setObjectName(Parameters::kKpDictionaryPath().c_str());
775  connect(_ui->toolButton_dictionaryPath, SIGNAL(clicked()), this, SLOT(changeDictionaryPath()));
776  _ui->checkBox_kp_newWordsComparedTogether->setObjectName(Parameters::kKpNewWordsComparedTogether().c_str());
777  _ui->subpix_winSize_kp->setObjectName(Parameters::kKpSubPixWinSize().c_str());
778  _ui->subpix_iterations_kp->setObjectName(Parameters::kKpSubPixIterations().c_str());
779  _ui->subpix_eps_kp->setObjectName(Parameters::kKpSubPixEps().c_str());
780 
781  _ui->subpix_winSize->setObjectName(Parameters::kKpSubPixWinSize().c_str());
782  _ui->subpix_iterations->setObjectName(Parameters::kKpSubPixIterations().c_str());
783  _ui->subpix_eps->setObjectName(Parameters::kKpSubPixEps().c_str());
784 
785  //SURF detector
786  _ui->surf_doubleSpinBox_hessianThr->setObjectName(Parameters::kSURFHessianThreshold().c_str());
787  _ui->surf_spinBox_octaves->setObjectName(Parameters::kSURFOctaves().c_str());
788  _ui->surf_spinBox_octaveLayers->setObjectName(Parameters::kSURFOctaveLayers().c_str());
789  _ui->checkBox_surfExtended->setObjectName(Parameters::kSURFExtended().c_str());
790  _ui->surf_checkBox_upright->setObjectName(Parameters::kSURFUpright().c_str());
791  _ui->surf_checkBox_gpuVersion->setObjectName(Parameters::kSURFGpuVersion().c_str());
792  _ui->surf_doubleSpinBox_gpuKeypointsRatio->setObjectName(Parameters::kSURFGpuKeypointsRatio().c_str());
793 
794  //SIFT detector
795  _ui->sift_spinBox_nFeatures->setObjectName(Parameters::kSIFTNFeatures().c_str());
796  _ui->sift_spinBox_nOctaveLayers->setObjectName(Parameters::kSIFTNOctaveLayers().c_str());
797  _ui->sift_doubleSpinBox_contrastThr->setObjectName(Parameters::kSIFTContrastThreshold().c_str());
798  _ui->sift_doubleSpinBox_edgeThr->setObjectName(Parameters::kSIFTEdgeThreshold().c_str());
799  _ui->sift_doubleSpinBox_sigma->setObjectName(Parameters::kSIFTSigma().c_str());
800 
801  //BRIEF descriptor
802  _ui->briefBytes->setObjectName(Parameters::kBRIEFBytes().c_str());
803 
804  //FAST detector
805  _ui->fastSuppressNonMax->setObjectName(Parameters::kFASTNonmaxSuppression().c_str());
806  _ui->fastThreshold->setObjectName(Parameters::kFASTThreshold().c_str());
807  _ui->fastThresholdMin->setObjectName(Parameters::kFASTMinThreshold().c_str());
808  _ui->fastThresholdMax->setObjectName(Parameters::kFASTMaxThreshold().c_str());
809  _ui->fastGridRows->setObjectName(Parameters::kFASTGridRows().c_str());
810  _ui->fastGridCols->setObjectName(Parameters::kFASTGridCols().c_str());
811  _ui->fastGpu->setObjectName(Parameters::kFASTGpu().c_str());
812  _ui->fastKeypointRatio->setObjectName(Parameters::kFASTGpuKeypointsRatio().c_str());
813 
814  //ORB detector
815  _ui->doubleSpinBox_ORBScaleFactor->setObjectName(Parameters::kORBScaleFactor().c_str());
816  _ui->spinBox_ORBNLevels->setObjectName(Parameters::kORBNLevels().c_str());
817  _ui->spinBox_ORBEdgeThreshold->setObjectName(Parameters::kORBEdgeThreshold().c_str());
818  _ui->spinBox_ORBFirstLevel->setObjectName(Parameters::kORBFirstLevel().c_str());
819  _ui->spinBox_ORBWTA_K->setObjectName(Parameters::kORBWTA_K().c_str());
820  _ui->spinBox_ORBScoreType->setObjectName(Parameters::kORBScoreType().c_str());
821  _ui->spinBox_ORBPatchSize->setObjectName(Parameters::kORBPatchSize().c_str());
822  _ui->checkBox_ORBGpu->setObjectName(Parameters::kORBGpu().c_str());
823 
824  //FREAK descriptor
825  _ui->checkBox_FREAKOrientationNormalized->setObjectName(Parameters::kFREAKOrientationNormalized().c_str());
826  _ui->checkBox_FREAKScaleNormalized->setObjectName(Parameters::kFREAKScaleNormalized().c_str());
827  _ui->doubleSpinBox_FREAKPatternScale->setObjectName(Parameters::kFREAKPatternScale().c_str());
828  _ui->spinBox_FREAKNOctaves->setObjectName(Parameters::kFREAKNOctaves().c_str());
829 
830  //GFTT detector
831  _ui->doubleSpinBox_GFTT_qualityLevel->setObjectName(Parameters::kGFTTQualityLevel().c_str());
832  _ui->doubleSpinBox_GFTT_minDistance->setObjectName(Parameters::kGFTTMinDistance().c_str());
833  _ui->spinBox_GFTT_blockSize->setObjectName(Parameters::kGFTTBlockSize().c_str());
834  _ui->checkBox_GFTT_useHarrisDetector->setObjectName(Parameters::kGFTTUseHarrisDetector().c_str());
835  _ui->doubleSpinBox_GFTT_k->setObjectName(Parameters::kGFTTK().c_str());
836 
837  //BRISK
838  _ui->spinBox_BRISK_thresh->setObjectName(Parameters::kBRISKThresh().c_str());
839  _ui->spinBox_BRISK_octaves->setObjectName(Parameters::kBRISKOctaves().c_str());
840  _ui->doubleSpinBox_BRISK_patterScale->setObjectName(Parameters::kBRISKPatternScale().c_str());
841 
842  //KAZE
843  _ui->checkBox_kaze_extended->setObjectName(Parameters::kKAZEExtended().c_str());
844  _ui->checkBox_kaze_upright->setObjectName(Parameters::kKAZEUpright().c_str());
845  _ui->doubleSpinBox_kaze_threshold->setObjectName(Parameters::kKAZEThreshold().c_str());
846  _ui->spinBox_kaze_octaves->setObjectName(Parameters::kKAZENOctaves().c_str());
847  _ui->spinBox_kaze_octavelayers->setObjectName(Parameters::kKAZENOctaveLayers().c_str());
848  _ui->spinBox_kaze_diffusivity->setObjectName(Parameters::kKAZEDiffusivity().c_str());
849 
850  // verifyHypotheses
851  _ui->groupBox_vh_epipolar2->setObjectName(Parameters::kVhEpEnabled().c_str());
852  _ui->surf_spinBox_matchCountMinAccepted->setObjectName(Parameters::kVhEpMatchCountMin().c_str());
853  _ui->surf_doubleSpinBox_ransacParam1->setObjectName(Parameters::kVhEpRansacParam1().c_str());
854  _ui->surf_doubleSpinBox_ransacParam2->setObjectName(Parameters::kVhEpRansacParam2().c_str());
855 
856  // RGB-D SLAM
857  _ui->general_checkBox_activateRGBD->setObjectName(Parameters::kRGBDEnabled().c_str());
858  _ui->rgdb_linearUpdate->setObjectName(Parameters::kRGBDLinearUpdate().c_str());
859  _ui->rgdb_angularUpdate->setObjectName(Parameters::kRGBDAngularUpdate().c_str());
860  _ui->rgdb_linearSpeedUpdate->setObjectName(Parameters::kRGBDLinearSpeedUpdate().c_str());
861  _ui->rgdb_angularSpeedUpdate->setObjectName(Parameters::kRGBDAngularSpeedUpdate().c_str());
862  _ui->rgbd_savedLocalizationIgnored->setObjectName(Parameters::kRGBDSavedLocalizationIgnored().c_str());
863  _ui->rgdb_rehearsalWeightIgnoredWhileMoving->setObjectName(Parameters::kMemRehearsalWeightIgnoredWhileMoving().c_str());
864  _ui->rgdb_newMapOdomChange->setObjectName(Parameters::kRGBDNewMapOdomChangeDistance().c_str());
865  _ui->odomScanHistory->setObjectName(Parameters::kRGBDNeighborLinkRefining().c_str());
866  _ui->spinBox_maxLocalLocationsRetrieved->setObjectName(Parameters::kRGBDMaxLocalRetrieved().c_str());
867 
868  _ui->graphOptimization_type->setObjectName(Parameters::kOptimizerStrategy().c_str());
869  _ui->graphOptimization_iterations->setObjectName(Parameters::kOptimizerIterations().c_str());
870  _ui->graphOptimization_covarianceIgnored->setObjectName(Parameters::kOptimizerVarianceIgnored().c_str());
871  _ui->graphOptimization_fromGraphEnd->setObjectName(Parameters::kRGBDOptimizeFromGraphEnd().c_str());
872  _ui->graphOptimization_maxError->setObjectName(Parameters::kRGBDOptimizeMaxError().c_str());
873  _ui->graphOptimization_stopEpsilon->setObjectName(Parameters::kOptimizerEpsilon().c_str());
874  _ui->graphOptimization_robust->setObjectName(Parameters::kOptimizerRobust().c_str());
875  _ui->graphOptimization_priorsIgnored->setObjectName(Parameters::kOptimizerPriorsIgnored().c_str());
876 
877  _ui->comboBox_g2o_solver->setObjectName(Parameters::kg2oSolver().c_str());
878  _ui->comboBox_g2o_optimizer->setObjectName(Parameters::kg2oOptimizer().c_str());
879  _ui->doubleSpinBox_g2o_pixelVariance->setObjectName(Parameters::kg2oPixelVariance().c_str());
880  _ui->doubleSpinBox_g2o_robustKernelDelta->setObjectName(Parameters::kg2oRobustKernelDelta().c_str());
881  _ui->doubleSpinBox_g2o_baseline->setObjectName(Parameters::kg2oBaseline().c_str());
882 
883  _ui->comboBox_gtsam_optimizer->setObjectName(Parameters::kGTSAMOptimizer().c_str());
884 
885  _ui->graphPlan_goalReachedRadius->setObjectName(Parameters::kRGBDGoalReachedRadius().c_str());
886  _ui->graphPlan_goalsSavedInUserData->setObjectName(Parameters::kRGBDGoalsSavedInUserData().c_str());
887  _ui->graphPlan_stuckIterations->setObjectName(Parameters::kRGBDPlanStuckIterations().c_str());
888  _ui->graphPlan_linearVelocity->setObjectName(Parameters::kRGBDPlanLinearVelocity().c_str());
889  _ui->graphPlan_angularVelocity->setObjectName(Parameters::kRGBDPlanAngularVelocity().c_str());
890 
891  _ui->groupBox_localDetection_time->setObjectName(Parameters::kRGBDProximityByTime().c_str());
892  _ui->groupBox_localDetection_space->setObjectName(Parameters::kRGBDProximityBySpace().c_str());
893  _ui->localDetection_radius->setObjectName(Parameters::kRGBDLocalRadius().c_str());
894  _ui->localDetection_maxDiffID->setObjectName(Parameters::kRGBDProximityMaxGraphDepth().c_str());
895  _ui->localDetection_maxNeighbors->setObjectName(Parameters::kRGBDProximityPathMaxNeighbors().c_str());
896  _ui->localDetection_maxPaths->setObjectName(Parameters::kRGBDProximityMaxPaths().c_str());
897  _ui->localDetection_pathFilteringRadius->setObjectName(Parameters::kRGBDProximityPathFilteringRadius().c_str());
898  _ui->localDetection_angle->setObjectName(Parameters::kRGBDProximityAngle().c_str());
899  _ui->checkBox_localSpacePathOdomPosesUsed->setObjectName(Parameters::kRGBDProximityPathRawPosesUsed().c_str());
900  _ui->rgdb_localImmunizationRatio->setObjectName(Parameters::kRGBDLocalImmunizationRatio().c_str());
901  _ui->loopClosure_reextract->setObjectName(Parameters::kRGBDLoopClosureReextractFeatures().c_str());
902  _ui->loopClosure_bunlde->setObjectName(Parameters::kRGBDLocalBundleOnLoopClosure().c_str());
903  _ui->checkbox_rgbd_createOccupancyGrid->setObjectName(Parameters::kRGBDCreateOccupancyGrid().c_str());
904 
905  // Registration
906  _ui->reg_repeatOnce->setObjectName(Parameters::kRegRepeatOnce().c_str());
907  _ui->comboBox_registrationStrategy->setObjectName(Parameters::kRegStrategy().c_str());
908  _ui->loopClosure_bowForce2D->setObjectName(Parameters::kRegForce3DoF().c_str());
909 
910  //RegistrationVis
911  _ui->loopClosure_bowMinInliers->setObjectName(Parameters::kVisMinInliers().c_str());
912  _ui->loopClosure_bowInlierDistance->setObjectName(Parameters::kVisInlierDistance().c_str());
913  _ui->loopClosure_bowIterations->setObjectName(Parameters::kVisIterations().c_str());
914  _ui->loopClosure_bowRefineIterations->setObjectName(Parameters::kVisRefineIterations().c_str());
915  _ui->loopClosure_estimationType->setObjectName(Parameters::kVisEstimationType().c_str());
916  connect(_ui->loopClosure_estimationType, SIGNAL(currentIndexChanged(int)), _ui->stackedWidget_loopClosureEstimation, SLOT(setCurrentIndex(int)));
917  _ui->stackedWidget_loopClosureEstimation->setCurrentIndex(Parameters::defaultVisEstimationType());
918  _ui->loopClosure_forwardEst->setObjectName(Parameters::kVisForwardEstOnly().c_str());
919  _ui->loopClosure_bowEpipolarGeometryVar->setObjectName(Parameters::kVisEpipolarGeometryVar().c_str());
920  _ui->loopClosure_pnpReprojError->setObjectName(Parameters::kVisPnPReprojError().c_str());
921  _ui->loopClosure_pnpFlags->setObjectName(Parameters::kVisPnPFlags().c_str());
922  _ui->loopClosure_pnpRefineIterations->setObjectName(Parameters::kVisPnPRefineIterations().c_str());
923  _ui->reextract_nn->setObjectName(Parameters::kVisCorNNType().c_str());
924  _ui->reextract_nndrRatio->setObjectName(Parameters::kVisCorNNDR().c_str());
925  _ui->spinBox_visCorGuessWinSize->setObjectName(Parameters::kVisCorGuessWinSize().c_str());
926  _ui->checkBox__visCorGuessMatchToProjection->setObjectName(Parameters::kVisCorGuessMatchToProjection().c_str());
927  _ui->reextract_type->setObjectName(Parameters::kVisFeatureType().c_str());
928  _ui->reextract_maxFeatures->setObjectName(Parameters::kVisMaxFeatures().c_str());
929  _ui->reextract_gridrows->setObjectName(Parameters::kVisGridRows().c_str());
930  _ui->reextract_gridcols->setObjectName(Parameters::kVisGridCols().c_str());
931  _ui->loopClosure_bowMaxDepth->setObjectName(Parameters::kVisMaxDepth().c_str());
932  _ui->loopClosure_bowMinDepth->setObjectName(Parameters::kVisMinDepth().c_str());
933  _ui->checkBox_visDepthAsMask->setObjectName(Parameters::kVisDepthAsMask().c_str());
934  _ui->loopClosure_roi->setObjectName(Parameters::kVisRoiRatios().c_str());
935  _ui->subpix_winSize->setObjectName(Parameters::kVisSubPixWinSize().c_str());
936  _ui->subpix_iterations->setObjectName(Parameters::kVisSubPixIterations().c_str());
937  _ui->subpix_eps->setObjectName(Parameters::kVisSubPixEps().c_str());
938  _ui->odom_flow_winSize_2->setObjectName(Parameters::kVisCorFlowWinSize().c_str());
939  _ui->odom_flow_maxLevel_2->setObjectName(Parameters::kVisCorFlowMaxLevel().c_str());
940  _ui->odom_flow_iterations_2->setObjectName(Parameters::kVisCorFlowIterations().c_str());
941  _ui->odom_flow_eps_2->setObjectName(Parameters::kVisCorFlowEps().c_str());
942  _ui->loopClosure_bundle->setObjectName(Parameters::kVisBundleAdjustment().c_str());
943 
944  //RegistrationIcp
945  _ui->globalDetection_icpMaxTranslation->setObjectName(Parameters::kIcpMaxTranslation().c_str());
946  _ui->globalDetection_icpMaxRotation->setObjectName(Parameters::kIcpMaxRotation().c_str());
947  _ui->loopClosure_icpVoxelSize->setObjectName(Parameters::kIcpVoxelSize().c_str());
948  _ui->loopClosure_icpDownsamplingStep->setObjectName(Parameters::kIcpDownsamplingStep().c_str());
949  _ui->loopClosure_icpMaxCorrespondenceDistance->setObjectName(Parameters::kIcpMaxCorrespondenceDistance().c_str());
950  _ui->loopClosure_icpIterations->setObjectName(Parameters::kIcpIterations().c_str());
951  _ui->loopClosure_icpEpsilon->setObjectName(Parameters::kIcpEpsilon().c_str());
952  _ui->loopClosure_icpRatio->setObjectName(Parameters::kIcpCorrespondenceRatio().c_str());
953  _ui->loopClosure_icpPointToPlane->setObjectName(Parameters::kIcpPointToPlane().c_str());
954  _ui->loopClosure_icpPointToPlaneNormals->setObjectName(Parameters::kIcpPointToPlaneK().c_str());
955  _ui->loopClosure_icpPointToPlaneNormalsRadius->setObjectName(Parameters::kIcpPointToPlaneRadius().c_str());
956  _ui->loopClosure_icpPointToPlaneNormalsMinComplexity->setObjectName(Parameters::kIcpPointToPlaneMinComplexity().c_str());
957 
958  _ui->groupBox_libpointmatcher->setObjectName(Parameters::kIcpPM().c_str());
959  _ui->lineEdit_IcpPMConfigPath->setObjectName(Parameters::kIcpPMConfig().c_str());
960  connect(_ui->toolButton_IcpConfigPath, SIGNAL(clicked()), this, SLOT(changeIcpPMConfigPath()));
961  _ui->doubleSpinBox_icpPMOutlierRatio->setObjectName(Parameters::kIcpPMOutlierRatio().c_str());
962  _ui->spinBox_icpPMMatcherKnn->setObjectName(Parameters::kIcpPMMatcherKnn().c_str());
963  _ui->doubleSpinBox_icpPMMatcherEpsilon->setObjectName(Parameters::kIcpPMMatcherEpsilon().c_str());
964 
965  // Occupancy grid
966  _ui->groupBox_grid_3d->setObjectName(Parameters::kGrid3D().c_str());
967  _ui->checkBox_grid_groundObstacle->setObjectName(Parameters::kGridGroundIsObstacle().c_str());
968  _ui->doubleSpinBox_grid_resolution->setObjectName(Parameters::kGridCellSize().c_str());
969  _ui->checkBox_grid_preVoxelFiltering->setObjectName(Parameters::kGridPreVoxelFiltering().c_str());
970  _ui->spinBox_grid_decimation->setObjectName(Parameters::kGridDepthDecimation().c_str());
971  _ui->doubleSpinBox_grid_maxDepth->setObjectName(Parameters::kGridRangeMax().c_str());
972  _ui->doubleSpinBox_grid_minDepth->setObjectName(Parameters::kGridRangeMin().c_str());
973  _ui->lineEdit_grid_roi->setObjectName(Parameters::kGridDepthRoiRatios().c_str());
974  _ui->checkBox_grid_projRayTracing->setObjectName(Parameters::kGridRayTracing().c_str());
975  _ui->doubleSpinBox_grid_footprintLength->setObjectName(Parameters::kGridFootprintLength().c_str());
976  _ui->doubleSpinBox_grid_footprintWidth->setObjectName(Parameters::kGridFootprintWidth().c_str());
977  _ui->doubleSpinBox_grid_footprintHeight->setObjectName(Parameters::kGridFootprintHeight().c_str());
978  _ui->checkBox_grid_flatObstaclesDetected->setObjectName(Parameters::kGridFlatObstacleDetected().c_str());
979  _ui->groupBox_grid_fromDepthImage->setObjectName(Parameters::kGridFromDepth().c_str());
980  _ui->checkBox_grid_projMapFrame->setObjectName(Parameters::kGridMapFrameProjection().c_str());
981  _ui->doubleSpinBox_grid_maxGroundAngle->setObjectName(Parameters::kGridMaxGroundAngle().c_str());
982  _ui->spinBox_grid_normalK->setObjectName(Parameters::kGridNormalK().c_str());
983  _ui->doubleSpinBox_grid_maxGroundHeight->setObjectName(Parameters::kGridMaxGroundHeight().c_str());
984  _ui->doubleSpinBox_grid_maxObstacleHeight->setObjectName(Parameters::kGridMaxObstacleHeight().c_str());
985  _ui->doubleSpinBox_grid_clusterRadius->setObjectName(Parameters::kGridClusterRadius().c_str());
986  _ui->spinBox_grid_minClusterSize->setObjectName(Parameters::kGridMinClusterSize().c_str());
987  _ui->doubleSpinBox_grid_minGroundHeight->setObjectName(Parameters::kGridMinGroundHeight().c_str());
988  _ui->spinBox_grid_noiseMinNeighbors->setObjectName(Parameters::kGridNoiseFilteringMinNeighbors().c_str());
989  _ui->doubleSpinBox_grid_noiseRadius->setObjectName(Parameters::kGridNoiseFilteringRadius().c_str());
990  _ui->groupBox_grid_normalsSegmentation->setObjectName(Parameters::kGridNormalsSegmentation().c_str());
991  _ui->checkBox_grid_unknownSpaceFilled->setObjectName(Parameters::kGridScan2dUnknownSpaceFilled().c_str());
992  _ui->spinBox_grid_scanDecimation->setObjectName(Parameters::kGridScanDecimation().c_str());
993 
994  _ui->checkBox_grid_fullUpdate->setObjectName(Parameters::kGridGlobalFullUpdate().c_str());
995  _ui->doubleSpinBox_grid_updateError->setObjectName(Parameters::kGridGlobalUpdateError().c_str());
996  _ui->doubleSpinBox_grid_minMapSize->setObjectName(Parameters::kGridGlobalMinSize().c_str());
997  _ui->spinBox_grid_maxNodes->setObjectName(Parameters::kGridGlobalMaxNodes().c_str());
998  _ui->doubleSpinBox_grid_footprintRadius->setObjectName(Parameters::kGridGlobalFootprintRadius().c_str());
999  _ui->doubleSpinBox_grid_occThr->setObjectName(Parameters::kGridGlobalOccupancyThr().c_str());
1000  _ui->doubleSpinBox_grid_probHit->setObjectName(Parameters::kGridGlobalProbHit().c_str());
1001  _ui->doubleSpinBox_grid_probMiss->setObjectName(Parameters::kGridGlobalProbMiss().c_str());
1002  _ui->doubleSpinBox_grid_clampingMin->setObjectName(Parameters::kGridGlobalProbClampingMin().c_str());
1003  _ui->doubleSpinBox_grid_clampingMax->setObjectName(Parameters::kGridGlobalProbClampingMax().c_str());
1004  _ui->checkBox_grid_erode->setObjectName(Parameters::kGridGlobalEroded().c_str());
1005 
1006  //Odometry
1007  _ui->odom_strategy->setObjectName(Parameters::kOdomStrategy().c_str());
1008  connect(_ui->odom_strategy, SIGNAL(currentIndexChanged(int)), _ui->stackedWidget_odometryType, SLOT(setCurrentIndex(int)));
1009  _ui->odom_strategy->setCurrentIndex(Parameters::defaultOdomStrategy());
1010  _ui->stackedWidget_odometryType->setCurrentIndex(Parameters::defaultOdomStrategy());
1011  _ui->odom_countdown->setObjectName(Parameters::kOdomResetCountdown().c_str());
1012  _ui->odom_holonomic->setObjectName(Parameters::kOdomHolonomic().c_str());
1013  _ui->odom_fillInfoData->setObjectName(Parameters::kOdomFillInfoData().c_str());
1014  _ui->odom_dataBufferSize->setObjectName(Parameters::kOdomImageBufferSize().c_str());
1015  _ui->odom_flow_keyframeThr->setObjectName(Parameters::kOdomKeyFrameThr().c_str());
1016  _ui->odom_VisKeyFrameThr->setObjectName(Parameters::kOdomVisKeyFrameThr().c_str());
1017  _ui->odom_flow_scanKeyframeThr->setObjectName(Parameters::kOdomScanKeyFrameThr().c_str());
1018  _ui->odom_flow_guessMotion->setObjectName(Parameters::kOdomGuessMotion().c_str());
1019  _ui->odom_imageDecimation->setObjectName(Parameters::kOdomImageDecimation().c_str());
1020  _ui->odom_alignWithGround->setObjectName(Parameters::kOdomAlignWithGround().c_str());
1021 
1022  //Odometry Frame to Map
1023  _ui->odom_localHistory->setObjectName(Parameters::kOdomF2MMaxSize().c_str());
1024  _ui->spinBox_odom_f2m_maxNewFeatures->setObjectName(Parameters::kOdomF2MMaxNewFeatures().c_str());
1025  _ui->spinBox_odom_f2m_scanMaxSize->setObjectName(Parameters::kOdomF2MScanMaxSize().c_str());
1026  _ui->doubleSpinBox_odom_f2m_scanRadius->setObjectName(Parameters::kOdomF2MScanSubtractRadius().c_str());
1027  _ui->doubleSpinBox_odom_f2m_scanAngle->setObjectName(Parameters::kOdomF2MScanSubtractAngle().c_str());
1028  _ui->odom_f2m_bundleStrategy->setObjectName(Parameters::kOdomF2MBundleAdjustment().c_str());
1029  _ui->odom_f2m_bundleMaxFrames->setObjectName(Parameters::kOdomF2MBundleAdjustmentMaxFrames().c_str());
1030 
1031  //Odometry Frame To Frame
1032  _ui->comboBox_odomf2f_corType->setObjectName(Parameters::kVisCorType().c_str());
1033 
1034  //Odometry Mono
1035  _ui->doubleSpinBox_minFlow->setObjectName(Parameters::kOdomMonoInitMinFlow().c_str());
1036  _ui->doubleSpinBox_minInitTranslation->setObjectName(Parameters::kOdomMonoInitMinTranslation().c_str());
1037  _ui->doubleSpinBox_minTranslation->setObjectName(Parameters::kOdomMonoMinTranslation().c_str());
1038  _ui->doubleSpinBox_maxVariance->setObjectName(Parameters::kOdomMonoMaxVariance().c_str());
1039 
1040  //Odometry particle filter
1041  _ui->odom_filteringStrategy->setObjectName(Parameters::kOdomFilteringStrategy().c_str());
1042  _ui->stackedWidget_odometryFiltering->setCurrentIndex(_ui->odom_filteringStrategy->currentIndex());
1043  connect(_ui->odom_filteringStrategy, SIGNAL(currentIndexChanged(int)), _ui->stackedWidget_odometryFiltering, SLOT(setCurrentIndex(int)));
1044  _ui->spinBox_particleSize->setObjectName(Parameters::kOdomParticleSize().c_str());
1045  _ui->doubleSpinBox_particleNoiseT->setObjectName(Parameters::kOdomParticleNoiseT().c_str());
1046  _ui->doubleSpinBox_particleLambdaT->setObjectName(Parameters::kOdomParticleLambdaT().c_str());
1047  _ui->doubleSpinBox_particleNoiseR->setObjectName(Parameters::kOdomParticleNoiseR().c_str());
1048  _ui->doubleSpinBox_particleLambdaR->setObjectName(Parameters::kOdomParticleLambdaR().c_str());
1049 
1050  //Odometry Kalman filter
1051  _ui->doubleSpinBox_kalmanProcessNoise->setObjectName(Parameters::kOdomKalmanProcessNoise().c_str());
1052  _ui->doubleSpinBox_kalmanMeasurementNoise->setObjectName(Parameters::kOdomKalmanMeasurementNoise().c_str());
1053 
1054  //Odometry Fovis
1055  _ui->spinBox_OdomFovisFeatureWindowSize->setObjectName(Parameters::kOdomFovisFeatureWindowSize().c_str());
1056  _ui->spinBox_OdomFovisMaxPyramidLevel->setObjectName(Parameters::kOdomFovisMaxPyramidLevel().c_str());
1057  _ui->spinBox_OdomFovisMinPyramidLevel->setObjectName(Parameters::kOdomFovisMinPyramidLevel().c_str());
1058  _ui->spinBox_OdomFovisTargetPixelsPerFeature->setObjectName(Parameters::kOdomFovisTargetPixelsPerFeature().c_str());
1059  _ui->spinBox_OdomFovisFastThreshold->setObjectName(Parameters::kOdomFovisFastThreshold().c_str());
1060  _ui->checkBox_OdomFovisUseAdaptiveThreshold->setObjectName(Parameters::kOdomFovisUseAdaptiveThreshold().c_str());
1061  _ui->doubleSpinBox_OdomFovisFastThresholdAdaptiveGain->setObjectName(Parameters::kOdomFovisFastThresholdAdaptiveGain().c_str());
1062  _ui->checkBox_OdomFovisUseHomographyInitialization->setObjectName(Parameters::kOdomFovisUseHomographyInitialization().c_str());
1063 
1064  _ui->checkBox_OdomFovisUseBucketing->setObjectName(Parameters::kOdomFovisUseBucketing().c_str());
1065  _ui->spinBox_OdomFovisBucketWidth->setObjectName(Parameters::kOdomFovisBucketWidth().c_str());
1066  _ui->spinBox_OdomFovisBucketHeight->setObjectName(Parameters::kOdomFovisBucketHeight().c_str());
1067  _ui->spinBox_OdomFovisMaxKeypointsPerBucket->setObjectName(Parameters::kOdomFovisMaxKeypointsPerBucket().c_str());
1068  _ui->checkBox_OdomFovisUseImageNormalization->setObjectName(Parameters::kOdomFovisUseImageNormalization().c_str());
1069 
1070  _ui->doubleSpinBox_OdomFovisInlierMaxReprojectionError->setObjectName(Parameters::kOdomFovisInlierMaxReprojectionError().c_str());
1071  _ui->doubleSpinBox_OdomFovisCliqueInlierThreshold->setObjectName(Parameters::kOdomFovisCliqueInlierThreshold().c_str());
1072  _ui->spinBox_OdomFovisMinFeaturesForEstimate->setObjectName(Parameters::kOdomFovisMinFeaturesForEstimate().c_str());
1073  _ui->doubleSpinBox_OdomFovisMaxMeanReprojectionError->setObjectName(Parameters::kOdomFovisMaxMeanReprojectionError().c_str());
1074  _ui->checkBox_OdomFovisUseSubpixelRefinement->setObjectName(Parameters::kOdomFovisUseSubpixelRefinement().c_str());
1075  _ui->spinBox_OdomFovisFeatureSearchWindow->setObjectName(Parameters::kOdomFovisFeatureSearchWindow().c_str());
1076  _ui->checkBox_OdomFovisUpdateTargetFeaturesWithRefined->setObjectName(Parameters::kOdomFovisUpdateTargetFeaturesWithRefined().c_str());
1077 
1078  _ui->checkBox_OdomFovisStereoRequireMutualMatch->setObjectName(Parameters::kOdomFovisStereoRequireMutualMatch().c_str());
1079  _ui->doubleSpinBox_OdomFovisStereoMaxDistEpipolarLine->setObjectName(Parameters::kOdomFovisStereoMaxDistEpipolarLine().c_str());
1080  _ui->doubleSpinBox_OdomFovisStereoMaxRefinementDisplacement->setObjectName(Parameters::kOdomFovisStereoMaxRefinementDisplacement().c_str());
1081  _ui->spinBox_OdomFovisStereoMaxDisparity->setObjectName(Parameters::kOdomFovisStereoMaxDisparity().c_str());
1082 
1083  // Odometry viso2
1084  _ui->spinBox_OdomViso2RansacIters->setObjectName(Parameters::kOdomViso2RansacIters().c_str());
1085  _ui->doubleSpinBox_OdomViso2InlierThreshold->setObjectName(Parameters::kOdomViso2InlierThreshold().c_str());
1086  _ui->checkBox_OdomViso2Reweighting->setObjectName(Parameters::kOdomViso2Reweighting().c_str());
1087 
1088  _ui->spinBox_OdomViso2MatchNmsN->setObjectName(Parameters::kOdomViso2MatchNmsN().c_str());
1089  _ui->spinBox_OdomViso2MatchNmsTau->setObjectName(Parameters::kOdomViso2MatchNmsTau().c_str());
1090  _ui->spinBox_OdomViso2MatchBinsize->setObjectName(Parameters::kOdomViso2MatchBinsize().c_str());
1091  _ui->spinBox_OdomViso2MatchRadius->setObjectName(Parameters::kOdomViso2MatchRadius().c_str());
1092  _ui->spinBox_OdomViso2MatchDispTolerance->setObjectName(Parameters::kOdomViso2MatchDispTolerance().c_str());
1093  _ui->spinBox_OdomViso2MatchOutlierDispTolerance->setObjectName(Parameters::kOdomViso2MatchOutlierDispTolerance().c_str());
1094  _ui->spinBox_OdomViso2MatchOutlierFlowTolerance->setObjectName(Parameters::kOdomViso2MatchOutlierFlowTolerance().c_str());
1095  _ui->checkBox_OdomViso2MatchMultiStage->setObjectName(Parameters::kOdomViso2MatchMultiStage().c_str());
1096  _ui->checkBox_OdomViso2MatchHalfResolution->setObjectName(Parameters::kOdomViso2MatchHalfResolution().c_str());
1097  _ui->spinBox_OdomViso2MatchRefinement->setObjectName(Parameters::kOdomViso2MatchRefinement().c_str());
1098 
1099  _ui->spinBox_OdomViso2BucketMaxFeatures->setObjectName(Parameters::kOdomViso2BucketMaxFeatures().c_str());
1100  _ui->doubleSpinBox_OdomViso2BucketWidth->setObjectName(Parameters::kOdomViso2BucketWidth().c_str());
1101  _ui->doubleSpinBox_OdomViso2BucketHeight->setObjectName(Parameters::kOdomViso2BucketHeight().c_str());
1102 
1103  // Odometry ORBSLAM2
1104  _ui->lineEdit_OdomORBSLAM2VocPath->setObjectName(Parameters::kOdomORBSLAM2VocPath().c_str());
1105  connect(_ui->toolButton_OdomORBSLAM2VocPath, SIGNAL(clicked()), this, SLOT(changeOdometryORBSLAM2Vocabulary()));
1106  _ui->doubleSpinBox_OdomORBSLAM2Bf->setObjectName(Parameters::kOdomORBSLAM2Bf().c_str());
1107  _ui->doubleSpinBox_OdomORBSLAM2ThDepth->setObjectName(Parameters::kOdomORBSLAM2ThDepth().c_str());
1108  _ui->doubleSpinBox_OdomORBSLAM2Fps->setObjectName(Parameters::kOdomORBSLAM2Fps().c_str());
1109  _ui->spinBox_OdomORBSLAM2MaxFeatures->setObjectName(Parameters::kOdomORBSLAM2MaxFeatures().c_str());
1110  _ui->spinBox_OdomORBSLAM2MapSize->setObjectName(Parameters::kOdomORBSLAM2MapSize().c_str());
1111 
1112  // Odometry Okvis
1113  _ui->lineEdit_OdomOkvisPath->setObjectName(Parameters::kOdomOKVISConfigPath().c_str());
1114  connect(_ui->toolButton_OdomOkvisPath, SIGNAL(clicked()), this, SLOT(changeOdometryOKVISConfigPath()));
1115 
1116  // Odometry LOAM
1117  _ui->odom_loam_sensor->setObjectName(Parameters::kOdomLOAMSensor().c_str());
1118  _ui->odom_loam_scan_period->setObjectName(Parameters::kOdomLOAMScanPeriod().c_str());
1119  _ui->odom_loam_linvar->setObjectName(Parameters::kOdomLOAMLinVar().c_str());
1120  _ui->odom_loam_angvar->setObjectName(Parameters::kOdomLOAMAngVar().c_str());
1121  _ui->odom_loam_localMapping->setObjectName(Parameters::kOdomLOAMLocalMapping().c_str());
1122 
1123  // Odometry MSCKF_VIO
1124  _ui->OdomMSCKFGridRow->setObjectName(Parameters::kOdomMSCKFGridRow().c_str());
1125  _ui->OdomMSCKFGridCol->setObjectName(Parameters::kOdomMSCKFGridCol().c_str());
1126  _ui->OdomMSCKFGridMinFeatureNum->setObjectName(Parameters::kOdomMSCKFGridMinFeatureNum().c_str());
1127  _ui->OdomMSCKFGridMaxFeatureNum->setObjectName(Parameters::kOdomMSCKFGridMaxFeatureNum().c_str());
1128  _ui->OdomMSCKFPyramidLevels->setObjectName(Parameters::kOdomMSCKFPyramidLevels().c_str());
1129  _ui->OdomMSCKFPatchSize->setObjectName(Parameters::kOdomMSCKFPatchSize().c_str());
1130  _ui->OdomMSCKFFastThreshold->setObjectName(Parameters::kOdomMSCKFFastThreshold().c_str());
1131  _ui->OdomMSCKFMaxIteration->setObjectName(Parameters::kOdomMSCKFMaxIteration().c_str());
1132  _ui->OdomMSCKFMaxCamStateSize->setObjectName(Parameters::kOdomMSCKFMaxCamStateSize().c_str());
1133  _ui->OdomMSCKFTrackPrecision->setObjectName(Parameters::kOdomMSCKFTrackPrecision().c_str());
1134  _ui->OdomMSCKFRansacThreshold->setObjectName(Parameters::kOdomMSCKFRansacThreshold().c_str());
1135  _ui->OdomMSCKFStereoThreshold->setObjectName(Parameters::kOdomMSCKFStereoThreshold().c_str());
1136  _ui->OdomMSCKFPositionStdThreshold->setObjectName(Parameters::kOdomMSCKFPositionStdThreshold().c_str());
1137  _ui->OdomMSCKFRotationThreshold->setObjectName(Parameters::kOdomMSCKFRotationThreshold().c_str());
1138  _ui->OdomMSCKFTranslationThreshold->setObjectName(Parameters::kOdomMSCKFTranslationThreshold().c_str());
1139  _ui->OdomMSCKFTrackingRateThreshold->setObjectName(Parameters::kOdomMSCKFTrackingRateThreshold().c_str());
1140  _ui->OdomMSCKFOptTranslationThreshold->setObjectName(Parameters::kOdomMSCKFOptTranslationThreshold().c_str());
1141  _ui->OdomMSCKFNoiseGyro->setObjectName(Parameters::kOdomMSCKFNoiseGyro().c_str());
1142  _ui->OdomMSCKFNoiseAcc->setObjectName(Parameters::kOdomMSCKFNoiseAcc().c_str());
1143  _ui->OdomMSCKFNoiseGyroBias->setObjectName(Parameters::kOdomMSCKFNoiseGyroBias().c_str());
1144  _ui->OdomMSCKFNoiseAccBias->setObjectName(Parameters::kOdomMSCKFNoiseAccBias().c_str());
1145  _ui->OdomMSCKFNoiseFeature->setObjectName(Parameters::kOdomMSCKFNoiseFeature().c_str());
1146  _ui->OdomMSCKFInitCovVel->setObjectName(Parameters::kOdomMSCKFInitCovVel().c_str());
1147  _ui->OdomMSCKFInitCovGyroBias->setObjectName(Parameters::kOdomMSCKFInitCovGyroBias().c_str());
1148  _ui->OdomMSCKFInitCovAccBias->setObjectName(Parameters::kOdomMSCKFInitCovAccBias().c_str());
1149  _ui->OdomMSCKFInitCovExRot->setObjectName(Parameters::kOdomMSCKFInitCovExRot().c_str());
1150  _ui->OdomMSCKFInitCovExTrans->setObjectName(Parameters::kOdomMSCKFInitCovExTrans().c_str());
1151 
1152  //Stereo
1153  _ui->stereo_winWidth->setObjectName(Parameters::kStereoWinWidth().c_str());
1154  _ui->stereo_winHeight->setObjectName(Parameters::kStereoWinHeight().c_str());
1155  _ui->stereo_maxLevel->setObjectName(Parameters::kStereoMaxLevel().c_str());
1156  _ui->stereo_iterations->setObjectName(Parameters::kStereoIterations().c_str());
1157  _ui->stereo_minDisparity->setObjectName(Parameters::kStereoMinDisparity().c_str());
1158  _ui->stereo_maxDisparity->setObjectName(Parameters::kStereoMaxDisparity().c_str());
1159  _ui->stereo_ssd->setObjectName(Parameters::kStereoSSD().c_str());
1160  _ui->stereo_flow_eps->setObjectName(Parameters::kStereoEps().c_str());
1161  _ui->stereo_opticalFlow->setObjectName(Parameters::kStereoOpticalFlow().c_str());
1162 
1163  //StereoBM
1164  _ui->stereobm_blockSize->setObjectName(Parameters::kStereoBMBlockSize().c_str());
1165  _ui->stereobm_minDisparity->setObjectName(Parameters::kStereoBMMinDisparity().c_str());
1166  _ui->stereobm_numDisparities->setObjectName(Parameters::kStereoBMNumDisparities().c_str());
1167  _ui->stereobm_preFilterCap->setObjectName(Parameters::kStereoBMPreFilterCap().c_str());
1168  _ui->stereobm_preFilterSize->setObjectName(Parameters::kStereoBMPreFilterSize().c_str());
1169  _ui->stereobm_speckleRange->setObjectName(Parameters::kStereoBMSpeckleRange().c_str());
1170  _ui->stereobm_speckleWinSize->setObjectName(Parameters::kStereoBMSpeckleWindowSize().c_str());
1171  _ui->stereobm_tetureThreshold->setObjectName(Parameters::kStereoBMTextureThreshold().c_str());
1172  _ui->stereobm_uniquessRatio->setObjectName(Parameters::kStereoBMUniquenessRatio().c_str());
1173 
1174  // reset default settings for the gui
1175  resetSettings(_ui->groupBox_generalSettingsGui0);
1176  resetSettings(_ui->groupBox_cloudRendering1);
1177  resetSettings(_ui->groupBox_filtering2);
1178  resetSettings(_ui->groupBox_gridMap2);
1179  resetSettings(_ui->groupBox_logging1);
1180  resetSettings(_ui->groupBox_source0);
1181 
1182  setupSignals();
1183  // custom signals
1184  connect(_ui->doubleSpinBox_kp_roi0, SIGNAL(valueChanged(double)), this, SLOT(updateKpROI()));
1185  connect(_ui->doubleSpinBox_kp_roi1, SIGNAL(valueChanged(double)), this, SLOT(updateKpROI()));
1186  connect(_ui->doubleSpinBox_kp_roi2, SIGNAL(valueChanged(double)), this, SLOT(updateKpROI()));
1187  connect(_ui->doubleSpinBox_kp_roi3, SIGNAL(valueChanged(double)), this, SLOT(updateKpROI()));
1188  connect(_ui->checkBox_useOdomFeatures, SIGNAL(toggled(bool)), this, SLOT(useOdomFeatures()));
1189 
1190  //Create a model from the stacked widgets
1191  // This will add all parameters to the parameters Map
1192  _ui->stackedWidget->setCurrentIndex(0);
1193  this->setupTreeView();
1194 
1196 }
1197 
1199  // remove tmp ini file
1200  QFile::remove(getTmpIniFilePath());
1201  delete _ui;
1202 }
1203 
1205 {
1206  UDEBUG("");
1207  //First set all default values
1208  const ParametersMap & defaults = Parameters::getDefaultParameters();
1209  for(ParametersMap::const_iterator iter=defaults.begin(); iter!=defaults.end(); ++iter)
1210  {
1211  this->setParameter(iter->first, iter->second);
1212  }
1213 
1214  this->readSettings();
1216 
1217  _initialized = true;
1218 }
1219 
1221 {
1222  QList<QGroupBox*> boxes = this->getGroupBoxes();
1223  for(int i =0;i<boxes.size();++i)
1224  {
1225  if(boxes[i] == _ui->groupBox_source0)
1226  {
1227  _ui->stackedWidget->setCurrentIndex(i);
1228  _ui->treeView->setCurrentIndex(_indexModel->index(i-2, 0));
1229  break;
1230  }
1231  }
1232 }
1233 
1235 {
1236  writeSettings();
1237 }
1238 
1240 {
1241  if(_indexModel)
1242  {
1243  _ui->treeView->setModel(0);
1244  delete _indexModel;
1245  }
1246  _indexModel = new QStandardItemModel(this);
1247  // Parse the model
1248  QList<QGroupBox*> boxes = this->getGroupBoxes();
1249  if(_ui->radioButton_basic->isChecked())
1250  {
1251  boxes = boxes.mid(0,7);
1252  }
1253  else // Advanced
1254  {
1255  boxes.removeAt(6);
1256  }
1257 
1258  QStandardItem * parentItem = _indexModel->invisibleRootItem();
1259  int index = 0;
1260  this->parseModel(boxes, parentItem, 0, index); // recursive method
1261  if(_ui->radioButton_advanced->isChecked() && index != _ui->stackedWidget->count()-1)
1262  {
1263  ULOGGER_ERROR("The tree model is not the same size of the stacked widgets...%d vs %d advanced stacks", index, _ui->stackedWidget->count()-1);
1264  }
1265  int currentIndex = _ui->stackedWidget->currentIndex();
1266  if(_ui->radioButton_basic->isChecked())
1267  {
1268  if(currentIndex >= 6)
1269  {
1270  _ui->stackedWidget->setCurrentIndex(6);
1271  currentIndex = 6;
1272  }
1273  }
1274  else // Advanced
1275  {
1276  if(currentIndex == 6)
1277  {
1278  _ui->stackedWidget->setCurrentIndex(7);
1279  }
1280  }
1281  _ui->treeView->setModel(_indexModel);
1282  _ui->treeView->expandToDepth(1);
1283 
1284  // should be after setModel()
1285  connect(_ui->treeView->selectionModel(), SIGNAL(currentChanged(const QModelIndex &, const QModelIndex &)), this, SLOT(clicked(const QModelIndex &, const QModelIndex &)));
1286 }
1287 
1288 // recursive...
1289 bool PreferencesDialog::parseModel(QList<QGroupBox*> & boxes, QStandardItem * parentItem, int currentLevel, int & absoluteIndex)
1290 {
1291  if(parentItem == 0)
1292  {
1293  ULOGGER_ERROR("Parent item is null !");
1294  return false;
1295  }
1296 
1297  QStandardItem * currentItem = 0;
1298  while(absoluteIndex < boxes.size())
1299  {
1300  QString objectName = boxes.at(absoluteIndex)->objectName();
1301  QString title = boxes.at(absoluteIndex)->title();
1302  bool ok = false;
1303  int lvl = QString(objectName.at(objectName.size()-1)).toInt(&ok);
1304  if(!ok)
1305  {
1306  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());
1307  return false;
1308  }
1309 
1310 
1311  if(lvl == currentLevel)
1312  {
1313  QStandardItem * item = new QStandardItem(title);
1314  item->setData(absoluteIndex);
1315  currentItem = item;
1316  //ULOGGER_DEBUG("PreferencesDialog::parseModel() lvl(%d) Added %s", currentLevel, title.toStdString().c_str());
1317  parentItem->appendRow(item);
1318  ++absoluteIndex;
1319  }
1320  else if(lvl > currentLevel)
1321  {
1322  if(lvl>currentLevel+1)
1323  {
1324  ULOGGER_ERROR("Intermediary lvl doesn't exist, lvl %d to %d, indexes %d and %d", currentLevel, lvl, absoluteIndex-1, absoluteIndex);
1325  return false;
1326  }
1327  else
1328  {
1329  parseModel(boxes, currentItem, currentLevel+1, absoluteIndex); // recursive
1330  }
1331  }
1332  else
1333  {
1334  return false;
1335  }
1336  }
1337  return true;
1338 }
1339 
1341 {
1343  for(rtabmap::ParametersMap::const_iterator iter=parameters.begin(); iter!=parameters.end(); ++iter)
1344  {
1345  QWidget * obj = _ui->stackedWidget->findChild<QWidget*>((*iter).first.c_str());
1346  if(obj)
1347  {
1348  // set tooltip as the parameter name
1349  obj->setToolTip(tr("%1 (Default=\"%2\")").arg(iter->first.c_str()).arg(iter->second.c_str()));
1350 
1351  QSpinBox * spin = qobject_cast<QSpinBox *>(obj);
1352  QDoubleSpinBox * doubleSpin = qobject_cast<QDoubleSpinBox *>(obj);
1353  QComboBox * combo = qobject_cast<QComboBox *>(obj);
1354  QCheckBox * check = qobject_cast<QCheckBox *>(obj);
1355  QRadioButton * radio = qobject_cast<QRadioButton *>(obj);
1356  QLineEdit * lineEdit = qobject_cast<QLineEdit *>(obj);
1357  QGroupBox * groupBox = qobject_cast<QGroupBox *>(obj);
1358  if(spin)
1359  {
1360  connect(spin, SIGNAL(valueChanged(int)), this, SLOT(addParameter(int)));
1361  }
1362  else if(doubleSpin)
1363  {
1364  connect(doubleSpin, SIGNAL(valueChanged(double)), this, SLOT(addParameter(double)));
1365  }
1366  else if(combo)
1367  {
1368  connect(combo, SIGNAL(currentIndexChanged(int)), this, SLOT(addParameter(int)));
1369  }
1370  else if(check)
1371  {
1372  connect(check, SIGNAL(toggled(bool)), this, SLOT(addParameter(bool)));
1373  }
1374  else if(radio)
1375  {
1376  connect(radio, SIGNAL(toggled(bool)), this, SLOT(addParameter(bool)));
1377  }
1378  else if(lineEdit)
1379  {
1380  connect(lineEdit, SIGNAL(textChanged(const QString &)), this, SLOT(addParameter(const QString &)));
1381  }
1382  else if(groupBox)
1383  {
1384  connect(groupBox, SIGNAL(toggled(bool)), this, SLOT(addParameter(bool)));
1385  }
1386  else
1387  {
1388  ULOGGER_WARN("QWidget called %s can't be cast to a supported widget", (*iter).first.c_str());
1389  }
1390  }
1391  else
1392  {
1393  ULOGGER_WARN("Can't find the related QWidget for parameter %s", (*iter).first.c_str());
1394  }
1395  }
1396 }
1397 
1398 void PreferencesDialog::clicked(const QModelIndex & current, const QModelIndex & previous)
1399  {
1400  QStandardItem * item = _indexModel->itemFromIndex(current);
1401  if(item && item->isEnabled())
1402  {
1403  int index = item->data().toInt();
1404  if(_ui->radioButton_advanced->isChecked() && index >= 6)
1405  {
1406  ++index;
1407  }
1408  _ui->stackedWidget->setCurrentIndex(index);
1409  _ui->scrollArea->horizontalScrollBar()->setValue(0);
1410  _ui->scrollArea->verticalScrollBar()->setValue(0);
1411  }
1412  }
1413 
1414 void PreferencesDialog::closeEvent(QCloseEvent *event)
1415 {
1416  UDEBUG("");
1417  _modifiedParameters.clear();
1421  event->accept();
1422 }
1423 
1424 void PreferencesDialog::closeDialog ( QAbstractButton * button )
1425 {
1426  UDEBUG("");
1427 
1428  QDialogButtonBox::ButtonRole role = _ui->buttonBox_global->buttonRole(button);
1429  switch(role)
1430  {
1431  case QDialogButtonBox::RejectRole:
1432  _modifiedParameters.clear();
1436  this->reject();
1437  break;
1438 
1439  case QDialogButtonBox::AcceptRole:
1440  updateBasicParameter();// make that changes without editing finished signal are updated.
1442  {
1443  if(validateForm())
1444  {
1446  this->accept();
1447  }
1448  }
1449  else
1450  {
1451  this->accept();
1452  }
1453  break;
1454 
1455  default:
1456  break;
1457  }
1458 }
1459 
1460 void PreferencesDialog::resetApply ( QAbstractButton * button )
1461 {
1462  QDialogButtonBox::ButtonRole role = _ui->buttonBox_local->buttonRole(button);
1463  switch(role)
1464  {
1465  case QDialogButtonBox::ApplyRole:
1466  updateBasicParameter();// make that changes without editing finished signal are updated.
1467  if(validateForm())
1468  {
1470  }
1471  break;
1472 
1473  case QDialogButtonBox::ResetRole:
1474  resetSettings(_ui->stackedWidget->currentIndex());
1475  break;
1476 
1477  default:
1478  break;
1479  }
1480 }
1481 
1482 void PreferencesDialog::resetSettings(QGroupBox * groupBox)
1483 {
1484  if(groupBox->objectName() == _ui->groupBox_generalSettingsGui0->objectName())
1485  {
1486  _ui->general_checkBox_imagesKept->setChecked(true);
1487  _ui->general_checkBox_cloudsKept->setChecked(true);
1488  _ui->checkBox_beep->setChecked(false);
1489  _ui->checkBox_stamps->setChecked(true);
1490  _ui->checkBox_cacheStatistics->setChecked(true);
1491  _ui->checkBox_notifyWhenNewGlobalPathIsReceived->setChecked(false);
1492  _ui->checkBox_verticalLayoutUsed->setChecked(true);
1493  _ui->checkBox_imageRejectedShown->setChecked(true);
1494  _ui->checkBox_imageHighestHypShown->setChecked(false);
1495  _ui->spinBox_odomQualityWarnThr->setValue(50);
1496  _ui->checkBox_odom_onlyInliersShown->setChecked(false);
1497  _ui->radioButton_posteriorGraphView->setChecked(true);
1498  _ui->radioButton_wordsGraphView->setChecked(false);
1499  _ui->radioButton_localizationsGraphView->setChecked(false);
1500  _ui->radioButton_nochangeGraphView->setChecked(false);
1501  _ui->checkbox_odomDisabled->setChecked(false);
1502  _ui->checkbox_groundTruthAlign->setChecked(true);
1503  }
1504  else if(groupBox->objectName() == _ui->groupBox_cloudRendering1->objectName())
1505  {
1506  for(int i=0; i<2; ++i)
1507  {
1508  _3dRenderingShowClouds[i]->setChecked(true);
1509  _3dRenderingDecimation[i]->setValue(4);
1510  _3dRenderingMaxDepth[i]->setValue(0.0);
1511  _3dRenderingMinDepth[i]->setValue(0.0);
1512  _3dRenderingRoiRatios[i]->setText("0.0 0.0 0.0 0.0");
1513  _3dRenderingShowScans[i]->setChecked(true);
1514  _3dRenderingShowFeatures[i]->setChecked(i==0?false:true);
1515  _3dRenderingShowFrustums[i]->setChecked(false);
1516 
1517  _3dRenderingDownsamplingScan[i]->setValue(1);
1518  _3dRenderingMaxRange[i]->setValue(0.0);
1519  _3dRenderingMinRange[i]->setValue(0.0);
1520  _3dRenderingVoxelSizeScan[i]->setValue(0.0);
1521  _3dRenderingColorScheme[i]->setValue(0);
1522  _3dRenderingOpacity[i]->setValue(i==0?1.0:0.75);
1523  _3dRenderingPtSize[i]->setValue(2);
1524  _3dRenderingColorSchemeScan[i]->setValue(0);
1525  _3dRenderingOpacityScan[i]->setValue(i==0?1.0:0.5);
1526  _3dRenderingPtSizeScan[i]->setValue(2);
1527  _3dRenderingPtSizeFeatures[i]->setValue(3);
1528  }
1529  _ui->doubleSpinBox_voxel->setValue(0);
1530  _ui->doubleSpinBox_noiseRadius->setValue(0);
1531  _ui->spinBox_noiseMinNeighbors->setValue(5);
1532 
1533  _ui->doubleSpinBox_ceilingFilterHeight->setValue(0);
1534  _ui->doubleSpinBox_floorFilterHeight->setValue(0);
1535  _ui->spinBox_normalKSearch->setValue(10);
1536  _ui->doubleSpinBox_normalRadiusSearch->setValue(0.0);
1537 
1538  _ui->doubleSpinBox_ceilingFilterHeight_scan->setValue(0);
1539  _ui->doubleSpinBox_floorFilterHeight_scan->setValue(0);
1540  _ui->spinBox_normalKSearch_scan->setValue(0);
1541  _ui->doubleSpinBox_normalRadiusSearch_scan->setValue(0.0);
1542 
1543  _ui->checkBox_showGraphs->setChecked(true);
1544  _ui->checkBox_showLabels->setChecked(false);
1545 
1546  _ui->doubleSpinBox_mesh_angleTolerance->setValue(15.0);
1547  _ui->groupBox_organized->setChecked(false);
1548 #if PCL_VERSION_COMPARE(>=, 1, 7, 2)
1549  _ui->checkBox_mesh_quad->setChecked(true);
1550 #else
1551  _ui->checkBox_mesh_quad->setChecked(false);
1552 #endif
1553  _ui->checkBox_mesh_texture->setChecked(false);
1554  _ui->spinBox_mesh_triangleSize->setValue(2);
1555  }
1556  else if(groupBox->objectName() == _ui->groupBox_filtering2->objectName())
1557  {
1558  _ui->radioButton_noFiltering->setChecked(true);
1559  _ui->radioButton_nodeFiltering->setChecked(false);
1560  _ui->radioButton_subtractFiltering->setChecked(false);
1561  _ui->doubleSpinBox_cloudFilterRadius->setValue(0.1);
1562  _ui->doubleSpinBox_cloudFilterAngle->setValue(30);
1563  _ui->spinBox_subtractFilteringMinPts->setValue(5);
1564  _ui->doubleSpinBox_subtractFilteringRadius->setValue(0.02);
1565  _ui->doubleSpinBox_subtractFilteringAngle->setValue(0);
1566  }
1567  else if(groupBox->objectName() == _ui->groupBox_gridMap2->objectName())
1568  {
1569  _ui->checkBox_map_shown->setChecked(false);
1570  _ui->doubleSpinBox_map_opacity->setValue(0.75);
1571 
1572  _ui->groupBox_octomap->setChecked(false);
1573  _ui->spinBox_octomap_treeDepth->setValue(16);
1574  _ui->checkBox_octomap_2dgrid->setChecked(true);
1575  _ui->checkBox_octomap_show3dMap->setChecked(true);
1576  _ui->comboBox_octomap_renderingType->setCurrentIndex(0);
1577  _ui->spinBox_octomap_pointSize->setValue(5);
1578  }
1579  else if(groupBox->objectName() == _ui->groupBox_logging1->objectName())
1580  {
1581  _ui->comboBox_loggerLevel->setCurrentIndex(2);
1582  _ui->comboBox_loggerEventLevel->setCurrentIndex(3);
1583  _ui->comboBox_loggerPauseLevel->setCurrentIndex(3);
1584  _ui->checkBox_logger_printTime->setChecked(true);
1585  _ui->checkBox_logger_printThreadId->setChecked(false);
1586  _ui->comboBox_loggerType->setCurrentIndex(1);
1587  for(int i=0; i<_ui->comboBox_loggerFilter->count(); ++i)
1588  {
1589  _ui->comboBox_loggerFilter->setItemChecked(i, false);
1590  }
1591  }
1592  else if(groupBox->objectName() == _ui->groupBox_source0->objectName())
1593  {
1594  _ui->general_doubleSpinBox_imgRate->setValue(0.0);
1595  _ui->source_mirroring->setChecked(false);
1596  _ui->lineEdit_calibrationFile->clear();
1597  _ui->comboBox_sourceType->setCurrentIndex(kSrcRGBD);
1598  _ui->lineEdit_sourceDevice->setText("");
1599  _ui->lineEdit_sourceLocalTransform->setText("0 0 1 -1 0 0 0 -1 0");
1600 
1601  _ui->source_comboBox_image_type->setCurrentIndex(kSrcUsbDevice-kSrcUsbDevice);
1602  _ui->source_images_spinBox_startPos->setValue(0);
1603  _ui->checkBox_rgb_rectify->setChecked(false);
1604  _ui->comboBox_cameraImages_bayerMode->setCurrentIndex(0);
1605 
1606  _ui->source_checkBox_ignoreOdometry->setChecked(false);
1607  _ui->source_checkBox_ignoreGoalDelay->setChecked(true);
1608  _ui->source_checkBox_ignoreGoals->setChecked(true);
1609  _ui->source_spinBox_databaseStartPos->setValue(0);
1610  _ui->source_spinBox_database_cameraIndex->setValue(-1);
1611  _ui->source_checkBox_useDbStamps->setChecked(true);
1612 
1613 #ifdef _WIN32
1614  _ui->comboBox_cameraRGBD->setCurrentIndex(kSrcOpenNI2-kSrcRGBD); // openni2
1615 #else
1617  {
1618  _ui->comboBox_cameraRGBD->setCurrentIndex(kSrcFreenect-kSrcRGBD); // freenect
1619  }
1620  else if(CameraOpenNI2::available())
1621  {
1622  _ui->comboBox_cameraRGBD->setCurrentIndex(kSrcOpenNI2-kSrcRGBD); // openni2
1623  }
1624  else
1625  {
1626  _ui->comboBox_cameraRGBD->setCurrentIndex(kSrcOpenNI_PCL-kSrcRGBD); // openni-pcl
1627  }
1628 #endif
1630  {
1631  _ui->comboBox_cameraStereo->setCurrentIndex(kSrcDC1394-kSrcStereo); // dc1394
1632  }
1634  {
1635  _ui->comboBox_cameraStereo->setCurrentIndex(kSrcFlyCapture2-kSrcStereo); // flycapture
1636  }
1637  else
1638  {
1639  _ui->comboBox_cameraStereo->setCurrentIndex(kSrcStereoImages-kSrcStereo); // stereo images
1640  }
1641 
1642  _ui->checkbox_rgbd_colorOnly->setChecked(false);
1643  _ui->spinBox_source_imageDecimation->setValue(1);
1644  _ui->checkbox_stereo_depthGenerated->setChecked(false);
1645  _ui->checkBox_stereo_exposureCompensation->setChecked(false);
1646  _ui->openni2_autoWhiteBalance->setChecked(true);
1647  _ui->openni2_autoExposure->setChecked(true);
1648  _ui->openni2_exposure->setValue(0);
1649  _ui->openni2_gain->setValue(100);
1650  _ui->openni2_mirroring->setChecked(false);
1651  _ui->openni2_stampsIdsUsed->setChecked(false);
1652  _ui->openni2_hshift->setValue(0);
1653  _ui->openni2_vshift->setValue(0);
1654  _ui->comboBox_freenect2Format->setCurrentIndex(1);
1655  _ui->doubleSpinBox_freenect2MinDepth->setValue(0.3);
1656  _ui->doubleSpinBox_freenect2MaxDepth->setValue(12.0);
1657  _ui->checkBox_freenect2BilateralFiltering->setChecked(true);
1658  _ui->checkBox_freenect2EdgeAwareFiltering->setChecked(true);
1659  _ui->checkBox_freenect2NoiseFiltering->setChecked(true);
1660  _ui->lineEdit_freenect2Pipeline->setText("");
1661  _ui->comboBox_k4w2Format->setCurrentIndex(1);
1662  _ui->comboBox_realsensePresetRGB->setCurrentIndex(0);
1663  _ui->comboBox_realsensePresetDepth->setCurrentIndex(2);
1664  _ui->checkbox_realsenseOdom->setChecked(false);
1665  _ui->checkbox_realsenseDepthScaledToRGBSize->setChecked(false);
1666  _ui->comboBox_realsenseRGBSource->setCurrentIndex(0);
1667  _ui->checkbox_rs2_emitter->setChecked(true);
1668  _ui->checkbox_rs2_irDepth->setChecked(false);
1669  _ui->lineEdit_openniOniPath->clear();
1670  _ui->lineEdit_openni2OniPath->clear();
1671  _ui->lineEdit_cameraRGBDImages_path_rgb->setText("");
1672  _ui->lineEdit_cameraRGBDImages_path_depth->setText("");
1673  _ui->doubleSpinBox_cameraRGBDImages_scale->setValue(1.0);
1674  _ui->spinBox_cameraRGBDImages_startIndex->setValue(0);
1675  _ui->lineEdit_source_distortionModel->setText("");
1676  _ui->groupBox_bilateral->setChecked(false);
1677  _ui->doubleSpinBox_bilateral_sigmaS->setValue(10.0);
1678  _ui->doubleSpinBox_bilateral_sigmaR->setValue(0.1);
1679 
1680  _ui->source_comboBox_image_type->setCurrentIndex(kSrcDC1394-kSrcDC1394);
1681  _ui->lineEdit_cameraStereoImages_path_left->setText("");
1682  _ui->lineEdit_cameraStereoImages_path_right->setText("");
1683  _ui->checkBox_stereo_rectify->setChecked(false);
1684  _ui->spinBox_cameraStereoImages_startIndex->setValue(0);
1685  _ui->lineEdit_cameraStereoVideo_path->setText("");
1686  _ui->lineEdit_cameraStereoVideo_path_2->setText("");
1687  _ui->spinBox_stereo_right_device->setValue(-1);
1688  _ui->comboBox_stereoZed_resolution->setCurrentIndex(2);
1689  _ui->comboBox_stereoZed_quality->setCurrentIndex(1);
1690  _ui->checkbox_stereoZed_selfCalibration->setChecked(true);
1691  _ui->comboBox_stereoZed_sensingMode->setCurrentIndex(0);
1692  _ui->spinBox_stereoZed_confidenceThr->setValue(100);
1693  _ui->checkbox_stereoZed_odom->setChecked(false);
1694  _ui->lineEdit_zedSvoPath->clear();
1695 
1696  _ui->checkBox_cameraImages_timestamps->setChecked(false);
1697  _ui->checkBox_cameraImages_syncTimeStamps->setChecked(true);
1698  _ui->lineEdit_cameraImages_timestamps->setText("");
1699  _ui->lineEdit_cameraImages_path_scans->setText("");
1700  _ui->lineEdit_cameraImages_laser_transform->setText("0 0 0 0 0 0");
1701  _ui->spinBox_cameraImages_max_scan_pts->setValue(0);
1702  _ui->spinBox_cameraImages_scanDownsampleStep->setValue(1);
1703  _ui->doubleSpinBox_cameraImages_scanVoxelSize->setValue(0.0f);
1704  _ui->lineEdit_cameraImages_odom->setText("");
1705  _ui->comboBox_cameraImages_odomFormat->setCurrentIndex(0);
1706  _ui->lineEdit_cameraImages_gt->setText("");
1707  _ui->comboBox_cameraImages_gtFormat->setCurrentIndex(0);
1708  _ui->doubleSpinBox_maxPoseTimeDiff->setValue(0.02);
1709  _ui->lineEdit_cameraImages_path_imu->setText("");
1710  _ui->lineEdit_cameraImages_imu_transform->setText("0 0 1 0 -1 0 1 0 0");
1711  _ui->spinBox_cameraImages_max_imu_rate->setValue(0);
1712 
1713  _ui->groupBox_scanFromDepth->setChecked(false);
1714  _ui->spinBox_cameraScanFromDepth_decimation->setValue(8);
1715  _ui->doubleSpinBox_cameraSCanFromDepth_maxDepth->setValue(4.0);
1716  _ui->doubleSpinBox_cameraImages_scanVoxelSize->setValue(0.025f);
1717  _ui->spinBox_cameraImages_scanNormalsK->setValue(20);
1718  _ui->doubleSpinBox_cameraImages_scanNormalsRadius->setValue(0.0);
1719  _ui->checkBox_cameraImages_scanForceGroundNormalsUp->setChecked(false);
1720 
1721  _ui->groupBox_depthFromScan->setChecked(false);
1722  _ui->groupBox_depthFromScan_fillHoles->setChecked(true);
1723  _ui->radioButton_depthFromScan_vertical->setChecked(true);
1724  _ui->radioButton_depthFromScan_horizontal->setChecked(false);
1725  _ui->checkBox_depthFromScan_fillBorders->setChecked(false);
1726  }
1727  else if(groupBox->objectName() == _ui->groupBox_rtabmap_basic0->objectName())
1728  {
1729  _ui->general_doubleSpinBox_timeThr_2->setValue(Parameters::defaultRtabmapTimeThr());
1730  _ui->general_doubleSpinBox_hardThr_2->setValue(Parameters::defaultRtabmapLoopThr());
1731  _ui->doubleSpinBox_similarityThreshold_2->setValue(Parameters::defaultMemRehearsalSimilarity());
1732  _ui->general_spinBox_imagesBufferSize_2->setValue(Parameters::defaultRtabmapImageBufferSize());
1733  _ui->general_spinBox_maxStMemSize_2->setValue(Parameters::defaultMemSTMSize());
1734  _ui->general_checkBox_publishStats_2->setChecked(Parameters::defaultRtabmapPublishStats());
1735  _ui->general_checkBox_activateRGBD_2->setChecked(Parameters::defaultRGBDEnabled());
1736  _ui->general_checkBox_SLAM_mode_2->setChecked(Parameters::defaultMemIncrementalMemory());
1737  _ui->general_doubleSpinBox_detectionRate_2->setValue(Parameters::defaultRtabmapDetectionRate());
1738  // match the advanced (spin and doubleSpin boxes)
1739  _ui->general_doubleSpinBox_timeThr->setValue(Parameters::defaultRtabmapTimeThr());
1740  _ui->general_doubleSpinBox_hardThr->setValue(Parameters::defaultRtabmapLoopThr());
1741  _ui->doubleSpinBox_similarityThreshold->setValue(Parameters::defaultMemRehearsalSimilarity());
1742  _ui->general_spinBox_imagesBufferSize->setValue(Parameters::defaultRtabmapImageBufferSize());
1743  _ui->general_spinBox_maxStMemSize->setValue(Parameters::defaultMemSTMSize());
1744  _ui->general_doubleSpinBox_detectionRate->setValue(Parameters::defaultRtabmapDetectionRate());
1745  }
1746  else
1747  {
1748  QObjectList children = groupBox->children();
1750  std::string key;
1751  for(int i=0; i<children.size(); ++i)
1752  {
1753  key = children.at(i)->objectName().toStdString();
1754  if(uContains(defaults, key))
1755  {
1756  if(key.compare(Parameters::kRtabmapWorkingDirectory().c_str()) == 0)
1757  {
1758  this->setParameter(key, getDefaultWorkingDirectory().toStdString());
1759  }
1760  else
1761  {
1762  this->setParameter(key, defaults.at(key));
1763  }
1764  if(qobject_cast<const QGroupBox*>(children.at(i)))
1765  {
1766  this->resetSettings((QGroupBox*)children.at(i));
1767  }
1768  }
1769  else if(qobject_cast<const QGroupBox*>(children.at(i)))
1770  {
1771  this->resetSettings((QGroupBox*)children.at(i));
1772  }
1773  else if(qobject_cast<const QStackedWidget*>(children.at(i)))
1774  {
1775  QStackedWidget * stackedWidget = (QStackedWidget*)children.at(i);
1776  for(int j=0; j<stackedWidget->count(); ++j)
1777  {
1778  const QObjectList & children2 = stackedWidget->widget(j)->children();
1779  for(int k=0; k<children2.size(); ++k)
1780  {
1781  if(qobject_cast<QGroupBox *>(children2.at(k)))
1782  {
1783  this->resetSettings((QGroupBox*)children2.at(k));
1784  }
1785  }
1786  }
1787  }
1788  }
1789 
1790  if(groupBox->findChild<QLineEdit*>(_ui->lineEdit_kp_roi->objectName()))
1791  {
1792  this->setupKpRoiPanel();
1793  }
1794 
1795  if(groupBox->objectName() == _ui->groupBox_odometry1->objectName())
1796  {
1797  _ui->odom_registration->setCurrentIndex(3);
1798  }
1799  }
1800 }
1801 
1803 {
1804  QList<QGroupBox*> boxes = this->getGroupBoxes();
1805  if(panelNumber >= 0 && panelNumber < boxes.size())
1806  {
1807  this->resetSettings(boxes.at(panelNumber));
1808  }
1809  else if(panelNumber == -1)
1810  {
1811  for(QList<QGroupBox*>::iterator iter = boxes.begin(); iter!=boxes.end(); ++iter)
1812  {
1813  this->resetSettings(*iter);
1814  }
1815  }
1816  else
1817  {
1818  ULOGGER_WARN("panel number and the number of stacked widget doesn't match");
1819  }
1820 
1821 }
1822 
1824 {
1825  return _ui->lineEdit_workingDirectory->text();
1826 }
1827 
1829 {
1830  QString privatePath = QDir::homePath() + "/.rtabmap";
1831  if(!QDir(privatePath).exists())
1832  {
1833  QDir::home().mkdir(".rtabmap");
1834  }
1835  return privatePath + "/rtabmap.ini";
1836 }
1837 
1839 {
1840  return getIniFilePath()+".tmp";
1841 }
1842 
1844 {
1845  QString path = QFileDialog::getOpenFileName(this, tr("Load settings..."), this->getWorkingDirectory(), "*.ini");
1846  if(!path.isEmpty())
1847  {
1848  this->readSettings(path);
1849  }
1850 }
1851 
1852 void PreferencesDialog::readSettings(const QString & filePath)
1853 {
1854  ULOGGER_DEBUG("%s", filePath.toStdString().c_str());
1855  readGuiSettings(filePath);
1856  readCameraSettings(filePath);
1857  if(!readCoreSettings(filePath))
1858  {
1859  _modifiedParameters.clear();
1861 
1862  // only keep GUI settings
1863  QStandardItem * parentItem = _indexModel->invisibleRootItem();
1864  if(parentItem)
1865  {
1866  for(int i=1; i<parentItem->rowCount(); ++i)
1867  {
1868  parentItem->child(i)->setEnabled(false);
1869  }
1870  }
1871  _ui->radioButton_basic->setEnabled(false);
1872  _ui->radioButton_advanced->setEnabled(false);
1873  }
1874  else
1875  {
1876  // enable settings
1877  QStandardItem * parentItem = _indexModel->invisibleRootItem();
1878  if(parentItem)
1879  {
1880  for(int i=0; i<parentItem->rowCount(); ++i)
1881  {
1882  parentItem->child(i)->setEnabled(true);
1883  }
1884  }
1885  _ui->radioButton_basic->setEnabled(true);
1886  _ui->radioButton_advanced->setEnabled(true);
1887  }
1888 }
1889 
1890 void PreferencesDialog::readGuiSettings(const QString & filePath)
1891 {
1892  QString path = getIniFilePath();
1893  if(!filePath.isEmpty())
1894  {
1895  path = filePath;
1896  }
1897  QSettings settings(path, QSettings::IniFormat);
1898  settings.beginGroup("Gui");
1899  settings.beginGroup("General");
1900  _ui->general_checkBox_imagesKept->setChecked(settings.value("imagesKept", _ui->general_checkBox_imagesKept->isChecked()).toBool());
1901  _ui->general_checkBox_cloudsKept->setChecked(settings.value("cloudsKept", _ui->general_checkBox_cloudsKept->isChecked()).toBool());
1902  _ui->comboBox_loggerLevel->setCurrentIndex(settings.value("loggerLevel", _ui->comboBox_loggerLevel->currentIndex()).toInt());
1903  _ui->comboBox_loggerEventLevel->setCurrentIndex(settings.value("loggerEventLevel", _ui->comboBox_loggerEventLevel->currentIndex()).toInt());
1904  _ui->comboBox_loggerPauseLevel->setCurrentIndex(settings.value("loggerPauseLevel", _ui->comboBox_loggerPauseLevel->currentIndex()).toInt());
1905  _ui->comboBox_loggerType->setCurrentIndex(settings.value("loggerType", _ui->comboBox_loggerType->currentIndex()).toInt());
1906  _ui->checkBox_logger_printTime->setChecked(settings.value("loggerPrintTime", _ui->checkBox_logger_printTime->isChecked()).toBool());
1907  _ui->checkBox_logger_printThreadId->setChecked(settings.value("loggerPrintThreadId", _ui->checkBox_logger_printThreadId->isChecked()).toBool());
1908  _ui->checkBox_verticalLayoutUsed->setChecked(settings.value("verticalLayoutUsed", _ui->checkBox_verticalLayoutUsed->isChecked()).toBool());
1909  _ui->checkBox_imageRejectedShown->setChecked(settings.value("imageRejectedShown", _ui->checkBox_imageRejectedShown->isChecked()).toBool());
1910  _ui->checkBox_imageHighestHypShown->setChecked(settings.value("imageHighestHypShown", _ui->checkBox_imageHighestHypShown->isChecked()).toBool());
1911  _ui->checkBox_beep->setChecked(settings.value("beep", _ui->checkBox_beep->isChecked()).toBool());
1912  _ui->checkBox_stamps->setChecked(settings.value("figure_time", _ui->checkBox_stamps->isChecked()).toBool());
1913  _ui->checkBox_cacheStatistics->setChecked(settings.value("figure_cache", _ui->checkBox_cacheStatistics->isChecked()).toBool());
1914  _ui->checkBox_notifyWhenNewGlobalPathIsReceived->setChecked(settings.value("notifyNewGlobalPath", _ui->checkBox_notifyWhenNewGlobalPathIsReceived->isChecked()).toBool());
1915  _ui->spinBox_odomQualityWarnThr->setValue(settings.value("odomQualityThr", _ui->spinBox_odomQualityWarnThr->value()).toInt());
1916  _ui->checkBox_odom_onlyInliersShown->setChecked(settings.value("odomOnlyInliersShown", _ui->checkBox_odom_onlyInliersShown->isChecked()).toBool());
1917  _ui->radioButton_posteriorGraphView->setChecked(settings.value("posteriorGraphView", _ui->radioButton_posteriorGraphView->isChecked()).toBool());
1918  _ui->radioButton_wordsGraphView->setChecked(settings.value("wordsGraphView", _ui->radioButton_wordsGraphView->isChecked()).toBool());
1919  _ui->radioButton_localizationsGraphView->setChecked(settings.value("localizationsGraphView", _ui->radioButton_localizationsGraphView->isChecked()).toBool());
1920  _ui->radioButton_nochangeGraphView->setChecked(settings.value("nochangeGraphView", _ui->radioButton_nochangeGraphView->isChecked()).toBool());
1921  _ui->checkbox_odomDisabled->setChecked(settings.value("odomDisabled", _ui->checkbox_odomDisabled->isChecked()).toBool());
1922  _ui->odom_registration->setCurrentIndex(settings.value("odomRegistration", _ui->odom_registration->currentIndex()).toInt());
1923  _ui->checkbox_groundTruthAlign->setChecked(settings.value("gtAlign", _ui->checkbox_groundTruthAlign->isChecked()).toBool());
1924 
1925  for(int i=0; i<2; ++i)
1926  {
1927  _3dRenderingShowClouds[i]->setChecked(settings.value(QString("showClouds%1").arg(i), _3dRenderingShowClouds[i]->isChecked()).toBool());
1928  _3dRenderingDecimation[i]->setValue(settings.value(QString("decimation%1").arg(i), _3dRenderingDecimation[i]->value()).toInt());
1929  _3dRenderingMaxDepth[i]->setValue(settings.value(QString("maxDepth%1").arg(i), _3dRenderingMaxDepth[i]->value()).toDouble());
1930  _3dRenderingMinDepth[i]->setValue(settings.value(QString("minDepth%1").arg(i), _3dRenderingMinDepth[i]->value()).toDouble());
1931  _3dRenderingRoiRatios[i]->setText(settings.value(QString("roiRatios%1").arg(i), _3dRenderingRoiRatios[i]->text()).toString());
1932  _3dRenderingShowScans[i]->setChecked(settings.value(QString("showScans%1").arg(i), _3dRenderingShowScans[i]->isChecked()).toBool());
1933  _3dRenderingShowFeatures[i]->setChecked(settings.value(QString("showFeatures%1").arg(i), _3dRenderingShowFeatures[i]->isChecked()).toBool());
1934  _3dRenderingShowFrustums[i]->setChecked(settings.value(QString("showFrustums%1").arg(i), _3dRenderingShowFrustums[i]->isChecked()).toBool());
1935 
1936  _3dRenderingDownsamplingScan[i]->setValue(settings.value(QString("downsamplingScan%1").arg(i), _3dRenderingDownsamplingScan[i]->value()).toInt());
1937  _3dRenderingMaxRange[i]->setValue(settings.value(QString("maxRange%1").arg(i), _3dRenderingMaxRange[i]->value()).toDouble());
1938  _3dRenderingMinRange[i]->setValue(settings.value(QString("minRange%1").arg(i), _3dRenderingMinRange[i]->value()).toDouble());
1939  _3dRenderingVoxelSizeScan[i]->setValue(settings.value(QString("voxelSizeScan%1").arg(i), _3dRenderingVoxelSizeScan[i]->value()).toDouble());
1940  _3dRenderingColorScheme[i]->setValue(settings.value(QString("colorScheme%1").arg(i), _3dRenderingColorScheme[i]->value()).toInt());
1941  _3dRenderingOpacity[i]->setValue(settings.value(QString("opacity%1").arg(i), _3dRenderingOpacity[i]->value()).toDouble());
1942  _3dRenderingPtSize[i]->setValue(settings.value(QString("ptSize%1").arg(i), _3dRenderingPtSize[i]->value()).toInt());
1943  _3dRenderingColorSchemeScan[i]->setValue(settings.value(QString("colorSchemeScan%1").arg(i), _3dRenderingColorSchemeScan[i]->value()).toInt());
1944  _3dRenderingOpacityScan[i]->setValue(settings.value(QString("opacityScan%1").arg(i), _3dRenderingOpacityScan[i]->value()).toDouble());
1945  _3dRenderingPtSizeScan[i]->setValue(settings.value(QString("ptSizeScan%1").arg(i), _3dRenderingPtSizeScan[i]->value()).toInt());
1946  _3dRenderingPtSizeFeatures[i]->setValue(settings.value(QString("ptSizeFeatures%1").arg(i), _3dRenderingPtSizeFeatures[i]->value()).toInt());
1947  }
1948  _ui->doubleSpinBox_voxel->setValue(settings.value("cloudVoxel", _ui->doubleSpinBox_voxel->value()).toDouble());
1949  _ui->doubleSpinBox_noiseRadius->setValue(settings.value("cloudNoiseRadius", _ui->doubleSpinBox_noiseRadius->value()).toDouble());
1950  _ui->spinBox_noiseMinNeighbors->setValue(settings.value("cloudNoiseMinNeighbors", _ui->spinBox_noiseMinNeighbors->value()).toInt());
1951  _ui->doubleSpinBox_ceilingFilterHeight->setValue(settings.value("cloudCeilingHeight", _ui->doubleSpinBox_ceilingFilterHeight->value()).toDouble());
1952  _ui->doubleSpinBox_floorFilterHeight->setValue(settings.value("cloudFloorHeight", _ui->doubleSpinBox_floorFilterHeight->value()).toDouble());
1953  _ui->spinBox_normalKSearch->setValue(settings.value("normalKSearch", _ui->spinBox_normalKSearch->value()).toInt());
1954  _ui->doubleSpinBox_normalRadiusSearch->setValue(settings.value("normalRadiusSearch", _ui->doubleSpinBox_normalRadiusSearch->value()).toDouble());
1955  _ui->doubleSpinBox_ceilingFilterHeight_scan->setValue(settings.value("scanCeilingHeight", _ui->doubleSpinBox_ceilingFilterHeight_scan->value()).toDouble());
1956  _ui->doubleSpinBox_floorFilterHeight_scan->setValue(settings.value("scanFloorHeight", _ui->doubleSpinBox_floorFilterHeight_scan->value()).toDouble());
1957  _ui->spinBox_normalKSearch_scan->setValue(settings.value("scanNormalKSearch", _ui->spinBox_normalKSearch_scan->value()).toInt());
1958  _ui->doubleSpinBox_normalRadiusSearch_scan->setValue(settings.value("scanNormalRadiusSearch", _ui->doubleSpinBox_normalRadiusSearch_scan->value()).toDouble());
1959 
1960  _ui->checkBox_showGraphs->setChecked(settings.value("showGraphs", _ui->checkBox_showGraphs->isChecked()).toBool());
1961  _ui->checkBox_showLabels->setChecked(settings.value("showLabels", _ui->checkBox_showLabels->isChecked()).toBool());
1962 
1963  _ui->radioButton_noFiltering->setChecked(settings.value("noFiltering", _ui->radioButton_noFiltering->isChecked()).toBool());
1964  _ui->radioButton_nodeFiltering->setChecked(settings.value("cloudFiltering", _ui->radioButton_nodeFiltering->isChecked()).toBool());
1965  _ui->doubleSpinBox_cloudFilterRadius->setValue(settings.value("cloudFilteringRadius", _ui->doubleSpinBox_cloudFilterRadius->value()).toDouble());
1966  _ui->doubleSpinBox_cloudFilterAngle->setValue(settings.value("cloudFilteringAngle", _ui->doubleSpinBox_cloudFilterAngle->value()).toDouble());
1967  _ui->radioButton_subtractFiltering->setChecked(settings.value("subtractFiltering", _ui->radioButton_subtractFiltering->isChecked()).toBool());
1968  _ui->spinBox_subtractFilteringMinPts->setValue(settings.value("subtractFilteringMinPts", _ui->spinBox_subtractFilteringMinPts->value()).toInt());
1969  _ui->doubleSpinBox_subtractFilteringRadius->setValue(settings.value("subtractFilteringRadius", _ui->doubleSpinBox_subtractFilteringRadius->value()).toDouble());
1970  _ui->doubleSpinBox_subtractFilteringAngle->setValue(settings.value("subtractFilteringAngle", _ui->doubleSpinBox_subtractFilteringAngle->value()).toDouble());
1971 
1972  _ui->checkBox_map_shown->setChecked(settings.value("gridMapShown", _ui->checkBox_map_shown->isChecked()).toBool());
1973  _ui->doubleSpinBox_map_opacity->setValue(settings.value("gridMapOpacity", _ui->doubleSpinBox_map_opacity->value()).toDouble());
1974 
1975  _ui->groupBox_octomap->setChecked(settings.value("octomap", _ui->groupBox_octomap->isChecked()).toBool());
1976  _ui->spinBox_octomap_treeDepth->setValue(settings.value("octomap_depth", _ui->spinBox_octomap_treeDepth->value()).toInt());
1977  _ui->checkBox_octomap_2dgrid->setChecked(settings.value("octomap_2dgrid", _ui->checkBox_octomap_2dgrid->isChecked()).toBool());
1978  _ui->checkBox_octomap_show3dMap->setChecked(settings.value("octomap_3dmap", _ui->checkBox_octomap_show3dMap->isChecked()).toBool());
1979  _ui->comboBox_octomap_renderingType->setCurrentIndex(settings.value("octomap_rendering_type", _ui->comboBox_octomap_renderingType->currentIndex()).toInt());
1980  _ui->spinBox_octomap_pointSize->setValue(settings.value("octomap_point_size", _ui->spinBox_octomap_pointSize->value()).toInt());
1981 
1982  _ui->groupBox_organized->setChecked(settings.value("meshing", _ui->groupBox_organized->isChecked()).toBool());
1983  _ui->doubleSpinBox_mesh_angleTolerance->setValue(settings.value("meshing_angle", _ui->doubleSpinBox_mesh_angleTolerance->value()).toDouble());
1984  _ui->checkBox_mesh_quad->setChecked(settings.value("meshing_quad", _ui->checkBox_mesh_quad->isChecked()).toBool());
1985  _ui->checkBox_mesh_texture->setChecked(settings.value("meshing_texture", _ui->checkBox_mesh_texture->isChecked()).toBool());
1986  _ui->spinBox_mesh_triangleSize->setValue(settings.value("meshing_triangle_size", _ui->spinBox_mesh_triangleSize->value()).toInt());
1987 
1988  settings.endGroup(); // General
1989 
1990  settings.endGroup(); // rtabmap
1991 }
1992 
1993 void PreferencesDialog::readCameraSettings(const QString & filePath)
1994 {
1995  QString path = getIniFilePath();
1996  if(!filePath.isEmpty())
1997  {
1998  path = filePath;
1999  }
2000  QSettings settings(path, QSettings::IniFormat);
2001 
2002  settings.beginGroup("Camera");
2003  _ui->general_doubleSpinBox_imgRate->setValue(settings.value("imgRate", _ui->general_doubleSpinBox_imgRate->value()).toDouble());
2004  _ui->source_mirroring->setChecked(settings.value("mirroring", _ui->source_mirroring->isChecked()).toBool());
2005  _ui->lineEdit_calibrationFile->setText(settings.value("calibrationName", _ui->lineEdit_calibrationFile->text()).toString());
2006  _ui->comboBox_sourceType->setCurrentIndex(settings.value("type", _ui->comboBox_sourceType->currentIndex()).toInt());
2007  _ui->lineEdit_sourceDevice->setText(settings.value("device",_ui->lineEdit_sourceDevice->text()).toString());
2008  _ui->lineEdit_sourceLocalTransform->setText(settings.value("localTransform",_ui->lineEdit_sourceLocalTransform->text()).toString());
2009  _ui->spinBox_source_imageDecimation->setValue(settings.value("imageDecimation",_ui->spinBox_source_imageDecimation->value()).toInt());
2010 
2011  settings.beginGroup("rgbd");
2012  _ui->comboBox_cameraRGBD->setCurrentIndex(settings.value("driver", _ui->comboBox_cameraRGBD->currentIndex()).toInt());
2013  _ui->checkbox_rgbd_colorOnly->setChecked(settings.value("rgbdColorOnly", _ui->checkbox_rgbd_colorOnly->isChecked()).toBool());
2014  _ui->lineEdit_source_distortionModel->setText(settings.value("distortion_model", _ui->lineEdit_source_distortionModel->text()).toString());
2015  _ui->groupBox_bilateral->setChecked(settings.value("bilateral", _ui->groupBox_bilateral->isChecked()).toBool());
2016  _ui->doubleSpinBox_bilateral_sigmaS->setValue(settings.value("bilateral_sigma_s", _ui->doubleSpinBox_bilateral_sigmaS->value()).toDouble());
2017  _ui->doubleSpinBox_bilateral_sigmaR->setValue(settings.value("bilateral_sigma_r", _ui->doubleSpinBox_bilateral_sigmaR->value()).toDouble());
2018  settings.endGroup(); // rgbd
2019 
2020  settings.beginGroup("stereo");
2021  _ui->comboBox_cameraStereo->setCurrentIndex(settings.value("driver", _ui->comboBox_cameraStereo->currentIndex()).toInt());
2022  _ui->checkbox_stereo_depthGenerated->setChecked(settings.value("depthGenerated", _ui->checkbox_stereo_depthGenerated->isChecked()).toBool());
2023  _ui->checkBox_stereo_exposureCompensation->setChecked(settings.value("exposureCompensation", _ui->checkBox_stereo_exposureCompensation->isChecked()).toBool());
2024  settings.endGroup(); // stereo
2025 
2026  settings.beginGroup("rgb");
2027  _ui->source_comboBox_image_type->setCurrentIndex(settings.value("driver", _ui->source_comboBox_image_type->currentIndex()).toInt());
2028  _ui->checkBox_rgb_rectify->setChecked(settings.value("rectify",_ui->checkBox_rgb_rectify->isChecked()).toBool());
2029  settings.endGroup(); // rgb
2030 
2031  settings.beginGroup("Openni");
2032  _ui->lineEdit_openniOniPath->setText(settings.value("oniPath", _ui->lineEdit_openniOniPath->text()).toString());
2033  settings.endGroup(); // Openni
2034 
2035  settings.beginGroup("Openni2");
2036  _ui->openni2_autoWhiteBalance->setChecked(settings.value("autoWhiteBalance", _ui->openni2_autoWhiteBalance->isChecked()).toBool());
2037  _ui->openni2_autoExposure->setChecked(settings.value("autoExposure", _ui->openni2_autoExposure->isChecked()).toBool());
2038  _ui->openni2_exposure->setValue(settings.value("exposure", _ui->openni2_exposure->value()).toInt());
2039  _ui->openni2_gain->setValue(settings.value("gain", _ui->openni2_gain->value()).toInt());
2040  _ui->openni2_mirroring->setChecked(settings.value("mirroring", _ui->openni2_mirroring->isChecked()).toBool());
2041  _ui->openni2_stampsIdsUsed->setChecked(settings.value("stampsIdsUsed", _ui->openni2_stampsIdsUsed->isChecked()).toBool());
2042  _ui->lineEdit_openni2OniPath->setText(settings.value("oniPath", _ui->lineEdit_openni2OniPath->text()).toString());
2043  _ui->openni2_hshift->setValue(settings.value("hshift", _ui->openni2_hshift->value()).toInt());
2044  _ui->openni2_vshift->setValue(settings.value("vshift", _ui->openni2_vshift->value()).toInt());
2045  settings.endGroup(); // Openni2
2046 
2047  settings.beginGroup("Freenect2");
2048  _ui->comboBox_freenect2Format->setCurrentIndex(settings.value("format", _ui->comboBox_freenect2Format->currentIndex()).toInt());
2049  _ui->doubleSpinBox_freenect2MinDepth->setValue(settings.value("minDepth", _ui->doubleSpinBox_freenect2MinDepth->value()).toDouble());
2050  _ui->doubleSpinBox_freenect2MaxDepth->setValue(settings.value("maxDepth", _ui->doubleSpinBox_freenect2MaxDepth->value()).toDouble());
2051  _ui->checkBox_freenect2BilateralFiltering->setChecked(settings.value("bilateralFiltering", _ui->checkBox_freenect2BilateralFiltering->isChecked()).toBool());
2052  _ui->checkBox_freenect2EdgeAwareFiltering->setChecked(settings.value("edgeAwareFiltering", _ui->checkBox_freenect2EdgeAwareFiltering->isChecked()).toBool());
2053  _ui->checkBox_freenect2NoiseFiltering->setChecked(settings.value("noiseFiltering", _ui->checkBox_freenect2NoiseFiltering->isChecked()).toBool());
2054  _ui->lineEdit_freenect2Pipeline->setText(settings.value("pipeline", _ui->lineEdit_freenect2Pipeline->text()).toString());
2055  settings.endGroup(); // Freenect2
2056 
2057  settings.beginGroup("K4W2");
2058  _ui->comboBox_k4w2Format->setCurrentIndex(settings.value("format", _ui->comboBox_k4w2Format->currentIndex()).toInt());
2059  settings.endGroup(); // K4W2
2060 
2061  settings.beginGroup("RealSense");
2062  _ui->comboBox_realsensePresetRGB->setCurrentIndex(settings.value("presetRGB", _ui->comboBox_realsensePresetRGB->currentIndex()).toInt());
2063  _ui->comboBox_realsensePresetDepth->setCurrentIndex(settings.value("presetDepth", _ui->comboBox_realsensePresetDepth->currentIndex()).toInt());
2064  _ui->checkbox_realsenseOdom->setChecked(settings.value("odom", _ui->checkbox_realsenseOdom->isChecked()).toBool());
2065  _ui->checkbox_realsenseDepthScaledToRGBSize->setChecked(settings.value("depthScaled", _ui->checkbox_realsenseDepthScaledToRGBSize->isChecked()).toBool());
2066  _ui->comboBox_realsenseRGBSource->setCurrentIndex(settings.value("rgbSource", _ui->comboBox_realsenseRGBSource->currentIndex()).toInt());
2067  settings.endGroup(); // RealSense
2068 
2069  settings.beginGroup("RealSense2");
2070  _ui->checkbox_rs2_emitter->setChecked(settings.value("emitter", _ui->checkbox_rs2_emitter->isChecked()).toBool());
2071  _ui->checkbox_rs2_irDepth->setChecked(settings.value("irdepth", _ui->checkbox_rs2_irDepth->isChecked()).toBool());
2072  settings.endGroup(); // RealSense
2073 
2074  settings.beginGroup("RGBDImages");
2075  _ui->lineEdit_cameraRGBDImages_path_rgb->setText(settings.value("path_rgb", _ui->lineEdit_cameraRGBDImages_path_rgb->text()).toString());
2076  _ui->lineEdit_cameraRGBDImages_path_depth->setText(settings.value("path_depth", _ui->lineEdit_cameraRGBDImages_path_depth->text()).toString());
2077  _ui->doubleSpinBox_cameraRGBDImages_scale->setValue(settings.value("scale", _ui->doubleSpinBox_cameraRGBDImages_scale->value()).toDouble());
2078  _ui->spinBox_cameraRGBDImages_startIndex->setValue(settings.value("start_index", _ui->spinBox_cameraRGBDImages_startIndex->value()).toInt());
2079  settings.endGroup(); // RGBDImages
2080 
2081  settings.beginGroup("StereoImages");
2082  _ui->lineEdit_cameraStereoImages_path_left->setText(settings.value("path_left", _ui->lineEdit_cameraStereoImages_path_left->text()).toString());
2083  _ui->lineEdit_cameraStereoImages_path_right->setText(settings.value("path_right", _ui->lineEdit_cameraStereoImages_path_right->text()).toString());
2084  _ui->checkBox_stereo_rectify->setChecked(settings.value("rectify",_ui->checkBox_stereo_rectify->isChecked()).toBool());
2085  _ui->spinBox_cameraStereoImages_startIndex->setValue(settings.value("start_index",_ui->spinBox_cameraStereoImages_startIndex->value()).toInt());
2086  settings.endGroup(); // StereoImages
2087 
2088  settings.beginGroup("StereoVideo");
2089  _ui->lineEdit_cameraStereoVideo_path->setText(settings.value("path", _ui->lineEdit_cameraStereoVideo_path->text()).toString());
2090  _ui->lineEdit_cameraStereoVideo_path_2->setText(settings.value("path2", _ui->lineEdit_cameraStereoVideo_path_2->text()).toString());
2091  _ui->spinBox_stereo_right_device->setValue(settings.value("device2", _ui->spinBox_stereo_right_device->value()).toInt());
2092  settings.endGroup(); // StereoVideo
2093 
2094  settings.beginGroup("StereoZed");
2095  _ui->comboBox_stereoZed_resolution->setCurrentIndex(settings.value("resolution", _ui->comboBox_stereoZed_resolution->currentIndex()).toInt());
2096  _ui->comboBox_stereoZed_quality->setCurrentIndex(settings.value("quality", _ui->comboBox_stereoZed_quality->currentIndex()).toInt());
2097  _ui->checkbox_stereoZed_selfCalibration->setChecked(settings.value("self_calibration", _ui->checkbox_stereoZed_selfCalibration->isChecked()).toBool());
2098  _ui->comboBox_stereoZed_sensingMode->setCurrentIndex(settings.value("sensing_mode", _ui->comboBox_stereoZed_sensingMode->currentIndex()).toInt());
2099  _ui->spinBox_stereoZed_confidenceThr->setValue(settings.value("confidence_thr", _ui->spinBox_stereoZed_confidenceThr->value()).toInt());
2100  _ui->checkbox_stereoZed_odom->setChecked(settings.value("odom", _ui->checkbox_stereoZed_odom->isChecked()).toBool());
2101  _ui->lineEdit_zedSvoPath->setText(settings.value("svo_path", _ui->lineEdit_zedSvoPath->text()).toString());
2102  settings.endGroup(); // StereoZed
2103 
2104 
2105  settings.beginGroup("Images");
2106  _ui->source_images_lineEdit_path->setText(settings.value("path", _ui->source_images_lineEdit_path->text()).toString());
2107  _ui->source_images_spinBox_startPos->setValue(settings.value("startPos",_ui->source_images_spinBox_startPos->value()).toInt());
2108  _ui->comboBox_cameraImages_bayerMode->setCurrentIndex(settings.value("bayerMode",_ui->comboBox_cameraImages_bayerMode->currentIndex()).toInt());
2109 
2110  _ui->checkBox_cameraImages_timestamps->setChecked(settings.value("filenames_as_stamps",_ui->checkBox_cameraImages_timestamps->isChecked()).toBool());
2111  _ui->checkBox_cameraImages_syncTimeStamps->setChecked(settings.value("sync_stamps",_ui->checkBox_cameraImages_syncTimeStamps->isChecked()).toBool());
2112  _ui->lineEdit_cameraImages_timestamps->setText(settings.value("stamps", _ui->lineEdit_cameraImages_timestamps->text()).toString());
2113  _ui->lineEdit_cameraImages_path_scans->setText(settings.value("path_scans", _ui->lineEdit_cameraImages_path_scans->text()).toString());
2114  _ui->lineEdit_cameraImages_laser_transform->setText(settings.value("scan_transform", _ui->lineEdit_cameraImages_laser_transform->text()).toString());
2115  _ui->spinBox_cameraImages_max_scan_pts->setValue(settings.value("scan_max_pts", _ui->spinBox_cameraImages_max_scan_pts->value()).toInt());
2116  _ui->spinBox_cameraImages_scanDownsampleStep->setValue(settings.value("scan_downsample_step", _ui->spinBox_cameraImages_scanDownsampleStep->value()).toInt());
2117  _ui->doubleSpinBox_cameraImages_scanVoxelSize->setValue(settings.value("scan_voxel_size", _ui->doubleSpinBox_cameraImages_scanVoxelSize->value()).toDouble());
2118  _ui->lineEdit_cameraImages_odom->setText(settings.value("odom_path", _ui->lineEdit_cameraImages_odom->text()).toString());
2119  _ui->comboBox_cameraImages_odomFormat->setCurrentIndex(settings.value("odom_format", _ui->comboBox_cameraImages_odomFormat->currentIndex()).toInt());
2120  _ui->lineEdit_cameraImages_gt->setText(settings.value("gt_path", _ui->lineEdit_cameraImages_gt->text()).toString());
2121  _ui->comboBox_cameraImages_gtFormat->setCurrentIndex(settings.value("gt_format", _ui->comboBox_cameraImages_gtFormat->currentIndex()).toInt());
2122  _ui->doubleSpinBox_maxPoseTimeDiff->setValue(settings.value("max_pose_time_diff", _ui->doubleSpinBox_maxPoseTimeDiff->value()).toDouble());
2123 
2124  _ui->lineEdit_cameraImages_path_imu->setText(settings.value("imu_path", _ui->lineEdit_cameraImages_path_imu->text()).toString());
2125  _ui->lineEdit_cameraImages_imu_transform->setText(settings.value("imu_local_transform", _ui->lineEdit_cameraImages_imu_transform->text()).toString());
2126  _ui->spinBox_cameraImages_max_imu_rate->setValue(settings.value("imu_rate", _ui->spinBox_cameraImages_max_imu_rate->value()).toInt());
2127  settings.endGroup(); // images
2128 
2129  settings.beginGroup("Video");
2130  _ui->source_video_lineEdit_path->setText(settings.value("path", _ui->source_video_lineEdit_path->text()).toString());
2131  settings.endGroup(); // video
2132 
2133  settings.beginGroup("ScanFromDepth");
2134  _ui->groupBox_scanFromDepth->setChecked(settings.value("enabled", _ui->groupBox_scanFromDepth->isChecked()).toBool());
2135  _ui->spinBox_cameraScanFromDepth_decimation->setValue(settings.value("decimation", _ui->spinBox_cameraScanFromDepth_decimation->value()).toInt());
2136  _ui->doubleSpinBox_cameraSCanFromDepth_maxDepth->setValue(settings.value("maxDepth", _ui->doubleSpinBox_cameraSCanFromDepth_maxDepth->value()).toDouble());
2137  _ui->doubleSpinBox_cameraImages_scanVoxelSize->setValue(settings.value("voxelSize", _ui->doubleSpinBox_cameraImages_scanVoxelSize->value()).toDouble());
2138  _ui->spinBox_cameraImages_scanNormalsK->setValue(settings.value("normalsK", _ui->spinBox_cameraImages_scanNormalsK->value()).toInt());
2139  _ui->doubleSpinBox_cameraImages_scanNormalsRadius->setValue(settings.value("normalsRadius", _ui->doubleSpinBox_cameraImages_scanNormalsRadius->value()).toDouble());
2140  _ui->checkBox_cameraImages_scanForceGroundNormalsUp->setChecked(settings.value("normalsUp", _ui->checkBox_cameraImages_scanForceGroundNormalsUp->isChecked()).toBool());
2141 
2142  settings.endGroup();//ScanFromDepth
2143 
2144  settings.beginGroup("DepthFromScan");
2145  _ui->groupBox_depthFromScan->setChecked(settings.value("depthFromScan", _ui->groupBox_depthFromScan->isChecked()).toBool());
2146  _ui->groupBox_depthFromScan_fillHoles->setChecked(settings.value("depthFromScanFillHoles", _ui->groupBox_depthFromScan_fillHoles->isChecked()).toBool());
2147  _ui->radioButton_depthFromScan_vertical->setChecked(settings.value("depthFromScanVertical", _ui->radioButton_depthFromScan_vertical->isChecked()).toBool());
2148  _ui->radioButton_depthFromScan_horizontal->setChecked(settings.value("depthFromScanHorizontal", _ui->radioButton_depthFromScan_horizontal->isChecked()).toBool());
2149  _ui->checkBox_depthFromScan_fillBorders->setChecked(settings.value("depthFromScanFillBorders", _ui->checkBox_depthFromScan_fillBorders->isChecked()).toBool());
2150  settings.endGroup();
2151 
2152  settings.beginGroup("Database");
2153  _ui->source_database_lineEdit_path->setText(settings.value("path",_ui->source_database_lineEdit_path->text()).toString());
2154  _ui->source_checkBox_ignoreOdometry->setChecked(settings.value("ignoreOdometry", _ui->source_checkBox_ignoreOdometry->isChecked()).toBool());
2155  _ui->source_checkBox_ignoreGoalDelay->setChecked(settings.value("ignoreGoalDelay", _ui->source_checkBox_ignoreGoalDelay->isChecked()).toBool());
2156  _ui->source_checkBox_ignoreGoals->setChecked(settings.value("ignoreGoals", _ui->source_checkBox_ignoreGoals->isChecked()).toBool());
2157  _ui->source_spinBox_databaseStartPos->setValue(settings.value("startPos", _ui->source_spinBox_databaseStartPos->value()).toInt());
2158  _ui->source_spinBox_database_cameraIndex->setValue(settings.value("cameraIndex", _ui->source_spinBox_database_cameraIndex->value()).toInt());
2159  _ui->source_checkBox_useDbStamps->setChecked(settings.value("useDatabaseStamps", _ui->source_checkBox_useDbStamps->isChecked()).toBool());
2160  settings.endGroup(); // Database
2161 
2162  settings.endGroup(); // Camera
2163 
2164  _calibrationDialog->loadSettings(settings, "CalibrationDialog");
2165 
2166 }
2167 
2169 {
2171 }
2172 
2173 bool PreferencesDialog::readCoreSettings(const QString & filePath)
2174 {
2175  QString path = getIniFilePath();
2176  if(!filePath.isEmpty())
2177  {
2178  path = filePath;
2179  }
2180 
2181  UDEBUG("%s", path.toStdString().c_str());
2182 
2183  if(!QFile::exists(path))
2184  {
2185  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));
2186  }
2187 
2188  ParametersMap parameters;
2189  Parameters::readINI(path.toStdString(), parameters);
2190 
2191  for(rtabmap::ParametersMap::const_iterator iter = parameters.begin(); iter!=parameters.end(); ++iter)
2192  {
2193  std::string value = iter->second;
2194  if(iter->first.compare(Parameters::kRtabmapWorkingDirectory()) == 0)
2195  {
2196  // The directory should exist if not the default one
2197  if(!QDir(value.c_str()).exists() && value.compare(getDefaultWorkingDirectory().toStdString()) != 0)
2198  {
2199  if(QDir(this->getWorkingDirectory().toStdString().c_str()).exists())
2200  {
2201  UWARN("Reading config: Not existing working directory \"%s\". Keeping old one (\"%s\").",
2202  value.c_str(),
2203  this->getWorkingDirectory().toStdString().c_str());
2204  value = this->getWorkingDirectory().toStdString();
2205  }
2206  else
2207  {
2208  std::string defaultWorkingDir = getDefaultWorkingDirectory().toStdString();
2209  UWARN("Reading config: Not existing working directory \"%s\". Using default one (\"%s\").",
2210  value.c_str(),
2211  defaultWorkingDir.c_str());
2212  value = defaultWorkingDir;
2213  }
2214  }
2215  }
2216  this->setParameter(iter->first, value);
2217  }
2218 
2219  // Add information about the working directory if not in the config file
2220  if(parameters.find(Parameters::kRtabmapWorkingDirectory()) == parameters.end())
2221  {
2222  if(!_initialized)
2223  {
2224  QMessageBox::information(this,
2225  tr("Working directory"),
2226  tr("RTAB-Map needs a working directory to put the database.\n\n"
2227  "By default, the directory \"%1\" is used.\n\n"
2228  "The working directory can be changed any time in the "
2229  "preferences menu.").arg(getDefaultWorkingDirectory()));
2230  }
2231  this->setParameter(Parameters::kRtabmapWorkingDirectory(), getDefaultWorkingDirectory().toStdString());
2232  UDEBUG("key.toStdString()=%s", getDefaultWorkingDirectory().toStdString().c_str());
2233  }
2234 
2235  return true;
2236 }
2237 
2239 {
2240  QString path = QFileDialog::getSaveFileName(this, tr("Save settings..."), this->getWorkingDirectory()+QDir::separator()+"config.ini", "*.ini");
2241  if(!path.isEmpty())
2242  {
2243  writeGuiSettings(path);
2244  writeCameraSettings(path);
2245  writeCoreSettings(path);
2246  return true;
2247  }
2248  return false;
2249 }
2250 
2252 {
2253  int button = QMessageBox::warning(this,
2254  tr("Reset settings..."),
2255  tr("This will reset all settings. Restore all settings to default without saving them first?"),
2256  QMessageBox::Cancel | QMessageBox::Yes | QMessageBox::Save,
2257  QMessageBox::Cancel);
2258  if(button == QMessageBox::Yes ||
2259  (button == QMessageBox::Save && saveConfigTo()))
2260  {
2261  this->resetSettings(-1);
2262 
2264  }
2265 }
2266 
2267 void PreferencesDialog::writeSettings(const QString & filePath)
2268 {
2269  writeGuiSettings(filePath);
2270  writeCameraSettings(filePath);
2271  writeCoreSettings(filePath);
2272 
2273  UDEBUG("_obsoletePanels=%d modified parameters=%d", (int)_obsoletePanels, (int)_modifiedParameters.size());
2274 
2275  if(_modifiedParameters.size())
2276  {
2278  }
2279 
2280  if(_obsoletePanels)
2281  {
2282  Q_EMIT settingsChanged(_obsoletePanels);
2283  }
2284 
2285  for(ParametersMap::iterator iter = _modifiedParameters.begin(); iter!=_modifiedParameters.end(); ++iter)
2286  {
2287  if (_parameters.at(iter->first).compare(iter->second) != 0)
2288  {
2289  bool different = true;
2290  if (Parameters::getType(iter->first).compare("double") == 0 ||
2291  Parameters::getType(iter->first).compare("float") == 0)
2292  {
2293  if (uStr2Double(_parameters.at(iter->first)) == uStr2Double(iter->second))
2294  {
2295  different = false;
2296  }
2297  }
2298  if (different)
2299  {
2300  UINFO("modified %s = %s->%s", iter->first.c_str(), _parameters.at(iter->first).c_str(), iter->second.c_str());
2301  }
2302  }
2303  }
2304 
2305  uInsert(_parameters, _modifiedParameters); // update cached parameters
2306  _modifiedParameters.clear();
2307  _obsoletePanels = kPanelDummy;
2308 }
2309 
2310 void PreferencesDialog::writeGuiSettings(const QString & filePath) const
2311 {
2312  QString path = getIniFilePath();
2313  if(!filePath.isEmpty())
2314  {
2315  path = filePath;
2316  }
2317  QSettings settings(path, QSettings::IniFormat);
2318  settings.beginGroup("Gui");
2319 
2320  settings.beginGroup("General");
2321  settings.remove("");
2322  settings.setValue("imagesKept", _ui->general_checkBox_imagesKept->isChecked());
2323  settings.setValue("cloudsKept", _ui->general_checkBox_cloudsKept->isChecked());
2324  settings.setValue("loggerLevel", _ui->comboBox_loggerLevel->currentIndex());
2325  settings.setValue("loggerEventLevel", _ui->comboBox_loggerEventLevel->currentIndex());
2326  settings.setValue("loggerPauseLevel", _ui->comboBox_loggerPauseLevel->currentIndex());
2327  settings.setValue("loggerType", _ui->comboBox_loggerType->currentIndex());
2328  settings.setValue("loggerPrintTime", _ui->checkBox_logger_printTime->isChecked());
2329  settings.setValue("loggerPrintThreadId", _ui->checkBox_logger_printThreadId->isChecked());
2330  settings.setValue("verticalLayoutUsed", _ui->checkBox_verticalLayoutUsed->isChecked());
2331  settings.setValue("imageRejectedShown", _ui->checkBox_imageRejectedShown->isChecked());
2332  settings.setValue("imageHighestHypShown", _ui->checkBox_imageHighestHypShown->isChecked());
2333  settings.setValue("beep", _ui->checkBox_beep->isChecked());
2334  settings.setValue("figure_time", _ui->checkBox_stamps->isChecked());
2335  settings.setValue("figure_cache", _ui->checkBox_cacheStatistics->isChecked());
2336  settings.setValue("notifyNewGlobalPath", _ui->checkBox_notifyWhenNewGlobalPathIsReceived->isChecked());
2337  settings.setValue("odomQualityThr", _ui->spinBox_odomQualityWarnThr->value());
2338  settings.setValue("odomOnlyInliersShown", _ui->checkBox_odom_onlyInliersShown->isChecked());
2339  settings.setValue("posteriorGraphView", _ui->radioButton_posteriorGraphView->isChecked());
2340  settings.setValue("wordsGraphView", _ui->radioButton_wordsGraphView->isChecked());
2341  settings.setValue("localizationsGraphView", _ui->radioButton_localizationsGraphView->isChecked());
2342  settings.setValue("nochangeGraphView", _ui->radioButton_nochangeGraphView->isChecked());
2343  settings.setValue("odomDisabled", _ui->checkbox_odomDisabled->isChecked());
2344  settings.setValue("odomRegistration", _ui->odom_registration->currentIndex());
2345  settings.setValue("gtAlign", _ui->checkbox_groundTruthAlign->isChecked());
2346 
2347  for(int i=0; i<2; ++i)
2348  {
2349  settings.setValue(QString("showClouds%1").arg(i), _3dRenderingShowClouds[i]->isChecked());
2350  settings.setValue(QString("decimation%1").arg(i), _3dRenderingDecimation[i]->value());
2351  settings.setValue(QString("maxDepth%1").arg(i), _3dRenderingMaxDepth[i]->value());
2352  settings.setValue(QString("minDepth%1").arg(i), _3dRenderingMinDepth[i]->value());
2353  settings.setValue(QString("roiRatios%1").arg(i), _3dRenderingRoiRatios[i]->text());
2354  settings.setValue(QString("showScans%1").arg(i), _3dRenderingShowScans[i]->isChecked());
2355  settings.setValue(QString("showFeatures%1").arg(i), _3dRenderingShowFeatures[i]->isChecked());
2356  settings.setValue(QString("showFrustums%1").arg(i), _3dRenderingShowFrustums[i]->isChecked());
2357 
2358  settings.setValue(QString("downsamplingScan%1").arg(i), _3dRenderingDownsamplingScan[i]->value());
2359  settings.setValue(QString("maxRange%1").arg(i), _3dRenderingMaxRange[i]->value());
2360  settings.setValue(QString("minRange%1").arg(i), _3dRenderingMinRange[i]->value());
2361  settings.setValue(QString("voxelSizeScan%1").arg(i), _3dRenderingVoxelSizeScan[i]->value());
2362  settings.setValue(QString("colorScheme%1").arg(i), _3dRenderingColorScheme[i]->value());
2363  settings.setValue(QString("opacity%1").arg(i), _3dRenderingOpacity[i]->value());
2364  settings.setValue(QString("ptSize%1").arg(i), _3dRenderingPtSize[i]->value());
2365  settings.setValue(QString("colorSchemeScan%1").arg(i), _3dRenderingColorSchemeScan[i]->value());
2366  settings.setValue(QString("opacityScan%1").arg(i), _3dRenderingOpacityScan[i]->value());
2367  settings.setValue(QString("ptSizeScan%1").arg(i), _3dRenderingPtSizeScan[i]->value());
2368  settings.setValue(QString("ptSizeFeatures%1").arg(i), _3dRenderingPtSizeFeatures[i]->value());
2369  }
2370  settings.setValue("cloudVoxel", _ui->doubleSpinBox_voxel->value());
2371  settings.setValue("cloudNoiseRadius", _ui->doubleSpinBox_noiseRadius->value());
2372  settings.setValue("cloudNoiseMinNeighbors", _ui->spinBox_noiseMinNeighbors->value());
2373  settings.setValue("cloudCeilingHeight", _ui->doubleSpinBox_ceilingFilterHeight->value());
2374  settings.setValue("cloudFloorHeight", _ui->doubleSpinBox_floorFilterHeight->value());
2375  settings.setValue("normalKSearch", _ui->spinBox_normalKSearch->value());
2376  settings.setValue("normalRadiusSearch", _ui->doubleSpinBox_normalRadiusSearch->value());
2377  settings.setValue("scanCeilingHeight", _ui->doubleSpinBox_ceilingFilterHeight_scan->value());
2378  settings.setValue("scanFloorHeight", _ui->doubleSpinBox_floorFilterHeight_scan->value());
2379  settings.setValue("scanNormalKSearch", _ui->spinBox_normalKSearch_scan->value());
2380  settings.setValue("scanNormalRadiusSearch", _ui->doubleSpinBox_normalRadiusSearch_scan->value());
2381 
2382  settings.setValue("showGraphs", _ui->checkBox_showGraphs->isChecked());
2383  settings.setValue("showLabels", _ui->checkBox_showLabels->isChecked());
2384 
2385  settings.setValue("noFiltering", _ui->radioButton_noFiltering->isChecked());
2386  settings.setValue("cloudFiltering", _ui->radioButton_nodeFiltering->isChecked());
2387  settings.setValue("cloudFilteringRadius", _ui->doubleSpinBox_cloudFilterRadius->value());
2388  settings.setValue("cloudFilteringAngle", _ui->doubleSpinBox_cloudFilterAngle->value());
2389  settings.setValue("subtractFiltering", _ui->radioButton_subtractFiltering->isChecked());
2390  settings.setValue("subtractFilteringMinPts", _ui->spinBox_subtractFilteringMinPts->value());
2391  settings.setValue("subtractFilteringRadius", _ui->doubleSpinBox_subtractFilteringRadius->value());
2392  settings.setValue("subtractFilteringAngle", _ui->doubleSpinBox_subtractFilteringAngle->value());
2393 
2394  settings.setValue("gridMapShown", _ui->checkBox_map_shown->isChecked());
2395  settings.setValue("gridMapOpacity", _ui->doubleSpinBox_map_opacity->value());
2396 
2397  settings.setValue("octomap", _ui->groupBox_octomap->isChecked());
2398  settings.setValue("octomap_depth", _ui->spinBox_octomap_treeDepth->value());
2399  settings.setValue("octomap_2dgrid", _ui->checkBox_octomap_2dgrid->isChecked());
2400  settings.setValue("octomap_3dmap", _ui->checkBox_octomap_show3dMap->isChecked());
2401  settings.setValue("octomap_rendering_type", _ui->comboBox_octomap_renderingType->currentIndex());
2402  settings.setValue("octomap_point_size", _ui->spinBox_octomap_pointSize->value());
2403 
2404 
2405  settings.setValue("meshing", _ui->groupBox_organized->isChecked());
2406  settings.setValue("meshing_angle", _ui->doubleSpinBox_mesh_angleTolerance->value());
2407  settings.setValue("meshing_quad", _ui->checkBox_mesh_quad->isChecked());
2408  settings.setValue("meshing_texture", _ui->checkBox_mesh_texture->isChecked());
2409  settings.setValue("meshing_triangle_size", _ui->spinBox_mesh_triangleSize->value());
2410 
2411  settings.endGroup(); // General
2412 
2413  settings.endGroup(); // rtabmap
2414 }
2415 
2416 void PreferencesDialog::writeCameraSettings(const QString & filePath) const
2417 {
2418  QString path = getIniFilePath();
2419  if(!filePath.isEmpty())
2420  {
2421  path = filePath;
2422  }
2423  QSettings settings(path, QSettings::IniFormat);
2424 
2425  settings.beginGroup("Camera");
2426  settings.remove("");
2427  settings.setValue("imgRate", _ui->general_doubleSpinBox_imgRate->value());
2428  settings.setValue("mirroring", _ui->source_mirroring->isChecked());
2429  settings.setValue("calibrationName", _ui->lineEdit_calibrationFile->text());
2430  settings.setValue("type", _ui->comboBox_sourceType->currentIndex());
2431  settings.setValue("device", _ui->lineEdit_sourceDevice->text());
2432  settings.setValue("localTransform", _ui->lineEdit_sourceLocalTransform->text());
2433  settings.setValue("imageDecimation", _ui->spinBox_source_imageDecimation->value());
2434 
2435  settings.beginGroup("rgbd");
2436  settings.setValue("driver", _ui->comboBox_cameraRGBD->currentIndex());
2437  settings.setValue("rgbdColorOnly", _ui->checkbox_rgbd_colorOnly->isChecked());
2438  settings.setValue("distortion_model", _ui->lineEdit_source_distortionModel->text());
2439  settings.setValue("bilateral", _ui->groupBox_bilateral->isChecked());
2440  settings.setValue("bilateral_sigma_s", _ui->doubleSpinBox_bilateral_sigmaS->value());
2441  settings.setValue("bilateral_sigma_r", _ui->doubleSpinBox_bilateral_sigmaR->value());
2442  settings.endGroup(); // rgbd
2443 
2444  settings.beginGroup("stereo");
2445  settings.setValue("driver", _ui->comboBox_cameraStereo->currentIndex());
2446  settings.setValue("depthGenerated", _ui->checkbox_stereo_depthGenerated->isChecked());
2447  settings.setValue("exposureCompensation", _ui->checkBox_stereo_exposureCompensation->isChecked());
2448  settings.endGroup(); // stereo
2449 
2450  settings.beginGroup("rgb");
2451  settings.setValue("driver", _ui->source_comboBox_image_type->currentIndex());
2452  settings.setValue("rectify", _ui->checkBox_rgb_rectify->isChecked());
2453  settings.endGroup(); // rgb
2454 
2455  settings.beginGroup("Openni");
2456  settings.setValue("oniPath", _ui->lineEdit_openniOniPath->text());
2457  settings.endGroup(); // Openni
2458 
2459  settings.beginGroup("Openni2");
2460  settings.setValue("autoWhiteBalance", _ui->openni2_autoWhiteBalance->isChecked());
2461  settings.setValue("autoExposure", _ui->openni2_autoExposure->isChecked());
2462  settings.setValue("exposure", _ui->openni2_exposure->value());
2463  settings.setValue("gain", _ui->openni2_gain->value());
2464  settings.setValue("mirroring", _ui->openni2_mirroring->isChecked());
2465  settings.setValue("stampsIdsUsed", _ui->openni2_stampsIdsUsed->isChecked());
2466  settings.setValue("oniPath", _ui->lineEdit_openni2OniPath->text());
2467  settings.setValue("hshift", _ui->openni2_hshift->value());
2468  settings.setValue("vshift", _ui->openni2_vshift->value());
2469  settings.endGroup(); // Openni2
2470 
2471  settings.beginGroup("Freenect2");
2472  settings.setValue("format", _ui->comboBox_freenect2Format->currentIndex());
2473  settings.setValue("minDepth", _ui->doubleSpinBox_freenect2MinDepth->value());
2474  settings.setValue("maxDepth", _ui->doubleSpinBox_freenect2MaxDepth->value());
2475  settings.setValue("bilateralFiltering", _ui->checkBox_freenect2BilateralFiltering->isChecked());
2476  settings.setValue("edgeAwareFiltering", _ui->checkBox_freenect2EdgeAwareFiltering->isChecked());
2477  settings.setValue("noiseFiltering", _ui->checkBox_freenect2NoiseFiltering->isChecked());
2478  settings.setValue("pipeline", _ui->lineEdit_freenect2Pipeline->text());
2479  settings.endGroup(); // Freenect2
2480 
2481  settings.beginGroup("K4W2");
2482  settings.setValue("format", _ui->comboBox_k4w2Format->currentIndex());
2483  settings.endGroup(); // K4W2
2484 
2485  settings.beginGroup("RealSense");
2486  settings.setValue("presetRGB", _ui->comboBox_realsensePresetRGB->currentIndex());
2487  settings.setValue("presetDepth", _ui->comboBox_realsensePresetDepth->currentIndex());
2488  settings.setValue("odom", _ui->checkbox_realsenseOdom->isChecked());
2489  settings.setValue("depthScaled", _ui->checkbox_realsenseDepthScaledToRGBSize->isChecked());
2490  settings.setValue("rgbSource", _ui->comboBox_realsenseRGBSource->currentIndex());
2491  settings.endGroup(); // RealSense
2492 
2493  settings.beginGroup("RealSense2");
2494  settings.setValue("emitter", _ui->checkbox_rs2_emitter->isChecked());
2495  settings.setValue("irdepth", _ui->checkbox_rs2_irDepth->isChecked());
2496  settings.endGroup(); // RealSense2
2497 
2498  settings.beginGroup("RGBDImages");
2499  settings.setValue("path_rgb", _ui->lineEdit_cameraRGBDImages_path_rgb->text());
2500  settings.setValue("path_depth", _ui->lineEdit_cameraRGBDImages_path_depth->text());
2501  settings.setValue("scale", _ui->doubleSpinBox_cameraRGBDImages_scale->value());
2502  settings.setValue("start_index", _ui->spinBox_cameraRGBDImages_startIndex->value());
2503  settings.endGroup(); // RGBDImages
2504 
2505  settings.beginGroup("StereoImages");
2506  settings.setValue("path_left", _ui->lineEdit_cameraStereoImages_path_left->text());
2507  settings.setValue("path_right", _ui->lineEdit_cameraStereoImages_path_right->text());
2508  settings.setValue("rectify", _ui->checkBox_stereo_rectify->isChecked());
2509  settings.setValue("start_index", _ui->spinBox_cameraStereoImages_startIndex->value());
2510  settings.endGroup(); // StereoImages
2511 
2512  settings.beginGroup("StereoVideo");
2513  settings.setValue("path", _ui->lineEdit_cameraStereoVideo_path->text());
2514  settings.setValue("path2", _ui->lineEdit_cameraStereoVideo_path_2->text());
2515  settings.setValue("device2", _ui->spinBox_stereo_right_device->value());
2516  settings.endGroup(); // StereoVideo
2517 
2518  settings.beginGroup("StereoZed");
2519  settings.setValue("resolution", _ui->comboBox_stereoZed_resolution->currentIndex());
2520  settings.setValue("quality", _ui->comboBox_stereoZed_quality->currentIndex());
2521  settings.setValue("self_calibration", _ui->checkbox_stereoZed_selfCalibration->isChecked());
2522  settings.setValue("sensing_mode", _ui->comboBox_stereoZed_sensingMode->currentIndex());
2523  settings.setValue("confidence_thr", _ui->spinBox_stereoZed_confidenceThr->value());
2524  settings.setValue("odom", _ui->checkbox_stereoZed_odom->isChecked());
2525  settings.setValue("svo_path", _ui->lineEdit_zedSvoPath->text());
2526  settings.endGroup(); // StereoZed
2527 
2528 
2529 
2530  settings.beginGroup("Images");
2531  settings.setValue("path", _ui->source_images_lineEdit_path->text());
2532  settings.setValue("startPos", _ui->source_images_spinBox_startPos->value());
2533  settings.setValue("bayerMode", _ui->comboBox_cameraImages_bayerMode->currentIndex());
2534  settings.setValue("filenames_as_stamps", _ui->checkBox_cameraImages_timestamps->isChecked());
2535  settings.setValue("sync_stamps", _ui->checkBox_cameraImages_syncTimeStamps->isChecked());
2536  settings.setValue("stamps", _ui->lineEdit_cameraImages_timestamps->text());
2537  settings.setValue("path_scans", _ui->lineEdit_cameraImages_path_scans->text());
2538  settings.setValue("scan_transform", _ui->lineEdit_cameraImages_laser_transform->text());
2539  settings.setValue("scan_max_pts", _ui->spinBox_cameraImages_max_scan_pts->value());
2540  settings.setValue("scan_downsample_step", _ui->spinBox_cameraImages_scanDownsampleStep->value());
2541  settings.setValue("scan_voxel_size", _ui->doubleSpinBox_cameraImages_scanVoxelSize->value());
2542  settings.setValue("odom_path", _ui->lineEdit_cameraImages_odom->text());
2543  settings.setValue("odom_format", _ui->comboBox_cameraImages_odomFormat->currentIndex());
2544  settings.setValue("gt_path", _ui->lineEdit_cameraImages_gt->text());
2545  settings.setValue("gt_format", _ui->comboBox_cameraImages_gtFormat->currentIndex());
2546  settings.setValue("max_pose_time_diff", _ui->doubleSpinBox_maxPoseTimeDiff->value());
2547  settings.setValue("imu_path", _ui->lineEdit_cameraImages_path_imu->text());
2548  settings.setValue("imu_local_transform", _ui->lineEdit_cameraImages_imu_transform->text());
2549  settings.setValue("imu_rate", _ui->spinBox_cameraImages_max_imu_rate->value());
2550  settings.endGroup(); // images
2551 
2552  settings.beginGroup("Video");
2553  settings.setValue("path", _ui->source_video_lineEdit_path->text());
2554  settings.endGroup(); // video
2555 
2556  settings.beginGroup("ScanFromDepth");
2557  settings.setValue("enabled", _ui->groupBox_scanFromDepth->isChecked());
2558  settings.setValue("decimation", _ui->spinBox_cameraScanFromDepth_decimation->value());
2559  settings.setValue("maxDepth", _ui->doubleSpinBox_cameraSCanFromDepth_maxDepth->value());
2560  settings.setValue("voxelSize", _ui->doubleSpinBox_cameraImages_scanVoxelSize->value());
2561  settings.setValue("normalsK", _ui->spinBox_cameraImages_scanNormalsK->value());
2562  settings.setValue("normalsRadius", _ui->doubleSpinBox_cameraImages_scanNormalsRadius->value());
2563  settings.setValue("normalsUp", _ui->checkBox_cameraImages_scanForceGroundNormalsUp->isChecked());
2564  settings.endGroup();
2565 
2566  settings.beginGroup("DepthFromScan");
2567  settings.setValue("depthFromScan", _ui->groupBox_depthFromScan->isChecked());
2568  settings.setValue("depthFromScanFillHoles", _ui->groupBox_depthFromScan_fillHoles->isChecked());
2569  settings.setValue("depthFromScanVertical", _ui->radioButton_depthFromScan_vertical->isChecked());
2570  settings.setValue("depthFromScanHorizontal", _ui->radioButton_depthFromScan_horizontal->isChecked());
2571  settings.setValue("depthFromScanFillBorders", _ui->checkBox_depthFromScan_fillBorders->isChecked());
2572  settings.endGroup();
2573 
2574  settings.beginGroup("Database");
2575  settings.setValue("path", _ui->source_database_lineEdit_path->text());
2576  settings.setValue("ignoreOdometry", _ui->source_checkBox_ignoreOdometry->isChecked());
2577  settings.setValue("ignoreGoalDelay", _ui->source_checkBox_ignoreGoalDelay->isChecked());
2578  settings.setValue("ignoreGoals", _ui->source_checkBox_ignoreGoals->isChecked());
2579  settings.setValue("startPos", _ui->source_spinBox_databaseStartPos->value());
2580  settings.setValue("cameraIndex", _ui->source_spinBox_database_cameraIndex->value());
2581  settings.setValue("useDatabaseStamps", _ui->source_checkBox_useDbStamps->isChecked());
2582  settings.endGroup(); // Database
2583 
2584  settings.endGroup(); // Camera
2585 
2586  _calibrationDialog->saveSettings(settings, "CalibrationDialog");
2587 }
2588 
2589 void PreferencesDialog::writeCoreSettings(const QString & filePath) const
2590 {
2591  QString path = getIniFilePath();
2592  if(!filePath.isEmpty())
2593  {
2594  path = filePath;
2595  }
2596 
2597  Parameters::writeINI(path.toStdString(), this->getAllParameters());
2598 }
2599 
2601 {
2602 #ifndef RTABMAP_NONFREE
2603  // verify that SURF/SIFT cannot be selected if not built with OpenCV nonfree module
2604  // BOW dictionary type
2605  if(_ui->comboBox_detector_strategy->currentIndex() <= 1)
2606  {
2607  QMessageBox::warning(this, tr("Parameter warning"),
2608  tr("Selected feature type (SURF/SIFT) is not available. RTAB-Map is not built "
2609  "with the nonfree module from OpenCV. ORB is set instead for the bag-of-words dictionary."));
2610  _ui->comboBox_detector_strategy->setCurrentIndex(Feature2D::kFeatureOrb);
2611  }
2612  // BOW Reextract features type
2613  if(_ui->reextract_type->currentIndex() <= 1)
2614  {
2615  QMessageBox::warning(this, tr("Parameter warning"),
2616  tr("Selected feature type (SURF/SIFT) is not available. RTAB-Map is not built "
2617  "with the nonfree module from OpenCV. Fast/Brief is set instead for the re-extraction "
2618  "of features on loop closure."));
2619  _ui->reextract_type->setCurrentIndex(Feature2D::kFeatureFastBrief);
2620  }
2621 #endif
2622 
2623 #if CV_MAJOR_VERSION < 3
2624  if (_ui->comboBox_detector_strategy->currentIndex() == Feature2D::kFeatureKaze)
2625  {
2626 #ifdef RTABMAP_NONFREE
2627  QMessageBox::warning(this, tr("Parameter warning"),
2628  tr("Selected feature type (KAZE) is not available on OpenCV2. SURF is set instead "
2629  "for the bag-of-words dictionary."));
2630  _ui->comboBox_detector_strategy->setCurrentIndex(Feature2D::kFeatureSurf);
2631 #else
2632  QMessageBox::warning(this, tr("Parameter warning"),
2633  tr("Selected feature type (KAZE) is not available on OpenCV2. ORB is set instead "
2634  "for the bag-of-words dictionary."));
2635  _ui->comboBox_detector_strategy->setCurrentIndex(Feature2D::kFeatureOrb);
2636 #endif
2637  }
2638  if (_ui->reextract_type->currentIndex() == Feature2D::kFeatureKaze)
2639  {
2640 #ifdef RTABMAP_NONFREE
2641  QMessageBox::warning(this, tr("Parameter warning"),
2642  tr("Selected feature type (KAZE) is not available on OpenCV2. SURF is set instead "
2643  "for the re-extraction of features on loop closure."));
2644  _ui->reextract_type->setCurrentIndex(Feature2D::kFeatureSurf);
2645 #else
2646  QMessageBox::warning(this, tr("Parameter warning"),
2647  tr("Selected feature type (KAZE) is not available on OpenCV2. ORB is set instead "
2648  "for the re-extraction of features on loop closure."));
2649  _ui->reextract_type->setCurrentIndex(Feature2D::kFeatureOrb);
2650 #endif
2651  }
2652 #endif
2653 
2654  // optimization strategy
2655  if(_ui->graphOptimization_type->currentIndex() == 0 && !Optimizer::isAvailable(Optimizer::kTypeTORO))
2656  {
2658  {
2659  QMessageBox::warning(this, tr("Parameter warning"),
2660  tr("Selected graph optimization strategy (TORO) is not available. RTAB-Map is not built "
2661  "with TORO. GTSAM is set instead for graph optimization strategy."));
2662  _ui->graphOptimization_type->setCurrentIndex(Optimizer::kTypeGTSAM);
2663  }
2664 #ifndef RTABMAP_ORB_SLAM2
2666  {
2667  QMessageBox::warning(this, tr("Parameter warning"),
2668  tr("Selected graph optimization strategy (TORO) is not available. RTAB-Map is not built "
2669  "with TORO. g2o is set instead for graph optimization strategy."));
2670  _ui->graphOptimization_type->setCurrentIndex(Optimizer::kTypeG2O);
2671  }
2672 #endif
2673  }
2674 #ifdef RTABMAP_ORB_SLAM2
2675  if(_ui->graphOptimization_type->currentIndex() == 1)
2676 #else
2677  if(_ui->graphOptimization_type->currentIndex() == 1 && !Optimizer::isAvailable(Optimizer::kTypeG2O))
2678 #endif
2679  {
2681  {
2682  QMessageBox::warning(this, tr("Parameter warning"),
2683  tr("Selected graph optimization strategy (g2o) is not available. RTAB-Map is not built "
2684  "with g2o. GTSAM is set instead for graph optimization strategy."));
2685  _ui->graphOptimization_type->setCurrentIndex(Optimizer::kTypeGTSAM);
2686  }
2688  {
2689  QMessageBox::warning(this, tr("Parameter warning"),
2690  tr("Selected graph optimization strategy (g2o) is not available. RTAB-Map is not built "
2691  "with g2o. TORO is set instead for graph optimization strategy."));
2692  _ui->graphOptimization_type->setCurrentIndex(Optimizer::kTypeTORO);
2693  }
2694  }
2695  if(_ui->graphOptimization_type->currentIndex() == 2 && !Optimizer::isAvailable(Optimizer::kTypeGTSAM))
2696  {
2697 #ifndef RTABMAP_ORB_SLAM2
2699  {
2700  QMessageBox::warning(this, tr("Parameter warning"),
2701  tr("Selected graph optimization strategy (GTSAM) is not available. RTAB-Map is not built "
2702  "with GTSAM. g2o is set instead for graph optimization strategy."));
2703  _ui->graphOptimization_type->setCurrentIndex(Optimizer::kTypeG2O);
2704  }
2705  else
2706 #endif
2708  {
2709  QMessageBox::warning(this, tr("Parameter warning"),
2710  tr("Selected graph optimization strategy (GTSAM) is not available. RTAB-Map is not built "
2711  "with GTSAM. TORO is set instead for graph optimization strategy."));
2712  _ui->graphOptimization_type->setCurrentIndex(Optimizer::kTypeTORO);
2713  }
2714  }
2715 
2716  // Registration bundle adjustment strategy
2717  if(_ui->loopClosure_bundle->currentIndex() == 1 && !Optimizer::isAvailable(Optimizer::kTypeG2O))
2718  {
2719  QMessageBox::warning(this, tr("Parameter warning"),
2720  tr("Selected visual registration bundle adjustment optimization strategy (g2o) is not available. RTAB-Map is not built "
2721  "with g2o. Bundle adjustment is disabled."));
2722  _ui->loopClosure_bundle->setCurrentIndex(0);
2723  }
2724  if(_ui->loopClosure_bundle->currentIndex() == 2 && !Optimizer::isAvailable(Optimizer::kTypeCVSBA))
2725  {
2726  QMessageBox::warning(this, tr("Parameter warning"),
2727  tr("Selected visual registration bundle adjustment optimization strategy (cvsba) is not available. RTAB-Map is not built "
2728  "with cvsba. Bundle adjustment is disabled."));
2729  _ui->loopClosure_bundle->setCurrentIndex(0);
2730  }
2731 
2732  // Local bundle adjustment strategy for odometry F2M
2733  if(_ui->odom_f2m_bundleStrategy->currentIndex() == 1 && !Optimizer::isAvailable(Optimizer::kTypeG2O))
2734  {
2735  QMessageBox::warning(this, tr("Parameter warning"),
2736  tr("Selected odometry local bundle adjustment optimization strategy (g2o) is not available. RTAB-Map is not built "
2737  "with g2o. Bundle adjustment is disabled."));
2738  _ui->odom_f2m_bundleStrategy->setCurrentIndex(0);
2739  }
2740  if(_ui->odom_f2m_bundleStrategy->currentIndex() == 2 && !Optimizer::isAvailable(Optimizer::kTypeCVSBA))
2741  {
2742  QMessageBox::warning(this, tr("Parameter warning"),
2743  tr("Selected odometry local bundle adjustment optimization strategy (cvsba) is not available. RTAB-Map is not built "
2744  "with cvsba. Bundle adjustment is disabled."));
2745  _ui->odom_f2m_bundleStrategy->setCurrentIndex(0);
2746  }
2747 
2748  // verify that Robust and Reject threshold are not set at the same time
2749  if(_ui->graphOptimization_robust->isChecked() && _ui->graphOptimization_maxError->value()>0.0)
2750  {
2751  QMessageBox::warning(this, tr("Parameter warning"),
2752  tr("Robust graph optimization and maximum optimization error threshold cannot be "
2753  "both used at the same time. Disabling robust optimization."));
2754  _ui->graphOptimization_robust->setChecked(false);
2755  }
2756 
2757  //verify binary features and nearest neighbor
2758  // BOW dictionary type
2759  if(_ui->comboBox_dictionary_strategy->currentIndex() == VWDictionary::kNNFlannLSH && _ui->comboBox_detector_strategy->currentIndex() <= 1)
2760  {
2761  QMessageBox::warning(this, tr("Parameter warning"),
2762  tr("With the selected feature type (SURF or SIFT), parameter \"Visual word->Nearest Neighbor\" "
2763  "cannot be LSH (used for binary descriptor). KD-tree is set instead for the bag-of-words dictionary."));
2764  _ui->comboBox_dictionary_strategy->setCurrentIndex(VWDictionary::kNNFlannKdTree);
2765  }
2766 
2767  // BOW Reextract features type
2768  if(_ui->reextract_nn->currentIndex() == VWDictionary::kNNFlannLSH && _ui->reextract_type->currentIndex() <= 1)
2769  {
2770  QMessageBox::warning(this, tr("Parameter warning"),
2771  tr("With the selected feature type (SURF or SIFT), parameter \"Visual word->Nearest Neighbor\" "
2772  "cannot be LSH (used for binary descriptor). KD-tree is set instead for the re-extraction "
2773  "of features on loop closure."));
2774  _ui->reextract_nn->setCurrentIndex(VWDictionary::kNNFlannKdTree);
2775  }
2776 
2777  if(_ui->doubleSpinBox_freenect2MinDepth->value() >= _ui->doubleSpinBox_freenect2MaxDepth->value())
2778  {
2779  QMessageBox::warning(this, tr("Parameter warning"),
2780  tr("Freenect2 minimum depth (%1 m) should be lower than maximum depth (%2 m). Setting maximum depth to %3 m.")
2781  .arg(_ui->doubleSpinBox_freenect2MinDepth->value())
2782  .arg(_ui->doubleSpinBox_freenect2MaxDepth->value())
2783  .arg(_ui->doubleSpinBox_freenect2MaxDepth->value()+1));
2784  _ui->doubleSpinBox_freenect2MaxDepth->setValue(_ui->doubleSpinBox_freenect2MaxDepth->value()+1);
2785  }
2786 
2787  if(_ui->surf_doubleSpinBox_maxDepth->value() > 0.0 &&
2788  _ui->surf_doubleSpinBox_minDepth->value() >= _ui->surf_doubleSpinBox_maxDepth->value())
2789  {
2790  QMessageBox::warning(this, tr("Parameter warning"),
2791  tr("Visual word minimum depth (%1 m) should be lower than maximum depth (%2 m). Setting maximum depth to %3 m.")
2792  .arg(_ui->surf_doubleSpinBox_minDepth->value())
2793  .arg(_ui->surf_doubleSpinBox_maxDepth->value())
2794  .arg(_ui->surf_doubleSpinBox_maxDepth->value()+1));
2795  _ui->doubleSpinBox_freenect2MinDepth->setValue(0);
2796  }
2797 
2798  if(_ui->loopClosure_bowMaxDepth->value() > 0.0 &&
2799  _ui->loopClosure_bowMinDepth->value() >= _ui->loopClosure_bowMaxDepth->value())
2800  {
2801  QMessageBox::warning(this, tr("Parameter warning"),
2802  tr("Visual registration word minimum depth (%1 m) should be lower than maximum depth (%2 m). Setting maximum depth to %3 m.")
2803  .arg(_ui->loopClosure_bowMinDepth->value())
2804  .arg(_ui->loopClosure_bowMaxDepth->value())
2805  .arg(_ui->loopClosure_bowMaxDepth->value()+1));
2806  _ui->loopClosure_bowMinDepth->setValue(0);
2807  }
2808 
2809  if(_ui->fastThresholdMax->value() < _ui->fastThresholdMin->value())
2810  {
2811  QMessageBox::warning(this, tr("Parameter warning"),
2812  tr("FAST minimum threshold cannot be lower than maximum threshold. Setting minimum to 1."));
2813  _ui->fastThresholdMin->setValue(1);
2814  }
2815  if(_ui->fastThreshold->value() > _ui->fastThresholdMax->value())
2816  {
2817  QMessageBox::warning(this, tr("Parameter warning"),
2818  tr("FAST threshold cannot be higher than maximum threshold. Maximum value set to current threshold."));
2819  _ui->fastThresholdMax->setValue(_ui->fastThreshold->value());
2820  }
2821  if(_ui->fastThreshold->value() < _ui->fastThresholdMin->value())
2822  {
2823  QMessageBox::warning(this, tr("Parameter warning"),
2824  tr("FAST threshold cannot be lower than minimum threshold. Minimum value set to current threshold."));
2825  _ui->fastThresholdMin->setValue(_ui->fastThreshold->value());
2826  }
2827 
2828  if(_ui->checkbox_odomDisabled->isChecked() &&
2829  _ui->general_checkBox_SLAM_mode->isChecked() &&
2830  _ui->general_checkBox_activateRGBD->isChecked())
2831  {
2832  QMessageBox::warning(this, tr("Parameter warning"),
2833  tr("Odometry is disabled but incremental RGB-D SLAM is activated! Re-enabling odometry."));
2834  _ui->checkbox_odomDisabled->setChecked(false);
2835  }
2836 
2837  return true;
2838 }
2839 
2841 {
2842  return tr("Reading parameters from the configuration file...");
2843 }
2844 
2845 void PreferencesDialog::showEvent ( QShowEvent * event )
2846 {
2847  if(_monitoringState)
2848  {
2849  // In monitoring state, you cannot change remote paths
2850  _ui->lineEdit_dictionaryPath->setEnabled(false);
2851  _ui->toolButton_dictionaryPath->setEnabled(false);
2852  _ui->label_dictionaryPath->setEnabled(false);
2853 
2854  _ui->groupBox_source0->setEnabled(false);
2855  _ui->groupBox_odometry1->setEnabled(false);
2856 
2857  _ui->checkBox_useOdomFeatures->setChecked(false);
2858  _ui->checkBox_useOdomFeatures->setEnabled(false);
2859 
2860  this->setWindowTitle(tr("Preferences [Monitoring mode]"));
2861  }
2862  else
2863  {
2864  _ui->lineEdit_dictionaryPath->setEnabled(true);
2865  _ui->toolButton_dictionaryPath->setEnabled(true);
2866  _ui->label_dictionaryPath->setEnabled(true);
2867 
2868  _ui->groupBox_source0->setEnabled(true);
2869  _ui->groupBox_odometry1->setEnabled(true);
2870 
2871  _ui->checkBox_useOdomFeatures->setEnabled(true);
2872 
2873  this->setWindowTitle(tr("Preferences"));
2874  }
2875 
2876  // setup logger filter
2877  std::map<std::string, unsigned long> threads = ULogger::getRegisteredThreads();
2878  std::vector<std::string> threadsChecked = this->getGeneralLoggerThreads();
2879  std::set<std::string> threadsCheckedSet(threadsChecked.begin(), threadsChecked.end());
2880  _ui->comboBox_loggerFilter->clear();
2881  for(std::map<std::string, unsigned long>::iterator iter=threads.begin(); iter!=threads.end(); ++iter)
2882  {
2883  if(threadsCheckedSet.find(iter->first.c_str()) != threadsCheckedSet.end())
2884  {
2885  _ui->comboBox_loggerFilter->addItem(QString(iter->first.c_str()), QVariant(true));
2886  }
2887  else
2888  {
2889  _ui->comboBox_loggerFilter->addItem(QString(iter->first.c_str()), QVariant(false));
2890  }
2891  }
2892 
2893  this->readSettingsBegin();
2894 }
2895 
2897 {
2898  _progressDialog->setLabelText(this->getParamMessage());
2899  _progressDialog->show();
2900 
2901  // this will let the MainThread to display the progress dialog before reading the parameters...
2902  QTimer::singleShot(10, this, SLOT(readSettingsEnd()));
2903 }
2904 
2906 {
2907  QApplication::processEvents();
2908 
2910 
2911  _progressDialog->setValue(1);
2912  if(this->isVisible())
2913  {
2914  _progressDialog->setLabelText(tr("Setup dialog..."));
2915 
2916  this->updatePredictionPlot();
2917  this->setupKpRoiPanel();
2918  }
2919 
2920  _progressDialog->setValue(2); // this will make closing...
2921 }
2922 
2923 void PreferencesDialog::saveWindowGeometry(const QWidget * window)
2924 {
2925  if(!window->objectName().isEmpty() && !window->isMaximized())
2926  {
2927  QSettings settings(getIniFilePath(), QSettings::IniFormat);
2928  settings.beginGroup("Gui");
2929  settings.beginGroup(window->objectName());
2930  settings.setValue("geometry", window->saveGeometry());
2931  settings.endGroup(); // "windowName"
2932  settings.endGroup(); // rtabmap
2933 
2934  QSettings settingsTmp(getTmpIniFilePath(), QSettings::IniFormat);
2935  settingsTmp.beginGroup("Gui");
2936  settingsTmp.beginGroup(window->objectName());
2937  settingsTmp.setValue("geometry", window->saveGeometry());
2938  settingsTmp.endGroup(); // "windowName"
2939  settingsTmp.endGroup(); // rtabmap
2940  }
2941 }
2942 
2944 {
2945  if(!window->objectName().isEmpty())
2946  {
2947  QByteArray bytes;
2948  QSettings settings(getIniFilePath(), QSettings::IniFormat);
2949  settings.beginGroup("Gui");
2950  settings.beginGroup(window->objectName());
2951  bytes = settings.value("geometry", QByteArray()).toByteArray();
2952  if(!bytes.isEmpty())
2953  {
2954  window->restoreGeometry(bytes);
2955  }
2956  settings.endGroup(); // "windowName"
2957  settings.endGroup(); // rtabmap
2958 
2959  QSettings settingsTmp(getTmpIniFilePath(), QSettings::IniFormat);
2960  settingsTmp.beginGroup("Gui");
2961  settingsTmp.beginGroup(window->objectName());
2962  settingsTmp.setValue("geometry", window->saveGeometry());
2963  settingsTmp.endGroup(); // "windowName"
2964  settingsTmp.endGroup(); // rtabmap
2965  }
2966 }
2967 
2968 void PreferencesDialog::saveMainWindowState(const QMainWindow * mainWindow)
2969 {
2970  if(!mainWindow->objectName().isEmpty())
2971  {
2972  saveWindowGeometry(mainWindow);
2973 
2974  QSettings settings(getIniFilePath(), QSettings::IniFormat);
2975  settings.beginGroup("Gui");
2976  settings.beginGroup(mainWindow->objectName());
2977  settings.setValue("state", mainWindow->saveState());
2978  settings.setValue("maximized", mainWindow->isMaximized());
2979  settings.setValue("status_bar", mainWindow->statusBar()->isVisible());
2980  settings.endGroup(); // "MainWindow"
2981  settings.endGroup(); // rtabmap
2982 
2983  QSettings settingsTmp(getTmpIniFilePath(), QSettings::IniFormat);
2984  settingsTmp.beginGroup("Gui");
2985  settingsTmp.beginGroup(mainWindow->objectName());
2986  settingsTmp.setValue("state", mainWindow->saveState());
2987  settingsTmp.setValue("maximized", mainWindow->isMaximized());
2988  settingsTmp.setValue("status_bar", mainWindow->statusBar()->isVisible());
2989  settingsTmp.endGroup(); // "MainWindow"
2990  settingsTmp.endGroup(); // rtabmap
2991  }
2992 }
2993 
2994 void PreferencesDialog::loadMainWindowState(QMainWindow * mainWindow, bool & maximized, bool & statusBarShown)
2995 {
2996  if(!mainWindow->objectName().isEmpty())
2997  {
2998  loadWindowGeometry(mainWindow);
2999 
3000  QByteArray bytes;
3001  QSettings settings(getIniFilePath(), QSettings::IniFormat);
3002  settings.beginGroup("Gui");
3003  settings.beginGroup(mainWindow->objectName());
3004  bytes = settings.value("state", QByteArray()).toByteArray();
3005  if(!bytes.isEmpty())
3006  {
3007  mainWindow->restoreState(bytes);
3008  }
3009  maximized = settings.value("maximized", false).toBool();
3010  statusBarShown = settings.value("status_bar", false).toBool();
3011  mainWindow->statusBar()->setVisible(statusBarShown);
3012  settings.endGroup(); // "MainWindow"
3013  settings.endGroup(); // rtabmap
3014 
3015  QSettings settingsTmp(getTmpIniFilePath(), QSettings::IniFormat);
3016  settingsTmp.beginGroup("Gui");
3017  settingsTmp.beginGroup(mainWindow->objectName());
3018  settingsTmp.setValue("state", mainWindow->saveState());
3019  settingsTmp.setValue("maximized", maximized);
3020  settingsTmp.setValue("status_bar", statusBarShown);
3021  settingsTmp.endGroup(); // "MainWindow"
3022  settingsTmp.endGroup(); // rtabmap
3023  }
3024 }
3025 
3026 void PreferencesDialog::saveWidgetState(const QWidget * widget)
3027 {
3028  if(!widget->objectName().isEmpty())
3029  {
3030  QSettings settings(getIniFilePath(), QSettings::IniFormat);
3031  settings.beginGroup("Gui");
3032  settings.beginGroup(widget->objectName());
3033 
3034  QSettings settingsTmp(getTmpIniFilePath(), QSettings::IniFormat);
3035  settingsTmp.beginGroup("Gui");
3036  settingsTmp.beginGroup(widget->objectName());
3037 
3038  const CloudViewer * cloudViewer = qobject_cast<const CloudViewer*>(widget);
3039  const ImageView * imageView = qobject_cast<const ImageView*>(widget);
3040  const ExportCloudsDialog * exportCloudsDialog = qobject_cast<const ExportCloudsDialog*>(widget);
3041  const ExportBundlerDialog * exportBundlerDialog = qobject_cast<const ExportBundlerDialog*>(widget);
3042  const PostProcessingDialog * postProcessingDialog = qobject_cast<const PostProcessingDialog *>(widget);
3043  const GraphViewer * graphViewer = qobject_cast<const GraphViewer *>(widget);
3044  const CalibrationDialog * calibrationDialog = qobject_cast<const CalibrationDialog *>(widget);
3045  const DepthCalibrationDialog * depthCalibrationDialog = qobject_cast<const DepthCalibrationDialog *>(widget);
3046 
3047  if(cloudViewer)
3048  {
3049  cloudViewer->saveSettings(settings);
3050  cloudViewer->saveSettings(settingsTmp);
3051  }
3052  else if(imageView)
3053  {
3054  imageView->saveSettings(settings);
3055  imageView->saveSettings(settingsTmp);
3056  }
3057  else if(exportCloudsDialog)
3058  {
3059  exportCloudsDialog->saveSettings(settings);
3060  exportCloudsDialog->saveSettings(settingsTmp);
3061  }
3062  else if(exportBundlerDialog)
3063  {
3064  exportBundlerDialog->saveSettings(settings);
3065  exportBundlerDialog->saveSettings(settingsTmp);
3066  }
3067  else if(postProcessingDialog)
3068  {
3069  postProcessingDialog->saveSettings(settings);
3070  postProcessingDialog->saveSettings(settingsTmp);
3071  }
3072  else if(graphViewer)
3073  {
3074  graphViewer->saveSettings(settings);
3075  graphViewer->saveSettings(settingsTmp);
3076  }
3077  else if(calibrationDialog)
3078  {
3079  calibrationDialog->saveSettings(settings);
3080  calibrationDialog->saveSettings(settingsTmp);
3081  }
3082  else if(depthCalibrationDialog)
3083  {
3084  depthCalibrationDialog->saveSettings(settings);
3085  depthCalibrationDialog->saveSettings(settingsTmp);
3086  }
3087  else
3088  {
3089  UERROR("Widget \"%s\" cannot be exported in config file.", widget->objectName().toStdString().c_str());
3090  }
3091 
3092  settings.endGroup(); // "name"
3093  settings.endGroup(); // Gui
3094  settingsTmp.endGroup();
3095  settingsTmp.endGroup();
3096  }
3097 }
3098 
3100 {
3101  if(!widget->objectName().isEmpty())
3102  {
3103  QByteArray bytes;
3104  QSettings settings(getIniFilePath(), QSettings::IniFormat);
3105  settings.beginGroup("Gui");
3106  settings.beginGroup(widget->objectName());
3107 
3108  QSettings settingsTmp(getTmpIniFilePath(), QSettings::IniFormat);
3109  settingsTmp.beginGroup("Gui");
3110  settingsTmp.beginGroup(widget->objectName());
3111 
3112  CloudViewer * cloudViewer = qobject_cast<CloudViewer*>(widget);
3113  ImageView * imageView = qobject_cast<ImageView*>(widget);
3114  ExportCloudsDialog * exportCloudsDialog = qobject_cast<ExportCloudsDialog*>(widget);
3115  ExportBundlerDialog * exportBundlerDialog = qobject_cast<ExportBundlerDialog*>(widget);
3116  PostProcessingDialog * postProcessingDialog = qobject_cast<PostProcessingDialog *>(widget);
3117  GraphViewer * graphViewer = qobject_cast<GraphViewer *>(widget);
3118  CalibrationDialog * calibrationDialog = qobject_cast<CalibrationDialog *>(widget);
3119  DepthCalibrationDialog * depthCalibrationDialog = qobject_cast<DepthCalibrationDialog *>(widget);
3120 
3121  if(cloudViewer)
3122  {
3123  cloudViewer->loadSettings(settings);
3124  cloudViewer->saveSettings(settingsTmp);
3125  }
3126  else if(imageView)
3127  {
3128  imageView->loadSettings(settings);
3129  imageView->saveSettings(settingsTmp);
3130  }
3131  else if(exportCloudsDialog)
3132  {
3133  exportCloudsDialog->loadSettings(settings);
3134  exportCloudsDialog->saveSettings(settingsTmp);
3135  }
3136  else if(exportBundlerDialog)
3137  {
3138  exportBundlerDialog->loadSettings(settings);
3139  exportBundlerDialog->saveSettings(settingsTmp);
3140  }
3141  else if(postProcessingDialog)
3142  {
3143  postProcessingDialog->loadSettings(settings);
3144  postProcessingDialog->saveSettings(settingsTmp);
3145  }
3146  else if(graphViewer)
3147  {
3148  graphViewer->loadSettings(settings);
3149  graphViewer->saveSettings(settingsTmp);
3150  }
3151  else if(calibrationDialog)
3152  {
3153  calibrationDialog->loadSettings(settings);
3154  calibrationDialog->saveSettings(settingsTmp);
3155  }
3156  else if(depthCalibrationDialog)
3157  {
3158  depthCalibrationDialog->loadSettings(settings);
3159  depthCalibrationDialog->saveSettings(settingsTmp);
3160  }
3161  else
3162  {
3163  UERROR("Widget \"%s\" cannot be loaded from config file.", widget->objectName().toStdString().c_str());
3164  }
3165 
3166  settings.endGroup(); //"name"
3167  settings.endGroup(); // Gui
3168  settingsTmp.endGroup(); //"name"
3169  settingsTmp.endGroup(); // Gui
3170  }
3171 }
3172 
3173 
3174 void PreferencesDialog::saveCustomConfig(const QString & section, const QString & key, const QString & value)
3175 {
3176  QSettings settings(getIniFilePath(), QSettings::IniFormat);
3177  settings.beginGroup("Gui");
3178  settings.beginGroup(section);
3179  settings.setValue(key, value);
3180  settings.endGroup(); // "section"
3181  settings.endGroup(); // rtabmap
3182 
3183  QSettings settingsTmp(getTmpIniFilePath(), QSettings::IniFormat);
3184  settingsTmp.beginGroup("Gui");
3185  settingsTmp.beginGroup(section);
3186  settingsTmp.setValue(key, value);
3187  settingsTmp.endGroup(); // "section"
3188  settingsTmp.endGroup(); // rtabmap
3189 }
3190 
3191 QString PreferencesDialog::loadCustomConfig(const QString & section, const QString & key)
3192 {
3193  QString value;
3194  QSettings settings(getIniFilePath(), QSettings::IniFormat);
3195  settings.beginGroup("Gui");
3196  settings.beginGroup(section);
3197  value = settings.value(key, QString()).toString();
3198  settings.endGroup(); // "section"
3199  settings.endGroup(); // rtabmap
3200 
3201  QSettings settingsTmp(getTmpIniFilePath(), QSettings::IniFormat);
3202  settingsTmp.beginGroup("Gui");
3203  settingsTmp.beginGroup(section);
3204  settingsTmp.setValue(key, value);
3205  settingsTmp.endGroup(); // "section"
3206  settingsTmp.endGroup(); // rtabmap
3207 
3208  return value;
3209 }
3210 
3212 {
3213  if(_parameters.size() != Parameters::getDefaultParameters().size())
3214  {
3215  UWARN("%d vs %d (Is PreferencesDialog::init() called?)", (int)_parameters.size(), (int)Parameters::getDefaultParameters().size());
3216  }
3217  ParametersMap parameters = _parameters;
3218  uInsert(parameters, _modifiedParameters);
3219 
3220  // It will be added manually for odometry
3221  parameters.erase(Parameters::kVisCorType());
3222 
3223  return parameters;
3224 }
3225 
3226 std::string PreferencesDialog::getParameter(const std::string & key) const
3227 {
3228  if(_modifiedParameters.find(key) != _modifiedParameters.end())
3229  {
3230  return _modifiedParameters.at(key);
3231  }
3232 
3233  UASSERT(_parameters.find(key) != _parameters.end());
3234  return _parameters.at(key);
3235 }
3236 
3237 void PreferencesDialog::updateParameters(const ParametersMap & parameters, bool setOtherParametersToDefault)
3238 {
3239  if(parameters.size())
3240  {
3241  for(rtabmap::ParametersMap::const_iterator iter = parameters.begin(); iter!=parameters.end(); ++iter)
3242  {
3243  this->setParameter(iter->first, iter->second);
3244  }
3245  if(setOtherParametersToDefault)
3246  {
3247  for(ParametersMap::const_iterator iter=Parameters::getDefaultParameters().begin();
3248  iter!=Parameters::getDefaultParameters().end();
3249  ++iter)
3250  {
3251  if(parameters.find(iter->first) == parameters.end() &&
3252  iter->first.compare(Parameters::kRtabmapWorkingDirectory())!=0)
3253  {
3254  this->setParameter(iter->first, iter->second);
3255  }
3256  }
3257  }
3258  if(!this->isVisible())
3259  {
3261  }
3262  }
3263 }
3264 
3266 {
3267  if(src >= kSrcRGBD && src<kSrcStereo)
3268  {
3269  _ui->comboBox_sourceType->setCurrentIndex(0);
3270  _ui->comboBox_cameraRGBD->setCurrentIndex(src - kSrcRGBD);
3271  if(src == kSrcOpenNI_PCL)
3272  {
3273  _ui->lineEdit_openniOniPath->clear();
3274  }
3275  else if(src == kSrcOpenNI2)
3276  {
3277  _ui->lineEdit_openni2OniPath->clear();
3278  }
3279  }
3280  else if(src >= kSrcStereo && src<kSrcRGB)
3281  {
3282  _ui->comboBox_sourceType->setCurrentIndex(1);
3283  _ui->comboBox_cameraStereo->setCurrentIndex(src - kSrcStereo);
3284  }
3285  else if(src >= kSrcRGB && src<kSrcDatabase)
3286  {
3287  _ui->comboBox_sourceType->setCurrentIndex(2);
3288  _ui->source_comboBox_image_type->setCurrentIndex(src - kSrcRGB);
3289  }
3290  else if(src >= kSrcDatabase)
3291  {
3292  _ui->comboBox_sourceType->setCurrentIndex(3);
3293  }
3294 
3295  if(validateForm())
3296  {
3297  // Even if there is no change, MainWindow should be notified
3299 
3301  }
3302  else
3303  {
3304  this->readSettingsBegin();
3305  }
3306 }
3307 
3308 bool sortCallback(const std::string & a, const std::string & b)
3309 {
3310  return uStrNumCmp(a,b) < 0;
3311 }
3312 
3314 {
3315  QString dir = _ui->source_database_lineEdit_path->text();
3316  if(dir.isEmpty())
3317  {
3318  dir = getWorkingDirectory();
3319  }
3320  QStringList paths = QFileDialog::getOpenFileNames(this, tr("Select file"), dir, tr("RTAB-Map database files (*.db)"));
3321  if(paths.size())
3322  {
3323  int r = QMessageBox::question(this, tr("Odometry in database..."), tr("Use odometry saved in database (if some saved)?"), QMessageBox::Yes | QMessageBox::No, QMessageBox::Yes);
3324  _ui->source_checkBox_ignoreOdometry->setChecked(r != QMessageBox::Yes);
3325 
3326  if (_ui->general_doubleSpinBox_detectionRate->value() != 0 && _ui->general_spinBox_imagesBufferSize->value() != 0)
3327  {
3328  r = QMessageBox::question(this, tr("Detection rate..."),
3329  tr("Do you want to process all frames? \n\nClicking \"Yes\" will set "
3330  "RTAB-Map's detection rate (%1 Hz) and buffer size (%2) to 0 to make "
3331  "sure that all frames are processed.")
3332  .arg(_ui->general_doubleSpinBox_detectionRate->value())
3333  .arg(_ui->general_spinBox_imagesBufferSize->value()),
3334  QMessageBox::Yes | QMessageBox::No, QMessageBox::Yes);
3335  if (r == QMessageBox::Yes)
3336  {
3337  _ui->general_doubleSpinBox_detectionRate->setValue(0.0);
3338  _ui->general_spinBox_imagesBufferSize->setValue(0);
3339  }
3340  }
3341 
3342  if(paths.size() > 1)
3343  {
3344  std::vector<std::string> vFileNames(paths.size());
3345  for(int i=0; i<paths.size(); ++i)
3346  {
3347  vFileNames[i] = paths[i].toStdString();
3348  }
3349  std::sort(vFileNames.begin(), vFileNames.end(), sortCallback);
3350  for(int i=0; i<paths.size(); ++i)
3351  {
3352  paths[i] = vFileNames[i].c_str();
3353  }
3354  }
3355 
3356  _ui->source_database_lineEdit_path->setText(paths.size()==1?paths.front():paths.join(";"));
3357  _ui->source_spinBox_databaseStartPos->setValue(0);
3358  _ui->source_spinBox_database_cameraIndex->setValue(-1);
3359  }
3360 }
3361 
3363 {
3364  DatabaseViewer * viewer = new DatabaseViewer(getIniFilePath(), this);
3365  viewer->setWindowModality(Qt::WindowModal);
3366  viewer->setAttribute(Qt::WA_DeleteOnClose, true);
3367  viewer->showCloseButton();
3368  if(viewer->openDatabase(_ui->source_database_lineEdit_path->text()))
3369  {
3370  viewer->show();
3371  }
3372  else
3373  {
3374  delete viewer;
3375  }
3376 }
3377 
3379 {
3380  if(!_ui->lineEdit_source_distortionModel->text().isEmpty() &&
3381  QFileInfo(_ui->lineEdit_source_distortionModel->text()).exists())
3382  {
3384  model.load(_ui->lineEdit_source_distortionModel->text().toStdString());
3385  if(model.isValid())
3386  {
3387  cv::Mat img = model.visualize();
3388  QString name = QFileInfo(_ui->lineEdit_source_distortionModel->text()).baseName()+".png";
3389  cv::imwrite(name.toStdString(), img);
3390  QDesktopServices::openUrl(QUrl::fromLocalFile(name));
3391  }
3392  else
3393  {
3394  QMessageBox::warning(this, tr("Distortion Model"), tr("Model loaded from \"%1\" is not valid!").arg(_ui->lineEdit_source_distortionModel->text()));
3395  }
3396  }
3397  else
3398  {
3399  QMessageBox::warning(this, tr("Distortion Model"), tr("File \"%1\" doesn't exist!").arg(_ui->lineEdit_source_distortionModel->text()));
3400  }
3401 }
3402 
3404 {
3405  QString dir = _ui->lineEdit_calibrationFile->text();
3406  if(dir.isEmpty())
3407  {
3408  dir = getWorkingDirectory()+"/camera_info";
3409  }
3410  else if(!dir.contains('.'))
3411  {
3412  dir = getWorkingDirectory()+"/camera_info/"+dir;
3413  }
3414  QString path = QFileDialog::getOpenFileName(this, tr("Select file"), dir, tr("Calibration file (*.yaml)"));
3415  if(path.size())
3416  {
3417  _ui->lineEdit_calibrationFile->setText(path);
3418  }
3419 }
3420 
3422 {
3423  QString dir = _ui->lineEdit_cameraImages_timestamps->text();
3424  if(dir.isEmpty())
3425  {
3426  dir = getWorkingDirectory();
3427  }
3428  QString path = QFileDialog::getOpenFileName(this, tr("Select file"), dir, tr("Timestamps file (*.txt)"));
3429  if(path.size())
3430  {
3431  _ui->lineEdit_cameraImages_timestamps->setText(path);
3432  }
3433 }
3434 
3436 {
3437  QString dir = _ui->lineEdit_cameraRGBDImages_path_rgb->text();
3438  if(dir.isEmpty())
3439  {
3440  dir = getWorkingDirectory();
3441  }
3442  QString path = QFileDialog::getExistingDirectory(this, tr("Select RGB images directory"), dir);
3443  if(path.size())
3444  {
3445  _ui->lineEdit_cameraRGBDImages_path_rgb->setText(path);
3446  }
3447 }
3448 
3449 
3451 {
3452  QString dir = _ui->lineEdit_cameraImages_path_scans->text();
3453  if(dir.isEmpty())
3454  {
3455  dir = getWorkingDirectory();
3456  }
3457  QString path = QFileDialog::getExistingDirectory(this, tr("Select scans directory"), dir);
3458  if(path.size())
3459  {
3460  _ui->lineEdit_cameraImages_path_scans->setText(path);
3461  }
3462 }
3463 
3465 {
3466  QString dir = _ui->lineEdit_cameraImages_path_imu->text();
3467  if(dir.isEmpty())
3468  {
3469  dir = getWorkingDirectory();
3470  }
3471  QString path = QFileDialog::getOpenFileName(this, tr("Select file "), dir, tr("EuRoC IMU file (*.csv)"));
3472  if(path.size())
3473  {
3474  _ui->lineEdit_cameraImages_path_imu->setText(path);
3475  }
3476 }
3477 
3478 
3480 {
3481  QString dir = _ui->lineEdit_cameraRGBDImages_path_depth->text();
3482  if(dir.isEmpty())
3483  {
3484  dir = getWorkingDirectory();
3485  }
3486  QString path = QFileDialog::getExistingDirectory(this, tr("Select depth images directory"), dir);
3487  if(path.size())
3488  {
3489  _ui->lineEdit_cameraRGBDImages_path_depth->setText(path);
3490  }
3491 }
3492 
3494 {
3495  QString dir = _ui->lineEdit_cameraImages_odom->text();
3496  if(dir.isEmpty())
3497  {
3498  dir = getWorkingDirectory();
3499  }
3500  QString path = QFileDialog::getOpenFileName(this, tr("Select file"), dir, tr("Odometry (*.txt *.log *.toro *.g2o *.csv)"));
3501  if(path.size())
3502  {
3503  QStringList list;
3504  for(int i=0; i<_ui->comboBox_cameraImages_odomFormat->count(); ++i)
3505  {
3506  list.push_back(_ui->comboBox_cameraImages_odomFormat->itemText(i));
3507  }
3508  QString item = QInputDialog::getItem(this, tr("Odometry Format"), tr("Format:"), list, _ui->comboBox_cameraImages_odomFormat->currentIndex(), false);
3509  if(!item.isEmpty())
3510  {
3511  _ui->lineEdit_cameraImages_odom->setText(path);
3512  _ui->comboBox_cameraImages_odomFormat->setCurrentIndex(_ui->comboBox_cameraImages_odomFormat->findText(item));
3513  }
3514  }
3515 }
3516 
3518 {
3519  QString dir = _ui->lineEdit_cameraImages_gt->text();
3520  if(dir.isEmpty())
3521  {
3522  dir = getWorkingDirectory();
3523  }
3524  QString path = QFileDialog::getOpenFileName(this, tr("Select file"), dir, tr("Ground Truth (*.txt *.log *.toro *.g2o *.csv)"));
3525  if(path.size())
3526  {
3527  QStringList list;
3528  for(int i=0; i<_ui->comboBox_cameraImages_gtFormat->count(); ++i)
3529  {
3530  list.push_back(_ui->comboBox_cameraImages_gtFormat->itemText(i));
3531  }
3532  QString item = QInputDialog::getItem(this, tr("Ground Truth Format"), tr("Format:"), list, _ui->comboBox_cameraImages_gtFormat->currentIndex(), false);
3533  if(!item.isEmpty())
3534  {
3535  _ui->lineEdit_cameraImages_gt->setText(path);
3536  _ui->comboBox_cameraImages_gtFormat->setCurrentIndex(_ui->comboBox_cameraImages_gtFormat->findText(item));
3537  }
3538  }
3539 }
3540 
3542 {
3543  QString dir = _ui->lineEdit_cameraStereoImages_path_left->text();
3544  if(dir.isEmpty())
3545  {
3546  dir = getWorkingDirectory();
3547  }
3548  QString path = QFileDialog::getExistingDirectory(this, tr("Select left images directory"), dir);
3549  if(path.size())
3550  {
3551  _ui->lineEdit_cameraStereoImages_path_left->setText(path);
3552  }
3553 }
3554 
3556 {
3557  QString dir = _ui->lineEdit_cameraStereoImages_path_right->text();
3558  if(dir.isEmpty())
3559  {
3560  dir = getWorkingDirectory();
3561  }
3562  QString path = QFileDialog::getExistingDirectory(this, tr("Select right images directory"), dir);
3563  if(path.size())
3564  {
3565  _ui->lineEdit_cameraStereoImages_path_right->setText(path);
3566  }
3567 }
3568 
3570 {
3571  QString dir = _ui->source_images_lineEdit_path->text();
3572  if(dir.isEmpty())
3573  {
3574  dir = getWorkingDirectory();
3575  }
3576  QString path = QFileDialog::getExistingDirectory(this, tr("Select images directory"), _ui->source_images_lineEdit_path->text());
3577  if(!path.isEmpty())
3578  {
3579  _ui->source_images_lineEdit_path->setText(path);
3580  _ui->source_images_spinBox_startPos->setValue(0);
3581  }
3582 }
3583 
3585 {
3586  QString dir = _ui->source_video_lineEdit_path->text();
3587  if(dir.isEmpty())
3588  {
3589  dir = getWorkingDirectory();
3590  }
3591  QString path = QFileDialog::getOpenFileName(this, tr("Select file"), _ui->source_video_lineEdit_path->text(), tr("Videos (*.avi *.mpg *.mp4 *.mov *.mkv)"));
3592  if(!path.isEmpty())
3593  {
3594  _ui->source_video_lineEdit_path->setText(path);
3595  }
3596 }
3597 
3599 {
3600  QString dir = _ui->lineEdit_cameraStereoVideo_path->text();
3601  if(dir.isEmpty())
3602  {
3603  dir = getWorkingDirectory();
3604  }
3605  QString path = QFileDialog::getOpenFileName(this, tr("Select file"), _ui->lineEdit_cameraStereoVideo_path->text(), tr("Videos (*.avi *.mpg *.mp4 *.mov *.mkv)"));
3606  if(!path.isEmpty())
3607  {
3608  _ui->lineEdit_cameraStereoVideo_path->setText(path);
3609  }
3610 }
3611 
3613 {
3614  QString dir = _ui->lineEdit_cameraStereoVideo_path_2->text();
3615  if(dir.isEmpty())
3616  {
3617  dir = getWorkingDirectory();
3618  }
3619  QString path = QFileDialog::getOpenFileName(this, tr("Select file"), _ui->lineEdit_cameraStereoVideo_path_2->text(), tr("Videos (*.avi *.mpg *.mp4 *.mov *.mkv)"));
3620  if(!path.isEmpty())
3621  {
3622  _ui->lineEdit_cameraStereoVideo_path_2->setText(path);
3623  }
3624 }
3625 
3627 {
3628  QString dir = _ui->lineEdit_source_distortionModel->text();
3629  if(dir.isEmpty())
3630  {
3631  dir = getWorkingDirectory();
3632  }
3633  QString path = QFileDialog::getOpenFileName(this, tr("Select file"), _ui->lineEdit_source_distortionModel->text(), tr("Distortion model (*.bin *.txt)"));
3634  if(!path.isEmpty())
3635  {
3636  _ui->lineEdit_source_distortionModel->setText(path);
3637  }
3638 }
3639 
3641 {
3642  QString dir = _ui->lineEdit_openniOniPath->text();
3643  if(dir.isEmpty())
3644  {
3645  dir = getWorkingDirectory();
3646  }
3647  QString path = QFileDialog::getOpenFileName(this, tr("Select file"), _ui->lineEdit_openniOniPath->text(), tr("OpenNI (*.oni)"));
3648  if(!path.isEmpty())
3649  {
3650  _ui->lineEdit_openniOniPath->setText(path);
3651  }
3652 }
3653 
3655 {
3656  QString dir = _ui->lineEdit_openni2OniPath->text();
3657  if(dir.isEmpty())
3658  {
3659  dir = getWorkingDirectory();
3660  }
3661  QString path = QFileDialog::getOpenFileName(this, tr("Select file"), _ui->lineEdit_openni2OniPath->text(), tr("OpenNI (*.oni)"));
3662  if(!path.isEmpty())
3663  {
3664  _ui->lineEdit_openni2OniPath->setText(path);
3665  }
3666 }
3667 
3669 {
3670  QString dir = _ui->lineEdit_zedSvoPath->text();
3671  if(dir.isEmpty())
3672  {
3673  dir = getWorkingDirectory();
3674  }
3675  QString path = QFileDialog::getOpenFileName(this, tr("Select file"), _ui->lineEdit_zedSvoPath->text(), tr("ZED (*.svo)"));
3676  if(!path.isEmpty())
3677  {
3678  _ui->lineEdit_zedSvoPath->setText(path);
3679  }
3680 }
3681 
3682 void PreferencesDialog::setParameter(const std::string & key, const std::string & value)
3683 {
3684  UDEBUG("%s=%s", key.c_str(), value.c_str());
3685  QWidget * obj = _ui->stackedWidget->findChild<QWidget*>(key.c_str());
3686  if(obj)
3687  {
3688  uInsert(_parameters, ParametersPair(key, value));
3689 
3690  QSpinBox * spin = qobject_cast<QSpinBox *>(obj);
3691  QDoubleSpinBox * doubleSpin = qobject_cast<QDoubleSpinBox *>(obj);
3692  QComboBox * combo = qobject_cast<QComboBox *>(obj);
3693  QCheckBox * check = qobject_cast<QCheckBox *>(obj);
3694  QRadioButton * radio = qobject_cast<QRadioButton *>(obj);
3695  QLineEdit * lineEdit = qobject_cast<QLineEdit *>(obj);
3696  QGroupBox * groupBox = qobject_cast<QGroupBox *>(obj);
3697  bool ok;
3698  if(spin)
3699  {
3700  spin->setValue(QString(value.c_str()).toInt(&ok));
3701  if(!ok)
3702  {
3703  UERROR("Conversion failed from \"%s\" for parameter %s", value.c_str(), key.c_str());
3704  }
3705  }
3706  else if(doubleSpin)
3707  {
3708  doubleSpin->setValue(QString(value.c_str()).toDouble(&ok));
3709  if(!ok)
3710  {
3711  UERROR("Conversion failed from \"%s\" for parameter %s", value.c_str(), key.c_str());
3712  }
3713  }
3714  else if(combo)
3715  {
3716  int valueInt = QString(value.c_str()).toInt(&ok);
3717  if(!ok)
3718  {
3719  UERROR("Conversion failed from \"%s\" for parameter %s", value.c_str(), key.c_str());
3720  }
3721  else
3722  {
3723 #ifndef RTABMAP_NONFREE
3724  if(valueInt <= 1 &&
3725  (combo->objectName().toStdString().compare(Parameters::kKpDetectorStrategy()) == 0 ||
3726  combo->objectName().toStdString().compare(Parameters::kVisFeatureType()) == 0))
3727  {
3728  UWARN("Trying to set \"%s\" to SIFT/SURF but RTAB-Map isn't built "
3729  "with the nonfree module from OpenCV. Keeping default combo value: %s.",
3730  combo->objectName().toStdString().c_str(),
3731  combo->currentText().toStdString().c_str());
3732  ok = false;
3733  }
3734 #endif
3735 #ifndef RTABMAP_ORB_SLAM2
3737 #endif
3738  {
3739  if(valueInt==1 && combo->objectName().toStdString().compare(Parameters::kOptimizerStrategy()) == 0)
3740  {
3741  UWARN("Trying to set \"%s\" to g2o but RTAB-Map isn't built "
3742  "with g2o. Keeping default combo value: %s.",
3743  combo->objectName().toStdString().c_str(),
3744  combo->currentText().toStdString().c_str());
3745  ok = false;
3746  }
3747  }
3749  {
3750  if(valueInt==2 && combo->objectName().toStdString().compare(Parameters::kOptimizerStrategy()) == 0)
3751  {
3752  UWARN("Trying to set \"%s\" to GTSAM but RTAB-Map isn't built "
3753  "with GTSAM. Keeping default combo value: %s.",
3754  combo->objectName().toStdString().c_str(),
3755  combo->currentText().toStdString().c_str());
3756  ok = false;
3757  }
3758  }
3759  if(ok)
3760  {
3761  combo->setCurrentIndex(valueInt);
3762  }
3763  }
3764 
3765  }
3766  else if(check)
3767  {
3768  _ui->checkBox_useOdomFeatures->blockSignals(true);
3769  check->setChecked(uStr2Bool(value.c_str()));
3770  _ui->checkBox_useOdomFeatures->blockSignals(false);
3771  }
3772  else if(radio)
3773  {
3774  radio->setChecked(uStr2Bool(value.c_str()));
3775  }
3776  else if(lineEdit)
3777  {
3778  lineEdit->setText(value.c_str());
3779  }
3780  else if(groupBox)
3781  {
3782  groupBox->setChecked(uStr2Bool(value.c_str()));
3783  }
3784  else
3785  {
3786  ULOGGER_WARN("QObject called %s can't be cast to a supported widget", key.c_str());
3787  }
3788  }
3789  else
3790  {
3791  ULOGGER_WARN("Can't find the related QObject for parameter %s", key.c_str());
3792  }
3793 }
3794 
3796 {
3797  if(sender())
3798  {
3799  this->addParameter(sender(), value);
3800  }
3801  else
3802  {
3803  ULOGGER_ERROR("This slot must be triggered by a signal, not a direct call...");
3804  }
3805 }
3806 
3808 {
3809  if(sender())
3810  {
3811  this->addParameter(sender(), value);
3812  }
3813  else
3814  {
3815  ULOGGER_ERROR("This slot must be triggered by a signal, not a direct call...");
3816  }
3817 }
3818 
3820 {
3821  if(sender())
3822  {
3823  this->addParameter(sender(), value);
3824  }
3825  else
3826  {
3827  ULOGGER_ERROR("This slot must be triggered by a signal, not a direct call...");
3828  }
3829 }
3830 
3831 void PreferencesDialog::addParameter(const QString & value)
3832 {
3833  if(sender())
3834  {
3835  this->addParameter(sender(), value);
3836  }
3837  else
3838  {
3839  ULOGGER_ERROR("This slot must be triggered by a signal, not a direct call...");
3840  }
3841 }
3842 
3843 void PreferencesDialog::addParameter(const QObject * object, int value)
3844 {
3845  if(object)
3846  {
3847  const QComboBox * comboBox = qobject_cast<const QComboBox*>(object);
3848  const QSpinBox * spinbox = qobject_cast<const QSpinBox*>(object);
3849  if(comboBox || spinbox)
3850  {
3851  // Add parameter
3852  UDEBUG("modify param %s=%s", object->objectName().toStdString().c_str(), uNumber2Str(value).c_str());
3853  uInsert(_modifiedParameters, rtabmap::ParametersPair(object->objectName().toStdString(), QString::number(value).toStdString()));
3854  }
3855  else
3856  {
3857  UWARN("Undefined object \"%s\"", object->objectName().toStdString().c_str());
3858  }
3859 
3860  }
3861  else
3862  {
3863  ULOGGER_ERROR("Object is null");
3864  }
3865 }
3866 
3867 void PreferencesDialog::addParameter(const QObject * object, bool value)
3868 {
3869  if(object)
3870  {
3871  const QCheckBox * checkbox = qobject_cast<const QCheckBox*>(object);
3872  const QRadioButton * radio = qobject_cast<const QRadioButton*>(object);
3873  const QGroupBox * groupBox = qobject_cast<const QGroupBox*>(object);
3874  if(checkbox || radio || groupBox)
3875  {
3876  // Add parameter
3877  UDEBUG("modify param %s=%s", object->objectName().toStdString().c_str(), uBool2Str(value).c_str());
3878  uInsert(_modifiedParameters, rtabmap::ParametersPair(object->objectName().toStdString(), uBool2Str(value)));
3879  }
3880  else
3881  {
3882  UWARN("Undefined object \"%s\"", object->objectName().toStdString().c_str());
3883  }
3884 
3885  }
3886  else
3887  {
3888  ULOGGER_ERROR("Object is null");
3889  }
3890 }
3891 
3892 void PreferencesDialog::addParameter(const QObject * object, double value)
3893 {
3894  if(object)
3895  {
3896  UDEBUG("modify param %s=%f", object->objectName().toStdString().c_str(), value);
3897  uInsert(_modifiedParameters, rtabmap::ParametersPair(object->objectName().toStdString(), QString::number(value).toStdString()));
3898  }
3899  else
3900  {
3901  ULOGGER_ERROR("Object is null");
3902  }
3903 }
3904 
3905 void PreferencesDialog::addParameter(const QObject * object, const QString & value)
3906 {
3907  if(object)
3908  {
3909  UDEBUG("modify param %s=%s", object->objectName().toStdString().c_str(), value.toStdString().c_str());
3910  uInsert(_modifiedParameters, rtabmap::ParametersPair(object->objectName().toStdString(), value.toStdString()));
3911  }
3912  else
3913  {
3914  ULOGGER_ERROR("Object is null");
3915  }
3916 }
3917 
3918 void PreferencesDialog::addParameters(const QObjectList & children)
3919 {
3920  //ULOGGER_DEBUG("PreferencesDialog::addParameters(QGroupBox) box %s has %d children", box->objectName().toStdString().c_str(), children.size());
3921  for(int i=0; i<children.size(); ++i)
3922  {
3923  const QSpinBox * spin = qobject_cast<const QSpinBox *>(children[i]);
3924  const QDoubleSpinBox * doubleSpin = qobject_cast<const QDoubleSpinBox *>(children[i]);
3925  const QComboBox * combo = qobject_cast<const QComboBox *>(children[i]);
3926  const QCheckBox * check = qobject_cast<const QCheckBox *>(children[i]);
3927  const QRadioButton * radio = qobject_cast<const QRadioButton *>(children[i]);
3928  const QLineEdit * lineEdit = qobject_cast<const QLineEdit *>(children[i]);
3929  const QGroupBox * groupBox = qobject_cast<const QGroupBox *>(children[i]);
3930  const QStackedWidget * stackedWidget = qobject_cast<const QStackedWidget *>(children[i]);
3931  if(spin)
3932  {
3933  this->addParameter(spin, spin->value());
3934  }
3935  else if(doubleSpin)
3936  {
3937  this->addParameter(doubleSpin, doubleSpin->value());
3938  }
3939  else if(combo)
3940  {
3941  this->addParameter(combo, combo->currentIndex());
3942  }
3943  else if(check)
3944  {
3945  this->addParameter(check, check->isChecked());
3946  }
3947  else if(radio)
3948  {
3949  this->addParameter(radio, radio->isChecked());
3950  }
3951  else if(lineEdit)
3952  {
3953  this->addParameter(lineEdit, lineEdit->text());
3954  }
3955  else if(groupBox)
3956  {
3957  if(groupBox->isCheckable())
3958  {
3959  this->addParameter(groupBox, groupBox->isChecked());
3960  }
3961  else
3962  {
3963  this->addParameters(groupBox);
3964  }
3965  }
3966  else if(stackedWidget)
3967  {
3968  this->addParameters(stackedWidget);
3969  }
3970  }
3971 }
3972 
3973 void PreferencesDialog::addParameters(const QStackedWidget * stackedWidget, int panel)
3974 {
3975  if(stackedWidget)
3976  {
3977  if(panel == -1)
3978  {
3979  for(int i=0; i<stackedWidget->count(); ++i)
3980  {
3981  const QObjectList & children = stackedWidget->widget(i)->children();
3982  addParameters(children);
3983  }
3984  }
3985  else
3986  {
3987  UASSERT(panel<stackedWidget->count());
3988  const QObjectList & children = stackedWidget->widget(panel)->children();
3989  addParameters(children);
3990  }
3991  }
3992 }
3993 
3994 void PreferencesDialog::addParameters(const QGroupBox * box)
3995 {
3996  if(box)
3997  {
3998  const QObjectList & children = box->children();
3999  addParameters(children);
4000  }
4001 }
4002 
4004 {
4005  // This method is used to update basic/advanced referred parameters, see above editingFinished()
4006 
4007  // basic to advanced (advanced to basic must be done by connecting signal valueChanged())
4008  if(sender() == _ui->general_doubleSpinBox_timeThr_2)
4009  {
4010  _ui->general_doubleSpinBox_timeThr->setValue(_ui->general_doubleSpinBox_timeThr_2->value());
4011  }
4012  else if(sender() == _ui->general_doubleSpinBox_hardThr_2)
4013  {
4014  _ui->general_doubleSpinBox_hardThr->setValue(_ui->general_doubleSpinBox_hardThr_2->value());
4015  }
4016  else if(sender() == _ui->general_doubleSpinBox_detectionRate_2)
4017  {
4018  _ui->general_doubleSpinBox_detectionRate->setValue(_ui->general_doubleSpinBox_detectionRate_2->value());
4019  }
4020  else if(sender() == _ui->general_spinBox_imagesBufferSize_2)
4021  {
4022  _ui->general_spinBox_imagesBufferSize->setValue(_ui->general_spinBox_imagesBufferSize_2->value());
4023  }
4024  else if(sender() == _ui->general_spinBox_maxStMemSize_2)
4025  {
4026  _ui->general_spinBox_maxStMemSize->setValue(_ui->general_spinBox_maxStMemSize_2->value());
4027  }
4028  else if(sender() == _ui->groupBox_publishing)
4029  {
4030  _ui->general_checkBox_publishStats_2->setChecked(_ui->groupBox_publishing->isChecked());
4031  }
4032  else if(sender() == _ui->general_checkBox_publishStats_2)
4033  {
4034  _ui->groupBox_publishing->setChecked(_ui->general_checkBox_publishStats_2->isChecked());
4035  }
4036  else if(sender() == _ui->doubleSpinBox_similarityThreshold_2)
4037  {
4038  _ui->doubleSpinBox_similarityThreshold->setValue(_ui->doubleSpinBox_similarityThreshold_2->value());
4039  }
4040  else if(sender() == _ui->general_checkBox_activateRGBD)
4041  {
4042  _ui->general_checkBox_activateRGBD_2->setChecked(_ui->general_checkBox_activateRGBD->isChecked());
4043  }
4044  else if(sender() == _ui->general_checkBox_activateRGBD_2)
4045  {
4046  _ui->general_checkBox_activateRGBD->setChecked(_ui->general_checkBox_activateRGBD_2->isChecked());
4047  }
4048  else if(sender() == _ui->general_checkBox_SLAM_mode)
4049  {
4050  _ui->general_checkBox_SLAM_mode_2->setChecked(_ui->general_checkBox_SLAM_mode->isChecked());
4051  }
4052  else if(sender() == _ui->general_checkBox_SLAM_mode_2)
4053  {
4054  _ui->general_checkBox_SLAM_mode->setChecked(_ui->general_checkBox_SLAM_mode_2->isChecked());
4055  }
4056  else
4057  {
4058  //update all values (only those using editingFinished signal)
4059  _ui->general_doubleSpinBox_timeThr->setValue(_ui->general_doubleSpinBox_timeThr_2->value());
4060  _ui->general_doubleSpinBox_hardThr->setValue(_ui->general_doubleSpinBox_hardThr_2->value());
4061  _ui->general_doubleSpinBox_detectionRate->setValue(_ui->general_doubleSpinBox_detectionRate_2->value());
4062  _ui->general_spinBox_imagesBufferSize->setValue(_ui->general_spinBox_imagesBufferSize_2->value());
4063  _ui->general_spinBox_maxStMemSize->setValue(_ui->general_spinBox_maxStMemSize_2->value());
4064  _ui->doubleSpinBox_similarityThreshold->setValue(_ui->doubleSpinBox_similarityThreshold_2->value());
4065  }
4066 }
4067 
4069 {
4070  ULOGGER_DEBUG("");
4072 }
4073 
4075 {
4076  ULOGGER_DEBUG("");
4078 }
4079 
4081 {
4082  ULOGGER_DEBUG("");
4084 }
4085 
4087 {
4089 }
4090 
4092 {
4093  QList<QGroupBox*> boxes;
4094  for(int i=0; i<_ui->stackedWidget->count(); ++i)
4095  {
4096  QGroupBox * gb = 0;
4097  const QObjectList & children = _ui->stackedWidget->widget(i)->children();
4098  for(int j=0; j<children.size(); ++j)
4099  {
4100  if((gb = qobject_cast<QGroupBox *>(children.at(j))))
4101  {
4102  //ULOGGER_DEBUG("PreferencesDialog::setupTreeView() index(%d) Added %s, box name=%s", i, gb->title().toStdString().c_str(), gb->objectName().toStdString().c_str());
4103  break;
4104  }
4105  }
4106  if(gb)
4107  {
4108  boxes.append(gb);
4109  }
4110  else
4111  {
4112  ULOGGER_ERROR("A QGroupBox must be included in the first level of children in stacked widget, index=%d", i);
4113  }
4114  }
4115  return boxes;
4116 }
4117 
4119 {
4120  QStringList values = _ui->lineEdit_bayes_predictionLC->text().simplified().split(' ');
4121  if(values.size() < 2)
4122  {
4123  UERROR("Error parsing prediction (must have at least 2 items) : %s",
4124  _ui->lineEdit_bayes_predictionLC->text().toStdString().c_str());
4125  return;
4126  }
4127  QVector<float> dataX((values.size()-2)*2 + 1);
4128  QVector<float> dataY((values.size()-2)*2 + 1);
4129  double value;
4130  double sum = 0;
4131  int lvl = 1;
4132  bool ok = false;
4133  bool error = false;
4134  int loopClosureIndex = (dataX.size()-1)/2;
4135  for(int i=0; i<values.size(); ++i)
4136  {
4137  value = values.at(i).toDouble(&ok);
4138  if(!ok)
4139  {
4140  UERROR("Error parsing prediction : \"%s\"", values.at(i).toStdString().c_str());
4141  error = true;
4142  }
4143  sum+=value;
4144  if(i==0)
4145  {
4146  //do nothing
4147  }
4148  else if(i == 1)
4149  {
4150  dataY[loopClosureIndex] = value;
4151  dataX[loopClosureIndex] = 0;
4152  }
4153  else
4154  {
4155  dataY[loopClosureIndex-lvl] = value;
4156  dataX[loopClosureIndex-lvl] = -lvl;
4157  dataY[loopClosureIndex+lvl] = value;
4158  dataX[loopClosureIndex+lvl] = lvl;
4159  ++lvl;
4160  }
4161  }
4162 
4163  _ui->label_prediction_sum->setNum(sum);
4164  if(error)
4165  {
4166  _ui->label_prediction_sum->setText(QString("<font color=#FF0000>") + _ui->label_prediction_sum->text() + "</font>");
4167  }
4168  else if(sum == 1.0)
4169  {
4170  _ui->label_prediction_sum->setText(QString("<font color=#00FF00>") + _ui->label_prediction_sum->text() + "</font>");
4171  }
4172  else if(sum > 1.0)
4173  {
4174  _ui->label_prediction_sum->setText(QString("<font color=#FFa500>") + _ui->label_prediction_sum->text() + "</font>");
4175  }
4176  else
4177  {
4178  _ui->label_prediction_sum->setText(QString("<font color=#000000>") + _ui->label_prediction_sum->text() + "</font>");
4179  }
4180 
4181  _ui->predictionPlot->removeCurves();
4182  _ui->predictionPlot->addCurve(new UPlotCurve("Prediction", dataX, dataY, _ui->predictionPlot));
4183 }
4184 
4186 {
4187  QStringList strings = _ui->lineEdit_kp_roi->text().split(' ');
4188  if(strings.size()!=4)
4189  {
4190  UERROR("ROI must have 4 values (%s)", _ui->lineEdit_kp_roi->text().toStdString().c_str());
4191  return;
4192  }
4193  _ui->doubleSpinBox_kp_roi0->setValue(strings[0].toDouble()*100.0);
4194  _ui->doubleSpinBox_kp_roi1->setValue(strings[1].toDouble()*100.0);
4195  _ui->doubleSpinBox_kp_roi2->setValue(strings[2].toDouble()*100.0);
4196  _ui->doubleSpinBox_kp_roi3->setValue(strings[3].toDouble()*100.0);
4197 }
4198 
4200 {
4201  QStringList strings;
4202  strings.append(QString::number(_ui->doubleSpinBox_kp_roi0->value()/100.0));
4203  strings.append(QString::number(_ui->doubleSpinBox_kp_roi1->value()/100.0));
4204  strings.append(QString::number(_ui->doubleSpinBox_kp_roi2->value()/100.0));
4205  strings.append(QString::number(_ui->doubleSpinBox_kp_roi3->value()/100.0));
4206  _ui->lineEdit_kp_roi->setText(strings.join(" "));
4207 }
4208 
4210 {
4211  Src driver = this->getSourceDriver();
4212  _ui->checkbox_stereo_depthGenerated->setVisible(
4214  _ui->comboBox_stereoZed_quality->currentIndex() == 0);
4215  _ui->label_stereo_depthGenerated->setVisible(
4217  _ui->comboBox_stereoZed_quality->currentIndex() == 0);
4218 
4219  _ui->checkBox_stereo_rectify->setEnabled(
4220  _ui->comboBox_cameraStereo->currentIndex() == kSrcStereoImages - kSrcStereo ||
4221  _ui->comboBox_cameraStereo->currentIndex() == kSrcStereoUsb - kSrcStereo ||
4222  _ui->comboBox_cameraStereo->currentIndex() == kSrcStereoVideo - kSrcStereo ||
4223  _ui->comboBox_cameraStereo->currentIndex() == kSrcDC1394 - kSrcStereo);
4224  _ui->checkBox_stereo_rectify->setVisible(_ui->checkBox_stereo_rectify->isEnabled());
4225  _ui->label_stereo_rectify->setVisible(_ui->checkBox_stereo_rectify->isEnabled());
4226 }
4227 
4229 {
4230  if(this->isVisible() && _ui->checkBox_useOdomFeatures->isChecked())
4231  {
4232  int r = QMessageBox::question(this, tr("Using odometry features for vocabulary..."),
4233  tr("Do you want to match vocabulary feature parameters "
4234  "with corresponding ones used for odometry?"), QMessageBox::Yes | QMessageBox::No, QMessageBox::Yes);
4235 
4236  if(r == QMessageBox::Yes)
4237  {
4238  _ui->comboBox_detector_strategy->setCurrentIndex(_ui->reextract_type->currentIndex());
4239  _ui->surf_doubleSpinBox_maxDepth->setValue(_ui->loopClosure_bowMaxDepth->value());
4240  _ui->surf_doubleSpinBox_minDepth->setValue(_ui->loopClosure_bowMinDepth->value());
4241  _ui->surf_spinBox_wordsPerImageTarget->setValue(_ui->reextract_maxFeatures->value());
4242  _ui->spinBox_KPGridRows->setValue(_ui->reextract_gridrows->value());
4243  _ui->spinBox_KPGridCols->setValue(_ui->reextract_gridcols->value());
4244  _ui->lineEdit_kp_roi->setText(_ui->loopClosure_roi->text());
4245  _ui->subpix_winSize_kp->setValue(_ui->subpix_winSize->value());
4246  _ui->subpix_iterations_kp->setValue(_ui->subpix_iterations->value());
4247  _ui->subpix_eps_kp->setValue(_ui->subpix_eps->value());
4248  }
4249  }
4250 }
4251 
4253 {
4254  QString directory = QFileDialog::getExistingDirectory(this, tr("Working directory"), _ui->lineEdit_workingDirectory->text());
4255  if(!directory.isEmpty())
4256  {
4257  ULOGGER_DEBUG("New working directory = %s", directory.toStdString().c_str());
4258  _ui->lineEdit_workingDirectory->setText(directory);
4259  }
4260 }
4261 
4263 {
4264  QString path;
4265  if(_ui->lineEdit_dictionaryPath->text().isEmpty())
4266  {
4267  path = QFileDialog::getOpenFileName(this, tr("Dictionary"), this->getWorkingDirectory(), tr("Dictionary (*.txt *.db)"));
4268  }
4269  else
4270  {
4271  path = QFileDialog::getOpenFileName(this, tr("Dictionary"), _ui->lineEdit_dictionaryPath->text(), tr("Dictionary (*.txt *.db)"));
4272  }
4273  if(!path.isEmpty())
4274  {
4275  _ui->lineEdit_dictionaryPath->setText(path);
4276  }
4277 }
4278 
4280 {
4281  QString path;
4282  if(_ui->lineEdit_OdomORBSLAM2VocPath->text().isEmpty())
4283  {
4284  path = QFileDialog::getOpenFileName(this, tr("ORBSLAM2 Vocabulary"), this->getWorkingDirectory(), tr("Vocabulary (*.txt)"));
4285  }
4286  else
4287  {
4288  path = QFileDialog::getOpenFileName(this, tr("ORBSLAM2 Vocabulary"), _ui->lineEdit_OdomORBSLAM2VocPath->text(), tr("Vocabulary (*.txt)"));
4289  }
4290  if(!path.isEmpty())
4291  {
4292  _ui->lineEdit_OdomORBSLAM2VocPath->setText(path);
4293  }
4294 }
4295 
4297 {
4298  QString path;
4299  if(_ui->lineEdit_OdomOkvisPath->text().isEmpty())
4300  {
4301  path = QFileDialog::getOpenFileName(this, tr("OKVIS Config"), this->getWorkingDirectory(), tr("OKVIS config (*.yaml)"));
4302  }
4303  else
4304  {
4305  path = QFileDialog::getOpenFileName(this, tr("OKVIS Config"), _ui->lineEdit_OdomOkvisPath->text(), tr("OKVIS config (*.yaml)"));
4306  }
4307  if(!path.isEmpty())
4308  {
4309  _ui->lineEdit_OdomOkvisPath->setText(path);
4310  }
4311 }
4312 
4314 {
4315  QString path;
4316  if(_ui->lineEdit_IcpPMConfigPath->text().isEmpty())
4317  {
4318  path = QFileDialog::getOpenFileName(this, tr("Select file"), this->getWorkingDirectory(), tr("libpointmatcher (*.yaml)"));
4319  }
4320  else
4321  {
4322  path = QFileDialog::getOpenFileName(this, tr("Select file"), _ui->lineEdit_IcpPMConfigPath->text(), tr("libpointmatcher (*.yaml)"));
4323  }
4324  if(!path.isEmpty())
4325  {
4326  _ui->lineEdit_IcpPMConfigPath->setText(path);
4327  }
4328 }
4329 
4331 {
4332  _ui->groupBox_sourceRGBD->setVisible(_ui->comboBox_sourceType->currentIndex() == 0);
4333  _ui->groupBox_sourceStereo->setVisible(_ui->comboBox_sourceType->currentIndex() == 1);
4334  _ui->groupBox_sourceRGB->setVisible(_ui->comboBox_sourceType->currentIndex() == 2);
4335  _ui->groupBox_sourceDatabase->setVisible(_ui->comboBox_sourceType->currentIndex() == 3);
4336 
4337  _ui->groupBox_scanFromDepth->setVisible(_ui->comboBox_sourceType->currentIndex() <= 1 || _ui->comboBox_sourceType->currentIndex() == 3);
4338 
4339  _ui->stackedWidget_rgbd->setVisible(_ui->comboBox_sourceType->currentIndex() == 0 &&
4340  (_ui->comboBox_cameraRGBD->currentIndex() == kSrcOpenNI2-kSrcRGBD ||
4341  _ui->comboBox_cameraRGBD->currentIndex() == kSrcFreenect2-kSrcRGBD ||
4342  _ui->comboBox_cameraRGBD->currentIndex() == kSrcK4W2 - kSrcRGBD ||
4343  _ui->comboBox_cameraRGBD->currentIndex() == kSrcRealSense - kSrcRGBD ||
4344  _ui->comboBox_cameraRGBD->currentIndex() == kSrcRGBDImages-kSrcRGBD ||
4345  _ui->comboBox_cameraRGBD->currentIndex() == kSrcOpenNI_PCL-kSrcRGBD ||
4346  _ui->comboBox_cameraRGBD->currentIndex() == kSrcRealSense2-kSrcRGBD));
4347  _ui->groupBox_openni2->setVisible(_ui->comboBox_sourceType->currentIndex() == 0 && _ui->comboBox_cameraRGBD->currentIndex() == kSrcOpenNI2-kSrcRGBD);
4348  _ui->groupBox_freenect2->setVisible(_ui->comboBox_sourceType->currentIndex() == 0 && _ui->comboBox_cameraRGBD->currentIndex() == kSrcFreenect2-kSrcRGBD);
4349  _ui->groupBox_k4w2->setVisible(_ui->comboBox_sourceType->currentIndex() == 0 && _ui->comboBox_cameraRGBD->currentIndex() == kSrcK4W2 - kSrcRGBD);
4350  _ui->groupBox_realsense->setVisible(_ui->comboBox_sourceType->currentIndex() == 0 && _ui->comboBox_cameraRGBD->currentIndex() == kSrcRealSense - kSrcRGBD);
4351  _ui->groupBox_realsense2->setVisible(_ui->comboBox_sourceType->currentIndex() == 0 && _ui->comboBox_cameraRGBD->currentIndex() == kSrcRealSense2 - kSrcRGBD);
4352  _ui->groupBox_cameraRGBDImages->setVisible(_ui->comboBox_sourceType->currentIndex() == 0 && _ui->comboBox_cameraRGBD->currentIndex() == kSrcRGBDImages-kSrcRGBD);
4353  _ui->groupBox_openni->setVisible(_ui->comboBox_sourceType->currentIndex() == 0 && _ui->comboBox_cameraRGBD->currentIndex() == kSrcOpenNI_PCL-kSrcRGBD);
4354 
4355  _ui->stackedWidget_stereo->setVisible(_ui->comboBox_sourceType->currentIndex() == 1 &&
4356  (_ui->comboBox_cameraStereo->currentIndex() == kSrcStereoVideo-kSrcStereo ||
4357  _ui->comboBox_cameraStereo->currentIndex() == kSrcStereoImages-kSrcStereo ||
4358  _ui->comboBox_cameraStereo->currentIndex() == kSrcStereoZed - kSrcStereo ||
4359  _ui->comboBox_cameraStereo->currentIndex() == kSrcStereoUsb - kSrcStereo));
4360  _ui->groupBox_cameraStereoImages->setVisible(_ui->comboBox_sourceType->currentIndex() == 1 && _ui->comboBox_cameraStereo->currentIndex() == kSrcStereoImages-kSrcStereo);
4361  _ui->groupBox_cameraStereoVideo->setVisible(_ui->comboBox_sourceType->currentIndex() == 1 && _ui->comboBox_cameraStereo->currentIndex() == kSrcStereoVideo - kSrcStereo);
4362  _ui->groupBox_cameraStereoUsb->setVisible(_ui->comboBox_sourceType->currentIndex() == 1 && _ui->comboBox_cameraStereo->currentIndex() == kSrcStereoUsb - kSrcStereo);
4363  _ui->groupBox_cameraStereoZed->setVisible(_ui->comboBox_sourceType->currentIndex() == 1 && _ui->comboBox_cameraStereo->currentIndex() == kSrcStereoZed - kSrcStereo);
4364 
4365  _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));
4366  _ui->source_groupBox_images->setVisible(_ui->comboBox_sourceType->currentIndex() == 2 && _ui->source_comboBox_image_type->currentIndex() == kSrcImages-kSrcRGB);
4367  _ui->source_groupBox_video->setVisible(_ui->comboBox_sourceType->currentIndex() == 2 && _ui->source_comboBox_image_type->currentIndex() == kSrcVideo-kSrcRGB);
4368 
4369  _ui->groupBox_sourceImages_optional->setVisible(
4370  (_ui->comboBox_sourceType->currentIndex() == 0 && _ui->comboBox_cameraRGBD->currentIndex() == kSrcRGBDImages-kSrcRGBD) ||
4371  (_ui->comboBox_sourceType->currentIndex() == 1 && _ui->comboBox_cameraStereo->currentIndex() == kSrcStereoImages-kSrcStereo) ||
4372  (_ui->comboBox_sourceType->currentIndex() == 2 && _ui->source_comboBox_image_type->currentIndex() == kSrcImages-kSrcRGB));
4373 
4374  _ui->groupBox_depthImageFiltering->setEnabled(
4375  _ui->comboBox_sourceType->currentIndex() == 0 || // RGBD
4376  _ui->comboBox_sourceType->currentIndex() == 3); // Database
4377  _ui->groupBox_depthImageFiltering->setVisible(_ui->groupBox_depthImageFiltering->isEnabled());
4378 
4379  //_ui->groupBox_scan->setVisible(_ui->comboBox_sourceType->currentIndex() != 3);
4380 
4381  _ui->groupBox_depthFromScan->setVisible(_ui->comboBox_sourceType->currentIndex() == 2 && _ui->source_comboBox_image_type->currentIndex() == kSrcImages-kSrcRGB);
4382 }
4383 
4384 /*** GETTERS ***/
4385 //General
4387 {
4388  return _ui->comboBox_loggerLevel->currentIndex();
4389 }
4391 {
4392  return _ui->comboBox_loggerEventLevel->currentIndex();
4393 }
4395 {
4396  return _ui->comboBox_loggerPauseLevel->currentIndex();
4397 }
4399 {
4400  return _ui->comboBox_loggerType->currentIndex();
4401 }
4403 {
4404  return _ui->checkBox_logger_printTime->isChecked();
4405 }
4407 {
4408  return _ui->checkBox_logger_printThreadId->isChecked();
4409 }
4410 std::vector<std::string> PreferencesDialog::getGeneralLoggerThreads() const
4411 {
4412  std::vector<std::string> threads;
4413  for(int i=0; i<_ui->comboBox_loggerFilter->count(); ++i)
4414  {
4415  if(_ui->comboBox_loggerFilter->itemData(i).toBool())
4416  {
4417  threads.push_back(_ui->comboBox_loggerFilter->itemText(i).toStdString());
4418  }
4419  }
4420  return threads;
4421 }
4423 {
4424  return _ui->checkBox_verticalLayoutUsed->isChecked();
4425 }
4427 {
4428  return _ui->checkBox_imageRejectedShown->isChecked();
4429 }
4431 {
4432  return _ui->checkBox_imageHighestHypShown->isChecked();
4433 }
4435 {
4436  return _ui->checkBox_beep->isChecked();
4437 }
4439 {
4440  return _ui->checkBox_stamps->isChecked();
4441 }
4443 {
4444  return _ui->checkBox_cacheStatistics->isChecked();
4445 }
4447 {
4448  return _ui->checkBox_notifyWhenNewGlobalPathIsReceived->isChecked();
4449 }
4451 {
4452  return _ui->spinBox_odomQualityWarnThr->value();
4453 }
4455 {
4456  return _ui->checkBox_odom_onlyInliersShown->isChecked();
4457 }
4459 {
4460  return _ui->radioButton_posteriorGraphView->isChecked();
4461 }
4463 {
4464  return _ui->radioButton_wordsGraphView->isChecked();
4465 }
4467 {
4468  return _ui->radioButton_localizationsGraphView->isChecked();
4469 }
4471 {
4472  return _ui->checkbox_odomDisabled->isChecked();
4473 }
4475 {
4476  return _ui->odom_registration->currentIndex();
4477 }
4479 {
4480  return _ui->checkbox_groundTruthAlign->isChecked();
4481 }
4482 
4484 {
4485  UASSERT(index >= 0 && index <= 1);
4486  return _3dRenderingShowClouds[index]->isChecked();
4487 }
4489 {
4490 #ifdef RTABMAP_OCTOMAP
4491  return _ui->groupBox_octomap->isChecked();
4492 #endif
4493  return false;
4494 }
4496 {
4497 #ifdef RTABMAP_OCTOMAP
4498  return _ui->groupBox_octomap->isChecked() && _ui->checkBox_octomap_show3dMap->isChecked();
4499 #endif
4500  return false;
4501 }
4503 {
4504  return _ui->comboBox_octomap_renderingType->currentIndex();
4505 }
4507 {
4508 #ifdef RTABMAP_OCTOMAP
4509  return _ui->groupBox_octomap->isChecked() && _ui->checkBox_octomap_2dgrid->isChecked();
4510 #endif
4511  return false;
4512 }
4514 {
4515  return _ui->spinBox_octomap_treeDepth->value();
4516 }
4518 {
4519  return _ui->spinBox_octomap_pointSize->value();
4520 }
4521 
4523 {
4524  return _ui->doubleSpinBox_voxel->value();
4525 }
4527 {
4528  return _ui->doubleSpinBox_noiseRadius->value();
4529 }
4531 {
4532  return _ui->spinBox_noiseMinNeighbors->value();
4533 }
4535 {
4536  return _ui->doubleSpinBox_ceilingFilterHeight->value();
4537 }
4539 {
4540  return _ui->doubleSpinBox_floorFilterHeight->value();
4541 }
4543 {
4544  return _ui->spinBox_normalKSearch->value();
4545 }
4547 {
4548  return _ui->doubleSpinBox_normalRadiusSearch->value();
4549 }
4551 {
4552  return _ui->doubleSpinBox_ceilingFilterHeight_scan->value();
4553 }
4555 {
4556  return _ui->doubleSpinBox_floorFilterHeight_scan->value();
4557 }
4559 {
4560  return _ui->spinBox_normalKSearch_scan->value();
4561 }
4563 {
4564  return _ui->doubleSpinBox_normalRadiusSearch_scan->value();
4565 }
4566 
4568 {
4569  return _ui->checkBox_showGraphs->isChecked();
4570 }
4572 {
4573  return _ui->checkBox_showLabels->isChecked();
4574 }
4576 {
4577  return _ui->groupBox_organized->isChecked();
4578 }
4580 {
4581  return _ui->doubleSpinBox_mesh_angleTolerance->value()*M_PI/180.0;
4582 }
4584 {
4585  return _ui->checkBox_mesh_quad->isChecked();
4586 }
4588 {
4589  return _ui->checkBox_mesh_texture->isChecked();
4590 }
4592 {
4593  return _ui->spinBox_mesh_triangleSize->value();
4594 }
4596 {
4597  UASSERT(index >= 0 && index <= 1);
4598  return _3dRenderingDecimation[index]->value()==0?1:_3dRenderingDecimation[index]->value();
4599 }
4601 {
4602  UASSERT(index >= 0 && index <= 1);
4603  return _3dRenderingMaxDepth[index]->value();
4604 }
4606 {
4607  UASSERT(index >= 0 && index <= 1);
4608  return _3dRenderingMinDepth[index]->value();
4609 }
4610 std::vector<float> PreferencesDialog::getCloudRoiRatios(int index) const
4611 {
4612  UASSERT(index >= 0 && index <= 1);
4613  std::vector<float> roiRatios;
4614  if(!_3dRenderingRoiRatios[index]->text().isEmpty())
4615  {
4616  QStringList values = _3dRenderingRoiRatios[index]->text().split(' ');
4617  if(values.size() == 4)
4618  {
4619  roiRatios.resize(4);
4620  for(int i=0; i<values.size(); ++i)
4621  {
4622  roiRatios[i] = uStr2Float(values[i].toStdString().c_str());
4623  }
4624  }
4625  }
4626  return roiRatios;
4627 }
4629 {
4630  UASSERT(index >= 0 && index <= 1);
4631  return _3dRenderingColorScheme[index]->value();
4632 }
4633 double PreferencesDialog::getCloudOpacity(int index) const
4634 {
4635  UASSERT(index >= 0 && index <= 1);
4636  return _3dRenderingOpacity[index]->value();
4637 }
4639 {
4640  UASSERT(index >= 0 && index <= 1);
4641  return _3dRenderingPtSize[index]->value();
4642 }
4643 
4644 bool PreferencesDialog::isScansShown(int index) const
4645 {
4646  UASSERT(index >= 0 && index <= 1);
4647  return _3dRenderingShowScans[index]->isChecked();
4648 }
4650 {
4651  UASSERT(index >= 0 && index <= 1);
4652  return _3dRenderingDownsamplingScan[index]->value();
4653 }
4654 double PreferencesDialog::getScanMaxRange(int index) const
4655 {
4656  UASSERT(index >= 0 && index <= 1);
4657  return _3dRenderingMaxRange[index]->value();
4658 }
4659 double PreferencesDialog::getScanMinRange(int index) const
4660 {
4661  UASSERT(index >= 0 && index <= 1);
4662  return _3dRenderingMinRange[index]->value();
4663 }
4665 {
4666  UASSERT(index >= 0 && index <= 1);
4667  return _3dRenderingVoxelSizeScan[index]->value();
4668 }
4670 {
4671  UASSERT(index >= 0 && index <= 1);
4672  return _3dRenderingColorSchemeScan[index]->value();
4673 }
4674 double PreferencesDialog::getScanOpacity(int index) const
4675 {
4676  UASSERT(index >= 0 && index <= 1);
4677  return _3dRenderingOpacityScan[index]->value();
4678 }
4680 {
4681  UASSERT(index >= 0 && index <= 1);
4682  return _3dRenderingPtSizeScan[index]->value();
4683 }
4684 
4686 {
4687  UASSERT(index >= 0 && index <= 1);
4688  return _3dRenderingShowFeatures[index]->isChecked();
4689 }
4691 {
4692  UASSERT(index >= 0 && index <= 1);
4693  return _3dRenderingShowFrustums[index]->isEnabled() && _3dRenderingShowFrustums[index]->isChecked();
4694 }
4696 {
4697  UASSERT(index >= 0 && index <= 1);
4698  return _3dRenderingPtSizeFeatures[index]->value();
4699 }
4700 
4702 {
4703  return _ui->radioButton_nodeFiltering->isChecked();
4704 }
4706 {
4707  return _ui->radioButton_subtractFiltering->isChecked();
4708 }
4710 {
4711  return _ui->doubleSpinBox_cloudFilterRadius->value();
4712 }
4714 {
4715  return _ui->doubleSpinBox_cloudFilterAngle->value();
4716 }
4718 {
4719  return _ui->spinBox_subtractFilteringMinPts->value();
4720 }
4722 {
4723  return _ui->doubleSpinBox_subtractFilteringRadius->value();
4724 }
4726 {
4727  return _ui->doubleSpinBox_subtractFilteringAngle->value()*M_PI/180.0;
4728 }
4730 {
4731  return _ui->checkBox_map_shown->isChecked();
4732 }
4734 {
4735  return _ui->groupBox_grid_fromDepthImage->isChecked();
4736 }
4738 {
4739  return _ui->checkBox_grid_projMapFrame->isChecked();
4740 }
4742 {
4743  return _ui->doubleSpinBox_grid_maxGroundAngle->value()*M_PI/180.0;
4744 }
4746 {
4747  return _ui->doubleSpinBox_grid_maxGroundHeight->value();
4748 }
4750 {
4751  return _ui->spinBox_grid_minClusterSize->value();
4752 }
4754 {
4755  return _ui->doubleSpinBox_grid_maxObstacleHeight->value();
4756 }
4758 {
4759  return _ui->checkBox_grid_flatObstaclesDetected->isChecked();
4760 }
4762 {
4763  return _ui->doubleSpinBox_map_opacity->value();
4764 }
4765 
4766 
4767 // Source
4769 {
4770  return _ui->general_doubleSpinBox_imgRate->value();
4771 }
4773 {
4774  return _ui->source_mirroring->isChecked();
4775 }
4777 {
4778  int index = _ui->comboBox_sourceType->currentIndex();
4779  if(index == 0)
4780  {
4781  return kSrcRGBD;
4782  }
4783  else if(index == 1)
4784  {
4785  return kSrcStereo;
4786  }
4787  else if(index == 2)
4788  {
4789  return kSrcRGB;
4790  }
4791  else if(index == 3)
4792  {
4793  return kSrcDatabase;
4794  }
4795  return kSrcUndef;
4796 }
4798 {
4800  if(type==kSrcRGBD)
4801  {
4802  return (PreferencesDialog::Src)(_ui->comboBox_cameraRGBD->currentIndex()+kSrcRGBD);
4803  }
4804  else if(type==kSrcStereo)
4805  {
4806  return (PreferencesDialog::Src)(_ui->comboBox_cameraStereo->currentIndex()+kSrcStereo);
4807  }
4808  else if(type==kSrcRGB)
4809  {
4810  return (PreferencesDialog::Src)(_ui->source_comboBox_image_type->currentIndex()+kSrcRGB);
4811  }
4812  else if(type==kSrcDatabase)
4813  {
4814  return kSrcDatabase;
4815  }
4816  return kSrcUndef;
4817 }
4819 {
4821  if(type==kSrcRGBD)
4822  {
4823  return _ui->comboBox_cameraRGBD->currentText();
4824  }
4825  else if(type==kSrcStereo)
4826  {
4827  return _ui->comboBox_cameraStereo->currentText();
4828  }
4829  else if(type==kSrcRGB)
4830  {
4831  return _ui->source_comboBox_image_type->currentText();
4832  }
4833  else if(type==kSrcDatabase)
4834  {
4835  return "Database";
4836  }
4837  return "";
4838 }
4839 
4841 {
4842  return _ui->lineEdit_sourceDevice->text();
4843 }
4844 
4846 {
4847  Transform t = Transform::fromString(_ui->lineEdit_sourceLocalTransform->text().replace("PI_2", QString::number(3.141592/2.0)).toStdString());
4848  if(t.isNull())
4849  {
4850  return Transform::getIdentity();
4851  }
4852  return t;
4853 }
4854 
4856 {
4857  Transform t = Transform::fromString(_ui->lineEdit_cameraImages_laser_transform->text().replace("PI_2", QString::number(3.141592/2.0)).toStdString());
4858  if(t.isNull())
4859  {
4860  return Transform::getIdentity();
4861  }
4862  return t;
4863 }
4864 
4866 {
4867  return _ui->lineEdit_cameraImages_path_imu->text();
4868 }
4870 {
4871  Transform t = Transform::fromString(_ui->lineEdit_cameraImages_imu_transform->text().replace("PI_2", QString::number(3.141592/2.0)).toStdString());
4872  if(t.isNull())
4873  {
4874  return Transform::getIdentity();
4875  }
4876  return t;
4877 }
4879 {
4880  return _ui->spinBox_cameraImages_max_imu_rate->value();
4881 }
4882 
4884 {
4885  return _ui->source_checkBox_useDbStamps->isChecked();
4886 }
4888 {
4889  return _ui->checkbox_rgbd_colorOnly->isChecked();
4890 }
4892 {
4893  return _ui->groupBox_depthImageFiltering->isEnabled();
4894 }
4896 {
4897  return _ui->lineEdit_source_distortionModel->text();
4898 }
4900 {
4901  return _ui->groupBox_bilateral->isChecked();
4902 }
4904 {
4905  return _ui->doubleSpinBox_bilateral_sigmaS->value();
4906 }
4908 {
4909  return _ui->doubleSpinBox_bilateral_sigmaR->value();
4910 }
4912 {
4913  return _ui->spinBox_source_imageDecimation->value();
4914 }
4916 {
4917  return _ui->checkbox_stereo_depthGenerated->isChecked();
4918 }
4920 {
4921  return _ui->checkBox_stereo_exposureCompensation->isChecked();
4922 }
4924 {
4925  return _ui->groupBox_scanFromDepth->isChecked();
4926 }
4928 {
4929  return _ui->spinBox_cameraScanFromDepth_decimation->value();
4930 }
4932 {
4933  return _ui->doubleSpinBox_cameraSCanFromDepth_maxDepth->value();
4934 }
4936 {
4937  return _ui->doubleSpinBox_cameraImages_scanVoxelSize->value();
4938 }
4940 {
4941  return _ui->spinBox_cameraImages_scanNormalsK->value();
4942 }
4944 {
4945  return _ui->doubleSpinBox_cameraImages_scanNormalsRadius->value();
4946 }
4947 
4948 Camera * PreferencesDialog::createCamera(bool useRawImages, bool useColor)
4949 {
4950  UDEBUG("");
4951  Src driver = this->getSourceDriver();
4952  Camera * camera = 0;
4953  if(driver == PreferencesDialog::kSrcOpenNI_PCL)
4954  {
4955  if(useRawImages)
4956  {
4957  QMessageBox::warning(this, tr("Calibration"),
4958  tr("Using raw images for \"OpenNI\" driver is not yet supported. "
4959  "Factory calibration loaded from OpenNI is used."), QMessageBox::Ok);
4960  return 0;
4961  }
4962  else
4963  {
4964  camera = new CameraOpenni(
4965  _ui->lineEdit_openniOniPath->text().isEmpty()?this->getSourceDevice().toStdString():_ui->lineEdit_openniOniPath->text().toStdString(),
4966  this->getGeneralInputRate(),
4967  this->getSourceLocalTransform());
4968  }
4969  }
4970  else if(driver == PreferencesDialog::kSrcOpenNI2)
4971  {
4972  camera = new CameraOpenNI2(
4973  _ui->lineEdit_openni2OniPath->text().isEmpty()?this->getSourceDevice().toStdString():_ui->lineEdit_openni2OniPath->text().toStdString(),
4975  this->getGeneralInputRate(),
4976  this->getSourceLocalTransform());
4977  }
4978  else if(driver == PreferencesDialog::kSrcFreenect)
4979  {
4980  camera = new CameraFreenect(
4981  this->getSourceDevice().isEmpty()?0:atoi(this->getSourceDevice().toStdString().c_str()),
4983  this->getGeneralInputRate(),
4984  this->getSourceLocalTransform());
4985  }
4986  else if(driver == PreferencesDialog::kSrcOpenNI_CV ||
4988  {
4989  if(useRawImages)
4990  {
4991  QMessageBox::warning(this, tr("Calibration"),
4992  tr("Using raw images for \"OpenNI\" driver is not yet supported. "
4993  "Factory calibration loaded from OpenNI is used."), QMessageBox::Ok);
4994  return 0;
4995  }
4996  else
4997  {
4998  camera = new CameraOpenNICV(
5000  this->getGeneralInputRate(),
5001  this->getSourceLocalTransform());
5002  }
5003  }
5004  else if(driver == kSrcFreenect2)
5005  {
5006  camera = new CameraFreenect2(
5007  this->getSourceDevice().isEmpty()?0:atoi(this->getSourceDevice().toStdString().c_str()),
5008  useRawImages?CameraFreenect2::kTypeColorIR:(CameraFreenect2::Type)_ui->comboBox_freenect2Format->currentIndex(),
5009  this->getGeneralInputRate(),
5010  this->getSourceLocalTransform(),
5011  _ui->doubleSpinBox_freenect2MinDepth->value(),
5012  _ui->doubleSpinBox_freenect2MaxDepth->value(),
5013  _ui->checkBox_freenect2BilateralFiltering->isChecked(),
5014  _ui->checkBox_freenect2EdgeAwareFiltering->isChecked(),
5015  _ui->checkBox_freenect2NoiseFiltering->isChecked(),
5016  _ui->lineEdit_freenect2Pipeline->text().toStdString());
5017  }
5018  else if (driver == kSrcK4W2)
5019  {
5020  camera = new CameraK4W2(
5021  this->getSourceDevice().isEmpty() ? 0 : atoi(this->getSourceDevice().toStdString().c_str()),
5022  (CameraK4W2::Type)_ui->comboBox_k4w2Format->currentIndex(),
5023  this->getGeneralInputRate(),
5024  this->getSourceLocalTransform());
5025  }
5026  else if (driver == kSrcRealSense)
5027  {
5028  if(useRawImages && _ui->comboBox_realsenseRGBSource->currentIndex()!=2)
5029  {
5030  QMessageBox::warning(this, tr("Calibration"),
5031  tr("Using raw images for \"RealSense\" driver is not yet supported for color and infrared streams. "
5032  "Factory calibration loaded from RealSense is used."), QMessageBox::Ok);
5033  return 0;
5034  }
5035  else
5036  {
5037  camera = new CameraRealSense(
5038  this->getSourceDevice().isEmpty() ? 0 : atoi(this->getSourceDevice().toStdString().c_str()),
5039  _ui->comboBox_realsensePresetRGB->currentIndex(),
5040  _ui->comboBox_realsensePresetDepth->currentIndex(),
5041  _ui->checkbox_realsenseOdom->isChecked(),
5042  this->getGeneralInputRate(),
5043  this->getSourceLocalTransform());
5044  ((CameraRealSense*)camera)->setDepthScaledToRGBSize(_ui->checkbox_realsenseDepthScaledToRGBSize->isChecked());
5045  ((CameraRealSense*)camera)->setRGBSource((CameraRealSense::RGBSource)_ui->comboBox_realsenseRGBSource->currentIndex());
5046  }
5047  }
5048  else if (driver == kSrcRealSense2)
5049  {
5050  if(useRawImages)
5051  {
5052  QMessageBox::warning(this, tr("Calibration"),
5053  tr("Using raw images for \"RealSense\" driver is not yet supported. "
5054  "Factory calibration loaded from RealSense2 is used."), QMessageBox::Ok);
5055  return 0;
5056  }
5057  else
5058  {
5059  camera = new CameraRealSense2(
5060  this->getSourceDevice().toStdString(),
5061  this->getGeneralInputRate(),
5062  this->getSourceLocalTransform());
5063  ((CameraRealSense2*)camera)->setEmitterEnabled(_ui->checkbox_rs2_emitter->isChecked());
5064  ((CameraRealSense2*)camera)->setIRDepthFormat(_ui->checkbox_rs2_irDepth->isChecked());
5065  }
5066  }
5067  else if(driver == kSrcRGBDImages)
5068  {
5069  camera = new CameraRGBDImages(
5070  _ui->lineEdit_cameraRGBDImages_path_rgb->text().append(QDir::separator()).toStdString(),
5071  _ui->lineEdit_cameraRGBDImages_path_depth->text().append(QDir::separator()).toStdString(),
5072  _ui->doubleSpinBox_cameraRGBDImages_scale->value(),
5073  this->getGeneralInputRate(),
5074  this->getSourceLocalTransform());
5075  ((CameraRGBDImages*)camera)->setStartIndex(_ui->spinBox_cameraRGBDImages_startIndex->value());
5076  ((CameraRGBDImages*)camera)->setBayerMode(_ui->comboBox_cameraImages_bayerMode->currentIndex()-1);
5077  ((CameraRGBDImages*)camera)->setOdometryPath(_ui->lineEdit_cameraImages_odom->text().toStdString(), _ui->comboBox_cameraImages_odomFormat->currentIndex());
5078  ((CameraRGBDImages*)camera)->setGroundTruthPath(_ui->lineEdit_cameraImages_gt->text().toStdString(), _ui->comboBox_cameraImages_gtFormat->currentIndex());
5079  ((CameraRGBDImages*)camera)->setMaxPoseTimeDiff(_ui->doubleSpinBox_maxPoseTimeDiff->value());
5080  ((CameraRGBDImages*)camera)->setScanPath(
5081  _ui->lineEdit_cameraImages_path_scans->text().isEmpty()?"":_ui->lineEdit_cameraImages_path_scans->text().append(QDir::separator()).toStdString(),
5082  _ui->spinBox_cameraImages_max_scan_pts->value(),
5083  _ui->spinBox_cameraImages_scanDownsampleStep->value(),
5084  _ui->doubleSpinBox_cameraImages_scanVoxelSize->value(),
5085  _ui->spinBox_cameraImages_scanNormalsK->value(),
5086  _ui->doubleSpinBox_cameraImages_scanNormalsRadius->value(),
5087  this->getLaserLocalTransform(),
5088  _ui->checkBox_cameraImages_scanForceGroundNormalsUp->isChecked());
5089  ((CameraRGBDImages*)camera)->setTimestamps(
5090  _ui->checkBox_cameraImages_timestamps->isChecked(),
5091  _ui->lineEdit_cameraImages_timestamps->text().toStdString(),
5092  _ui->checkBox_cameraImages_syncTimeStamps->isChecked());
5093  }
5094  else if(driver == kSrcDC1394)
5095  {
5096  camera = new CameraStereoDC1394(
5097  this->getGeneralInputRate(),
5098  this->getSourceLocalTransform());
5099  }
5100  else if(driver == kSrcFlyCapture2)
5101  {
5102  if(useRawImages)
5103  {
5104  QMessageBox::warning(this, tr("Calibration"),
5105  tr("Using raw images for \"FlyCapture2\" driver is not yet supported. "
5106  "Factory calibration loaded from FlyCapture2 is used."), QMessageBox::Ok);
5107  return 0;
5108  }
5109  else
5110  {
5111  camera = new CameraStereoFlyCapture2(
5112  this->getGeneralInputRate(),
5113  this->getSourceLocalTransform());
5114  }
5115  }
5116  else if(driver == kSrcStereoImages)
5117  {
5118  camera = new CameraStereoImages(
5119  _ui->lineEdit_cameraStereoImages_path_left->text().append(QDir::separator()).toStdString(),
5120  _ui->lineEdit_cameraStereoImages_path_right->text().append(QDir::separator()).toStdString(),
5121  _ui->checkBox_stereo_rectify->isChecked() && !useRawImages,
5122  this->getGeneralInputRate(),
5123  this->getSourceLocalTransform());
5124  ((CameraStereoImages*)camera)->setStartIndex(_ui->spinBox_cameraStereoImages_startIndex->value());
5125  ((CameraStereoImages*)camera)->setBayerMode(_ui->comboBox_cameraImages_bayerMode->currentIndex()-1);
5126  ((CameraStereoImages*)camera)->setOdometryPath(_ui->lineEdit_cameraImages_odom->text().toStdString(), _ui->comboBox_cameraImages_odomFormat->currentIndex());
5127  ((CameraStereoImages*)camera)->setGroundTruthPath(_ui->lineEdit_cameraImages_gt->text().toStdString(), _ui->comboBox_cameraImages_gtFormat->currentIndex());
5128  ((CameraStereoImages*)camera)->setMaxPoseTimeDiff(_ui->doubleSpinBox_maxPoseTimeDiff->value());
5129  ((CameraStereoImages*)camera)->setScanPath(
5130  _ui->lineEdit_cameraImages_path_scans->text().isEmpty()?"":_ui->lineEdit_cameraImages_path_scans->text().append(QDir::separator()).toStdString(),
5131  _ui->spinBox_cameraImages_max_scan_pts->value(),
5132  _ui->spinBox_cameraImages_scanDownsampleStep->value(),
5133  _ui->doubleSpinBox_cameraImages_scanVoxelSize->value(),
5134  _ui->spinBox_cameraImages_scanNormalsK->value(),
5135  _ui->doubleSpinBox_cameraImages_scanNormalsRadius->value(),
5136  this->getLaserLocalTransform(),
5137  _ui->checkBox_cameraImages_scanForceGroundNormalsUp->isChecked());
5138  ((CameraStereoImages*)camera)->setTimestamps(
5139  _ui->checkBox_cameraImages_timestamps->isChecked(),
5140  _ui->lineEdit_cameraImages_timestamps->text().toStdString(),
5141  _ui->checkBox_cameraImages_syncTimeStamps->isChecked());
5142 
5143  }
5144  else if (driver == kSrcStereoUsb)
5145  {
5146  if(_ui->spinBox_stereo_right_device->value()>=0)
5147  {
5148  camera = new CameraStereoVideo(
5149  this->getSourceDevice().isEmpty() ? 0 : atoi(this->getSourceDevice().toStdString().c_str()),
5150  _ui->spinBox_stereo_right_device->value(),
5151  _ui->checkBox_stereo_rectify->isChecked() && !useRawImages,
5152  this->getGeneralInputRate(),
5153  this->getSourceLocalTransform());
5154  }
5155  else
5156  {
5157  camera = new CameraStereoVideo(
5158  this->getSourceDevice().isEmpty() ? 0 : atoi(this->getSourceDevice().toStdString().c_str()),
5159  _ui->checkBox_stereo_rectify->isChecked() && !useRawImages,
5160  this->getGeneralInputRate(),
5161  this->getSourceLocalTransform());
5162  }
5163  }
5164  else if(driver == kSrcStereoVideo)
5165  {
5166  if(!_ui->lineEdit_cameraStereoVideo_path_2->text().isEmpty())
5167  {
5168  // left and right videos
5169  camera = new CameraStereoVideo(
5170  _ui->lineEdit_cameraStereoVideo_path->text().toStdString(),
5171  _ui->lineEdit_cameraStereoVideo_path_2->text().toStdString(),
5172  _ui->checkBox_stereo_rectify->isChecked() && !useRawImages,
5173  this->getGeneralInputRate(),
5174  this->getSourceLocalTransform());
5175  }
5176  else
5177  {
5178  // side-by-side video
5179  camera = new CameraStereoVideo(
5180  _ui->lineEdit_cameraStereoVideo_path->text().toStdString(),
5181  _ui->checkBox_stereo_rectify->isChecked() && !useRawImages,
5182  this->getGeneralInputRate(),
5183  this->getSourceLocalTransform());
5184  }
5185  }
5186  else if (driver == kSrcStereoZed)
5187  {
5188  UDEBUG("ZED");
5189  if(!_ui->lineEdit_zedSvoPath->text().isEmpty())
5190  {
5191  camera = new CameraStereoZed(
5192  _ui->lineEdit_zedSvoPath->text().toStdString(),
5193  _ui->comboBox_stereoZed_quality->currentIndex(),
5194  _ui->comboBox_stereoZed_sensingMode->currentIndex(),
5195  _ui->spinBox_stereoZed_confidenceThr->value(),
5196  _ui->checkbox_stereoZed_odom->isChecked(),
5197  this->getGeneralInputRate(),
5198  this->getSourceLocalTransform(),
5199  _ui->checkbox_stereoZed_selfCalibration->isChecked());
5200  }
5201  else
5202  {
5203  camera = new CameraStereoZed(
5204  this->getSourceDevice().isEmpty()?0:atoi(this->getSourceDevice().toStdString().c_str()),
5205  _ui->comboBox_stereoZed_resolution->currentIndex(),
5206  _ui->comboBox_stereoZed_quality->currentIndex(),
5207  _ui->comboBox_stereoZed_sensingMode->currentIndex(),
5208  _ui->spinBox_stereoZed_confidenceThr->value(),
5209  _ui->checkbox_stereoZed_odom->isChecked(),
5210  this->getGeneralInputRate(),
5211  this->getSourceLocalTransform(),
5212  _ui->checkbox_stereoZed_selfCalibration->isChecked());
5213  }
5214  }
5215  else if(driver == kSrcUsbDevice)
5216  {
5217  camera = new CameraVideo(
5218  this->getSourceDevice().isEmpty()?0:atoi(this->getSourceDevice().toStdString().c_str()),
5219  _ui->checkBox_rgb_rectify->isChecked() && !useRawImages,
5220  this->getGeneralInputRate(),
5221  this->getSourceLocalTransform());
5222  }
5223  else if(driver == kSrcVideo)
5224  {
5225  camera = new CameraVideo(
5226  _ui->source_video_lineEdit_path->text().toStdString(),
5227  _ui->checkBox_rgb_rectify->isChecked() && !useRawImages,
5228  this->getGeneralInputRate(),
5229  this->getSourceLocalTransform());
5230  }
5231  else if(driver == kSrcImages)
5232  {
5233  camera = new CameraImages(
5234  _ui->source_images_lineEdit_path->text().toStdString(),
5235  this->getGeneralInputRate(),
5236  this->getSourceLocalTransform());
5237 
5238  ((CameraImages*)camera)->setStartIndex(_ui->source_images_spinBox_startPos->value());
5239  ((CameraImages*)camera)->setImagesRectified(_ui->checkBox_rgb_rectify->isChecked() && !useRawImages);
5240 
5241  ((CameraImages*)camera)->setBayerMode(_ui->comboBox_cameraImages_bayerMode->currentIndex()-1);
5242  ((CameraImages*)camera)->setOdometryPath(
5243  _ui->lineEdit_cameraImages_odom->text().toStdString(),
5244  _ui->comboBox_cameraImages_odomFormat->currentIndex());
5245  ((CameraImages*)camera)->setGroundTruthPath(
5246  _ui->lineEdit_cameraImages_gt->text().toStdString(),
5247  _ui->comboBox_cameraImages_gtFormat->currentIndex());
5248  ((CameraImages*)camera)->setMaxPoseTimeDiff(_ui->doubleSpinBox_maxPoseTimeDiff->value());
5249  ((CameraImages*)camera)->setScanPath(
5250  _ui->lineEdit_cameraImages_path_scans->text().isEmpty()?"":_ui->lineEdit_cameraImages_path_scans->text().append(QDir::separator()).toStdString(),
5251  _ui->spinBox_cameraImages_max_scan_pts->value(),
5252  _ui->spinBox_cameraImages_scanDownsampleStep->value(),
5253  _ui->doubleSpinBox_cameraImages_scanVoxelSize->value(),
5254  _ui->spinBox_cameraImages_scanNormalsK->value(),
5255  _ui->doubleSpinBox_cameraImages_scanNormalsRadius->value(),
5256  this->getLaserLocalTransform(),
5257  _ui->checkBox_cameraImages_scanForceGroundNormalsUp->isChecked());
5258  ((CameraImages*)camera)->setDepthFromScan(
5259  _ui->groupBox_depthFromScan->isChecked(),
5260  !_ui->groupBox_depthFromScan_fillHoles->isChecked()?0:_ui->radioButton_depthFromScan_vertical->isChecked()?1:-1,
5261  _ui->checkBox_depthFromScan_fillBorders->isChecked());
5262  ((CameraImages*)camera)->setTimestamps(
5263  _ui->checkBox_cameraImages_timestamps->isChecked(),
5264  _ui->lineEdit_cameraImages_timestamps->text().toStdString(),
5265  _ui->checkBox_cameraImages_syncTimeStamps->isChecked());
5266  }
5267  else if(driver == kSrcDatabase)
5268  {
5269  camera = new DBReader(_ui->source_database_lineEdit_path->text().toStdString(),
5270  _ui->source_checkBox_useDbStamps->isChecked()?-1:this->getGeneralInputRate(),
5271  _ui->source_checkBox_ignoreOdometry->isChecked(),
5272  _ui->source_checkBox_ignoreGoalDelay->isChecked(),
5273  _ui->source_checkBox_ignoreGoals->isChecked(),
5274  _ui->source_spinBox_databaseStartPos->value(),
5275  _ui->source_spinBox_database_cameraIndex->value());
5276  }
5277  else
5278  {
5279  UFATAL("Source driver undefined (%d)!", driver);
5280  }
5281 
5282  if(camera)
5283  {
5284  UDEBUG("Init");
5285  QString dir = this->getCameraInfoDir();
5286  QString calibrationFile = _ui->lineEdit_calibrationFile->text();
5287  if(!(driver >= kSrcRGB && driver <= kSrcVideo))
5288  {
5289  calibrationFile.remove("_left.yaml").remove("_right.yaml").remove("_pose.yaml").remove("_rgb.yaml").remove("_depth.yaml");
5290  }
5291  QString name = QFileInfo(calibrationFile.remove(".yaml")).baseName();
5292  if(!_ui->lineEdit_calibrationFile->text().isEmpty())
5293  {
5294  QDir d = QFileInfo(_ui->lineEdit_calibrationFile->text()).dir();
5295  if(!_ui->lineEdit_calibrationFile->text().remove(QFileInfo(_ui->lineEdit_calibrationFile->text()).baseName()).isEmpty())
5296  {
5297  dir = d.absolutePath();
5298  }
5299  }
5300 
5301  // don't set calibration folder if we want raw images
5302  if(!camera->init(useRawImages?"":dir.toStdString(), name.toStdString()))
5303  {
5304  UWARN("init camera failed... ");
5305  QMessageBox::warning(this,
5306  tr("RTAB-Map"),
5307  tr("Camera initialization failed..."));
5308  delete camera;
5309  camera = 0;
5310  }
5311  else
5312  {
5313  //should be after initialization
5314  if(driver == kSrcOpenNI2)
5315  {
5316  ((CameraOpenNI2*)camera)->setAutoWhiteBalance(_ui->openni2_autoWhiteBalance->isChecked());
5317  ((CameraOpenNI2*)camera)->setAutoExposure(_ui->openni2_autoExposure->isChecked());
5318  ((CameraOpenNI2*)camera)->setMirroring(_ui->openni2_mirroring->isChecked());
5319  ((CameraOpenNI2*)camera)->setOpenNI2StampsAndIDsUsed(_ui->openni2_stampsIdsUsed->isChecked());
5321  {
5322  ((CameraOpenNI2*)camera)->setExposure(_ui->openni2_exposure->value());
5323  ((CameraOpenNI2*)camera)->setGain(_ui->openni2_gain->value());
5324  }
5325  ((CameraOpenNI2*)camera)->setIRDepthShift(_ui->openni2_hshift->value(), _ui->openni2_vshift->value());
5326  ((CameraOpenNI2*)camera)->setMirroring(_ui->openni2_mirroring->isChecked());
5327  }
5328  }
5329  }
5330 
5331  UDEBUG("");
5332  return camera;
5333 }
5334 
5336 {
5337  return _ui->groupBox_publishing->isChecked();
5338 }
5340 {
5341  return _ui->general_doubleSpinBox_hardThr->value();
5342 }
5344 {
5345  return _ui->general_doubleSpinBox_vp->value();
5346 }
5348 {
5349  return _ui->doubleSpinBox_similarityThreshold->value();
5350 }
5352 {
5353  return _ui->odom_strategy->currentIndex();
5354 }
5356 {
5357  return _ui->odom_dataBufferSize->value();
5358 }
5359 
5361 {
5362  return (this->getWorkingDirectory().isEmpty()?".":this->getWorkingDirectory())+"/camera_info";
5363 }
5364 
5366 {
5367  return _ui->general_checkBox_imagesKept->isChecked();
5368 }
5370 {
5371  return _ui->general_checkBox_cloudsKept->isChecked();
5372 }
5374 {
5375  return _ui->general_doubleSpinBox_timeThr->value();
5376 }
5378 {
5379  return _ui->general_doubleSpinBox_detectionRate->value();
5380 }
5382 {
5383  return _ui->general_checkBox_SLAM_mode->isChecked();
5384 }
5386 {
5387  return _ui->general_checkBox_activateRGBD->isChecked();
5388 }
5390 {
5391  return _ui->surf_spinBox_wordsPerImageTarget->value();
5392 }
5393 
5394 /*** SETTERS ***/
5396 {
5397  ULOGGER_DEBUG("imgRate=%2.2f", value);
5398  if(_ui->general_doubleSpinBox_imgRate->value() != value)
5399  {
5400  _ui->general_doubleSpinBox_imgRate->setValue(value);
5401  if(validateForm())
5402  {
5404  }
5405  else
5406  {
5407  this->readSettingsBegin();
5408  }
5409  }
5410 }
5411 
5413 {
5414  ULOGGER_DEBUG("detectionRate=%2.2f", value);
5415  if(_ui->general_doubleSpinBox_detectionRate->value() != value)
5416  {
5417  _ui->general_doubleSpinBox_detectionRate->setValue(value);
5418  if(validateForm())
5419  {
5421  }
5422  else
5423  {
5424  this->readSettingsBegin();
5425  }
5426  }
5427 }
5428 
5430 {
5431  ULOGGER_DEBUG("timeLimit=%fs", value);
5432  if(_ui->general_doubleSpinBox_timeThr->value() != value)
5433  {
5434  _ui->general_doubleSpinBox_timeThr->setValue(value);
5435  if(validateForm())
5436  {
5438  }
5439  else
5440  {
5441  this->readSettingsBegin();
5442  }
5443  }
5444 }
5445 
5447 {
5448  ULOGGER_DEBUG("slam mode=%s", enabled?"true":"false");
5449  if(_ui->general_checkBox_SLAM_mode->isChecked() != enabled)
5450  {
5451  _ui->general_checkBox_SLAM_mode->setChecked(enabled);
5452  if(validateForm())
5453  {
5455  }
5456  else
5457  {
5458  this->readSettingsBegin();
5459  }
5460  }
5461 }
5462 
5464 {
5465  Camera * camera = this->createCamera();
5466  if(!camera)
5467  {
5468  return;
5469  }
5470 
5471  IMUThread * imuThread = 0;
5472  if((this->getSourceDriver() == kSrcStereoImages ||
5473  this->getSourceDriver() == kSrcRGBDImages ||
5474  this->getSourceDriver() == kSrcImages) &&
5475  !_ui->lineEdit_cameraImages_path_imu->text().isEmpty())
5476  {
5478  {
5479  QMessageBox::warning(this, tr("Source IMU Path"),
5480  tr("IMU path is set but odometry chosen doesn't support IMU, ignoring IMU..."), QMessageBox::Ok);
5481  }
5482  else
5483  {
5484  imuThread = new IMUThread(_ui->spinBox_cameraImages_max_imu_rate->value(), this->getIMULocalTransform());
5485  if(!imuThread->init(_ui->lineEdit_cameraImages_path_imu->text().toStdString()))
5486  {
5487  QMessageBox::warning(this, tr("Source IMU Path"),
5488  tr("Initialization of IMU data has failed! Path=%1.").arg(_ui->lineEdit_cameraImages_path_imu->text()), QMessageBox::Ok);
5489  delete camera;
5490  delete imuThread;
5491  return;
5492  }
5493  }
5494  }
5495 
5496  ParametersMap parameters = this->getAllParameters();
5497  if(getOdomRegistrationApproach() < 3)
5498  {
5499  uInsert(parameters, ParametersPair(Parameters::kRegStrategy(), uNumber2Str(getOdomRegistrationApproach())));
5500  }
5501 
5502  int odomStrategy = Parameters::defaultOdomStrategy();
5503  Parameters::parse(parameters, Parameters::kOdomStrategy(), odomStrategy);
5504  if(odomStrategy == 1)
5505  {
5506  // Only Frame To Frame supports all VisCorType
5507  parameters.insert(ParametersPair(Parameters::kVisCorType(), this->getParameter(Parameters::kVisCorType())));
5508  }
5509 
5510  Odometry * odometry = Odometry::create(parameters);
5511 
5512  OdometryThread odomThread(
5513  odometry, // take ownership of odometry
5514  _ui->odom_dataBufferSize->value());
5515  odomThread.registerToEventsManager();
5516 
5517  OdometryViewer * odomViewer = new OdometryViewer(10,
5518  _ui->spinBox_decimation_odom->value(),
5519  0.0f,
5520  _ui->doubleSpinBox_maxDepth_odom->value(),
5521  this->getOdomQualityWarnThr(),
5522  this,
5523  this->getAllParameters());
5524  odomViewer->setWindowTitle(tr("Odometry viewer"));
5525  odomViewer->resize(1280, 480+QPushButton().minimumHeight());
5526  odomViewer->registerToEventsManager();
5527 
5528  CameraThread cameraThread(camera, this->getAllParameters()); // take ownership of camera
5529  cameraThread.setMirroringEnabled(isSourceMirroring());
5530  cameraThread.setColorOnly(_ui->checkbox_rgbd_colorOnly->isChecked());
5531  cameraThread.setImageDecimation(_ui->spinBox_source_imageDecimation->value());
5532  cameraThread.setStereoToDepth(_ui->checkbox_stereo_depthGenerated->isChecked());
5533  cameraThread.setStereoExposureCompensation(_ui->checkBox_stereo_exposureCompensation->isChecked());
5534  cameraThread.setScanFromDepth(
5535  _ui->groupBox_scanFromDepth->isChecked(),
5536  _ui->spinBox_cameraScanFromDepth_decimation->value(),
5537  _ui->doubleSpinBox_cameraSCanFromDepth_maxDepth->value(),
5538  _ui->doubleSpinBox_cameraImages_scanVoxelSize->value(),
5539  _ui->spinBox_cameraImages_scanNormalsK->value(),
5540  _ui->doubleSpinBox_cameraImages_scanNormalsRadius->value());
5542  {
5543  if(_ui->groupBox_bilateral->isChecked())
5544  {
5545  cameraThread.enableBilateralFiltering(
5546  _ui->doubleSpinBox_bilateral_sigmaS->value(),
5547  _ui->doubleSpinBox_bilateral_sigmaR->value());
5548  }
5549  if(!_ui->lineEdit_source_distortionModel->text().isEmpty())
5550  {
5551  cameraThread.setDistortionModel(_ui->lineEdit_source_distortionModel->text().toStdString());
5552  }
5553  }
5554 
5555  UEventsManager::createPipe(&cameraThread, &odomThread, "CameraEvent");
5556  if(imuThread)
5557  {
5558  UEventsManager::createPipe(imuThread, &odomThread, "IMUEvent");
5559  }
5560  UEventsManager::createPipe(&odomThread, odomViewer, "OdometryEvent");
5561  UEventsManager::createPipe(odomViewer, &odomThread, "OdometryResetEvent");
5562 
5563  odomThread.start();
5564  cameraThread.start();
5565 
5566  if(imuThread)
5567  {
5568  imuThread->start();
5569  }
5570 
5571  odomViewer->exec();
5572  delete odomViewer;
5573 
5574  if(imuThread)
5575  {
5576  imuThread->join(true);
5577  delete imuThread;
5578  }
5579  cameraThread.join(true);
5580  odomThread.join(true);
5581 }
5582 
5584 {
5585  CameraViewer * window = new CameraViewer(this, this->getAllParameters());
5586  window->setWindowTitle(tr("Camera viewer"));
5587  window->resize(1280, 480+QPushButton().minimumHeight());
5588  window->registerToEventsManager();
5589 
5590  Camera * camera = this->createCamera();
5591  if(camera)
5592  {
5593  CameraThread cameraThread(camera, this->getAllParameters());
5594  cameraThread.setMirroringEnabled(isSourceMirroring());
5595  cameraThread.setColorOnly(_ui->checkbox_rgbd_colorOnly->isChecked());
5596  cameraThread.setImageDecimation(_ui->spinBox_source_imageDecimation->value());
5597  cameraThread.setStereoToDepth(_ui->checkbox_stereo_depthGenerated->isChecked());
5598  cameraThread.setStereoExposureCompensation(_ui->checkBox_stereo_exposureCompensation->isChecked());
5599  cameraThread.setScanFromDepth(
5600  _ui->groupBox_scanFromDepth->isChecked(),
5601  _ui->spinBox_cameraScanFromDepth_decimation->value(),
5602  _ui->doubleSpinBox_cameraSCanFromDepth_maxDepth->value(),
5603  _ui->doubleSpinBox_cameraImages_scanVoxelSize->value(),
5604  _ui->spinBox_cameraImages_scanNormalsK->value(),
5605  _ui->doubleSpinBox_cameraImages_scanNormalsRadius->value());
5607  {
5608  if(_ui->groupBox_bilateral->isChecked())
5609  {
5610  cameraThread.enableBilateralFiltering(
5611  _ui->doubleSpinBox_bilateral_sigmaS->value(),
5612  _ui->doubleSpinBox_bilateral_sigmaR->value());
5613  }
5614  if(!_ui->lineEdit_source_distortionModel->text().isEmpty())
5615  {
5616  cameraThread.setDistortionModel(_ui->lineEdit_source_distortionModel->text().toStdString());
5617  }
5618  }
5619  UEventsManager::createPipe(&cameraThread, window, "CameraEvent");
5620 
5621  cameraThread.start();
5622  window->exec();
5623  delete window;
5624  cameraThread.join(true);
5625  }
5626  else
5627  {
5628  delete window;
5629  }
5630 }
5631 
5633 {
5634  if(this->getSourceType() == kSrcDatabase)
5635  {
5636  QMessageBox::warning(this,
5637  tr("Calibration"),
5638  tr("Cannot calibrate database source!"));
5639  return;
5640  }
5641 
5642  if(!this->getCameraInfoDir().isEmpty())
5643  {
5644  QDir dir(this->getCameraInfoDir());
5645  if (!dir.exists())
5646  {
5647  UINFO("Creating camera_info directory: \"%s\"", this->getCameraInfoDir().toStdString().c_str());
5648  if(!dir.mkpath(this->getCameraInfoDir()))
5649  {
5650  UWARN("Could create camera_info directory: \"%s\"", this->getCameraInfoDir().toStdString().c_str());
5651  }
5652  }
5653  }
5654 
5655  Src driver = this->getSourceDriver();
5657  {
5658  // 3 steps calibration: RGB -> IR -> Extrinsic
5659  QMessageBox::StandardButton button = QMessageBox::question(this, tr("Calibration"),
5660  tr("With \"%1\" driver, Color and IR cameras cannot be streamed at the "
5661  "same time. A 3-steps calibration is required (Color -> IR -> extrinsics). We will "
5662  "start with the Color camera calibration. Do you want to continue?").arg(this->getSourceDriverStr()),
5663  QMessageBox::Yes | QMessageBox::No | QMessageBox::Ignore, QMessageBox::Yes);
5664 
5665  if(button == QMessageBox::Yes || button == QMessageBox::Ignore)
5666  {
5668 
5669  Camera * camera = 0;
5670 
5671  // Step 1: RGB
5672  if(button != QMessageBox::Ignore)
5673  {
5674  camera = this->createCamera(true, true); // RAW color
5675  if(!camera)
5676  {
5677  return;
5678  }
5679 
5680  _calibrationDialog->setStereoMode(false); // this forces restart
5681  _calibrationDialog->setCameraName(QString(camera->getSerial().c_str())+"_rgb");
5683  CameraThread cameraThread(camera, this->getAllParameters());
5684  UEventsManager::createPipe(&cameraThread, _calibrationDialog, "CameraEvent");
5685  cameraThread.start();
5686  _calibrationDialog->exec();
5688  cameraThread.join(true);
5689  camera = 0;
5690  }
5691 
5692  button = QMessageBox::question(this, tr("Calibration"),
5693  tr("We will now calibrate the IR camera. Hide the IR projector with a Post-It and "
5694  "make sure you have enough ambient IR light (e.g., external IR source or sunlight!) to see the "
5695  "checkboard with the IR camera. Do you want to continue?"),
5696  QMessageBox::Yes | QMessageBox::No | QMessageBox::Ignore, QMessageBox::Yes);
5697  if(button == QMessageBox::Yes || button == QMessageBox::Ignore)
5698  {
5699  // Step 2: IR
5700  if(button != QMessageBox::Ignore)
5701  {
5702  camera = this->createCamera(true, false); // RAW ir
5703  if(!camera)
5704  {
5705  return;
5706  }
5707 
5708  _calibrationDialog->setStereoMode(false); // this forces restart
5709  _calibrationDialog->setCameraName(QString(camera->getSerial().c_str())+"_depth");
5711  CameraThread cameraThread(camera, this->getAllParameters());
5712  UEventsManager::createPipe(&cameraThread, _calibrationDialog, "CameraEvent");
5713  cameraThread.start();
5714  _calibrationDialog->exec();
5716  cameraThread.join(true);
5717  camera = 0;
5718  }
5719 
5720  button = QMessageBox::question(this, tr("Calibration"),
5721  tr("We will now calibrate the extrinsics. Important: Make sure "
5722  "the cameras and the checkboard don't move and that both "
5723  "cameras can see the checkboard. We will repeat this "
5724  "multiple times. Each time, you will have to move the camera (or "
5725  "checkboard) for a different point of view. Do you want to "
5726  "continue?"),
5727  QMessageBox::Yes | QMessageBox::No, QMessageBox::Yes);
5728 
5729  bool ok = false;
5730  int totalSamples = 0;
5731  if(button == QMessageBox::Yes)
5732  {
5733  totalSamples = QInputDialog::getInt(this, tr("Calibration"), tr("Samples: "), 3, 1, 99, 1, &ok);
5734  }
5735 
5736  if(ok)
5737  {
5738  int count = 0;
5739  _calibrationDialog->setStereoMode(true, "depth", "rgb"); // this forces restart
5741  _calibrationDialog->setModal(true);
5743  _calibrationDialog->show();
5744  CameraModel irModel;
5745  CameraModel rgbModel;
5746  std::string serial;
5747  for(;count < totalSamples && button == QMessageBox::Yes; )
5748  {
5749  // Step 3: Extrinsics
5750  camera = this->createCamera(false, true); // Rectified color
5751  if(!camera)
5752  {
5753  return;
5754  }
5755  SensorData rgbData = camera->takeImage();
5756  UASSERT(rgbData.cameraModels().size() == 1);
5757  rgbModel = rgbData.cameraModels()[0];
5758  delete camera;
5759  camera = this->createCamera(false, false); // Rectified ir
5760  if(!camera)
5761  {
5762  return;
5763  }
5764  SensorData irData = camera->takeImage();
5765  serial = camera->getSerial();
5766  UASSERT(irData.cameraModels().size() == 1);
5767  irModel = irData.cameraModels()[0];
5768  delete camera;
5769 
5770  if(!rgbData.imageRaw().empty() && !irData.imageRaw().empty())
5771  {
5772  // assume rgb sensor is on right (e.g., Kinect, Xtion Live Pro)
5773  int pair = _calibrationDialog->getStereoPairs();
5774  _calibrationDialog->processImages(irData.imageRaw(), rgbData.imageRaw(), serial.c_str());
5775  if(_calibrationDialog->getStereoPairs() - pair > 0)
5776  {
5777  ++count;
5778  if(count < totalSamples)
5779  {
5780  button = QMessageBox::question(this, tr("Calibration"),
5781  tr("A stereo pair has been taken (total=%1/%2). Move the checkboard or "
5782  "camera to another position. Press \"Yes\" when you are ready "
5783  "for the next capture.").arg(count).arg(totalSamples),
5784  QMessageBox::Yes | QMessageBox::Abort, QMessageBox::Yes);
5785  }
5786  }
5787  else
5788  {
5789  button = QMessageBox::question(this, tr("Calibration"),
5790  tr("Could not detect the checkboard on both images or "
5791  "the point of view didn't change enough. Try again?"),
5792  QMessageBox::Yes | QMessageBox::No, QMessageBox::Yes);
5793  }
5794  }
5795  else
5796  {
5797  button = QMessageBox::question(this, tr("Calibration"),
5798  tr("Failed to start the camera. Try again?"), QMessageBox::Yes | QMessageBox::No, QMessageBox::Yes);
5799  }
5800  }
5801  if(count == totalSamples && button == QMessageBox::Yes)
5802  {
5803  StereoCameraModel stereoModel = _calibrationDialog->stereoCalibration(irModel, rgbModel, true);
5804  stereoModel.setName(stereoModel.name(), "depth", "rgb");
5805  if(stereoModel.stereoTransform().isNull())
5806  {
5807  QMessageBox::warning(this, tr("Calibration"),
5808  tr("Extrinsic calibration has failed! Look on the terminal "
5809  "for possible error messages. Make sure corresponding calibration files exist "
5810  "in \"%1\" folder for camera \"%2\" or calibration name set. If not, re-do "
5811  "step 1 and 2 and make sure to export the calibration files.").arg(this->getCameraInfoDir()).arg(serial.c_str()), QMessageBox::Ok);
5812  }
5813  else if(stereoModel.saveStereoTransform(this->getCameraInfoDir().toStdString()))
5814  {
5815  QMessageBox::information(this, tr("Calibration"),
5816  tr("Calibration is completed! Extrinsics have been saved to \"%1/%2_pose.yaml\"").arg(this->getCameraInfoDir()).arg(stereoModel.name().c_str()), QMessageBox::Ok);
5817  }
5818  }
5819  }
5820  }
5821  }
5822  }
5823  else // standard calibration
5824  {
5825  Camera * camera = this->createCamera(true);
5826  if(!camera)
5827  {
5828  return;
5829  }
5830 
5831  bool freenect2 = driver == kSrcFreenect2;
5832  _calibrationDialog->setStereoMode(this->getSourceType() != kSrcRGB && driver != kSrcRealSense, freenect2?"rgb":"left", freenect2?"depth":"right"); // RGB+Depth or left+right
5836 
5837  CameraThread cameraThread(camera, this->getAllParameters());
5838  UEventsManager::createPipe(&cameraThread, _calibrationDialog, "CameraEvent");
5839 
5840  cameraThread.start();
5841 
5842  _calibrationDialog->exec();
5844 
5845  cameraThread.join(true);
5846  }
5847 }
5848 
5850 {
5852  if(_createCalibrationDialog->exec() == QMessageBox::Accepted)
5853  {
5854  _ui->lineEdit_calibrationFile->setText(_createCalibrationDialog->cameraName());
5855  }
5856 }
5857 
5858 }
5859 
d
int getCloudColorScheme(int index) const
static bool parse(const ParametersMap &parameters, const std::string &key, bool &value)
Definition: Parameters.cpp:446
void processImages(const cv::Mat &imageLeft, const cv::Mat &imageRight, const QString &cameraName)
QVector< QSpinBox * > _3dRenderingDownsamplingScan
void setParameter(const std::string &key, const std::string &value)
Camera * createCamera(bool useRawImages=false, bool useColor=true)
double getScanMinRange(int index) const
void saveMainWindowState(const QMainWindow *mainWindow)
void updateParameters(const ParametersMap &parameters, bool setOtherParametersToDefault=false)
static void createPipe(const UEventsSender *sender, const UEventsHandler *receiver, const std::string &eventName)
void start()
Definition: UThread.cpp:122
void setStereoExposureCompensation(bool enabled)
Definition: CameraThread.h:63
rtabmap::ParametersMap _parameters
static bool isCSparseAvailable()
double getSubtractFilteringRadius() const
bool init(const std::string &path)
Definition: IMUThread.cpp:50
double getCeilingFilteringHeight() const
double UTILITE_EXP uStr2Double(const std::string &str)
rtabmap::ParametersMap getAllParameters() const
f
Transform stereoTransform() const
virtual void readCameraSettings(const QString &filePath=QString())
CalibrationDialog * _calibrationDialog
int uStrNumCmp(const std::string &a, const std::string &b)
Definition: UStl.h:719
void setDepthScaledToRGBSize(bool enabled)
void loadSettings(QSettings &settings, const QString &group="")
std::pair< std::string, std::string > ParametersPair
Definition: Parameters.h:42
cv::Mat visualize(const std::string &path="") const
static Transform getIdentity()
Definition: Transform.cpp:364
bool UTILITE_EXP uStr2Bool(const char *str)
PreferencesDialog::Src getSourceType() const
virtual QString getIniFilePath() const
void enableBilateralFiltering(float sigmaS, float sigmaR)
Transform getLaserLocalTransform() const
static std::map< std::string, unsigned long > getRegisteredThreads()
Definition: ULogger.cpp:247
QStandardItemModel * _indexModel
float UTILITE_EXP uStr2Float(const std::string &str)
std::vector< float > getCloudRoiRatios(int index) const
std::map< std::string, std::string > ParametersMap
Definition: Parameters.h:41
std::string UTILITE_EXP uBool2Str(bool boolean)
void readSettings(const QString &filePath=QString())
static bool isCholmodAvailable()
static void writeINI(const std::string &configFile, const ParametersMap &parameters)
Some conversion functions.
void setSwitchedImages(bool switched)
virtual void readGuiSettings(const QString &filePath=QString())
double getScanMaxRange(int index) const
std::vector< std::string > getGeneralLoggerThreads() const
static bool available()
Definition: CameraRGBD.cpp:382
const cv::Mat & imageRaw() const
Definition: SensorData.h:161
static bool isAvailable(Optimizer::Type type)
Definition: Optimizer.cpp:46
bool parseModel(QList< QGroupBox * > &boxes, QStandardItem *parentItem, int currentLevel, int &absoluteIndex)
#define UFATAL(...)
double getCloudVoxelSizeScan(int index) const
Transform getIMULocalTransform() const
double getCloudOpacity(int index) const
void loadMainWindowState(QMainWindow *mainWindow, bool &maximized, bool &statusBarShown)
static bool available()
Definition: CameraRGBD.cpp:272
virtual bool readCoreSettings(const QString &filePath=QString())
QVector< QSpinBox * > _3dRenderingPtSize
virtual void closeEvent(QCloseEvent *event)
QVector< QDoubleSpinBox * > _3dRenderingVoxelSizeScan
QVector< QCheckBox * > _3dRenderingShowFrustums
virtual std::string getSerial() const =0
PreferencesDialog::Src getSourceDriver() const
void saveCustomConfig(const QString &section, const QString &key, const QString &value)
void setSavingDirectory(const QString &savingDirectory)
virtual bool init(const std::string &calibrationFolder=".", const std::string &cameraName="")=0
#define UASSERT(condition)
QString getSourceDistortionModel() const
void setColorOnly(bool colorOnly)
Definition: CameraThread.h:64
SensorData takeImage(CameraInfo *info=0)
Definition: Camera.cpp:67
Wrappers of STL for convenient functions.
double getSourceScanNormalsRadius() const
bool isNull() const
Definition: Transform.cpp:107
QVector< QSpinBox * > _3dRenderingPtSizeFeatures
#define ULOGGER_DEBUG(...)
Definition: ULogger.h:53
virtual void setStartIndex(int index)
Definition: CameraRGBD.h:500
void setDetectionRate(double value)
QVector< QSpinBox * > _3dRenderingPtSizeScan
double getScanNormalRadiusSearch() const
void saveSettings(QSettings &settings, const QString &group="") const
int getDownsamplingStepScan(int index) const
QVector< QLineEdit * > _3dRenderingRoiRatios
QList< QGroupBox * > getGroupBoxes()
int getCloudDecimation(int index) const
virtual void writeGuiSettings(const QString &filePath=QString()) const
bool saveStereoTransform(const std::string &directory) const
int getScanPointSize(int index) const
bool isSourceStereoExposureCompensation() const
virtual void setStartIndex(int index)
Definition: CameraRGB.h:71
static Odometry * create(const ParametersMap &parameters)
Definition: Odometry.cpp:53
Ui_preferencesDialog * _ui
void saveWindowGeometry(const QWidget *window)
bool isFeaturesShown(int index) const
int getCloudPointSize(int index) const
QVector< QDoubleSpinBox * > _3dRenderingOpacity
void setDistortionModel(const std::string &path)
virtual void showEvent(QShowEvent *event)
QVector< QSpinBox * > _3dRenderingDecimation
bool openDatabase(const QString &path)
bool isScansShown(int index) const
virtual void writeCameraSettings(const QString &filePath=QString()) const
void setMirroringEnabled(bool enabled)
Definition: CameraThread.h:62
bool uContains(const std::list< V > &list, const V &value)
Definition: UStl.h:409
bool isFrustumsShown(int index) const
double getScanCeilingFilteringHeight() const
virtual void writeCoreSettings(const QString &filePath=QString()) const
void setImageDecimation(int decimation)
Definition: CameraThread.h:65
QVector< QDoubleSpinBox * > _3dRenderingMaxDepth
void registerToEventsManager()
QVector< QCheckBox * > _3dRenderingShowFeatures
static std::string getType(const std::string &paramKey)
Definition: Parameters.cpp:416
void closeDialog(QAbstractButton *button)
#define false
Definition: ConvertUTF.c:56
double getScanOpacity(int index) const
QVector< QSpinBox * > _3dRenderingColorSchemeScan
static const ParametersMap & getDefaultParameters()
Definition: Parameters.h:695
void resetSettings(int panelNumber)
QString loadCustomConfig(const QString &section, const QString &key)
const std::vector< CameraModel > & cameraModels() const
Definition: SensorData.h:193
std::string getParameter(const std::string &key) const
QVector< QDoubleSpinBox * > _3dRenderingOpacityScan
void setScanFromDepth(bool enabled, int decimation=4, float maxDepth=4.0f, float voxelSize=0.0f, int normalsK=0, int normalsRadius=0.0f)
Definition: CameraThread.h:72
void setStereoToDepth(bool enabled)
Definition: CameraThread.h:66
void setStereoMode(bool stereo, const QString &leftSuffix="left", const QString &rightSuffix="right")
virtual QString getDefaultWorkingDirectory() const
void setProgressVisibility(bool visible)
#define UDEBUG(...)
void saveWidgetState(const QWidget *widget)
int getFeaturesPointSize(int index) const
void showCloseButton(bool visible=true)
void loadSettings(QSettings &settings, const QString &group="")
QVector< QDoubleSpinBox * > _3dRenderingMinDepth
#define UERROR(...)
#define ULOGGER_WARN(...)
Definition: ULogger.h:55
virtual void setStartIndex(int index)
Definition: CameraStereo.h:191
ULogger class and convenient macros.
#define UWARN(...)
void loadWindowGeometry(QWidget *window)
PreferencesDialog(QWidget *parent=0)
void setName(const std::string &name, const std::string &leftSuffix="left", const std::string &rightSuffix="right")
void settingsChanged(PreferencesDialog::PANEL_FLAGS)
void writeSettings(const QString &filePath=QString())
static void readINI(const std::string &configFile, ParametersMap &parameters, bool modifiedOnly=false)
Definition: Parameters.cpp:953
QProgressDialog * _progressDialog
double getSourceScanFromDepthMaxDepth() const
double getScanFloorFilteringHeight() const
void resetApply(QAbstractButton *button)
bool sortCallback(const std::string &a, const std::string &b)
void unregisterFromEventsManager()
QVector< QDoubleSpinBox * > _3dRenderingMinRange
void clicked(const QModelIndex &current, const QModelIndex &previous)
void join(bool killFirst=false)
Definition: UThread.cpp:85
void saveSettings(QSettings &settings, const QString &group="") const
QVector< QCheckBox * > _3dRenderingShowScans
double getSubtractFilteringAngle() const
double getCloudMaxDepth(int index) const
static bool available()
static bool exposureGainAvailable()
Definition: CameraRGBD.cpp:391
#define ULOGGER_ERROR(...)
Definition: ULogger.h:56
void setCameraName(const QString &name)
QVector< QSpinBox * > _3dRenderingColorScheme
QVector< QDoubleSpinBox * > _3dRenderingMaxRange
void loadWidgetState(QWidget *widget)
static Transform fromString(const std::string &string)
Definition: Transform.cpp:415
rtabmap::ParametersMap _modifiedParameters
bool isCloudsShown(int index) const
bool notifyWhenNewGlobalPathIsReceived() const
std::string UTILITE_EXP uNumber2Str(unsigned int number)
Definition: UConversion.cpp:90
void addParameters(const QObjectList &children)
int getScanColorScheme(int index) const
virtual QString getTmpIniFilePath() const
static std::string createDefaultWorkingDirectory()
Definition: Parameters.cpp:58
static bool available()
Definition: CameraRGBD.cpp:110
QVector< QCheckBox * > _3dRenderingShowClouds
double getCloudMinDepth(int index) const
void uInsert(std::map< K, V > &map, const std::pair< K, V > &pair)
Definition: UStl.h:443
StereoCameraModel stereoCalibration(const CameraModel &left, const CameraModel &right, bool ignoreStereoRectification) const
const std::string & name() const
#define UINFO(...)
Transform getSourceLocalTransform() const
CreateSimpleCalibrationDialog * _createCalibrationDialog


rtabmap
Author(s): Mathieu Labbe
autogenerated on Wed Jun 5 2019 22:41:32