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


rtabmap
Author(s): Mathieu Labbe
autogenerated on Mon Dec 14 2020 03:34:59