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


rtabmap
Author(s): Mathieu Labbe
autogenerated on Mon Jan 23 2023 03:37:29