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 
17 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
18 ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
19 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
20 DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY
21 DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
22 (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
23 LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
24 ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
25 (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
26 SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
27 */
28 
29 #include <pcl/pcl_config.h>
30 #if PCL_VERSION_COMPARE(>=, 1, 8, 0)
31 // Should be first on windows to avoid "WinSock.h has already been included" error
33 #endif
34 
39 
40 #include <QtCore/QSettings>
41 #include <QtCore/QDir>
42 #include <QtCore/QTimer>
43 #include <QUrl>
44 
45 #include <QButtonGroup>
46 #include <QFileDialog>
47 #include <QInputDialog>
48 #include <QMessageBox>
49 #include <QtGui/QStandardItemModel>
50 #include <QMainWindow>
51 #include <QProgressDialog>
52 #include <QScrollBar>
53 #include <QStatusBar>
54 #include <QFormLayout>
55 #include <QDesktopServices>
56 #include <QtGui/QCloseEvent>
57 
58 #include "ui_preferencesDialog.h"
59 
60 #include "rtabmap/core/Version.h"
62 #include "rtabmap/core/Odometry.h"
65 #include "rtabmap/core/CameraRGB.h"
67 #include "rtabmap/core/IMUFilter.h"
68 #include "rtabmap/core/IMUThread.h"
69 #include "rtabmap/core/Memory.h"
71 #include "rtabmap/core/Optimizer.h"
73 #include "rtabmap/core/DBReader.h"
75 
79 #include "rtabmap/gui/ImageView.h"
86 
89 #include <rtabmap/utilite/UStl.h>
91 #include "rtabmap/utilite/UPlot.h"
92 
93 // Presets
94 #include "camera_tof_icp_ini.h"
95 #include "lidar3d_icp_ini.h"
96 
97 #include <opencv2/opencv_modules.hpp>
99 #if CV_MAJOR_VERSION < 3
100 #ifdef HAVE_OPENCV_GPU
101  #include <opencv2/gpu/gpu.hpp>
102 #endif
103 #else
104 #ifdef HAVE_OPENCV_CUDAFEATURES2D
105  #include <opencv2/core/cuda.hpp>
106 #endif
107 #endif
108 
109 using namespace rtabmap;
110 
111 namespace rtabmap {
112 
114  QDialog(parent),
115  _obsoletePanels(kPanelDummy),
116  _ui(0),
117  _indexModel(0),
118  _initialized(false),
119  _progressDialog(new QProgressDialog(this)),
120  _calibrationDialog(new CalibrationDialog(false, ".", false, this)),
121  _createCalibrationDialog(new CreateSimpleCalibrationDialog(".", "", this))
122 {
123  ULOGGER_DEBUG("");
124  _calibrationDialog->setWindowFlags(Qt::Window);
125  _calibrationDialog->setWindowTitle(tr("Calibration"));
126 
127  _progressDialog->setWindowTitle(tr("Read parameters..."));
128  _progressDialog->setMaximum(2);
129  _progressDialog->setValue(2);
130 
131  _ui = new Ui_preferencesDialog();
132  _ui->setupUi(this);
133 
134  bool haveCuda = false;
135 #if CV_MAJOR_VERSION < 3
136 #ifdef HAVE_OPENCV_GPU
137  haveCuda = cv::gpu::getCudaEnabledDeviceCount() != 0;
138 #endif
139 #else
140 #ifdef HAVE_OPENCV_CUDAFEATURES2D
141  haveCuda = cv::cuda::getCudaEnabledDeviceCount() != 0;
142 #endif
143 #endif
144  if(!haveCuda)
145  {
146  _ui->surf_checkBox_gpuVersion->setChecked(false);
147  _ui->surf_checkBox_gpuVersion->setEnabled(false);
148  _ui->label_surf_checkBox_gpuVersion->setEnabled(false);
149  _ui->surf_doubleSpinBox_gpuKeypointsRatio->setEnabled(false);
150  _ui->label_surf_checkBox_gpuKeypointsRatio->setEnabled(false);
151 
152  _ui->fastGpu->setChecked(false);
153  _ui->fastGpu->setEnabled(false);
154  _ui->label_fastGPU->setEnabled(false);
155  _ui->fastKeypointRatio->setEnabled(false);
156  _ui->label_fastGPUKptRatio->setEnabled(false);
157 
158  _ui->checkBox_ORBGpu->setChecked(false);
159  _ui->checkBox_ORBGpu->setEnabled(false);
160  _ui->label_orbGpu->setEnabled(false);
161 
162  // disable BruteForceGPU option
163  _ui->comboBox_dictionary_strategy->setItemData(4, 0, Qt::UserRole - 1);
164  _ui->reextract_nn->setItemData(4, 0, Qt::UserRole - 1);
165  }
166 
167 #ifndef RTABMAP_OCTOMAP
168  _ui->groupBox_octomap->setChecked(false);
169  _ui->groupBox_octomap->setEnabled(false);
170 #endif
171 
172 #ifndef RTABMAP_GRIDMAP
173  _ui->checkBox_elevation_shown->setChecked(false);
174  _ui->checkBox_elevation_shown->setEnabled(false);
175  _ui->label_show_elevation->setEnabled(false);
176 #endif
177 
178 #ifndef RTABMAP_REALSENSE_SLAM
179  _ui->checkbox_realsenseOdom->setChecked(false);
180  _ui->checkbox_realsenseOdom->setEnabled(false);
181  _ui->label_realsenseOdom->setEnabled(false);
182 #endif
183 
184 #ifndef RTABMAP_FOVIS
185  _ui->odom_strategy->setItemData(2, 0, Qt::UserRole - 1);
186 #endif
187 #ifndef RTABMAP_VISO2
188  _ui->odom_strategy->setItemData(3, 0, Qt::UserRole - 1);
189 #endif
190 #ifndef RTABMAP_DVO
191  _ui->odom_strategy->setItemData(4, 0, Qt::UserRole - 1);
192 #endif
193 #ifndef RTABMAP_ORB_SLAM
194  _ui->odom_strategy->setItemData(5, 0, Qt::UserRole - 1);
195 #elif RTABMAP_ORB_SLAM == 3
196  _ui->odom_strategy->setItemText(5, "ORB SLAM 3");
197  _ui->groupBox_odomORBSLAM->setTitle("ORB SLAM 3");
198 #else
199  _ui->odom_strategy->setItemText(5, "ORB SLAM 2");
200  _ui->groupBox_odomORBSLAM->setTitle("ORB SLAM 2");
201 #endif
202 #ifndef RTABMAP_OKVIS
203  _ui->odom_strategy->setItemData(6, 0, Qt::UserRole - 1);
204 #endif
205 #ifndef RTABMAP_LOAM
206  _ui->odom_strategy->setItemData(7, 0, Qt::UserRole - 1);
207 #endif
208 #ifndef RTABMAP_MSCKF_VIO
209  _ui->odom_strategy->setItemData(8, 0, Qt::UserRole - 1);
210 #endif
211 #ifndef RTABMAP_VINS
212  _ui->odom_strategy->setItemData(9, 0, Qt::UserRole - 1);
213 #endif
214 #ifndef RTABMAP_OPENVINS
215  _ui->odom_strategy->setItemData(10, 0, Qt::UserRole - 1);
216 #endif
217 #ifndef RTABMAP_FLOAM
218  _ui->odom_strategy->setItemData(11, 0, Qt::UserRole - 1);
219 #endif
220 #ifndef RTABMAP_OPEN3D
221  _ui->odom_strategy->setItemData(12, 0, Qt::UserRole - 1);
222 #endif
223 
224 #if CV_MAJOR_VERSION < 3
225  _ui->stereosgbm_mode->setItemData(2, 0, Qt::UserRole - 1);
226 #endif
227 
228 //SURF
229 #ifndef RTABMAP_NONFREE
230  _ui->comboBox_detector_strategy->setItemData(0, 0, Qt::UserRole - 1);
231  _ui->comboBox_detector_strategy->setItemData(12, 0, Qt::UserRole - 1);
232  _ui->comboBox_detector_strategy->setItemData(14, 0, Qt::UserRole - 1);
233  _ui->vis_feature_detector->setItemData(0, 0, Qt::UserRole - 1);
234  _ui->vis_feature_detector->setItemData(12, 0, Qt::UserRole - 1);
235  _ui->vis_feature_detector->setItemData(14, 0, Qt::UserRole - 1);
236 #endif
237 
238 // SIFT
239 #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)))
240 #ifndef RTABMAP_NONFREE
241  _ui->comboBox_detector_strategy->setItemData(1, 0, Qt::UserRole - 1);
242  _ui->vis_feature_detector->setItemData(1, 0, Qt::UserRole - 1);
243 #endif
244 #endif
245 
246 #if CV_MAJOR_VERSION >= 3 && !defined(HAVE_OPENCV_XFEATURES2D)
247  _ui->comboBox_detector_strategy->setItemData(3, 0, Qt::UserRole - 1);
248  _ui->comboBox_detector_strategy->setItemData(4, 0, Qt::UserRole - 1);
249  _ui->comboBox_detector_strategy->setItemData(5, 0, Qt::UserRole - 1);
250  _ui->comboBox_detector_strategy->setItemData(6, 0, Qt::UserRole - 1);
251  _ui->comboBox_detector_strategy->setItemData(12, 0, Qt::UserRole - 1);
252  _ui->comboBox_detector_strategy->setItemData(13, 0, Qt::UserRole - 1);
253  _ui->comboBox_detector_strategy->setItemData(14, 0, Qt::UserRole - 1);
254  _ui->vis_feature_detector->setItemData(3, 0, Qt::UserRole - 1);
255  _ui->vis_feature_detector->setItemData(4, 0, Qt::UserRole - 1);
256  _ui->vis_feature_detector->setItemData(5, 0, Qt::UserRole - 1);
257  _ui->vis_feature_detector->setItemData(6, 0, Qt::UserRole - 1);
258  _ui->vis_feature_detector->setItemData(12, 0, Qt::UserRole - 1);
259  _ui->vis_feature_detector->setItemData(13, 0, Qt::UserRole - 1);
260  _ui->vis_feature_detector->setItemData(14, 0, Qt::UserRole - 1);
261 #endif
262 
263 #ifndef RTABMAP_ORB_OCTREE
264  _ui->comboBox_detector_strategy->setItemData(10, 0, Qt::UserRole - 1);
265  _ui->vis_feature_detector->setItemData(10, 0, Qt::UserRole - 1);
266 #endif
267 
268 #ifndef RTABMAP_TORCH
269  _ui->comboBox_detector_strategy->setItemData(11, 0, Qt::UserRole - 1);
270  _ui->vis_feature_detector->setItemData(11, 0, Qt::UserRole - 1);
271 #endif
272 
273 #ifndef RTABMAP_PYTHON
274  _ui->comboBox_detector_strategy->setItemData(15, 0, Qt::UserRole - 1);
275  _ui->vis_feature_detector->setItemData(15, 0, Qt::UserRole - 1);
276  _ui->reextract_nn->setItemData(6, 0, Qt::UserRole - 1);
277  _ui->comboBox_globalDescriptorExtractor->setItemData(1, 0, Qt::UserRole - 1);
278 #endif
279 
280 #if !defined(HAVE_OPENCV_XFEATURES2D) || (CV_MAJOR_VERSION == 3 && (CV_MINOR_VERSION<4 || CV_MINOR_VERSION==4 && CV_SUBMINOR_VERSION<1))
281  _ui->reextract_nn->setItemData(7, 0, Qt::UserRole - 1);
282 #endif
283 
284 #if CV_MAJOR_VERSION >= 3
285  _ui->groupBox_fast_opencv2->setEnabled(false);
286 #else
287  _ui->comboBox_detector_strategy->setItemData(9, 0, Qt::UserRole - 1); // No KAZE
288  _ui->comboBox_detector_strategy->setItemData(13, 0, Qt::UserRole - 1); // No DAISY
289  _ui->comboBox_detector_strategy->setItemData(14, 0, Qt::UserRole - 1); // No DAISY
290  _ui->vis_feature_detector->setItemData(9, 0, Qt::UserRole - 1); // No KAZE
291  _ui->vis_feature_detector->setItemData(13, 0, Qt::UserRole - 1); // No DAISY
292  _ui->vis_feature_detector->setItemData(14, 0, Qt::UserRole - 1); // No DAISY
293 #endif
294 
295  _ui->comboBox_cameraImages_odomFormat->setItemData(4, 0, Qt::UserRole - 1);
296  _ui->comboBox_cameraImages_gtFormat->setItemData(4, 0, Qt::UserRole - 1);
298  {
299  _ui->graphOptimization_type->setItemData(1, 0, Qt::UserRole - 1);
300  _ui->odom_f2m_bundleStrategy->setItemData(1, 0, Qt::UserRole - 1);
301  _ui->loopClosure_bundle->setItemData(1, 0, Qt::UserRole - 1);
302  _ui->groupBoxx_g2o->setEnabled(false);
303  }
304 #ifdef RTABMAP_ORB_SLAM
305  else
306  {
307  // only graph optimization is disabled, g2o (from ORB_SLAM2) is valid only for SBA
308  _ui->graphOptimization_type->setItemData(1, 0, Qt::UserRole - 1);
309  }
310 #endif
312  {
313  _ui->comboBox_g2o_solver->setItemData(0, 0, Qt::UserRole - 1);
314  }
316  {
317  _ui->comboBox_g2o_solver->setItemData(2, 0, Qt::UserRole - 1);
318  }
320  {
321  _ui->graphOptimization_type->setItemData(0, 0, Qt::UserRole - 1);
322  }
324  {
325  _ui->graphOptimization_type->setItemData(2, 0, Qt::UserRole - 1);
326  }
328  {
329  _ui->odom_f2m_bundleStrategy->setItemData(2, 0, Qt::UserRole - 1);
330  _ui->loopClosure_bundle->setItemData(2, 0, Qt::UserRole - 1);
331  }
333  {
334  _ui->graphOptimization_type->setItemData(3, 0, Qt::UserRole - 1);
335  _ui->odom_f2m_bundleStrategy->setItemData(3, 0, Qt::UserRole - 1);
336  _ui->loopClosure_bundle->setItemData(3, 0, Qt::UserRole - 1);
337  }
338 #ifdef RTABMAP_VERTIGO
340 #endif
341  {
342  _ui->graphOptimization_robust->setEnabled(false);
343  }
344 #ifndef RTABMAP_POINTMATCHER
345  _ui->comboBox_icpStrategy->setItemData(1, 0, Qt::UserRole - 1);
346 #endif
347 #ifndef RTABMAP_CCCORELIB
348  _ui->comboBox_icpStrategy->setItemData(2, 0, Qt::UserRole - 1);
349 #endif
351  {
352  _ui->comboBox_cameraRGBD->setItemData(kSrcOpenNI_PCL - kSrcRGBD, 0, Qt::UserRole - 1);
353  }
355  {
356  _ui->comboBox_cameraRGBD->setItemData(kSrcFreenect - kSrcRGBD, 0, Qt::UserRole - 1);
357  }
359  {
360  _ui->comboBox_cameraRGBD->setItemData(kSrcOpenNI_CV - kSrcRGBD, 0, Qt::UserRole - 1);
361  _ui->comboBox_cameraRGBD->setItemData(kSrcOpenNI_CV_ASUS - kSrcRGBD, 0, Qt::UserRole - 1);
362  }
364  {
365  _ui->comboBox_cameraRGBD->setItemData(kSrcOpenNI2 - kSrcRGBD, 0, Qt::UserRole - 1);
366  }
368  {
369  _ui->comboBox_cameraRGBD->setItemData(kSrcFreenect2 - kSrcRGBD, 0, Qt::UserRole - 1);
370  }
371  if (!CameraK4W2::available())
372  {
373  _ui->comboBox_cameraRGBD->setItemData(kSrcK4W2 - kSrcRGBD, 0, Qt::UserRole - 1);
374  }
375  if (!CameraK4A::available())
376  {
377  _ui->comboBox_cameraRGBD->setItemData(kSrcK4A - kSrcRGBD, 0, Qt::UserRole - 1);
378  }
380  {
381  _ui->comboBox_cameraRGBD->setItemData(kSrcRealSense - kSrcRGBD, 0, Qt::UserRole - 1);
382  }
384  {
385  _ui->comboBox_cameraRGBD->setItemData(kSrcRealSense2 - kSrcRGBD, 0, Qt::UserRole - 1);
386  _ui->comboBox_cameraStereo->setItemData(kSrcStereoRealSense2 - kSrcStereo, 0, Qt::UserRole - 1);
387  _ui->comboBox_odom_sensor->setItemData(1, 0, Qt::UserRole - 1);
388  }
390  {
391  _ui->comboBox_cameraStereo->setItemData(kSrcDC1394 - kSrcStereo, 0, Qt::UserRole - 1);
392  }
394  {
395  _ui->comboBox_cameraStereo->setItemData(kSrcFlyCapture2 - kSrcStereo, 0, Qt::UserRole - 1);
396  }
398  {
399  _ui->comboBox_cameraStereo->setItemData(kSrcStereoZed - kSrcStereo, 0, Qt::UserRole - 1);
400  _ui->comboBox_odom_sensor->setItemData(2, 0, Qt::UserRole - 1);
401  }
402  else if(CameraStereoZed::sdkVersion() < 4)
403  {
404  _ui->comboBox_stereoZed_resolution->setItemData(2, 0, Qt::UserRole - 1);
405  _ui->comboBox_stereoZed_resolution->setItemData(4, 0, Qt::UserRole - 1);
406  _ui->comboBox_stereoZed_resolution->setItemData(6, 0, Qt::UserRole - 1);
407  _ui->comboBox_stereoZed_quality->setItemData(3, 0, Qt::UserRole - 1);
408  }
410  {
411  _ui->comboBox_cameraStereo->setItemData(kSrcStereoTara - kSrcStereo, 0, Qt::UserRole - 1);
412  }
414  {
415  _ui->comboBox_cameraStereo->setItemData(kSrcStereoMyntEye - kSrcStereo, 0, Qt::UserRole - 1);
416  }
418  {
419  _ui->comboBox_cameraStereo->setItemData(kSrcStereoZedOC - kSrcStereo, 0, Qt::UserRole - 1);
420  }
422  {
423  _ui->comboBox_cameraStereo->setItemData(kSrcStereoDepthAI - kSrcStereo, 0, Qt::UserRole - 1);
424  }
426  {
427  _ui->comboBox_cameraRGBD->setItemData(kSrcSeerSense - kSrcRGBD, 0, Qt::UserRole - 1);
428  _ui->comboBox_odom_sensor->setItemData(3, 0, Qt::UserRole - 1);
429  }
430  _ui->openni2_exposure->setEnabled(CameraOpenNI2::exposureGainAvailable());
431  _ui->openni2_gain->setEnabled(CameraOpenNI2::exposureGainAvailable());
432 
433 #if PCL_VERSION_COMPARE(<, 1, 7, 2)
434  _ui->checkBox_showFrustums->setEnabled(false);
435  _ui->checkBox_showFrustums->setChecked(false);
436  _ui->checkBox_showOdomFrustums->setEnabled(false);
437  _ui->checkBox_showOdomFrustums->setChecked(false);
438 #endif
439 
440  //if OpenCV < 3.4.2
441 #if CV_MAJOR_VERSION < 3 || (CV_MAJOR_VERSION == 3 && (CV_MINOR_VERSION <4 || (CV_MINOR_VERSION ==4 && CV_SUBMINOR_VERSION<2)))
442  _ui->ArucoDictionary->setItemData(17, 0, Qt::UserRole - 1);
443  _ui->ArucoDictionary->setItemData(18, 0, Qt::UserRole - 1);
444  _ui->ArucoDictionary->setItemData(19, 0, Qt::UserRole - 1);
445  _ui->ArucoDictionary->setItemData(20, 0, Qt::UserRole - 1);
446 #endif
447 #ifndef HAVE_OPENCV_ARUCO
448  _ui->label_markerDetection->setText(_ui->label_markerDetection->text()+" This option works only if OpenCV has been built with \"aruco\" module.");
449 #endif
450 
451 #ifndef RTABMAP_MADGWICK
452  _ui->comboBox_imuFilter_strategy->setItemData(1, 0, Qt::UserRole - 1);
453 #endif
454 
455  // in case we change the ui, we should not forget to change stuff related to this parameter
456  UASSERT(_ui->odom_registration->count() == 4);
457 
458  // Default Driver
459  connect(_ui->comboBox_sourceType, SIGNAL(currentIndexChanged(int)), this, SLOT(updateSourceGrpVisibility()));
460  connect(_ui->comboBox_cameraRGBD, SIGNAL(currentIndexChanged(int)), this, SLOT(updateSourceGrpVisibility()));
461  connect(_ui->source_comboBox_image_type, SIGNAL(currentIndexChanged(int)), this, SLOT(updateSourceGrpVisibility()));
462  connect(_ui->comboBox_cameraStereo, SIGNAL(currentIndexChanged(int)), this, SLOT(updateSourceGrpVisibility()));
463  connect(_ui->comboBox_imuFilter_strategy, SIGNAL(currentIndexChanged(int)), this, SLOT(updateSourceGrpVisibility()));
464  connect(_ui->comboBox_odom_sensor, SIGNAL(currentIndexChanged(int)), this, SLOT(updateSourceGrpVisibility()));
465  connect(_ui->comboBox_lidar_src, SIGNAL(currentIndexChanged(int)), this, SLOT(updateSourceGrpVisibility()));
466  connect(_ui->checkBox_source_scanFromDepth, SIGNAL(stateChanged(int)), this, SLOT(updateSourceGrpVisibility()));
467  this->resetSettings(_ui->groupBox_source0);
468 
469  _ui->predictionPlot->showLegend(false);
470 
471  QButtonGroup * buttonGroup = new QButtonGroup(this);
472  buttonGroup->addButton(_ui->radioButton_basic);
473  buttonGroup->addButton(_ui->radioButton_advanced);
474 
475  // Connect
476  connect(_ui->buttonBox_global, SIGNAL(clicked(QAbstractButton *)), this, SLOT(closeDialog(QAbstractButton *)));
477  connect(_ui->buttonBox_local, SIGNAL(clicked(QAbstractButton *)), this, SLOT(resetApply(QAbstractButton *)));
478  connect(_ui->pushButton_loadConfig, SIGNAL(clicked()), this, SLOT(loadConfigFrom()));
479  connect(_ui->pushButton_saveConfig, SIGNAL(clicked()), this, SLOT(saveConfigTo()));
480  connect(_ui->pushButton_resetConfig, SIGNAL(clicked()), this, SLOT(resetConfig()));
481  connect(_ui->pushButton_presets_camera_tof_icp, SIGNAL(clicked()), this, SLOT(loadPreset()));
482  connect(_ui->pushButton_presets_lidar_3d_icp, SIGNAL(clicked()), this, SLOT(loadPreset()));
483  connect(_ui->radioButton_basic, SIGNAL(toggled(bool)), this, SLOT(setupTreeView()));
484  connect(_ui->pushButton_testOdometry, SIGNAL(clicked()), this, SLOT(testOdometry()));
485  connect(_ui->pushButton_test_camera, SIGNAL(clicked()), this, SLOT(testCamera()));
486  connect(_ui->pushButton_test_lidar, SIGNAL(clicked()), this, SLOT(testLidar()));
487 
488  // General panel
489  connect(_ui->general_checkBox_imagesKept, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteGeneralPanel()));
490  connect(_ui->general_checkBox_missing_cache_republished, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteGeneralPanel()));
491  connect(_ui->general_checkBox_cloudsKept, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteGeneralPanel()));
492  connect(_ui->checkBox_verticalLayoutUsed, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteGeneralPanel()));
493  connect(_ui->checkBox_imageRejectedShown, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteGeneralPanel()));
494  connect(_ui->checkBox_imageHighestHypShown, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteGeneralPanel()));
495  connect(_ui->checkBox_beep, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteGeneralPanel()));
496  connect(_ui->checkBox_stamps, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteGeneralPanel()));
497  connect(_ui->checkBox_cacheStatistics, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteGeneralPanel()));
498  connect(_ui->checkBox_notifyWhenNewGlobalPathIsReceived, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteGeneralPanel()));
499  connect(_ui->spinBox_odomQualityWarnThr, SIGNAL(valueChanged(int)), this, SLOT(makeObsoleteGeneralPanel()));
500  connect(_ui->checkBox_odom_onlyInliersShown, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteGeneralPanel()));
501  connect(_ui->radioButton_posteriorGraphView, SIGNAL(toggled(bool)), this, SLOT(makeObsoleteGeneralPanel()));
502  connect(_ui->radioButton_wordsGraphView, SIGNAL(toggled(bool)), this, SLOT(makeObsoleteGeneralPanel()));
503  connect(_ui->radioButton_localizationsGraphView, SIGNAL(toggled(bool)), this, SLOT(makeObsoleteGeneralPanel()));
504  connect(_ui->radioButton_localizationsGraphViewOdomCache, SIGNAL(toggled(bool)), this, SLOT(makeObsoleteGeneralPanel()));
505  connect(_ui->radioButton_nochangeGraphView, SIGNAL(toggled(bool)), this, SLOT(makeObsoleteGeneralPanel()));
506  connect(_ui->checkbox_odomDisabled, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteGeneralPanel()));
507  connect(_ui->odom_registration, SIGNAL(currentIndexChanged(int)), this, SLOT(makeObsoleteGeneralPanel()));
508  connect(_ui->odom_f2m_gravitySigma, SIGNAL(valueChanged(double)), this, SLOT(makeObsoleteGeneralPanel()));
509  connect(_ui->checkbox_groundTruthAlign, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteGeneralPanel()));
510 
511  // Cloud rendering panel
512  _3dRenderingShowClouds.resize(2);
513  _3dRenderingShowClouds[0] = _ui->checkBox_showClouds;
514  _3dRenderingShowClouds[1] = _ui->checkBox_showOdomClouds;
515 
516  _3dRenderingDecimation.resize(2);
517  _3dRenderingDecimation[0] = _ui->spinBox_decimation;
518  _3dRenderingDecimation[1] = _ui->spinBox_decimation_odom;
519 
520  _3dRenderingMaxDepth.resize(2);
521  _3dRenderingMaxDepth[0] = _ui->doubleSpinBox_maxDepth;
522  _3dRenderingMaxDepth[1] = _ui->doubleSpinBox_maxDepth_odom;
523 
524  _3dRenderingMinDepth.resize(2);
525  _3dRenderingMinDepth[0] = _ui->doubleSpinBox_minDepth;
526  _3dRenderingMinDepth[1] = _ui->doubleSpinBox_minDepth_odom;
527 
528  _3dRenderingRoiRatios.resize(2);
529  _3dRenderingRoiRatios[0] = _ui->lineEdit_roiRatios;
530  _3dRenderingRoiRatios[1] = _ui->lineEdit_roiRatios_odom;
531 
532  _3dRenderingColorScheme.resize(2);
533  _3dRenderingColorScheme[0] = _ui->spinBox_colorScheme;
534  _3dRenderingColorScheme[1] = _ui->spinBox_colorScheme_odom;
535 
536  _3dRenderingOpacity.resize(2);
537  _3dRenderingOpacity[0] = _ui->doubleSpinBox_opacity;
538  _3dRenderingOpacity[1] = _ui->doubleSpinBox_opacity_odom;
539 
540  _3dRenderingPtSize.resize(2);
541  _3dRenderingPtSize[0] = _ui->spinBox_ptsize;
542  _3dRenderingPtSize[1] = _ui->spinBox_ptsize_odom;
543 
544  _3dRenderingShowScans.resize(2);
545  _3dRenderingShowScans[0] = _ui->checkBox_showScans;
546  _3dRenderingShowScans[1] = _ui->checkBox_showOdomScans;
547 
549  _3dRenderingDownsamplingScan[0] = _ui->spinBox_downsamplingScan;
550  _3dRenderingDownsamplingScan[1] = _ui->spinBox_downsamplingScan_odom;
551 
552  _3dRenderingMaxRange.resize(2);
553  _3dRenderingMaxRange[0] = _ui->doubleSpinBox_maxRange;
554  _3dRenderingMaxRange[1] = _ui->doubleSpinBox_maxRange_odom;
555 
556  _3dRenderingMinRange.resize(2);
557  _3dRenderingMinRange[0] = _ui->doubleSpinBox_minRange;
558  _3dRenderingMinRange[1] = _ui->doubleSpinBox_minRange_odom;
559 
560  _3dRenderingVoxelSizeScan.resize(2);
561  _3dRenderingVoxelSizeScan[0] = _ui->doubleSpinBox_voxelSizeScan;
562  _3dRenderingVoxelSizeScan[1] = _ui->doubleSpinBox_voxelSizeScan_odom;
563 
564  _3dRenderingColorSchemeScan.resize(2);
565  _3dRenderingColorSchemeScan[0] = _ui->spinBox_colorSchemeScan;
566  _3dRenderingColorSchemeScan[1] = _ui->spinBox_colorSchemeScan_odom;
567 
568  _3dRenderingOpacityScan.resize(2);
569  _3dRenderingOpacityScan[0] = _ui->doubleSpinBox_opacity_scan;
570  _3dRenderingOpacityScan[1] = _ui->doubleSpinBox_opacity_odom_scan;
571 
572  _3dRenderingPtSizeScan.resize(2);
573  _3dRenderingPtSizeScan[0] = _ui->spinBox_ptsize_scan;
574  _3dRenderingPtSizeScan[1] = _ui->spinBox_ptsize_odom_scan;
575 
576  _3dRenderingShowFeatures.resize(2);
577  _3dRenderingShowFeatures[0] = _ui->checkBox_showFeatures;
578  _3dRenderingShowFeatures[1] = _ui->checkBox_showOdomFeatures;
579 
580  _3dRenderingShowFrustums.resize(2);
581  _3dRenderingShowFrustums[0] = _ui->checkBox_showFrustums;
582  _3dRenderingShowFrustums[1] = _ui->checkBox_showOdomFrustums;
583 
584  _3dRenderingPtSizeFeatures.resize(2);
585  _3dRenderingPtSizeFeatures[0] = _ui->spinBox_ptsize_features;
586  _3dRenderingPtSizeFeatures[1] = _ui->spinBox_ptsize_odom_features;
587 
588  _3dRenderingGravity.resize(2);
589  _3dRenderingGravity[0] = _ui->checkBox_showIMUGravity;
590  _3dRenderingGravity[1] = _ui->checkBox_showIMUGravity_odom;
591 
592  _3dRenderingGravityLength.resize(2);
593  _3dRenderingGravityLength[0] = _ui->doubleSpinBox_lengthIMUGravity;
594  _3dRenderingGravityLength[1] = _ui->doubleSpinBox_lengthIMUGravity_odom;
595 
596  for(int i=0; i<2; ++i)
597  {
598  connect(_3dRenderingShowClouds[i], SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteCloudRenderingPanel()));
599  connect(_3dRenderingDecimation[i], SIGNAL(valueChanged(int)), this, SLOT(makeObsoleteCloudRenderingPanel()));
600  connect(_3dRenderingMaxDepth[i], SIGNAL(valueChanged(double)), this, SLOT(makeObsoleteCloudRenderingPanel()));
601  connect(_3dRenderingMinDepth[i], SIGNAL(valueChanged(double)), this, SLOT(makeObsoleteCloudRenderingPanel()));
602  connect(_3dRenderingRoiRatios[i], SIGNAL(textChanged(const QString &)), this, SLOT(makeObsoleteCloudRenderingPanel()));
603  connect(_3dRenderingShowScans[i], SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteCloudRenderingPanel()));
604  connect(_3dRenderingShowFeatures[i], SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteCloudRenderingPanel()));
605  connect(_3dRenderingShowFrustums[i], SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteCloudRenderingPanel()));
606 
607  connect(_3dRenderingDownsamplingScan[i], SIGNAL(valueChanged(int)), this, SLOT(makeObsoleteCloudRenderingPanel()));
608  connect(_3dRenderingMaxRange[i], SIGNAL(valueChanged(double)), this, SLOT(makeObsoleteCloudRenderingPanel()));
609  connect(_3dRenderingMinRange[i], SIGNAL(valueChanged(double)), this, SLOT(makeObsoleteCloudRenderingPanel()));
610  connect(_3dRenderingVoxelSizeScan[i], SIGNAL(valueChanged(double)), this, SLOT(makeObsoleteCloudRenderingPanel()));
611  connect(_3dRenderingColorScheme[i], SIGNAL(valueChanged(int)), this, SLOT(makeObsoleteCloudRenderingPanel()));
612  connect(_3dRenderingOpacity[i], SIGNAL(valueChanged(double)), this, SLOT(makeObsoleteCloudRenderingPanel()));
613  connect(_3dRenderingPtSize[i], SIGNAL(valueChanged(int)), this, SLOT(makeObsoleteCloudRenderingPanel()));
614  connect(_3dRenderingColorSchemeScan[i], SIGNAL(valueChanged(int)), this, SLOT(makeObsoleteCloudRenderingPanel()));
615  connect(_3dRenderingOpacityScan[i], SIGNAL(valueChanged(double)), this, SLOT(makeObsoleteCloudRenderingPanel()));
616  connect(_3dRenderingPtSizeScan[i], SIGNAL(valueChanged(int)), this, SLOT(makeObsoleteCloudRenderingPanel()));
617  connect(_3dRenderingPtSizeFeatures[i], SIGNAL(valueChanged(int)), this, SLOT(makeObsoleteCloudRenderingPanel()));
618  connect(_3dRenderingGravity[i], SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteCloudRenderingPanel()));
619  connect(_3dRenderingGravityLength[i], SIGNAL(valueChanged(double)), this, SLOT(makeObsoleteCloudRenderingPanel()));
620 
621  }
622  connect(_ui->doubleSpinBox_voxel, SIGNAL(valueChanged(double)), this, SLOT(makeObsoleteCloudRenderingPanel()));
623  connect(_ui->doubleSpinBox_noiseRadius, SIGNAL(valueChanged(double)), this, SLOT(makeObsoleteCloudRenderingPanel()));
624  connect(_ui->spinBox_noiseMinNeighbors, SIGNAL(valueChanged(int)), this, SLOT(makeObsoleteCloudRenderingPanel()));
625  connect(_ui->doubleSpinBox_ceilingFilterHeight, SIGNAL(valueChanged(double)), this, SLOT(makeObsoleteCloudRenderingPanel()));
626  connect(_ui->doubleSpinBox_floorFilterHeight, SIGNAL(valueChanged(double)), this, SLOT(makeObsoleteCloudRenderingPanel()));
627  connect(_ui->spinBox_normalKSearch, SIGNAL(valueChanged(int)), this, SLOT(makeObsoleteCloudRenderingPanel()));
628  connect(_ui->doubleSpinBox_normalRadiusSearch, SIGNAL(valueChanged(double)), this, SLOT(makeObsoleteCloudRenderingPanel()));
629  connect(_ui->doubleSpinBox_ceilingFilterHeight_scan, SIGNAL(valueChanged(double)), this, SLOT(makeObsoleteCloudRenderingPanel()));
630  connect(_ui->doubleSpinBox_floorFilterHeight_scan, SIGNAL(valueChanged(double)), this, SLOT(makeObsoleteCloudRenderingPanel()));
631  connect(_ui->spinBox_normalKSearch_scan, SIGNAL(valueChanged(int)), this, SLOT(makeObsoleteCloudRenderingPanel()));
632  connect(_ui->doubleSpinBox_normalRadiusSearch_scan, SIGNAL(valueChanged(double)), this, SLOT(makeObsoleteCloudRenderingPanel()));
633 
634  connect(_ui->checkBox_showGraphs, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteCloudRenderingPanel()));
635  connect(_ui->checkBox_showLabels, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteCloudRenderingPanel()));
636  connect(_ui->checkBox_showFrames, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteCloudRenderingPanel()));
637  connect(_ui->checkBox_showLandmarks, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteCloudRenderingPanel()));
638  connect(_ui->doubleSpinBox_landmarkSize, SIGNAL(valueChanged(double)), this, SLOT(makeObsoleteCloudRenderingPanel()));
639  connect(_ui->checkBox_showIMUGravity, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteCloudRenderingPanel()));
640  connect(_ui->checkBox_showIMUAcc, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteCloudRenderingPanel()));
641 
642  connect(_ui->radioButton_noFiltering, SIGNAL(toggled(bool)), this, SLOT(makeObsoleteCloudRenderingPanel()));
643  connect(_ui->radioButton_nodeFiltering, SIGNAL(toggled(bool)), this, SLOT(makeObsoleteCloudRenderingPanel()));
644  connect(_ui->radioButton_subtractFiltering, SIGNAL(toggled(bool)), this, SLOT(makeObsoleteCloudRenderingPanel()));
645  connect(_ui->doubleSpinBox_cloudFilterRadius, SIGNAL(valueChanged(double)), this, SLOT(makeObsoleteCloudRenderingPanel()));
646  connect(_ui->doubleSpinBox_cloudFilterAngle, SIGNAL(valueChanged(double)), this, SLOT(makeObsoleteCloudRenderingPanel()));
647  connect(_ui->spinBox_subtractFilteringMinPts, SIGNAL(valueChanged(int)), this, SLOT(makeObsoleteCloudRenderingPanel()));
648  connect(_ui->doubleSpinBox_subtractFilteringRadius, SIGNAL(valueChanged(double)), this, SLOT(makeObsoleteCloudRenderingPanel()));
649  connect(_ui->doubleSpinBox_subtractFilteringAngle, SIGNAL(valueChanged(double)), this, SLOT(makeObsoleteCloudRenderingPanel()));
650 
651  connect(_ui->doubleSpinBox_map_resolution, SIGNAL(valueChanged(double)), this, SLOT(makeObsoleteCloudRenderingPanel()));
652  connect(_ui->checkBox_map_shown, SIGNAL(clicked(bool)), this, SLOT(makeObsoleteCloudRenderingPanel()));
653  connect(_ui->doubleSpinBox_map_opacity, SIGNAL(valueChanged(double)), this, SLOT(makeObsoleteCloudRenderingPanel()));
654  connect(_ui->checkBox_elevation_shown, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteCloudRenderingPanel()));
655 
656  connect(_ui->groupBox_octomap, SIGNAL(toggled(bool)), this, SLOT(makeObsoleteCloudRenderingPanel()));
657  connect(_ui->spinBox_octomap_treeDepth, SIGNAL(valueChanged(int)), this, SLOT(makeObsoleteCloudRenderingPanel()));
658  connect(_ui->checkBox_octomap_2dgrid, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteCloudRenderingPanel()));
659  connect(_ui->checkBox_octomap_show3dMap, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteCloudRenderingPanel()));
660  connect(_ui->comboBox_octomap_renderingType, SIGNAL(currentIndexChanged(int)), this, SLOT(makeObsoleteCloudRenderingPanel()));
661  connect(_ui->spinBox_octomap_pointSize, SIGNAL(valueChanged(int)), this, SLOT(makeObsoleteCloudRenderingPanel()));
662 
663  connect(_ui->groupBox_organized, SIGNAL(toggled(bool)), this, SLOT(makeObsoleteCloudRenderingPanel()));
664  connect(_ui->doubleSpinBox_mesh_angleTolerance, SIGNAL(valueChanged(double)), this, SLOT(makeObsoleteCloudRenderingPanel()));
665  connect(_ui->checkBox_mesh_quad, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteCloudRenderingPanel()));
666  connect(_ui->checkBox_mesh_texture, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteCloudRenderingPanel()));
667  connect(_ui->spinBox_mesh_triangleSize, SIGNAL(valueChanged(int)), this, SLOT(makeObsoleteCloudRenderingPanel()));
668 
669  //Logging panel
670  connect(_ui->comboBox_loggerLevel, SIGNAL(currentIndexChanged(int)), this, SLOT(makeObsoleteLoggingPanel()));
671  connect(_ui->comboBox_loggerEventLevel, SIGNAL(currentIndexChanged(int)), this, SLOT(makeObsoleteLoggingPanel()));
672  connect(_ui->comboBox_loggerPauseLevel, SIGNAL(currentIndexChanged(int)), this, SLOT(makeObsoleteLoggingPanel()));
673  connect(_ui->checkBox_logger_printTime, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteLoggingPanel()));
674  connect(_ui->checkBox_logger_printThreadId, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteLoggingPanel()));
675  connect(_ui->comboBox_loggerType, SIGNAL(currentIndexChanged(int)), this, SLOT(makeObsoleteLoggingPanel()));
676  _ui->comboBox_loggerFilter->SetDisplayText("Select:");
677  connect(_ui->comboBox_loggerFilter, SIGNAL(itemChanged()), this, SLOT(makeObsoleteLoggingPanel()));
678 
679  //Source panel
680  connect(_ui->general_doubleSpinBox_imgRate, SIGNAL(valueChanged(double)), this, SLOT(makeObsoleteSourcePanel()));
681  connect(_ui->general_doubleSpinBox_imgRate, SIGNAL(valueChanged(double)), _ui->doubleSpinBox_OdomORBSLAMFps, SLOT(setValue(double)));
682  connect(_ui->source_mirroring, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
683  connect(_ui->toolButton_source_path_calibration, SIGNAL(clicked()), this, SLOT(selectCalibrationPath()));
684  connect(_ui->lineEdit_calibrationFile, SIGNAL(textChanged(const QString &)), this, SLOT(makeObsoleteSourcePanel()));
685  _ui->stackedWidget_src->setCurrentIndex(_ui->comboBox_sourceType->currentIndex());
686  connect(_ui->comboBox_sourceType, SIGNAL(currentIndexChanged(int)), _ui->stackedWidget_src, SLOT(setCurrentIndex(int)));
687  connect(_ui->comboBox_sourceType, SIGNAL(currentIndexChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
688  connect(_ui->lineEdit_sourceDevice, SIGNAL(textChanged(const QString &)), this, SLOT(makeObsoleteSourcePanel()));
689  connect(_ui->lineEdit_sourceLocalTransform, SIGNAL(textChanged(const QString &)), this, SLOT(makeObsoleteSourcePanel()));
690 
691  //RGB source
692  _ui->stackedWidget_image->setCurrentIndex(_ui->source_comboBox_image_type->currentIndex());
693  connect(_ui->source_comboBox_image_type, SIGNAL(currentIndexChanged(int)), _ui->stackedWidget_image, SLOT(setCurrentIndex(int)));
694  connect(_ui->source_comboBox_image_type, SIGNAL(currentIndexChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
695  connect(_ui->checkBox_rgb_rectify, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
696  //images group
697  connect(_ui->source_images_toolButton_selectSource, SIGNAL(clicked()), this, SLOT(selectSourceImagesPath()));
698  connect(_ui->source_images_lineEdit_path, SIGNAL(textChanged(const QString &)), this, SLOT(makeObsoleteSourcePanel()));
699  connect(_ui->source_images_spinBox_startPos, SIGNAL(valueChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
700  connect(_ui->source_images_spinBox_maxFrames, SIGNAL(valueChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
701  connect(_ui->comboBox_cameraImages_bayerMode, SIGNAL(currentIndexChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
702  // usb group
703  connect(_ui->spinBox_usbcam_streamWidth, SIGNAL(valueChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
704  connect(_ui->spinBox_usbcam_streamHeight, SIGNAL(valueChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
705  //video group
706  connect(_ui->source_video_toolButton_selectSource, SIGNAL(clicked()), this, SLOT(selectSourceVideoPath()));
707  connect(_ui->source_video_lineEdit_path, SIGNAL(textChanged(const QString &)), this, SLOT(makeObsoleteSourcePanel()));
708  //database group
709  connect(_ui->source_database_toolButton_selectSource, SIGNAL(clicked()), this, SLOT(selectSourceDatabase()));
710  connect(_ui->toolButton_dbViewer, SIGNAL(clicked()), this, SLOT(openDatabaseViewer()));
711  connect(_ui->groupBox_sourceDatabase, SIGNAL(toggled(bool)), this, SLOT(makeObsoleteSourcePanel()));
712  connect(_ui->source_database_lineEdit_path, SIGNAL(textChanged(const QString &)), this, SLOT(makeObsoleteSourcePanel()));
713  connect(_ui->source_checkBox_ignoreOdometry, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
714  connect(_ui->source_checkBox_ignoreGoalDelay, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
715  connect(_ui->source_checkBox_ignoreGoals, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
716  connect(_ui->source_checkBox_ignoreLandmarks, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
717  connect(_ui->source_checkBox_ignoreFeatures, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
718  connect(_ui->source_checkBox_ignorePriors, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
719  connect(_ui->source_spinBox_databaseStartId, SIGNAL(valueChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
720  connect(_ui->source_spinBox_databaseStopId, SIGNAL(valueChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
721  connect(_ui->source_checkBox_useDbStamps, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
722  connect(_ui->source_spinBox_database_cameraIndex, SIGNAL(valueChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
723  connect(_ui->source_checkBox_stereoToDepthDB, SIGNAL(toggled(bool)), _ui->checkbox_stereo_depthGenerated, SLOT(setChecked(bool)));
724  connect(_ui->checkbox_stereo_depthGenerated, SIGNAL(toggled(bool)), _ui->source_checkBox_stereoToDepthDB, SLOT(setChecked(bool)));
725 
726  //openni group
727  _ui->stackedWidget_rgbd->setCurrentIndex(_ui->comboBox_cameraRGBD->currentIndex());
728  connect(_ui->comboBox_cameraRGBD, SIGNAL(currentIndexChanged(int)), _ui->stackedWidget_rgbd, SLOT(setCurrentIndex(int)));
729  connect(_ui->comboBox_cameraRGBD, SIGNAL(currentIndexChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
730  _ui->stackedWidget_stereo->setCurrentIndex(_ui->comboBox_cameraStereo->currentIndex());
731  connect(_ui->comboBox_cameraStereo, SIGNAL(currentIndexChanged(int)), _ui->stackedWidget_stereo, SLOT(setCurrentIndex(int)));
732  connect(_ui->comboBox_cameraStereo, SIGNAL(currentIndexChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
733  connect(_ui->openni2_autoWhiteBalance, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
734  connect(_ui->openni2_autoExposure, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
735  connect(_ui->openni2_exposure, SIGNAL(valueChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
736  connect(_ui->openni2_gain, SIGNAL(valueChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
737  connect(_ui->openni2_mirroring, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
738  connect(_ui->openni2_stampsIdsUsed, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
739  connect(_ui->openni2_hshift, SIGNAL(valueChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
740  connect(_ui->openni2_vshift, SIGNAL(valueChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
741  connect(_ui->openni2_depth_decimation, SIGNAL(valueChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
742  connect(_ui->comboBox_freenect2Format, SIGNAL(currentIndexChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
743  connect(_ui->doubleSpinBox_freenect2MinDepth, SIGNAL(valueChanged(double)), this, SLOT(makeObsoleteSourcePanel()));
744  connect(_ui->doubleSpinBox_freenect2MaxDepth, SIGNAL(valueChanged(double)), this, SLOT(makeObsoleteSourcePanel()));
745  connect(_ui->checkBox_freenect2BilateralFiltering, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
746  connect(_ui->checkBox_freenect2EdgeAwareFiltering, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
747  connect(_ui->checkBox_freenect2NoiseFiltering, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
748  connect(_ui->lineEdit_freenect2Pipeline, SIGNAL(textChanged(const QString &)), this, SLOT(makeObsoleteSourcePanel()));
749  connect(_ui->comboBox_k4w2Format, SIGNAL(currentIndexChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
750  connect(_ui->comboBox_realsensePresetRGB, SIGNAL(currentIndexChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
751  connect(_ui->comboBox_realsensePresetDepth, SIGNAL(currentIndexChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
752  connect(_ui->checkbox_realsenseOdom, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
753  connect(_ui->checkbox_realsenseDepthScaledToRGBSize, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
754  connect(_ui->comboBox_realsenseRGBSource, SIGNAL(currentIndexChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
755  connect(_ui->checkbox_rs2_emitter, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
756  connect(_ui->checkbox_rs2_irMode, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
757  connect(_ui->checkbox_rs2_irDepth, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
758  connect(_ui->spinBox_rs2_width, SIGNAL(valueChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
759  connect(_ui->spinBox_rs2_height, SIGNAL(valueChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
760  connect(_ui->spinBox_rs2_rate, SIGNAL(valueChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
761  connect(_ui->spinBox_rs2_width_depth, SIGNAL(valueChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
762  connect(_ui->spinBox_rs2_height_depth, SIGNAL(valueChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
763  connect(_ui->spinBox_rs2_rate_depth, SIGNAL(valueChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
764  connect(_ui->checkbox_rs2_globalTimeStync, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
765  connect(_ui->lineEdit_rs2_jsonFile, SIGNAL(textChanged(const QString &)), this, SLOT(makeObsoleteSourcePanel()));
766  connect(_ui->toolButton_rs2_jsonFile, SIGNAL(clicked()), this, SLOT(selectSourceRealsense2JsonPath()));
767 
768  connect(_ui->toolButton_cameraImages_timestamps, SIGNAL(clicked()), this, SLOT(selectSourceImagesStamps()));
769  connect(_ui->lineEdit_cameraImages_timestamps, SIGNAL(textChanged(const QString &)), this, SLOT(makeObsoleteSourcePanel()));
770  connect(_ui->toolButton_cameraRGBDImages_path_rgb, SIGNAL(clicked()), this, SLOT(selectSourceRGBDImagesPathRGB()));
771  connect(_ui->toolButton_cameraRGBDImages_path_depth, SIGNAL(clicked()), this, SLOT(selectSourceRGBDImagesPathDepth()));
772  connect(_ui->toolButton_cameraImages_path_scans, SIGNAL(clicked()), this, SLOT(selectSourceImagesPathScans()));
773  connect(_ui->toolButton_cameraImages_path_imu, SIGNAL(clicked()), this, SLOT(selectSourceImagesPathIMU()));
774  connect(_ui->toolButton_cameraImages_odom, SIGNAL(clicked()), this, SLOT(selectSourceImagesPathOdom()));
775  connect(_ui->toolButton_cameraImages_gt, SIGNAL(clicked()), this, SLOT(selectSourceImagesPathGt()));
776  connect(_ui->lineEdit_cameraRGBDImages_path_rgb, SIGNAL(textChanged(const QString &)), this, SLOT(makeObsoleteSourcePanel()));
777  connect(_ui->lineEdit_cameraRGBDImages_path_depth, SIGNAL(textChanged(const QString &)), this, SLOT(makeObsoleteSourcePanel()));
778  connect(_ui->checkBox_cameraImages_configForEachFrame, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
779  connect(_ui->checkBox_cameraImages_timestamps, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
780  connect(_ui->checkBox_cameraImages_syncTimeStamps, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
781  connect(_ui->doubleSpinBox_cameraRGBDImages_scale, SIGNAL(valueChanged(double)), this, SLOT(makeObsoleteSourcePanel()));
782  connect(_ui->spinBox_cameraRGBDImages_startIndex, SIGNAL(valueChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
783  connect(_ui->spinBox_cameraRGBDImages_maxFrames, SIGNAL(valueChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
784  connect(_ui->lineEdit_cameraImages_path_scans, SIGNAL(textChanged(const QString &)), this, SLOT(makeObsoleteSourcePanel()));
785  connect(_ui->lineEdit_cameraImages_laser_transform, SIGNAL(textChanged(const QString &)), this, SLOT(makeObsoleteSourcePanel()));
786  connect(_ui->spinBox_cameraImages_max_scan_pts, SIGNAL(valueChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
787  connect(_ui->lineEdit_cameraImages_odom, SIGNAL(textChanged(const QString &)), this, SLOT(makeObsoleteSourcePanel()));
788  connect(_ui->comboBox_cameraImages_odomFormat, SIGNAL(currentIndexChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
789  connect(_ui->lineEdit_cameraImages_gt, SIGNAL(textChanged(const QString &)), this, SLOT(makeObsoleteSourcePanel()));
790  connect(_ui->comboBox_cameraImages_gtFormat, SIGNAL(currentIndexChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
791  connect(_ui->doubleSpinBox_maxPoseTimeDiff, SIGNAL(valueChanged(double)), this, SLOT(makeObsoleteSourcePanel()));
792  connect(_ui->lineEdit_cameraImages_path_imu, SIGNAL(textChanged(const QString &)), this, SLOT(makeObsoleteSourcePanel()));
793  connect(_ui->lineEdit_cameraImages_imu_transform, SIGNAL(textChanged(const QString &)), this, SLOT(makeObsoleteSourcePanel()));
794  connect(_ui->spinBox_cameraImages_max_imu_rate, SIGNAL(valueChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
795  connect(_ui->groupBox_depthFromScan, SIGNAL(toggled(bool)), this, SLOT(makeObsoleteSourcePanel()));
796  connect(_ui->groupBox_depthFromScan_fillHoles, SIGNAL(toggled(bool)), this, SLOT(makeObsoleteSourcePanel()));
797  connect(_ui->radioButton_depthFromScan_vertical, SIGNAL(toggled(bool)), this, SLOT(makeObsoleteSourcePanel()));
798  connect(_ui->radioButton_depthFromScan_horizontal, SIGNAL(toggled(bool)), this, SLOT(makeObsoleteSourcePanel()));
799  connect(_ui->checkBox_depthFromScan_fillBorders, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
800 
801  connect(_ui->toolButton_cameraStereoImages_path_left, SIGNAL(clicked()), this, SLOT(selectSourceStereoImagesPathLeft()));
802  connect(_ui->toolButton_cameraStereoImages_path_right, SIGNAL(clicked()), this, SLOT(selectSourceStereoImagesPathRight()));
803  connect(_ui->lineEdit_cameraStereoImages_path_left, SIGNAL(textChanged(const QString &)), this, SLOT(makeObsoleteSourcePanel()));
804  connect(_ui->lineEdit_cameraStereoImages_path_right, SIGNAL(textChanged(const QString &)), this, SLOT(makeObsoleteSourcePanel()));
805  connect(_ui->checkBox_stereo_rectify, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
806  connect(_ui->spinBox_cameraStereoImages_startIndex, SIGNAL(valueChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
807  connect(_ui->spinBox_cameraStereoImages_maxFrames, SIGNAL(valueChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
808 
809  connect(_ui->toolButton_cameraStereoVideo_path, SIGNAL(clicked()), this, SLOT(selectSourceStereoVideoPath()));
810  connect(_ui->toolButton_cameraStereoVideo_path_2, SIGNAL(clicked()), this, SLOT(selectSourceStereoVideoPath2()));
811  connect(_ui->lineEdit_cameraStereoVideo_path, SIGNAL(textChanged(const QString &)), this, SLOT(makeObsoleteSourcePanel()));
812  connect(_ui->lineEdit_cameraStereoVideo_path_2, SIGNAL(textChanged(const QString &)), this, SLOT(makeObsoleteSourcePanel()));
813 
814  connect(_ui->spinBox_stereo_right_device, SIGNAL(valueChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
815  connect(_ui->spinBox_stereousbcam_streamWidth, SIGNAL(valueChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
816  connect(_ui->spinBox_stereousbcam_streamHeight, SIGNAL(valueChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
817 
818  connect(_ui->comboBox_stereoZed_resolution, SIGNAL(currentIndexChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
819  connect(_ui->comboBox_stereoZed_quality, SIGNAL(currentIndexChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
820  connect(_ui->comboBox_stereoZed_quality, SIGNAL(currentIndexChanged(int)), this, SLOT(updateStereoDisparityVisibility()));
821  connect(_ui->checkbox_stereoZed_selfCalibration, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
822  connect(_ui->comboBox_cameraStereo, SIGNAL(currentIndexChanged(int)), this, SLOT(updateStereoDisparityVisibility()));
823  connect(_ui->comboBox_stereoZed_sensingMode, SIGNAL(currentIndexChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
824  connect(_ui->spinBox_stereoZed_confidenceThr, SIGNAL(valueChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
825  connect(_ui->spinBox_stereoZed_texturenessConfidenceThr, SIGNAL(valueChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
826  connect(_ui->toolButton_zedSvoPath, SIGNAL(clicked()), this, SLOT(selectSourceSvoPath()));
827  connect(_ui->lineEdit_zedSvoPath, SIGNAL(textChanged(const QString &)), this, SLOT(makeObsoleteSourcePanel()));
828 
829  connect(_ui->checkbox_stereoMyntEye_rectify, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
830  connect(_ui->checkbox_stereoMyntEye_depth, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
831  connect(_ui->checkbox_stereoMyntEye_autoExposure, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
832  connect(_ui->spinBox_stereoMyntEye_gain, SIGNAL(valueChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
833  connect(_ui->spinBox_stereoMyntEye_brightness, SIGNAL(valueChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
834  connect(_ui->spinBox_stereoMyntEye_contrast, SIGNAL(valueChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
835  connect(_ui->spinBox_stereoMyntEye_irControl, SIGNAL(valueChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
836 
837  connect(_ui->comboBox_depthai_resolution, SIGNAL(currentIndexChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
838  connect(_ui->comboBox_depthai_output_mode, SIGNAL(currentIndexChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
839  connect(_ui->spinBox_depthai_conf_threshold, SIGNAL(valueChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
840  connect(_ui->spinBox_depthai_lrc_threshold, SIGNAL(valueChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
841  connect(_ui->checkBox_depthai_extended_disparity, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
842  connect(_ui->comboBox_depthai_subpixel_fractional_bits, SIGNAL(currentIndexChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
843  connect(_ui->comboBox_depthai_disparity_companding, SIGNAL(currentIndexChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
844  connect(_ui->checkBox_depthai_use_spec_translation, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
845  connect(_ui->doubleSpinBox_depthai_alpha_scaling, SIGNAL(valueChanged(double)), this, SLOT(makeObsoleteSourcePanel()));
846  connect(_ui->checkBox_depthai_imu_published, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
847  connect(_ui->doubleSpinBox_depthai_dot_intensity, SIGNAL(valueChanged(double)), this, SLOT(makeObsoleteSourcePanel()));
848  connect(_ui->doubleSpinBox_depthai_flood_intensity, SIGNAL(valueChanged(double)), this, SLOT(makeObsoleteSourcePanel()));
849  connect(_ui->comboBox_depthai_detect_features, SIGNAL(currentIndexChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
850  connect(_ui->lineEdit_depthai_blob_path, SIGNAL(textChanged(const QString &)), this, SLOT(makeObsoleteSourcePanel()));
851  connect(_ui->toolButton_depthai_blob_path, SIGNAL(clicked()), this, SLOT(selectSourceDepthaiBlobPath()));
852 
853  connect(_ui->checkbox_rgbd_colorOnly, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
854  connect(_ui->spinBox_source_imageDecimation, SIGNAL(valueChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
855  connect(_ui->comboBox_source_histogramMethod, SIGNAL(currentIndexChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
856  connect(_ui->checkbox_source_feature_detection, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
857  connect(_ui->checkbox_stereo_depthGenerated, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
858  connect(_ui->checkBox_stereo_exposureCompensation, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
859  connect(_ui->pushButton_calibrate, SIGNAL(clicked()), this, SLOT(calibrate()));
860  connect(_ui->pushButton_calibrate_simple, SIGNAL(clicked()), this, SLOT(calibrateSimple()));
861  connect(_ui->toolButton_openniOniPath, SIGNAL(clicked()), this, SLOT(selectSourceOniPath()));
862  connect(_ui->toolButton_openni2OniPath, SIGNAL(clicked()), this, SLOT(selectSourceOni2Path()));
863  connect(_ui->comboBox_k4a_rgb_resolution, SIGNAL(currentIndexChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
864  connect(_ui->comboBox_k4a_framerate, SIGNAL(currentIndexChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
865  connect(_ui->comboBox_k4a_depth_resolution, SIGNAL(currentIndexChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
866  connect(_ui->checkbox_k4a_irDepth, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
867  connect(_ui->toolButton_k4a_mkv, SIGNAL(clicked()), this, SLOT(selectSourceMKVPath()));
868  connect(_ui->toolButton_source_distortionModel, SIGNAL(clicked()), this, SLOT(selectSourceDistortionModel()));
869  connect(_ui->toolButton_distortionModel, SIGNAL(clicked()), this, SLOT(visualizeDistortionModel()));
870  connect(_ui->lineEdit_openniOniPath, SIGNAL(textChanged(const QString &)), this, SLOT(makeObsoleteSourcePanel()));
871  connect(_ui->lineEdit_openni2OniPath, SIGNAL(textChanged(const QString &)), this, SLOT(makeObsoleteSourcePanel()));
872  connect(_ui->lineEdit_k4a_mkv, SIGNAL(textChanged(const QString &)), this, SLOT(makeObsoleteSourcePanel()));
873  connect(_ui->source_checkBox_useMKVStamps, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
874  connect(_ui->lineEdit_source_distortionModel, SIGNAL(textChanged(const QString &)), this, SLOT(makeObsoleteSourcePanel()));
875  connect(_ui->groupBox_bilateral, SIGNAL(toggled(bool)), this, SLOT(makeObsoleteSourcePanel()));
876  connect(_ui->doubleSpinBox_bilateral_sigmaS, SIGNAL(valueChanged(double)), this, SLOT(makeObsoleteSourcePanel()));
877  connect(_ui->doubleSpinBox_bilateral_sigmaR, SIGNAL(valueChanged(double)), this, SLOT(makeObsoleteSourcePanel()));
878 
879  connect(_ui->lineEdit_odom_sensor_extrinsics, SIGNAL(textChanged(const QString &)), this, SLOT(makeObsoleteSourcePanel()));
880  connect(_ui->comboBox_odom_sensor, SIGNAL(currentIndexChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
881  connect(_ui->toolButton_odom_sensor_path_calibration, SIGNAL(clicked()), this, SLOT(selectOdomSensorCalibrationPath()));
882  connect(_ui->pushButton_odom_sensor_calibrate, SIGNAL(clicked()), this, SLOT(calibrateOdomSensorExtrinsics()));
883  connect(_ui->lineEdit_odom_sensor_path_calibration, SIGNAL(textChanged(const QString &)), this, SLOT(makeObsoleteSourcePanel()));
884  connect(_ui->lineEdit_odomSourceDevice, SIGNAL(textChanged(const QString &)), this, SLOT(makeObsoleteSourcePanel()));
885  connect(_ui->doubleSpinBox_odom_sensor_time_offset, SIGNAL(valueChanged(double)), this, SLOT(makeObsoleteSourcePanel()));
886  connect(_ui->doubleSpinBox_odom_sensor_scale_factor, SIGNAL(valueChanged(double)), this, SLOT(makeObsoleteSourcePanel()));
887  connect(_ui->doubleSpinBox_odom_sensor_wait_time, SIGNAL(valueChanged(double)), this, SLOT(makeObsoleteSourcePanel()));
888  connect(_ui->checkBox_odom_sensor_use_as_gt, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
889 
890  connect(_ui->comboBox_imuFilter_strategy, SIGNAL(currentIndexChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
891  connect(_ui->comboBox_imuFilter_strategy, SIGNAL(currentIndexChanged(int)), _ui->stackedWidget_imuFilter, SLOT(setCurrentIndex(int)));
892  _ui->stackedWidget_imuFilter->setCurrentIndex(_ui->comboBox_imuFilter_strategy->currentIndex());
893  connect(_ui->checkBox_imuFilter_baseFrameConversion, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
894  connect(_ui->checkbox_publishInterIMU, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
895 
896  connect(_ui->comboBox_lidar_src, SIGNAL(currentIndexChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
897  connect(_ui->comboBox_lidar_src, SIGNAL(currentIndexChanged(int)), _ui->stackedWidget_lidar_src, SLOT(setCurrentIndex(int)));
898  _ui->stackedWidget_lidar_src->setCurrentIndex(_ui->comboBox_lidar_src->currentIndex());
899  connect(_ui->checkBox_source_scanDeskewing, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
900  connect(_ui->checkBox_source_scanFromDepth, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
901  connect(_ui->spinBox_source_scanDownsampleStep, SIGNAL(valueChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
902  connect(_ui->doubleSpinBox_source_scanRangeMin, SIGNAL(valueChanged(double)), this, SLOT(makeObsoleteSourcePanel()));
903  connect(_ui->doubleSpinBox_source_scanRangeMax, SIGNAL(valueChanged(double)), this, SLOT(makeObsoleteSourcePanel()));
904  connect(_ui->doubleSpinBox_source_scanVoxelSize, SIGNAL(valueChanged(double)), this, SLOT(makeObsoleteSourcePanel()));
905  connect(_ui->spinBox_source_scanNormalsK, SIGNAL(valueChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
906  connect(_ui->doubleSpinBox_source_scanNormalsRadius, SIGNAL(valueChanged(double)), this, SLOT(makeObsoleteSourcePanel()));
907  connect(_ui->doubleSpinBox_source_scanNormalsForceGroundUp, SIGNAL(valueChanged(double)), this, SLOT(makeObsoleteSourcePanel()));
908 
909  connect(_ui->lineEdit_lidar_local_transform, SIGNAL(textChanged(const QString &)), this, SLOT(makeObsoleteSourcePanel()));
910  connect(_ui->toolButton_vlp16_pcap_path, SIGNAL(clicked()), this, SLOT(selectVlp16PcapPath()));
911  connect(_ui->lineEdit_vlp16_pcap_path, SIGNAL(textChanged(const QString &)), this, SLOT(makeObsoleteSourcePanel()));
912  connect(_ui->spinBox_vlp16_ip1, SIGNAL(valueChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
913  connect(_ui->spinBox_vlp16_ip2, SIGNAL(valueChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
914  connect(_ui->spinBox_vlp16_ip2, SIGNAL(valueChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
915  connect(_ui->spinBox_vlp16_ip4, SIGNAL(valueChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
916  connect(_ui->spinBox_vlp16_port, SIGNAL(valueChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
917  connect(_ui->checkBox_vlp16_organized, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
918  connect(_ui->checkBox_vlp16_hostTime, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
919  connect(_ui->checkBox_vlp16_stamp_last, SIGNAL(stateChanged(int)), this, SLOT(makeObsoleteSourcePanel()));
920 
921  //Rtabmap basic
922  connect(_ui->general_doubleSpinBox_timeThr, SIGNAL(valueChanged(double)), _ui->general_doubleSpinBox_timeThr_2, SLOT(setValue(double)));
923  connect(_ui->general_doubleSpinBox_hardThr, SIGNAL(valueChanged(double)), _ui->general_doubleSpinBox_hardThr_2, SLOT(setValue(double)));
924  connect(_ui->doubleSpinBox_similarityThreshold, SIGNAL(valueChanged(double)), _ui->doubleSpinBox_similarityThreshold_2, SLOT(setValue(double)));
925  connect(_ui->general_doubleSpinBox_detectionRate, SIGNAL(valueChanged(double)), _ui->general_doubleSpinBox_detectionRate_2, SLOT(setValue(double)));
926  connect(_ui->general_spinBox_imagesBufferSize, SIGNAL(valueChanged(int)), _ui->general_spinBox_imagesBufferSize_2, SLOT(setValue(int)));
927  connect(_ui->general_spinBox_maxStMemSize, SIGNAL(valueChanged(int)), _ui->general_spinBox_maxStMemSize_2, SLOT(setValue(int)));
928 
929  connect(_ui->general_doubleSpinBox_timeThr_2, SIGNAL(editingFinished()), this, SLOT(updateBasicParameter()));
930  connect(_ui->general_doubleSpinBox_hardThr_2, SIGNAL(editingFinished()), this, SLOT(updateBasicParameter()));
931  connect(_ui->doubleSpinBox_similarityThreshold_2, SIGNAL(editingFinished()), this, SLOT(updateBasicParameter()));
932  connect(_ui->general_doubleSpinBox_detectionRate_2, SIGNAL(editingFinished()), this, SLOT(updateBasicParameter()));
933  connect(_ui->general_spinBox_imagesBufferSize_2, SIGNAL(editingFinished()), this, SLOT(updateBasicParameter()));
934  connect(_ui->general_spinBox_maxStMemSize_2, SIGNAL(editingFinished()), this, SLOT(updateBasicParameter()));
935  connect(_ui->groupBox_publishing, SIGNAL(toggled(bool)), this, SLOT(updateBasicParameter()));
936  connect(_ui->general_checkBox_publishStats_2, SIGNAL(stateChanged(int)), this, SLOT(updateBasicParameter()));
937  connect(_ui->general_checkBox_activateRGBD, SIGNAL(stateChanged(int)), this, SLOT(updateBasicParameter()));
938  connect(_ui->general_checkBox_activateRGBD_2, SIGNAL(stateChanged(int)), this, SLOT(updateBasicParameter()));
939  connect(_ui->general_checkBox_SLAM_mode, SIGNAL(stateChanged(int)), this, SLOT(updateBasicParameter()));
940  connect(_ui->general_checkBox_SLAM_mode_2, SIGNAL(stateChanged(int)), this, SLOT(updateBasicParameter()));
941 
942  // Map objects name with the corresponding parameter key, needed for the addParameter() slots
943  //Rtabmap
944  _ui->groupBox_publishing->setObjectName(Parameters::kRtabmapPublishStats().c_str());
945  _ui->general_checkBox_publishRawData->setObjectName(Parameters::kRtabmapPublishLastSignature().c_str());
946  _ui->general_checkBox_publishPdf->setObjectName(Parameters::kRtabmapPublishPdf().c_str());
947  _ui->general_checkBox_publishLikelihood->setObjectName(Parameters::kRtabmapPublishLikelihood().c_str());
948  _ui->general_checkBox_publishRMSE->setObjectName(Parameters::kRtabmapComputeRMSE().c_str());
949  _ui->general_checkBox_saveWMState->setObjectName(Parameters::kRtabmapSaveWMState().c_str());
950  _ui->general_checkBox_publishRAM->setObjectName(Parameters::kRtabmapPublishRAMUsage().c_str());
951  _ui->general_checkBox_statisticLogsBufferedInRAM->setObjectName(Parameters::kRtabmapStatisticLogsBufferedInRAM().c_str());
952  _ui->groupBox_statistics->setObjectName(Parameters::kRtabmapStatisticLogged().c_str());
953  _ui->general_checkBox_statisticLoggedHeaders->setObjectName(Parameters::kRtabmapStatisticLoggedHeaders().c_str());
954  _ui->general_doubleSpinBox_timeThr->setObjectName(Parameters::kRtabmapTimeThr().c_str());
955  _ui->general_spinBox_memoryThr->setObjectName(Parameters::kRtabmapMemoryThr().c_str());
956  _ui->general_doubleSpinBox_detectionRate->setObjectName(Parameters::kRtabmapDetectionRate().c_str());
957  _ui->general_spinBox_imagesBufferSize->setObjectName(Parameters::kRtabmapImageBufferSize().c_str());
958  _ui->general_checkBox_createIntermediateNodes->setObjectName(Parameters::kRtabmapCreateIntermediateNodes().c_str());
959  _ui->general_spinBox_maxRetrieved->setObjectName(Parameters::kRtabmapMaxRetrieved().c_str());
960  _ui->general_spinBox_max_republished->setObjectName(Parameters::kRtabmapMaxRepublished().c_str());
961  _ui->general_checkBox_startNewMapOnLoopClosure->setObjectName(Parameters::kRtabmapStartNewMapOnLoopClosure().c_str());
962  _ui->general_checkBox_startNewMapOnGoodSignature->setObjectName(Parameters::kRtabmapStartNewMapOnGoodSignature().c_str());
963  _ui->general_checkBox_imagesAlreadyRectified->setObjectName(Parameters::kRtabmapImagesAlreadyRectified().c_str());
964  _ui->general_checkBox_rectifyOnlyFeatures->setObjectName(Parameters::kRtabmapRectifyOnlyFeatures().c_str());
965  _ui->checkBox_rtabmap_loopGPS->setObjectName(Parameters::kRtabmapLoopGPS().c_str());
966  _ui->lineEdit_workingDirectory->setObjectName(Parameters::kRtabmapWorkingDirectory().c_str());
967  connect(_ui->toolButton_workingDirectory, SIGNAL(clicked()), this, SLOT(changeWorkingDirectory()));
968 
969  // Memory
970  _ui->general_checkBox_keepRawData->setObjectName(Parameters::kMemImageKept().c_str());
971  _ui->general_checkBox_keepBinaryData->setObjectName(Parameters::kMemBinDataKept().c_str());
972  _ui->general_checkBox_saveIntermediateNodeData->setObjectName(Parameters::kMemIntermediateNodeDataKept().c_str());
973  _ui->lineEdit_rgbCompressionFormat->setObjectName(Parameters::kMemImageCompressionFormat().c_str());
974  _ui->general_checkBox_keepDescriptors->setObjectName(Parameters::kMemRawDescriptorsKept().c_str());
975  _ui->general_checkBox_saveDepth16bits->setObjectName(Parameters::kMemSaveDepth16Format().c_str());
976  _ui->general_checkBox_compressionParallelized->setObjectName(Parameters::kMemCompressionParallelized().c_str());
977  _ui->general_checkBox_reduceGraph->setObjectName(Parameters::kMemReduceGraph().c_str());
978  _ui->general_checkBox_keepNotLinkedNodes->setObjectName(Parameters::kMemNotLinkedNodesKept().c_str());
979  _ui->general_spinBox_maxStMemSize->setObjectName(Parameters::kMemSTMSize().c_str());
980  _ui->doubleSpinBox_similarityThreshold->setObjectName(Parameters::kMemRehearsalSimilarity().c_str());
981  _ui->general_checkBox_SLAM_mode->setObjectName(Parameters::kMemIncrementalMemory().c_str());
982  _ui->general_checkBox_saveLocalizationData->setObjectName(Parameters::kMemLocalizationDataSaved().c_str());
983  _ui->general_doubleSpinBox_recentWmRatio->setObjectName(Parameters::kMemRecentWmRatio().c_str());
984  _ui->general_checkBox_transferSortingByWeightId->setObjectName(Parameters::kMemTransferSortingByWeightId().c_str());
985  _ui->general_checkBox_RehearsalIdUpdatedToNewOne->setObjectName(Parameters::kMemRehearsalIdUpdatedToNewOne().c_str());
986  _ui->general_checkBox_generateIds->setObjectName(Parameters::kMemGenerateIds().c_str());
987  _ui->general_checkBox_badSignaturesIgnored->setObjectName(Parameters::kMemBadSignaturesIgnored().c_str());
988  _ui->general_checkBox_createMapLabels->setObjectName(Parameters::kMemMapLabelsAdded().c_str());
989  _ui->general_checkBox_initWMWithAllNodes->setObjectName(Parameters::kMemInitWMWithAllNodes().c_str());
990  _ui->checkBox_localSpaceScanMatchingIDsSaved->setObjectName(Parameters::kRGBDScanMatchingIdsSavedInLinks().c_str());
991  _ui->checkBox_localSpaceCreateGlobalScanMap->setObjectName(Parameters::kRGBDProximityGlobalScanMap().c_str());
992  _ui->spinBox_imagePreDecimation->setObjectName(Parameters::kMemImagePreDecimation().c_str());
993  _ui->spinBox_imagePostDecimation->setObjectName(Parameters::kMemImagePostDecimation().c_str());
994  _ui->general_spinBox_laserScanDownsample->setObjectName(Parameters::kMemLaserScanDownsampleStepSize().c_str());
995  _ui->general_doubleSpinBox_laserScanVoxelSize->setObjectName(Parameters::kMemLaserScanVoxelSize().c_str());
996  _ui->general_spinBox_laserScanNormalK->setObjectName(Parameters::kMemLaserScanNormalK().c_str());
997  _ui->general_doubleSpinBox_laserScanNormalRadius->setObjectName(Parameters::kMemLaserScanNormalRadius().c_str());
998  _ui->checkBox_useOdomFeatures->setObjectName(Parameters::kMemUseOdomFeatures().c_str());
999  _ui->memCovOffDiagIgnored->setObjectName(Parameters::kMemCovOffDiagIgnored().c_str());
1000  _ui->general_checkBox_rotateImagesUpsideUp->setObjectName(Parameters::kMemRotateImagesUpsideUp().c_str());
1001 
1002  // Database
1003  _ui->checkBox_dbInMemory->setObjectName(Parameters::kDbSqlite3InMemory().c_str());
1004  _ui->spinBox_dbCacheSize->setObjectName(Parameters::kDbSqlite3CacheSize().c_str());
1005  _ui->comboBox_dbJournalMode->setObjectName(Parameters::kDbSqlite3JournalMode().c_str());
1006  _ui->comboBox_dbSynchronous->setObjectName(Parameters::kDbSqlite3Synchronous().c_str());
1007  _ui->comboBox_dbTempStore->setObjectName(Parameters::kDbSqlite3TempStore().c_str());
1008  _ui->lineEdit_targetDatabaseVersion->setObjectName(Parameters::kDbTargetVersion().c_str());
1009 
1010 
1011  // Create hypotheses
1012  _ui->general_doubleSpinBox_hardThr->setObjectName(Parameters::kRtabmapLoopThr().c_str());
1013  _ui->general_doubleSpinBox_agressiveThr->setObjectName(Parameters::kRGBDAggressiveLoopThr().c_str());
1014  _ui->general_doubleSpinBox_loopRatio->setObjectName(Parameters::kRtabmapLoopRatio().c_str());
1015  _ui->comboBox_virtualPlaceLikelihoodRatio->setObjectName(Parameters::kRtabmapVirtualPlaceLikelihoodRatio().c_str());
1016  _ui->comboBox_globalDescriptorExtractor->setObjectName(Parameters::kMemGlobalDescriptorStrategy().c_str());
1017  connect(_ui->comboBox_globalDescriptorExtractor, SIGNAL(currentIndexChanged(int)), this, SLOT(updateGlobalDescriptorVisibility()));
1018 
1019  //Bayes
1020  _ui->general_doubleSpinBox_vp->setObjectName(Parameters::kBayesVirtualPlacePriorThr().c_str());
1021  _ui->lineEdit_bayes_predictionLC->setObjectName(Parameters::kBayesPredictionLC().c_str());
1022  _ui->checkBox_bayes_fullPredictionUpdate->setObjectName(Parameters::kBayesFullPredictionUpdate().c_str());
1023  connect(_ui->lineEdit_bayes_predictionLC, SIGNAL(textChanged(const QString &)), this, SLOT(updatePredictionPlot()));
1024 
1025  //Keypoint-based
1026  _ui->comboBox_dictionary_strategy->setObjectName(Parameters::kKpNNStrategy().c_str());
1027  _ui->checkBox_dictionary_incremental->setObjectName(Parameters::kKpIncrementalDictionary().c_str());
1028  _ui->checkBox_kp_incrementalFlann->setObjectName(Parameters::kKpIncrementalFlann().c_str());
1029  _ui->checkBox_kp_byteToFloat->setObjectName(Parameters::kKpByteToFloat().c_str());
1030  _ui->surf_doubleSpinBox_rebalancingFactor->setObjectName(Parameters::kKpFlannRebalancingFactor().c_str());
1031  _ui->comboBox_detector_strategy->setObjectName(Parameters::kKpDetectorStrategy().c_str());
1032  _ui->surf_doubleSpinBox_nndrRatio->setObjectName(Parameters::kKpNndrRatio().c_str());
1033  _ui->surf_doubleSpinBox_maxDepth->setObjectName(Parameters::kKpMaxDepth().c_str());
1034  _ui->surf_doubleSpinBox_minDepth->setObjectName(Parameters::kKpMinDepth().c_str());
1035  _ui->checkBox_memDepthAsMask->setObjectName(Parameters::kMemDepthAsMask().c_str());
1036  _ui->checkBox_memStereoFromMotion->setObjectName(Parameters::kMemStereoFromMotion().c_str());
1037  _ui->surf_spinBox_wordsPerImageTarget->setObjectName(Parameters::kKpMaxFeatures().c_str());
1038  _ui->checkBox_kp_ssc->setObjectName(Parameters::kKpSSC().c_str());
1039  _ui->spinBox_KPGridRows->setObjectName(Parameters::kKpGridRows().c_str());
1040  _ui->spinBox_KPGridCols->setObjectName(Parameters::kKpGridCols().c_str());
1041  _ui->surf_doubleSpinBox_ratioBadSign->setObjectName(Parameters::kKpBadSignRatio().c_str());
1042  _ui->checkBox_kp_tfIdfLikelihoodUsed->setObjectName(Parameters::kKpTfIdfLikelihoodUsed().c_str());
1043  _ui->checkBox_kp_parallelized->setObjectName(Parameters::kKpParallelized().c_str());
1044  _ui->lineEdit_kp_roi->setObjectName(Parameters::kKpRoiRatios().c_str());
1045  _ui->lineEdit_dictionaryPath->setObjectName(Parameters::kKpDictionaryPath().c_str());
1046  connect(_ui->toolButton_dictionaryPath, SIGNAL(clicked()), this, SLOT(changeDictionaryPath()));
1047  _ui->checkBox_kp_newWordsComparedTogether->setObjectName(Parameters::kKpNewWordsComparedTogether().c_str());
1048  _ui->subpix_winSize_kp->setObjectName(Parameters::kKpSubPixWinSize().c_str());
1049  _ui->subpix_iterations_kp->setObjectName(Parameters::kKpSubPixIterations().c_str());
1050  _ui->subpix_eps_kp->setObjectName(Parameters::kKpSubPixEps().c_str());
1051 
1052  _ui->subpix_winSize->setObjectName(Parameters::kKpSubPixWinSize().c_str());
1053  _ui->subpix_iterations->setObjectName(Parameters::kKpSubPixIterations().c_str());
1054  _ui->subpix_eps->setObjectName(Parameters::kKpSubPixEps().c_str());
1055 
1056  //SURF detector
1057  _ui->surf_doubleSpinBox_hessianThr->setObjectName(Parameters::kSURFHessianThreshold().c_str());
1058  _ui->surf_spinBox_octaves->setObjectName(Parameters::kSURFOctaves().c_str());
1059  _ui->surf_spinBox_octaveLayers->setObjectName(Parameters::kSURFOctaveLayers().c_str());
1060  _ui->checkBox_surfExtended->setObjectName(Parameters::kSURFExtended().c_str());
1061  _ui->surf_checkBox_upright->setObjectName(Parameters::kSURFUpright().c_str());
1062  _ui->surf_checkBox_gpuVersion->setObjectName(Parameters::kSURFGpuVersion().c_str());
1063  _ui->surf_doubleSpinBox_gpuKeypointsRatio->setObjectName(Parameters::kSURFGpuKeypointsRatio().c_str());
1064 
1065  //SIFT detector
1066  _ui->sift_spinBox_nFeatures->setObjectName(Parameters::kSIFTNFeatures().c_str());
1067  _ui->sift_spinBox_nOctaveLayers->setObjectName(Parameters::kSIFTNOctaveLayers().c_str());
1068  _ui->sift_doubleSpinBox_contrastThr->setObjectName(Parameters::kSIFTContrastThreshold().c_str());
1069  _ui->sift_doubleSpinBox_edgeThr->setObjectName(Parameters::kSIFTEdgeThreshold().c_str());
1070  _ui->sift_doubleSpinBox_sigma->setObjectName(Parameters::kSIFTSigma().c_str());
1071  _ui->sift_checkBox_rootsift->setObjectName(Parameters::kSIFTRootSIFT().c_str());
1072 
1073  //BRIEF descriptor
1074  _ui->briefBytes->setObjectName(Parameters::kBRIEFBytes().c_str());
1075 
1076  //FAST detector
1077  _ui->fastSuppressNonMax->setObjectName(Parameters::kFASTNonmaxSuppression().c_str());
1078  _ui->fastThreshold->setObjectName(Parameters::kFASTThreshold().c_str());
1079  _ui->fastThresholdMin->setObjectName(Parameters::kFASTMinThreshold().c_str());
1080  _ui->fastThresholdMax->setObjectName(Parameters::kFASTMaxThreshold().c_str());
1081  _ui->fastGridRows->setObjectName(Parameters::kFASTGridRows().c_str());
1082  _ui->fastGridCols->setObjectName(Parameters::kFASTGridCols().c_str());
1083  _ui->fastGpu->setObjectName(Parameters::kFASTGpu().c_str());
1084  _ui->fastKeypointRatio->setObjectName(Parameters::kFASTGpuKeypointsRatio().c_str());
1085  _ui->fastCV->setObjectName(Parameters::kFASTCV().c_str());
1086 
1087  //ORB detector
1088  _ui->doubleSpinBox_ORBScaleFactor->setObjectName(Parameters::kORBScaleFactor().c_str());
1089  _ui->spinBox_ORBNLevels->setObjectName(Parameters::kORBNLevels().c_str());
1090  _ui->spinBox_ORBEdgeThreshold->setObjectName(Parameters::kORBEdgeThreshold().c_str());
1091  _ui->spinBox_ORBFirstLevel->setObjectName(Parameters::kORBFirstLevel().c_str());
1092  _ui->spinBox_ORBWTA_K->setObjectName(Parameters::kORBWTA_K().c_str());
1093  _ui->spinBox_ORBScoreType->setObjectName(Parameters::kORBScoreType().c_str());
1094  _ui->spinBox_ORBPatchSize->setObjectName(Parameters::kORBPatchSize().c_str());
1095  _ui->checkBox_ORBGpu->setObjectName(Parameters::kORBGpu().c_str());
1096 
1097  //FREAK descriptor
1098  _ui->checkBox_FREAKOrientationNormalized->setObjectName(Parameters::kFREAKOrientationNormalized().c_str());
1099  _ui->checkBox_FREAKScaleNormalized->setObjectName(Parameters::kFREAKScaleNormalized().c_str());
1100  _ui->doubleSpinBox_FREAKPatternScale->setObjectName(Parameters::kFREAKPatternScale().c_str());
1101  _ui->spinBox_FREAKNOctaves->setObjectName(Parameters::kFREAKNOctaves().c_str());
1102 
1103  //GFTT detector
1104  _ui->doubleSpinBox_GFTT_qualityLevel->setObjectName(Parameters::kGFTTQualityLevel().c_str());
1105  _ui->doubleSpinBox_GFTT_minDistance->setObjectName(Parameters::kGFTTMinDistance().c_str());
1106  _ui->spinBox_GFTT_blockSize->setObjectName(Parameters::kGFTTBlockSize().c_str());
1107  _ui->checkBox_GFTT_useHarrisDetector->setObjectName(Parameters::kGFTTUseHarrisDetector().c_str());
1108  _ui->doubleSpinBox_GFTT_k->setObjectName(Parameters::kGFTTK().c_str());
1109 
1110  //BRISK
1111  _ui->spinBox_BRISK_thresh->setObjectName(Parameters::kBRISKThresh().c_str());
1112  _ui->spinBox_BRISK_octaves->setObjectName(Parameters::kBRISKOctaves().c_str());
1113  _ui->doubleSpinBox_BRISK_patterScale->setObjectName(Parameters::kBRISKPatternScale().c_str());
1114 
1115  //KAZE
1116  _ui->checkBox_kaze_extended->setObjectName(Parameters::kKAZEExtended().c_str());
1117  _ui->checkBox_kaze_upright->setObjectName(Parameters::kKAZEUpright().c_str());
1118  _ui->doubleSpinBox_kaze_threshold->setObjectName(Parameters::kKAZEThreshold().c_str());
1119  _ui->spinBox_kaze_octaves->setObjectName(Parameters::kKAZENOctaves().c_str());
1120  _ui->spinBox_kaze_octavelayers->setObjectName(Parameters::kKAZENOctaveLayers().c_str());
1121  _ui->spinBox_kaze_diffusivity->setObjectName(Parameters::kKAZEDiffusivity().c_str());
1122 
1123  // SuperPoint Torch
1124  _ui->lineEdit_sptorch_path->setObjectName(Parameters::kSuperPointModelPath().c_str());
1125  connect(_ui->toolButton_sptorch_path, SIGNAL(clicked()), this, SLOT(changeSuperPointModelPath()));
1126  _ui->doubleSpinBox_sptorch_threshold->setObjectName(Parameters::kSuperPointThreshold().c_str());
1127  _ui->checkBox_sptorch_nms->setObjectName(Parameters::kSuperPointNMS().c_str());
1128  _ui->spinBox_sptorch_minDistance->setObjectName(Parameters::kSuperPointNMSRadius().c_str());
1129  _ui->checkBox_sptorch_cuda->setObjectName(Parameters::kSuperPointCuda().c_str());
1130 
1131  // PyMatcher
1132  _ui->lineEdit_pymatcher_path->setObjectName(Parameters::kPyMatcherPath().c_str());
1133  connect(_ui->toolButton_pymatcher_path, SIGNAL(clicked()), this, SLOT(changePyMatcherPath()));
1134  _ui->pymatcher_matchThreshold->setObjectName(Parameters::kPyMatcherThreshold().c_str());
1135  _ui->pymatcher_iterations->setObjectName(Parameters::kPyMatcherIterations().c_str());
1136  _ui->checkBox_pymatcher_cuda->setObjectName(Parameters::kPyMatcherCuda().c_str());
1137  _ui->lineEdit_pymatcher_model->setObjectName(Parameters::kPyMatcherModel().c_str());
1138  connect(_ui->toolButton_pymatcher_model, SIGNAL(clicked()), this, SLOT(changePyMatcherModel()));
1139 
1140  // PyDetector
1141  _ui->lineEdit_pydetector_path->setObjectName(Parameters::kPyDetectorPath().c_str());
1142  connect(_ui->toolButton_pydetector_path, SIGNAL(clicked()), this, SLOT(changePyDetectorPath()));
1143  _ui->checkBox_pydetector_cuda->setObjectName(Parameters::kPyDetectorCuda().c_str());
1144 
1145  // GMS
1146  _ui->checkBox_gms_withRotation->setObjectName(Parameters::kGMSWithRotation().c_str());
1147  _ui->checkBox_gms_withScale->setObjectName(Parameters::kGMSWithScale().c_str());
1148  _ui->gms_thresholdFactor->setObjectName(Parameters::kGMSThresholdFactor().c_str());
1149 
1150  // PyDescriptor
1151  _ui->lineEdit_pydescriptor_path->setObjectName(Parameters::kPyDescriptorPath().c_str());
1152  connect(_ui->toolButton_pydescriptor_path, SIGNAL(clicked()), this, SLOT(changePyDescriptorPath()));
1153  _ui->pydescriptor_dim->setObjectName(Parameters::kPyDescriptorDim().c_str());
1154 
1155  // verifyHypotheses
1156  _ui->groupBox_vh_epipolar2->setObjectName(Parameters::kVhEpEnabled().c_str());
1157  _ui->surf_spinBox_matchCountMinAccepted->setObjectName(Parameters::kVhEpMatchCountMin().c_str());
1158  _ui->surf_doubleSpinBox_ransacParam1->setObjectName(Parameters::kVhEpRansacParam1().c_str());
1159  _ui->surf_doubleSpinBox_ransacParam2->setObjectName(Parameters::kVhEpRansacParam2().c_str());
1160 
1161  // RGB-D SLAM
1162  _ui->general_checkBox_activateRGBD->setObjectName(Parameters::kRGBDEnabled().c_str());
1163  _ui->rgdb_linearUpdate->setObjectName(Parameters::kRGBDLinearUpdate().c_str());
1164  _ui->rgdb_angularUpdate->setObjectName(Parameters::kRGBDAngularUpdate().c_str());
1165  _ui->rgdb_linearSpeedUpdate->setObjectName(Parameters::kRGBDLinearSpeedUpdate().c_str());
1166  _ui->rgdb_angularSpeedUpdate->setObjectName(Parameters::kRGBDAngularSpeedUpdate().c_str());
1167  _ui->rgbd_forceOdom3DoF->setObjectName(Parameters::kRGBDForceOdom3DoF().c_str());
1168  _ui->rgbd_savedLocalizationIgnored->setObjectName(Parameters::kRGBDStartAtOrigin().c_str());
1169  _ui->rgdb_rehearsalWeightIgnoredWhileMoving->setObjectName(Parameters::kMemRehearsalWeightIgnoredWhileMoving().c_str());
1170  _ui->rgdb_newMapOdomChange->setObjectName(Parameters::kRGBDNewMapOdomChangeDistance().c_str());
1171  _ui->odomScanHistory->setObjectName(Parameters::kRGBDNeighborLinkRefining().c_str());
1172  _ui->odomGravity->setObjectName(Parameters::kMemUseOdomGravity().c_str());
1173  _ui->spinBox_maxLocalLocationsRetrieved->setObjectName(Parameters::kRGBDMaxLocalRetrieved().c_str());
1174  _ui->rgbd_loopCovLimited->setObjectName(Parameters::kRGBDLoopCovLimited().c_str());
1175 
1176  _ui->graphOptimization_type->setObjectName(Parameters::kOptimizerStrategy().c_str());
1177  _ui->graphOptimization_iterations->setObjectName(Parameters::kOptimizerIterations().c_str());
1178  _ui->graphOptimization_covarianceIgnored->setObjectName(Parameters::kOptimizerVarianceIgnored().c_str());
1179  _ui->graphOptimization_fromGraphEnd->setObjectName(Parameters::kRGBDOptimizeFromGraphEnd().c_str());
1180  _ui->graphOptimization_maxError->setObjectName(Parameters::kRGBDOptimizeMaxError().c_str());
1181  _ui->graphOptimization_gravitySigma->setObjectName(Parameters::kOptimizerGravitySigma().c_str());
1182  _ui->graphOptimization_stopEpsilon->setObjectName(Parameters::kOptimizerEpsilon().c_str());
1183  _ui->graphOptimization_robust->setObjectName(Parameters::kOptimizerRobust().c_str());
1184  _ui->graphOptimization_priorsIgnored->setObjectName(Parameters::kOptimizerPriorsIgnored().c_str());
1185  _ui->graphOptimization_landmarksIgnored->setObjectName(Parameters::kOptimizerLandmarksIgnored().c_str());
1186 
1187  _ui->comboBox_g2o_solver->setObjectName(Parameters::kg2oSolver().c_str());
1188  _ui->comboBox_g2o_optimizer->setObjectName(Parameters::kg2oOptimizer().c_str());
1189  _ui->doubleSpinBox_g2o_pixelVariance->setObjectName(Parameters::kg2oPixelVariance().c_str());
1190  _ui->doubleSpinBox_g2o_robustKernelDelta->setObjectName(Parameters::kg2oRobustKernelDelta().c_str());
1191  _ui->doubleSpinBox_g2o_baseline->setObjectName(Parameters::kg2oBaseline().c_str());
1192 
1193  _ui->comboBox_gtsam_optimizer->setObjectName(Parameters::kGTSAMOptimizer().c_str());
1194  _ui->gtsam_incremental->setObjectName(Parameters::kGTSAMIncremental().c_str());
1195  _ui->gtsam_incremental_threshold->setObjectName(Parameters::kGTSAMIncRelinearizeThreshold().c_str());
1196  _ui->gtsam_incremental_skip->setObjectName(Parameters::kGTSAMIncRelinearizeSkip().c_str());
1197 
1198  _ui->graphPlan_goalReachedRadius->setObjectName(Parameters::kRGBDGoalReachedRadius().c_str());
1199  _ui->graphPlan_goalsSavedInUserData->setObjectName(Parameters::kRGBDGoalsSavedInUserData().c_str());
1200  _ui->graphPlan_stuckIterations->setObjectName(Parameters::kRGBDPlanStuckIterations().c_str());
1201  _ui->graphPlan_linearVelocity->setObjectName(Parameters::kRGBDPlanLinearVelocity().c_str());
1202  _ui->graphPlan_angularVelocity->setObjectName(Parameters::kRGBDPlanAngularVelocity().c_str());
1203 
1204  _ui->groupBox_localDetection_time->setObjectName(Parameters::kRGBDProximityByTime().c_str());
1205  _ui->groupBox_localDetection_space->setObjectName(Parameters::kRGBDProximityBySpace().c_str());
1206  _ui->localDetection_radius->setObjectName(Parameters::kRGBDLocalRadius().c_str());
1207  _ui->maxLocalizationDistance->setObjectName(Parameters::kRGBDMaxLoopClosureDistance().c_str());
1208  _ui->localDetection_maxDiffID->setObjectName(Parameters::kRGBDProximityMaxGraphDepth().c_str());
1209  _ui->localDetection_maxNeighbors->setObjectName(Parameters::kRGBDProximityPathMaxNeighbors().c_str());
1210  _ui->localDetection_maxPaths->setObjectName(Parameters::kRGBDProximityMaxPaths().c_str());
1211  _ui->localDetection_pathFilteringRadius->setObjectName(Parameters::kRGBDProximityPathFilteringRadius().c_str());
1212  _ui->localDetection_angle->setObjectName(Parameters::kRGBDProximityAngle().c_str());
1213  _ui->localDetection_mergedScanCovFactor->setObjectName(Parameters::kRGBDProximityMergedScanCovFactor().c_str());
1214  _ui->checkBox_localSpaceOdomGuess->setObjectName(Parameters::kRGBDProximityOdomGuess().c_str());
1215  _ui->checkBox_localSpacePathOdomPosesUsed->setObjectName(Parameters::kRGBDProximityPathRawPosesUsed().c_str());
1216  _ui->rgdb_localImmunizationRatio->setObjectName(Parameters::kRGBDLocalImmunizationRatio().c_str());
1217  _ui->loopClosure_identityGuess->setObjectName(Parameters::kRGBDLoopClosureIdentityGuess().c_str());
1218  _ui->loopClosure_reextract->setObjectName(Parameters::kRGBDLoopClosureReextractFeatures().c_str());
1219  _ui->loopClosure_bunlde->setObjectName(Parameters::kRGBDLocalBundleOnLoopClosure().c_str());
1220  _ui->loopClosure_invertedReg->setObjectName(Parameters::kRGBDInvertedReg().c_str());
1221  _ui->checkbox_rgbd_createOccupancyGrid->setObjectName(Parameters::kRGBDCreateOccupancyGrid().c_str());
1222  _ui->RGBDMarkerDetection->setObjectName(Parameters::kRGBDMarkerDetection().c_str());
1223  _ui->spinBox_maxOdomCacheSize->setObjectName(Parameters::kRGBDMaxOdomCacheSize().c_str());
1224  _ui->checkbox_localizationSmoothing->setObjectName(Parameters::kRGBDLocalizationSmoothing().c_str());
1225  _ui->doubleSpinBox_localizationPriorError->setObjectName(Parameters::kRGBDLocalizationPriorError().c_str());
1226 
1227  // Registration
1228  _ui->reg_repeatOnce->setObjectName(Parameters::kRegRepeatOnce().c_str());
1229  _ui->comboBox_registrationStrategy->setObjectName(Parameters::kRegStrategy().c_str());
1230  _ui->loopClosure_bowForce2D->setObjectName(Parameters::kRegForce3DoF().c_str());
1231 
1232  //RegistrationVis
1233  _ui->loopClosure_bowMinInliers->setObjectName(Parameters::kVisMinInliers().c_str());
1234  _ui->loopClosure_bowInlierDistance->setObjectName(Parameters::kVisInlierDistance().c_str());
1235  _ui->loopClosure_bowIterations->setObjectName(Parameters::kVisIterations().c_str());
1236  _ui->loopClosure_bowRefineIterations->setObjectName(Parameters::kVisRefineIterations().c_str());
1237  _ui->visMeanDistance->setObjectName(Parameters::kVisMeanInliersDistance().c_str());
1238  _ui->visMinDistribution->setObjectName(Parameters::kVisMinInliersDistribution().c_str());
1239  _ui->loopClosure_estimationType->setObjectName(Parameters::kVisEstimationType().c_str());
1240  connect(_ui->loopClosure_estimationType, SIGNAL(currentIndexChanged(int)), _ui->stackedWidget_loopClosureEstimation, SLOT(setCurrentIndex(int)));
1241  _ui->stackedWidget_loopClosureEstimation->setCurrentIndex(Parameters::defaultVisEstimationType());
1242  _ui->loopClosure_forwardEst->setObjectName(Parameters::kVisForwardEstOnly().c_str());
1243  _ui->loopClosure_bowEpipolarGeometryVar->setObjectName(Parameters::kVisEpipolarGeometryVar().c_str());
1244  _ui->loopClosure_pnpReprojError->setObjectName(Parameters::kVisPnPReprojError().c_str());
1245  _ui->loopClosure_pnpFlags->setObjectName(Parameters::kVisPnPFlags().c_str());
1246  _ui->loopClosure_pnpRefineIterations->setObjectName(Parameters::kVisPnPRefineIterations().c_str());
1247  _ui->loopClosure_pnpVarMedianRatio->setObjectName(Parameters::kVisPnPVarianceMedianRatio().c_str());
1248  _ui->loopClosure_pnpMaxVariance->setObjectName(Parameters::kVisPnPMaxVariance().c_str());
1249  _ui->loopClosure_pnpSamplingPolicy->setObjectName(Parameters::kVisPnPSamplingPolicy().c_str());
1250  _ui->loopClosure_pnpSplitLinearCovComponents->setObjectName(Parameters::kVisPnPSplitLinearCovComponents().c_str());
1251  _ui->reextract_nn->setObjectName(Parameters::kVisCorNNType().c_str());
1252  connect(_ui->reextract_nn, SIGNAL(currentIndexChanged(int)), this, SLOT(updateFeatureMatchingVisibility()));
1253  _ui->reextract_nndrRatio->setObjectName(Parameters::kVisCorNNDR().c_str());
1254  _ui->spinBox_visCorGuessWinSize->setObjectName(Parameters::kVisCorGuessWinSize().c_str());
1255  _ui->checkBox_visCorGuessMatchToProjection->setObjectName(Parameters::kVisCorGuessMatchToProjection().c_str());
1256  _ui->vis_feature_detector->setObjectName(Parameters::kVisFeatureType().c_str());
1257  _ui->reextract_maxFeatures->setObjectName(Parameters::kVisMaxFeatures().c_str());
1258  _ui->checkBox_visSSC->setObjectName(Parameters::kVisSSC().c_str());
1259  _ui->reextract_gridrows->setObjectName(Parameters::kVisGridRows().c_str());
1260  _ui->reextract_gridcols->setObjectName(Parameters::kVisGridCols().c_str());
1261  _ui->loopClosure_bowMaxDepth->setObjectName(Parameters::kVisMaxDepth().c_str());
1262  _ui->loopClosure_bowMinDepth->setObjectName(Parameters::kVisMinDepth().c_str());
1263  _ui->checkBox_visDepthAsMask->setObjectName(Parameters::kVisDepthAsMask().c_str());
1264  _ui->loopClosure_roi->setObjectName(Parameters::kVisRoiRatios().c_str());
1265  _ui->subpix_winSize->setObjectName(Parameters::kVisSubPixWinSize().c_str());
1266  _ui->subpix_iterations->setObjectName(Parameters::kVisSubPixIterations().c_str());
1267  _ui->subpix_eps->setObjectName(Parameters::kVisSubPixEps().c_str());
1268  _ui->odom_flow_winSize_2->setObjectName(Parameters::kVisCorFlowWinSize().c_str());
1269  _ui->odom_flow_maxLevel_2->setObjectName(Parameters::kVisCorFlowMaxLevel().c_str());
1270  _ui->odom_flow_iterations_2->setObjectName(Parameters::kVisCorFlowIterations().c_str());
1271  _ui->odom_flow_eps_2->setObjectName(Parameters::kVisCorFlowEps().c_str());
1272  _ui->loopClosure_bundle->setObjectName(Parameters::kVisBundleAdjustment().c_str());
1273 
1274  //RegistrationIcp
1275  _ui->comboBox_icpStrategy->setObjectName(Parameters::kIcpStrategy().c_str());
1276  connect(_ui->comboBox_icpStrategy, SIGNAL(currentIndexChanged(int)), _ui->stackedWidget_icpStrategy, SLOT(setCurrentIndex(int)));
1277  _ui->comboBox_icpStrategy->setCurrentIndex(Parameters::defaultIcpStrategy());
1278  _ui->globalDetection_icpMaxTranslation->setObjectName(Parameters::kIcpMaxTranslation().c_str());
1279  _ui->globalDetection_icpMaxRotation->setObjectName(Parameters::kIcpMaxRotation().c_str());
1280  _ui->loopClosure_icpVoxelSize->setObjectName(Parameters::kIcpVoxelSize().c_str());
1281  _ui->loopClosure_icpDownsamplingStep->setObjectName(Parameters::kIcpDownsamplingStep().c_str());
1282  _ui->loopClosure_icpRangeMin->setObjectName(Parameters::kIcpRangeMin().c_str());
1283  _ui->loopClosure_icpRangeMax->setObjectName(Parameters::kIcpRangeMax().c_str());
1284  _ui->loopClosure_icpFiltersEnabled->setObjectName(Parameters::kIcpFiltersEnabled().c_str());
1285  _ui->loopClosure_icpMaxCorrespondenceDistance->setObjectName(Parameters::kIcpMaxCorrespondenceDistance().c_str());
1286  _ui->loopClosure_icpReciprocalCorrespondences->setObjectName(Parameters::kIcpReciprocalCorrespondences().c_str());
1287  _ui->loopClosure_icpIterations->setObjectName(Parameters::kIcpIterations().c_str());
1288  _ui->loopClosure_icpEpsilon->setObjectName(Parameters::kIcpEpsilon().c_str());
1289  _ui->loopClosure_icpRatio->setObjectName(Parameters::kIcpCorrespondenceRatio().c_str());
1290  _ui->doubleSpinBox_icpOutlierRatio->setObjectName(Parameters::kIcpOutlierRatio().c_str());
1291  _ui->loopClosure_icpPointToPlane->setObjectName(Parameters::kIcpPointToPlane().c_str());
1292  _ui->loopClosure_icpPointToPlaneNormals->setObjectName(Parameters::kIcpPointToPlaneK().c_str());
1293  _ui->loopClosure_icpPointToPlaneNormalsRadius->setObjectName(Parameters::kIcpPointToPlaneRadius().c_str());
1294  _ui->loopClosure_icpPointToPlaneGroundNormalsUp->setObjectName(Parameters::kIcpPointToPlaneGroundNormalsUp().c_str());
1295  _ui->loopClosure_icpPointToPlaneNormalsMinComplexity->setObjectName(Parameters::kIcpPointToPlaneMinComplexity().c_str());
1296  _ui->loopClosure_icpPointToPlaneLowComplexityStrategy->setObjectName(Parameters::kIcpPointToPlaneLowComplexityStrategy().c_str());
1297  _ui->loopClosure_icpDebugExportFormat->setObjectName(Parameters::kIcpDebugExportFormat().c_str());
1298 
1299  _ui->lineEdit_IcpPMConfigPath->setObjectName(Parameters::kIcpPMConfig().c_str());
1300  connect(_ui->toolButton_IcpConfigPath, SIGNAL(clicked()), this, SLOT(changeIcpPMConfigPath()));
1301  _ui->spinBox_icpPMMatcherKnn->setObjectName(Parameters::kIcpPMMatcherKnn().c_str());
1302  _ui->doubleSpinBox_icpPMMatcherEpsilon->setObjectName(Parameters::kIcpPMMatcherEpsilon().c_str());
1303  _ui->loopClosure_icpPMMatcherIntensity->setObjectName(Parameters::kIcpPMMatcherIntensity().c_str());
1304  _ui->loopClosure_icpForce4DoF->setObjectName(Parameters::kIcpForce4DoF().c_str());
1305 
1306  _ui->spinBox_icpCCSamplingLimit->setObjectName(Parameters::kIcpCCSamplingLimit().c_str());
1307  _ui->checkBox_icpCCFilterOutFarthestPoints->setObjectName(Parameters::kIcpCCFilterOutFarthestPoints().c_str());
1308  _ui->doubleSpinBox_icpCCMaxFinalRMS->setObjectName(Parameters::kIcpCCMaxFinalRMS().c_str());
1309 
1310 
1311  // Occupancy grid
1312  _ui->groupBox_grid_3d->setObjectName(Parameters::kGrid3D().c_str());
1313  _ui->checkBox_grid_groundObstacle->setObjectName(Parameters::kGridGroundIsObstacle().c_str());
1314  _ui->doubleSpinBox_grid_resolution->setObjectName(Parameters::kGridCellSize().c_str());
1315  _ui->checkBox_grid_preVoxelFiltering->setObjectName(Parameters::kGridPreVoxelFiltering().c_str());
1316  _ui->spinBox_grid_decimation->setObjectName(Parameters::kGridDepthDecimation().c_str());
1317  _ui->doubleSpinBox_grid_maxDepth->setObjectName(Parameters::kGridRangeMax().c_str());
1318  _ui->doubleSpinBox_grid_minDepth->setObjectName(Parameters::kGridRangeMin().c_str());
1319  _ui->lineEdit_grid_roi->setObjectName(Parameters::kGridDepthRoiRatios().c_str());
1320  _ui->checkBox_grid_projRayTracing->setObjectName(Parameters::kGridRayTracing().c_str());
1321  _ui->doubleSpinBox_grid_footprintLength->setObjectName(Parameters::kGridFootprintLength().c_str());
1322  _ui->doubleSpinBox_grid_footprintWidth->setObjectName(Parameters::kGridFootprintWidth().c_str());
1323  _ui->doubleSpinBox_grid_footprintHeight->setObjectName(Parameters::kGridFootprintHeight().c_str());
1324  _ui->checkBox_grid_flatObstaclesDetected->setObjectName(Parameters::kGridFlatObstacleDetected().c_str());
1325  _ui->comboBox_grid_sensor->setObjectName(Parameters::kGridSensor().c_str());
1326  _ui->checkBox_grid_projMapFrame->setObjectName(Parameters::kGridMapFrameProjection().c_str());
1327  _ui->doubleSpinBox_grid_maxGroundAngle->setObjectName(Parameters::kGridMaxGroundAngle().c_str());
1328  _ui->spinBox_grid_normalK->setObjectName(Parameters::kGridNormalK().c_str());
1329  _ui->doubleSpinBox_grid_maxGroundHeight->setObjectName(Parameters::kGridMaxGroundHeight().c_str());
1330  _ui->doubleSpinBox_grid_maxObstacleHeight->setObjectName(Parameters::kGridMaxObstacleHeight().c_str());
1331  _ui->doubleSpinBox_grid_clusterRadius->setObjectName(Parameters::kGridClusterRadius().c_str());
1332  _ui->spinBox_grid_minClusterSize->setObjectName(Parameters::kGridMinClusterSize().c_str());
1333  _ui->doubleSpinBox_grid_minGroundHeight->setObjectName(Parameters::kGridMinGroundHeight().c_str());
1334  _ui->spinBox_grid_noiseMinNeighbors->setObjectName(Parameters::kGridNoiseFilteringMinNeighbors().c_str());
1335  _ui->doubleSpinBox_grid_noiseRadius->setObjectName(Parameters::kGridNoiseFilteringRadius().c_str());
1336  _ui->groupBox_grid_normalsSegmentation->setObjectName(Parameters::kGridNormalsSegmentation().c_str());
1337  _ui->checkBox_grid_unknownSpaceFilled->setObjectName(Parameters::kGridScan2dUnknownSpaceFilled().c_str());
1338  _ui->spinBox_grid_scanDecimation->setObjectName(Parameters::kGridScanDecimation().c_str());
1339 
1340  _ui->doubleSpinBox_grid_updateError->setObjectName(Parameters::kGridGlobalUpdateError().c_str());
1341  _ui->doubleSpinBox_grid_minMapSize->setObjectName(Parameters::kGridGlobalMinSize().c_str());
1342  _ui->spinBox_grid_maxNodes->setObjectName(Parameters::kGridGlobalMaxNodes().c_str());
1343  _ui->doubleSpinBox_grid_altitudeDelta->setObjectName(Parameters::kGridGlobalAltitudeDelta().c_str());
1344  _ui->doubleSpinBox_grid_footprintRadius->setObjectName(Parameters::kGridGlobalFootprintRadius().c_str());
1345  _ui->doubleSpinBox_grid_occThr->setObjectName(Parameters::kGridGlobalOccupancyThr().c_str());
1346  _ui->doubleSpinBox_grid_probHit->setObjectName(Parameters::kGridGlobalProbHit().c_str());
1347  _ui->doubleSpinBox_grid_probMiss->setObjectName(Parameters::kGridGlobalProbMiss().c_str());
1348  _ui->doubleSpinBox_grid_clampingMin->setObjectName(Parameters::kGridGlobalProbClampingMin().c_str());
1349  _ui->doubleSpinBox_grid_clampingMax->setObjectName(Parameters::kGridGlobalProbClampingMax().c_str());
1350  _ui->checkBox_grid_erode->setObjectName(Parameters::kGridGlobalEroded().c_str());
1351  _ui->spinBox_grid_floodfilldepth->setObjectName(Parameters::kGridGlobalFloodFillDepth().c_str());
1352 
1353  //Odometry
1354  _ui->odom_strategy->setObjectName(Parameters::kOdomStrategy().c_str());
1355  connect(_ui->odom_strategy, SIGNAL(currentIndexChanged(int)), this, SLOT(updateOdometryStackedIndex(int)));
1356  _ui->odom_strategy->setCurrentIndex(Parameters::defaultOdomStrategy());
1357  updateOdometryStackedIndex(Parameters::defaultOdomStrategy());
1358  _ui->odom_countdown->setObjectName(Parameters::kOdomResetCountdown().c_str());
1359  _ui->odom_holonomic->setObjectName(Parameters::kOdomHolonomic().c_str());
1360  _ui->odom_fillInfoData->setObjectName(Parameters::kOdomFillInfoData().c_str());
1361  _ui->odom_dataBufferSize->setObjectName(Parameters::kOdomImageBufferSize().c_str());
1362  _ui->odom_flow_keyframeThr->setObjectName(Parameters::kOdomKeyFrameThr().c_str());
1363  _ui->odom_VisKeyFrameThr->setObjectName(Parameters::kOdomVisKeyFrameThr().c_str());
1364  _ui->odom_flow_scanKeyframeThr->setObjectName(Parameters::kOdomScanKeyFrameThr().c_str());
1365  _ui->odom_flow_guessMotion->setObjectName(Parameters::kOdomGuessMotion().c_str());
1366  _ui->odom_guess_smoothing_delay->setObjectName(Parameters::kOdomGuessSmoothingDelay().c_str());
1367  _ui->odom_imageDecimation->setObjectName(Parameters::kOdomImageDecimation().c_str());
1368  _ui->odom_alignWithGround->setObjectName(Parameters::kOdomAlignWithGround().c_str());
1369  _ui->odom_lidar_deskewing->setObjectName(Parameters::kOdomDeskewing().c_str());
1370 
1371  //Odometry Frame to Map
1372  _ui->odom_localHistory->setObjectName(Parameters::kOdomF2MMaxSize().c_str());
1373  _ui->spinBox_odom_f2m_maxNewFeatures->setObjectName(Parameters::kOdomF2MMaxNewFeatures().c_str());
1374  _ui->spinBox_odom_f2m_scanMaxSize->setObjectName(Parameters::kOdomF2MScanMaxSize().c_str());
1375  _ui->doubleSpinBox_odom_f2m_scanRadius->setObjectName(Parameters::kOdomF2MScanSubtractRadius().c_str());
1376  _ui->doubleSpinBox_odom_f2m_scanAngle->setObjectName(Parameters::kOdomF2MScanSubtractAngle().c_str());
1377  _ui->doubleSpinBox_odom_f2m_scanRange->setObjectName(Parameters::kOdomF2MScanRange().c_str());
1378  _ui->odom_f2m_validDepthRatio->setObjectName(Parameters::kOdomF2MValidDepthRatio().c_str());
1379  _ui->odom_f2m_bundleStrategy->setObjectName(Parameters::kOdomF2MBundleAdjustment().c_str());
1380  _ui->odom_f2m_bundleMaxFrames->setObjectName(Parameters::kOdomF2MBundleAdjustmentMaxFrames().c_str());
1381 
1382  //Odometry Frame To Frame
1383  _ui->comboBox_odomf2f_corType->setObjectName(Parameters::kVisCorType().c_str());
1384 
1385  //Odometry Mono
1386  _ui->doubleSpinBox_minFlow->setObjectName(Parameters::kOdomMonoInitMinFlow().c_str());
1387  _ui->doubleSpinBox_minInitTranslation->setObjectName(Parameters::kOdomMonoInitMinTranslation().c_str());
1388  _ui->doubleSpinBox_minTranslation->setObjectName(Parameters::kOdomMonoMinTranslation().c_str());
1389  _ui->doubleSpinBox_maxVariance->setObjectName(Parameters::kOdomMonoMaxVariance().c_str());
1390 
1391  //Odometry particle filter
1392  _ui->odom_filteringStrategy->setObjectName(Parameters::kOdomFilteringStrategy().c_str());
1393  _ui->stackedWidget_odometryFiltering->setCurrentIndex(_ui->odom_filteringStrategy->currentIndex());
1394  connect(_ui->odom_filteringStrategy, SIGNAL(currentIndexChanged(int)), _ui->stackedWidget_odometryFiltering, SLOT(setCurrentIndex(int)));
1395  _ui->spinBox_particleSize->setObjectName(Parameters::kOdomParticleSize().c_str());
1396  _ui->doubleSpinBox_particleNoiseT->setObjectName(Parameters::kOdomParticleNoiseT().c_str());
1397  _ui->doubleSpinBox_particleLambdaT->setObjectName(Parameters::kOdomParticleLambdaT().c_str());
1398  _ui->doubleSpinBox_particleNoiseR->setObjectName(Parameters::kOdomParticleNoiseR().c_str());
1399  _ui->doubleSpinBox_particleLambdaR->setObjectName(Parameters::kOdomParticleLambdaR().c_str());
1400 
1401  //Odometry Kalman filter
1402  _ui->doubleSpinBox_kalmanProcessNoise->setObjectName(Parameters::kOdomKalmanProcessNoise().c_str());
1403  _ui->doubleSpinBox_kalmanMeasurementNoise->setObjectName(Parameters::kOdomKalmanMeasurementNoise().c_str());
1404 
1405  //Odometry Fovis
1406  _ui->spinBox_OdomFovisFeatureWindowSize->setObjectName(Parameters::kOdomFovisFeatureWindowSize().c_str());
1407  _ui->spinBox_OdomFovisMaxPyramidLevel->setObjectName(Parameters::kOdomFovisMaxPyramidLevel().c_str());
1408  _ui->spinBox_OdomFovisMinPyramidLevel->setObjectName(Parameters::kOdomFovisMinPyramidLevel().c_str());
1409  _ui->spinBox_OdomFovisTargetPixelsPerFeature->setObjectName(Parameters::kOdomFovisTargetPixelsPerFeature().c_str());
1410  _ui->spinBox_OdomFovisFastThreshold->setObjectName(Parameters::kOdomFovisFastThreshold().c_str());
1411  _ui->checkBox_OdomFovisUseAdaptiveThreshold->setObjectName(Parameters::kOdomFovisUseAdaptiveThreshold().c_str());
1412  _ui->doubleSpinBox_OdomFovisFastThresholdAdaptiveGain->setObjectName(Parameters::kOdomFovisFastThresholdAdaptiveGain().c_str());
1413  _ui->checkBox_OdomFovisUseHomographyInitialization->setObjectName(Parameters::kOdomFovisUseHomographyInitialization().c_str());
1414 
1415  _ui->checkBox_OdomFovisUseBucketing->setObjectName(Parameters::kOdomFovisUseBucketing().c_str());
1416  _ui->spinBox_OdomFovisBucketWidth->setObjectName(Parameters::kOdomFovisBucketWidth().c_str());
1417  _ui->spinBox_OdomFovisBucketHeight->setObjectName(Parameters::kOdomFovisBucketHeight().c_str());
1418  _ui->spinBox_OdomFovisMaxKeypointsPerBucket->setObjectName(Parameters::kOdomFovisMaxKeypointsPerBucket().c_str());
1419  _ui->checkBox_OdomFovisUseImageNormalization->setObjectName(Parameters::kOdomFovisUseImageNormalization().c_str());
1420 
1421  _ui->doubleSpinBox_OdomFovisInlierMaxReprojectionError->setObjectName(Parameters::kOdomFovisInlierMaxReprojectionError().c_str());
1422  _ui->doubleSpinBox_OdomFovisCliqueInlierThreshold->setObjectName(Parameters::kOdomFovisCliqueInlierThreshold().c_str());
1423  _ui->spinBox_OdomFovisMinFeaturesForEstimate->setObjectName(Parameters::kOdomFovisMinFeaturesForEstimate().c_str());
1424  _ui->doubleSpinBox_OdomFovisMaxMeanReprojectionError->setObjectName(Parameters::kOdomFovisMaxMeanReprojectionError().c_str());
1425  _ui->checkBox_OdomFovisUseSubpixelRefinement->setObjectName(Parameters::kOdomFovisUseSubpixelRefinement().c_str());
1426  _ui->spinBox_OdomFovisFeatureSearchWindow->setObjectName(Parameters::kOdomFovisFeatureSearchWindow().c_str());
1427  _ui->checkBox_OdomFovisUpdateTargetFeaturesWithRefined->setObjectName(Parameters::kOdomFovisUpdateTargetFeaturesWithRefined().c_str());
1428 
1429  _ui->checkBox_OdomFovisStereoRequireMutualMatch->setObjectName(Parameters::kOdomFovisStereoRequireMutualMatch().c_str());
1430  _ui->doubleSpinBox_OdomFovisStereoMaxDistEpipolarLine->setObjectName(Parameters::kOdomFovisStereoMaxDistEpipolarLine().c_str());
1431  _ui->doubleSpinBox_OdomFovisStereoMaxRefinementDisplacement->setObjectName(Parameters::kOdomFovisStereoMaxRefinementDisplacement().c_str());
1432  _ui->spinBox_OdomFovisStereoMaxDisparity->setObjectName(Parameters::kOdomFovisStereoMaxDisparity().c_str());
1433 
1434  // Odometry viso2
1435  _ui->spinBox_OdomViso2RansacIters->setObjectName(Parameters::kOdomViso2RansacIters().c_str());
1436  _ui->doubleSpinBox_OdomViso2InlierThreshold->setObjectName(Parameters::kOdomViso2InlierThreshold().c_str());
1437  _ui->checkBox_OdomViso2Reweighting->setObjectName(Parameters::kOdomViso2Reweighting().c_str());
1438 
1439  _ui->spinBox_OdomViso2MatchNmsN->setObjectName(Parameters::kOdomViso2MatchNmsN().c_str());
1440  _ui->spinBox_OdomViso2MatchNmsTau->setObjectName(Parameters::kOdomViso2MatchNmsTau().c_str());
1441  _ui->spinBox_OdomViso2MatchBinsize->setObjectName(Parameters::kOdomViso2MatchBinsize().c_str());
1442  _ui->spinBox_OdomViso2MatchRadius->setObjectName(Parameters::kOdomViso2MatchRadius().c_str());
1443  _ui->spinBox_OdomViso2MatchDispTolerance->setObjectName(Parameters::kOdomViso2MatchDispTolerance().c_str());
1444  _ui->spinBox_OdomViso2MatchOutlierDispTolerance->setObjectName(Parameters::kOdomViso2MatchOutlierDispTolerance().c_str());
1445  _ui->spinBox_OdomViso2MatchOutlierFlowTolerance->setObjectName(Parameters::kOdomViso2MatchOutlierFlowTolerance().c_str());
1446  _ui->checkBox_OdomViso2MatchMultiStage->setObjectName(Parameters::kOdomViso2MatchMultiStage().c_str());
1447  _ui->checkBox_OdomViso2MatchHalfResolution->setObjectName(Parameters::kOdomViso2MatchHalfResolution().c_str());
1448  _ui->spinBox_OdomViso2MatchRefinement->setObjectName(Parameters::kOdomViso2MatchRefinement().c_str());
1449 
1450  _ui->spinBox_OdomViso2BucketMaxFeatures->setObjectName(Parameters::kOdomViso2BucketMaxFeatures().c_str());
1451  _ui->doubleSpinBox_OdomViso2BucketWidth->setObjectName(Parameters::kOdomViso2BucketWidth().c_str());
1452  _ui->doubleSpinBox_OdomViso2BucketHeight->setObjectName(Parameters::kOdomViso2BucketHeight().c_str());
1453 
1454  // Odometry ORBSLAM
1455  _ui->lineEdit_OdomORBSLAMVocPath->setObjectName(Parameters::kOdomORBSLAMVocPath().c_str());
1456  connect(_ui->toolButton_OdomORBSLAMVocPath, SIGNAL(clicked()), this, SLOT(changeOdometryORBSLAMVocabulary()));
1457  _ui->doubleSpinBox_OdomORBSLAMBf->setObjectName(Parameters::kOdomORBSLAMBf().c_str());
1458  _ui->doubleSpinBox_OdomORBSLAMThDepth->setObjectName(Parameters::kOdomORBSLAMThDepth().c_str());
1459  _ui->doubleSpinBox_OdomORBSLAMFps->setObjectName(Parameters::kOdomORBSLAMFps().c_str());
1460  _ui->spinBox_OdomORBSLAMMaxFeatures->setObjectName(Parameters::kOdomORBSLAMMaxFeatures().c_str());
1461  _ui->spinBox_OdomORBSLAMMapSize->setObjectName(Parameters::kOdomORBSLAMMapSize().c_str());
1462  _ui->groupBox_OdomORBSLAMInertial->setObjectName(Parameters::kOdomORBSLAMInertial().c_str());
1463  _ui->doubleSpinBox_ORBSLAMGyroNoise->setObjectName(Parameters::kOdomORBSLAMGyroNoise().c_str());
1464  _ui->doubleSpinBox_ORBSLAMAccNoise->setObjectName(Parameters::kOdomORBSLAMAccNoise().c_str());
1465  _ui->doubleSpinBox_ORBSLAMGyroWalk->setObjectName(Parameters::kOdomORBSLAMGyroWalk().c_str());
1466  _ui->doubleSpinBox_ORBSLAMAccWalk->setObjectName(Parameters::kOdomORBSLAMAccWalk().c_str());
1467  _ui->doubleSpinBox_ORBSLAMSamplingRate->setObjectName(Parameters::kOdomORBSLAMSamplingRate().c_str());
1468 
1469  // Odometry Okvis
1470  _ui->lineEdit_OdomOkvisPath->setObjectName(Parameters::kOdomOKVISConfigPath().c_str());
1471  connect(_ui->toolButton_OdomOkvisPath, SIGNAL(clicked()), this, SLOT(changeOdometryOKVISConfigPath()));
1472 
1473  // Odometry LOAM
1474  _ui->odom_loam_sensor->setObjectName(Parameters::kOdomLOAMSensor().c_str());
1475  _ui->odom_loam_scan_period->setObjectName(Parameters::kOdomLOAMScanPeriod().c_str());
1476  _ui->odom_loam_resolution->setObjectName(Parameters::kOdomLOAMResolution().c_str());
1477  _ui->odom_loam_linvar->setObjectName(Parameters::kOdomLOAMLinVar().c_str());
1478  _ui->odom_loam_angvar->setObjectName(Parameters::kOdomLOAMAngVar().c_str());
1479  _ui->odom_loam_localMapping->setObjectName(Parameters::kOdomLOAMLocalMapping().c_str());
1480 
1481  // Odometry MSCKF_VIO
1482  _ui->OdomMSCKFGridRow->setObjectName(Parameters::kOdomMSCKFGridRow().c_str());
1483  _ui->OdomMSCKFGridCol->setObjectName(Parameters::kOdomMSCKFGridCol().c_str());
1484  _ui->OdomMSCKFGridMinFeatureNum->setObjectName(Parameters::kOdomMSCKFGridMinFeatureNum().c_str());
1485  _ui->OdomMSCKFGridMaxFeatureNum->setObjectName(Parameters::kOdomMSCKFGridMaxFeatureNum().c_str());
1486  _ui->OdomMSCKFPyramidLevels->setObjectName(Parameters::kOdomMSCKFPyramidLevels().c_str());
1487  _ui->OdomMSCKFPatchSize->setObjectName(Parameters::kOdomMSCKFPatchSize().c_str());
1488  _ui->OdomMSCKFFastThreshold->setObjectName(Parameters::kOdomMSCKFFastThreshold().c_str());
1489  _ui->OdomMSCKFMaxIteration->setObjectName(Parameters::kOdomMSCKFMaxIteration().c_str());
1490  _ui->OdomMSCKFMaxCamStateSize->setObjectName(Parameters::kOdomMSCKFMaxCamStateSize().c_str());
1491  _ui->OdomMSCKFTrackPrecision->setObjectName(Parameters::kOdomMSCKFTrackPrecision().c_str());
1492  _ui->OdomMSCKFRansacThreshold->setObjectName(Parameters::kOdomMSCKFRansacThreshold().c_str());
1493  _ui->OdomMSCKFStereoThreshold->setObjectName(Parameters::kOdomMSCKFStereoThreshold().c_str());
1494  _ui->OdomMSCKFPositionStdThreshold->setObjectName(Parameters::kOdomMSCKFPositionStdThreshold().c_str());
1495  _ui->OdomMSCKFRotationThreshold->setObjectName(Parameters::kOdomMSCKFRotationThreshold().c_str());
1496  _ui->OdomMSCKFTranslationThreshold->setObjectName(Parameters::kOdomMSCKFTranslationThreshold().c_str());
1497  _ui->OdomMSCKFTrackingRateThreshold->setObjectName(Parameters::kOdomMSCKFTrackingRateThreshold().c_str());
1498  _ui->OdomMSCKFOptTranslationThreshold->setObjectName(Parameters::kOdomMSCKFOptTranslationThreshold().c_str());
1499  _ui->OdomMSCKFNoiseGyro->setObjectName(Parameters::kOdomMSCKFNoiseGyro().c_str());
1500  _ui->OdomMSCKFNoiseAcc->setObjectName(Parameters::kOdomMSCKFNoiseAcc().c_str());
1501  _ui->OdomMSCKFNoiseGyroBias->setObjectName(Parameters::kOdomMSCKFNoiseGyroBias().c_str());
1502  _ui->OdomMSCKFNoiseAccBias->setObjectName(Parameters::kOdomMSCKFNoiseAccBias().c_str());
1503  _ui->OdomMSCKFNoiseFeature->setObjectName(Parameters::kOdomMSCKFNoiseFeature().c_str());
1504  _ui->OdomMSCKFInitCovVel->setObjectName(Parameters::kOdomMSCKFInitCovVel().c_str());
1505  _ui->OdomMSCKFInitCovGyroBias->setObjectName(Parameters::kOdomMSCKFInitCovGyroBias().c_str());
1506  _ui->OdomMSCKFInitCovAccBias->setObjectName(Parameters::kOdomMSCKFInitCovAccBias().c_str());
1507  _ui->OdomMSCKFInitCovExRot->setObjectName(Parameters::kOdomMSCKFInitCovExRot().c_str());
1508  _ui->OdomMSCKFInitCovExTrans->setObjectName(Parameters::kOdomMSCKFInitCovExTrans().c_str());
1509 
1510  // Odometry VINS
1511  _ui->lineEdit_OdomVinsPath->setObjectName(Parameters::kOdomVINSConfigPath().c_str());
1512  connect(_ui->toolButton_OdomVinsPath, SIGNAL(clicked()), this, SLOT(changeOdometryVINSConfigPath()));
1513 
1514  // Odometry OpenVINS
1515  _ui->checkBox_OdomOpenVINSUseStereo->setObjectName(Parameters::kOdomOpenVINSUseStereo().c_str());
1516  _ui->checkBox_OdomOpenVINSUseKLT->setObjectName(Parameters::kOdomOpenVINSUseKLT().c_str());
1517  _ui->spinBox_OdomOpenVINSNumPts->setObjectName(Parameters::kOdomOpenVINSNumPts().c_str());
1518  _ui->spinBox_OdomOpenVINSMinPxDist->setObjectName(Parameters::kOdomOpenVINSMinPxDist().c_str());
1519  _ui->checkBox_OdomOpenVINSFiTriangulate1d->setObjectName(Parameters::kOdomOpenVINSFiTriangulate1d().c_str());
1520  _ui->checkBox_OdomOpenVINSFiRefineFeatures->setObjectName(Parameters::kOdomOpenVINSFiRefineFeatures().c_str());
1521  _ui->spinBox_OdomOpenVINSFiMaxRuns->setObjectName(Parameters::kOdomOpenVINSFiMaxRuns().c_str());
1522  _ui->doubleSpinBox_OdomOpenVINSFiMaxBaseline->setObjectName(Parameters::kOdomOpenVINSFiMaxBaseline().c_str());
1523  _ui->doubleSpinBox_OdomOpenVINSFiMaxCondNumber->setObjectName(Parameters::kOdomOpenVINSFiMaxCondNumber().c_str());
1524 
1525  _ui->checkBox_OdomOpenVINSUseFEJ->setObjectName(Parameters::kOdomOpenVINSUseFEJ().c_str());
1526  _ui->comboBox_OdomOpenVINSIntegration->setObjectName(Parameters::kOdomOpenVINSIntegration().c_str());
1527  _ui->checkBox_OdomOpenVINSCalibCamExtrinsics->setObjectName(Parameters::kOdomOpenVINSCalibCamExtrinsics().c_str());
1528  _ui->checkBox_OdomOpenVINSCalibCamIntrinsics->setObjectName(Parameters::kOdomOpenVINSCalibCamIntrinsics().c_str());
1529  _ui->checkBox_OdomOpenVINSCalibCamTimeoffset->setObjectName(Parameters::kOdomOpenVINSCalibCamTimeoffset().c_str());
1530  _ui->checkBox_OdomOpenVINSCalibIMUIntrinsics->setObjectName(Parameters::kOdomOpenVINSCalibIMUIntrinsics().c_str());
1531  _ui->checkBox_OdomOpenVINSCalibIMUGSensitivity->setObjectName(Parameters::kOdomOpenVINSCalibIMUGSensitivity().c_str());
1532  _ui->spinBox_OdomOpenVINSMaxClones->setObjectName(Parameters::kOdomOpenVINSMaxClones().c_str());
1533  _ui->spinBox_OdomOpenVINSMaxSLAM->setObjectName(Parameters::kOdomOpenVINSMaxSLAM().c_str());
1534  _ui->spinBox_OdomOpenVINSMaxSLAMInUpdate->setObjectName(Parameters::kOdomOpenVINSMaxSLAMInUpdate().c_str());
1535  _ui->spinBox_OdomOpenVINSMaxMSCKFInUpdate->setObjectName(Parameters::kOdomOpenVINSMaxMSCKFInUpdate().c_str());
1536  _ui->comboBox_OdomOpenVINSFeatRepMSCKF->setObjectName(Parameters::kOdomOpenVINSFeatRepMSCKF().c_str());
1537  _ui->comboBox_OdomOpenVINSFeatRepSLAM->setObjectName(Parameters::kOdomOpenVINSFeatRepSLAM().c_str());
1538  _ui->doubleSpinBox_OdomOpenVINSDtSLAMDelay->setObjectName(Parameters::kOdomOpenVINSDtSLAMDelay().c_str());
1539  _ui->doubleSpinBox_OdomOpenVINSGravityMag->setObjectName(Parameters::kOdomOpenVINSGravityMag().c_str());
1540  _ui->lineEdit_OdomOpenVINSLeftMaskPath->setObjectName(Parameters::kOdomOpenVINSLeftMaskPath().c_str());
1541  connect(_ui->toolButton_OdomOpenVINSLeftMaskPath, SIGNAL(clicked()), this, SLOT(changeOdometryOpenVINSLeftMask()));
1542  _ui->lineEdit_OdomOpenVINSRightMaskPath->setObjectName(Parameters::kOdomOpenVINSRightMaskPath().c_str());
1543  connect(_ui->toolButton_OdomOpenVINSRightMaskPath, SIGNAL(clicked()), this, SLOT(changeOdometryOpenVINSRightMask()));
1544 
1545  _ui->doubleSpinBox_OdomOpenVINSInitWindowTime->setObjectName(Parameters::kOdomOpenVINSInitWindowTime().c_str());
1546  _ui->doubleSpinBox_OdomOpenVINSInitIMUThresh->setObjectName(Parameters::kOdomOpenVINSInitIMUThresh().c_str());
1547  _ui->doubleSpinBox_OdomOpenVINSInitMaxDisparity->setObjectName(Parameters::kOdomOpenVINSInitMaxDisparity().c_str());
1548  _ui->spinBox_OdomOpenVINSInitMaxFeatures->setObjectName(Parameters::kOdomOpenVINSInitMaxFeatures().c_str());
1549  _ui->checkBox_OdomOpenVINSInitDynUse->setObjectName(Parameters::kOdomOpenVINSInitDynUse().c_str());
1550  _ui->checkBox_OdomOpenVINSInitDynMLEOptCalib->setObjectName(Parameters::kOdomOpenVINSInitDynMLEOptCalib().c_str());
1551  _ui->spinBox_OdomOpenVINSInitDynMLEMaxIter->setObjectName(Parameters::kOdomOpenVINSInitDynMLEMaxIter().c_str());
1552  _ui->doubleSpinBox_OdomOpenVINSInitDynMLEMaxTime->setObjectName(Parameters::kOdomOpenVINSInitDynMLEMaxTime().c_str());
1553  _ui->spinBox_OdomOpenVINSInitDynMLEMaxThreads->setObjectName(Parameters::kOdomOpenVINSInitDynMLEMaxThreads().c_str());
1554  _ui->spinBox_OdomOpenVINSInitDynNumPose->setObjectName(Parameters::kOdomOpenVINSInitDynNumPose().c_str());
1555  _ui->doubleSpinBox_OdomOpenVINSInitDynMinDeg->setObjectName(Parameters::kOdomOpenVINSInitDynMinDeg().c_str());
1556  _ui->doubleSpinBox_OdomOpenVINSInitDynInflationOri->setObjectName(Parameters::kOdomOpenVINSInitDynInflationOri().c_str());
1557  _ui->doubleSpinBox_OdomOpenVINSInitDynInflationVel->setObjectName(Parameters::kOdomOpenVINSInitDynInflationVel().c_str());
1558  _ui->doubleSpinBox_OdomOpenVINSInitDynInflationBg->setObjectName(Parameters::kOdomOpenVINSInitDynInflationBg().c_str());
1559  _ui->doubleSpinBox_OdomOpenVINSInitDynInflationBa->setObjectName(Parameters::kOdomOpenVINSInitDynInflationBa().c_str());
1560  _ui->doubleSpinBox_OdomOpenVINSInitDynMinRecCond->setObjectName(Parameters::kOdomOpenVINSInitDynMinRecCond().c_str());
1561 
1562  _ui->checkBox_OdomOpenVINSTryZUPT->setObjectName(Parameters::kOdomOpenVINSTryZUPT().c_str());
1563  _ui->doubleSpinBox_OdomOpenVINSZUPTChi2Multiplier->setObjectName(Parameters::kOdomOpenVINSZUPTChi2Multiplier().c_str());
1564  _ui->doubleSpinBox_OdomOpenVINSZUPTMaxVelodicy->setObjectName(Parameters::kOdomOpenVINSZUPTMaxVelodicy().c_str());
1565  _ui->doubleSpinBox_OdomOpenVINSZUPTNoiseMultiplier->setObjectName(Parameters::kOdomOpenVINSZUPTNoiseMultiplier().c_str());
1566  _ui->doubleSpinBox_OdomOpenVINSZUPTMaxDisparity->setObjectName(Parameters::kOdomOpenVINSZUPTMaxDisparity().c_str());
1567  _ui->checkBox_OdomOpenVINSZUPTOnlyAtBeginning->setObjectName(Parameters::kOdomOpenVINSZUPTOnlyAtBeginning().c_str());
1568 
1569  _ui->doubleSpinBox_OdomOpenVINSAccelerometerNoiseDensity->setObjectName(Parameters::kOdomOpenVINSAccelerometerNoiseDensity().c_str());
1570  _ui->doubleSpinBox_OdomOpenVINSAccelerometerRandomWalk->setObjectName(Parameters::kOdomOpenVINSAccelerometerRandomWalk().c_str());
1571  _ui->doubleSpinBox_OdomOpenVINSGyroscopeNoiseDensity->setObjectName(Parameters::kOdomOpenVINSGyroscopeNoiseDensity().c_str());
1572  _ui->doubleSpinBox_OdomOpenVINSGyroscopeRandomWalk->setObjectName(Parameters::kOdomOpenVINSGyroscopeRandomWalk().c_str());
1573  _ui->doubleSpinBox_OdomOpenVINSUpMSCKFSigmaPx->setObjectName(Parameters::kOdomOpenVINSUpMSCKFSigmaPx().c_str());
1574  _ui->doubleSpinBox_OdomOpenVINSUpMSCKFChi2Multiplier->setObjectName(Parameters::kOdomOpenVINSUpMSCKFChi2Multiplier().c_str());
1575  _ui->doubleSpinBox_OdomOpenVINSUpSLAMSigmaPx->setObjectName(Parameters::kOdomOpenVINSUpSLAMSigmaPx().c_str());
1576  _ui->doubleSpinBox_OdomOpenVINSUpSLAMChi2Multiplier->setObjectName(Parameters::kOdomOpenVINSUpSLAMChi2Multiplier().c_str());
1577 
1578  //Stereo
1579  _ui->stereo_winWidth->setObjectName(Parameters::kStereoWinWidth().c_str());
1580  _ui->stereo_winHeight->setObjectName(Parameters::kStereoWinHeight().c_str());
1581  _ui->stereo_maxLevel->setObjectName(Parameters::kStereoMaxLevel().c_str());
1582  _ui->stereo_iterations->setObjectName(Parameters::kStereoIterations().c_str());
1583  _ui->stereo_minDisparity->setObjectName(Parameters::kStereoMinDisparity().c_str());
1584  _ui->stereo_maxDisparity->setObjectName(Parameters::kStereoMaxDisparity().c_str());
1585  _ui->stereo_ssd->setObjectName(Parameters::kStereoSSD().c_str());
1586  _ui->stereo_flow_eps->setObjectName(Parameters::kStereoEps().c_str());
1587  _ui->stereo_opticalFlow->setObjectName(Parameters::kStereoOpticalFlow().c_str());
1588 
1589  // Odometry Open3D
1590  _ui->odom_open3d_method->setObjectName(Parameters::kOdomOpen3DMethod().c_str());
1591  _ui->odom_open3d_max_depth->setObjectName(Parameters::kOdomOpen3DMaxDepth().c_str());
1592 
1593  //StereoDense
1594  _ui->comboBox_stereoDense_strategy->setObjectName(Parameters::kStereoDenseStrategy().c_str());
1595  connect(_ui->comboBox_stereoDense_strategy, SIGNAL(currentIndexChanged(int)), _ui->stackedWidget_stereoDense, SLOT(setCurrentIndex(int)));
1596  _ui->comboBox_stereoDense_strategy->setCurrentIndex(Parameters::defaultStereoDenseStrategy());
1597  _ui->stackedWidget_stereoDense->setCurrentIndex(Parameters::defaultStereoDenseStrategy());
1598 
1599  //StereoBM
1600  _ui->stereobm_blockSize->setObjectName(Parameters::kStereoBMBlockSize().c_str());
1601  _ui->stereobm_minDisparity->setObjectName(Parameters::kStereoBMMinDisparity().c_str());
1602  _ui->stereobm_numDisparities->setObjectName(Parameters::kStereoBMNumDisparities().c_str());
1603  _ui->stereobm_preFilterCap->setObjectName(Parameters::kStereoBMPreFilterCap().c_str());
1604  _ui->stereobm_preFilterSize->setObjectName(Parameters::kStereoBMPreFilterSize().c_str());
1605  _ui->stereobm_speckleRange->setObjectName(Parameters::kStereoBMSpeckleRange().c_str());
1606  _ui->stereobm_speckleWinSize->setObjectName(Parameters::kStereoBMSpeckleWindowSize().c_str());
1607  _ui->stereobm_tetureThreshold->setObjectName(Parameters::kStereoBMTextureThreshold().c_str());
1608  _ui->stereobm_uniquessRatio->setObjectName(Parameters::kStereoBMUniquenessRatio().c_str());
1609  _ui->stereobm_disp12MaxDiff->setObjectName(Parameters::kStereoBMDisp12MaxDiff().c_str());
1610 
1611  //StereoSGBM
1612  _ui->stereosgbm_blockSize->setObjectName(Parameters::kStereoSGBMBlockSize().c_str());
1613  _ui->stereosgbm_minDisparity->setObjectName(Parameters::kStereoSGBMMinDisparity().c_str());
1614  _ui->stereosgbm_numDisparities->setObjectName(Parameters::kStereoSGBMNumDisparities().c_str());
1615  _ui->stereosgbm_preFilterCap->setObjectName(Parameters::kStereoSGBMPreFilterCap().c_str());
1616  _ui->stereosgbm_speckleRange->setObjectName(Parameters::kStereoSGBMSpeckleRange().c_str());
1617  _ui->stereosgbm_speckleWinSize->setObjectName(Parameters::kStereoSGBMSpeckleWindowSize().c_str());
1618  _ui->stereosgbm_uniquessRatio->setObjectName(Parameters::kStereoSGBMUniquenessRatio().c_str());
1619  _ui->stereosgbm_disp12MaxDiff->setObjectName(Parameters::kStereoSGBMDisp12MaxDiff().c_str());
1620  _ui->stereosgbm_p1->setObjectName(Parameters::kStereoSGBMP1().c_str());
1621  _ui->stereosgbm_p2->setObjectName(Parameters::kStereoSGBMP2().c_str());
1622  _ui->stereosgbm_mode->setObjectName(Parameters::kStereoSGBMMode().c_str());
1623 
1624  // Aruco marker
1625  _ui->ArucoDictionary->setObjectName(Parameters::kMarkerDictionary().c_str());
1626  _ui->ArucoMarkerLength->setObjectName(Parameters::kMarkerLength().c_str());
1627  _ui->ArucoMaxDepthError->setObjectName(Parameters::kMarkerMaxDepthError().c_str());
1628  _ui->ArucoVarianceLinear->setObjectName(Parameters::kMarkerVarianceLinear().c_str());
1629  _ui->ArucoVarianceAngular->setObjectName(Parameters::kMarkerVarianceAngular().c_str());
1630  _ui->ArucoMarkerRangeMin->setObjectName(Parameters::kMarkerMinRange().c_str());
1631  _ui->ArucoMarkerRangeMax->setObjectName(Parameters::kMarkerMaxRange().c_str());
1632  _ui->ArucoMarkerPriors->setObjectName(Parameters::kMarkerPriors().c_str());
1633  _ui->ArucoPriorsVarianceLinear->setObjectName(Parameters::kMarkerPriorsVarianceLinear().c_str());
1634  _ui->ArucoPriorsVarianceAngular->setObjectName(Parameters::kMarkerPriorsVarianceAngular().c_str());
1635  _ui->ArucoCornerRefinementMethod->setObjectName(Parameters::kMarkerCornerRefinementMethod().c_str());
1636 
1637  // IMU filter
1638  _ui->doubleSpinBox_imuFilterMadgwickGain->setObjectName(Parameters::kImuFilterMadgwickGain().c_str());
1639  _ui->doubleSpinBox_imuFilterMadgwickZeta->setObjectName(Parameters::kImuFilterMadgwickZeta().c_str());
1640  _ui->doubleSpinBox_imuFilterComplementaryGainAcc->setObjectName(Parameters::kImuFilterComplementaryGainAcc().c_str());
1641  _ui->doubleSpinBox_imuFilterComplementaryBiasAlpha->setObjectName(Parameters::kImuFilterComplementaryBiasAlpha().c_str());
1642  _ui->checkBox_imuFilterComplementaryDoAdaptiveGain->setObjectName(Parameters::kImuFilterComplementaryDoAdpativeGain().c_str());
1643  _ui->checkBox_imuFilterComplementaryDoBiasEstimation->setObjectName(Parameters::kImuFilterComplementaryDoBiasEstimation().c_str());
1644 
1645  // reset default settings for the gui
1646  resetSettings(_ui->groupBox_generalSettingsGui0);
1647  resetSettings(_ui->groupBox_cloudRendering1);
1648  resetSettings(_ui->groupBox_filtering2);
1649  resetSettings(_ui->groupBox_gridMap2);
1650  resetSettings(_ui->groupBox_logging1);
1651  resetSettings(_ui->groupBox_source0);
1652 
1653  setupSignals();
1654  // custom signals
1655  connect(_ui->doubleSpinBox_kp_roi0, SIGNAL(valueChanged(double)), this, SLOT(updateKpROI()));
1656  connect(_ui->doubleSpinBox_kp_roi1, SIGNAL(valueChanged(double)), this, SLOT(updateKpROI()));
1657  connect(_ui->doubleSpinBox_kp_roi2, SIGNAL(valueChanged(double)), this, SLOT(updateKpROI()));
1658  connect(_ui->doubleSpinBox_kp_roi3, SIGNAL(valueChanged(double)), this, SLOT(updateKpROI()));
1659  connect(_ui->checkBox_useOdomFeatures, SIGNAL(toggled(bool)), this, SLOT(useOdomFeatures()));
1660 
1661  //Create a model from the stacked widgets
1662  // This will add all parameters to the parameters Map
1663  _ui->stackedWidget->setCurrentIndex(0);
1664  this->setupTreeView();
1665 
1667 
1670 }
1671 
1673  // remove tmp ini file
1674  QFile::remove(getTmpIniFilePath());
1675  delete _ui;
1676 }
1677 
1678 void PreferencesDialog::init(const QString & iniFilePath)
1679 {
1680  UDEBUG("");
1681  //First set all default values
1682  const ParametersMap & defaults = Parameters::getDefaultParameters();
1683  for(ParametersMap::const_iterator iter=defaults.begin(); iter!=defaults.end(); ++iter)
1684  {
1685  this->setParameter(iter->first, iter->second);
1686  }
1687 
1688  this->readSettings(iniFilePath);
1689 
1691 
1692  _initialized = true;
1693 }
1694 
1696 {
1697  QList<QGroupBox*> boxes = this->getGroupBoxes();
1698  for(int i =0;i<boxes.size();++i)
1699  {
1700  if(boxes[i] == _ui->groupBox_source0)
1701  {
1702  _ui->stackedWidget->setCurrentIndex(i);
1703  _ui->treeView->setCurrentIndex(_indexModel->index(i-2, 0));
1704  break;
1705  }
1706  }
1707 }
1708 
1710 {
1711  writeSettings();
1712 }
1713 
1715 {
1716  if(_indexModel)
1717  {
1718  _ui->treeView->setModel(0);
1719  delete _indexModel;
1720  }
1721  _indexModel = new QStandardItemModel(this);
1722  // Parse the model
1723  QList<QGroupBox*> boxes = this->getGroupBoxes();
1724  if(_ui->radioButton_basic->isChecked())
1725  {
1726  boxes = boxes.mid(0,7);
1727  }
1728  else // Advanced
1729  {
1730  boxes.removeAt(6);
1731  }
1732 
1733  QStandardItem * parentItem = _indexModel->invisibleRootItem();
1734  int index = 0;
1735  this->parseModel(boxes, parentItem, 0, index); // recursive method
1736  if(_ui->radioButton_advanced->isChecked() && index != _ui->stackedWidget->count()-1)
1737  {
1738  ULOGGER_ERROR("The tree model is not the same size of the stacked widgets...%d vs %d advanced stacks", index, _ui->stackedWidget->count()-1);
1739  }
1740  int currentIndex = _ui->stackedWidget->currentIndex();
1741  if(_ui->radioButton_basic->isChecked())
1742  {
1743  if(currentIndex >= 6)
1744  {
1745  _ui->stackedWidget->setCurrentIndex(6);
1746  currentIndex = 6;
1747  }
1748  }
1749  else // Advanced
1750  {
1751  if(currentIndex == 6)
1752  {
1753  _ui->stackedWidget->setCurrentIndex(7);
1754  }
1755  }
1756  _ui->treeView->setModel(_indexModel);
1757  _ui->treeView->expandToDepth(1);
1758 
1759  // should be after setModel()
1760  connect(_ui->treeView->selectionModel(), SIGNAL(currentChanged(const QModelIndex &, const QModelIndex &)), this, SLOT(clicked(const QModelIndex &, const QModelIndex &)));
1761 }
1762 
1763 // recursive...
1764 bool PreferencesDialog::parseModel(QList<QGroupBox*> & boxes, QStandardItem * parentItem, int currentLevel, int & absoluteIndex)
1765 {
1766  if(parentItem == 0)
1767  {
1768  ULOGGER_ERROR("Parent item is null !");
1769  return false;
1770  }
1771 
1772  QStandardItem * currentItem = 0;
1773  while(absoluteIndex < boxes.size())
1774  {
1775  QString objectName = boxes.at(absoluteIndex)->objectName();
1776  QString title = boxes.at(absoluteIndex)->title();
1777  bool ok = false;
1778  int lvl = QString(objectName.at(objectName.size()-1)).toInt(&ok);
1779  if(!ok)
1780  {
1781  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());
1782  return false;
1783  }
1784 
1785 
1786  if(lvl == currentLevel)
1787  {
1788  QStandardItem * item = new QStandardItem(title);
1789  item->setData(absoluteIndex);
1790  currentItem = item;
1791  //ULOGGER_DEBUG("PreferencesDialog::parseModel() lvl(%d) Added %s", currentLevel, title.toStdString().c_str());
1792  parentItem->appendRow(item);
1793  ++absoluteIndex;
1794  }
1795  else if(lvl > currentLevel)
1796  {
1797  if(lvl>currentLevel+1)
1798  {
1799  ULOGGER_ERROR("Intermediary lvl doesn't exist, lvl %d to %d, indexes %d and %d", currentLevel, lvl, absoluteIndex-1, absoluteIndex);
1800  return false;
1801  }
1802  else
1803  {
1804  parseModel(boxes, currentItem, currentLevel+1, absoluteIndex); // recursive
1805  }
1806  }
1807  else
1808  {
1809  return false;
1810  }
1811  }
1812  return true;
1813 }
1814 
1816 {
1818  for(rtabmap::ParametersMap::const_iterator iter=parameters.begin(); iter!=parameters.end(); ++iter)
1819  {
1820  QWidget * obj = _ui->stackedWidget->findChild<QWidget*>((*iter).first.c_str());
1821  if(obj)
1822  {
1823  // set tooltip as the parameter name
1824  obj->setToolTip(tr("%1 (Default=\"%2\")").arg(iter->first.c_str()).arg(iter->second.c_str()));
1825 
1826  QSpinBox * spin = qobject_cast<QSpinBox *>(obj);
1827  QDoubleSpinBox * doubleSpin = qobject_cast<QDoubleSpinBox *>(obj);
1828  QComboBox * combo = qobject_cast<QComboBox *>(obj);
1829  QCheckBox * check = qobject_cast<QCheckBox *>(obj);
1830  QRadioButton * radio = qobject_cast<QRadioButton *>(obj);
1831  QLineEdit * lineEdit = qobject_cast<QLineEdit *>(obj);
1832  QGroupBox * groupBox = qobject_cast<QGroupBox *>(obj);
1833  if(spin)
1834  {
1835  connect(spin, SIGNAL(valueChanged(int)), this, SLOT(addParameter(int)));
1836  }
1837  else if(doubleSpin)
1838  {
1839  connect(doubleSpin, SIGNAL(valueChanged(double)), this, SLOT(addParameter(double)));
1840  }
1841  else if(combo)
1842  {
1843  connect(combo, SIGNAL(currentIndexChanged(int)), this, SLOT(addParameter(int)));
1844  }
1845  else if(check)
1846  {
1847  connect(check, SIGNAL(toggled(bool)), this, SLOT(addParameter(bool)));
1848  }
1849  else if(radio)
1850  {
1851  connect(radio, SIGNAL(toggled(bool)), this, SLOT(addParameter(bool)));
1852  }
1853  else if(lineEdit)
1854  {
1855  connect(lineEdit, SIGNAL(textChanged(const QString &)), this, SLOT(addParameter(const QString &)));
1856  }
1857  else if(groupBox)
1858  {
1859  connect(groupBox, SIGNAL(toggled(bool)), this, SLOT(addParameter(bool)));
1860  }
1861  else
1862  {
1863  ULOGGER_WARN("QWidget called %s can't be cast to a supported widget", (*iter).first.c_str());
1864  }
1865  }
1866  else
1867  {
1868  ULOGGER_WARN("Can't find the related QWidget for parameter %s", (*iter).first.c_str());
1869  }
1870  }
1871 }
1872 
1873 void PreferencesDialog::clicked(const QModelIndex & current, const QModelIndex & previous)
1874  {
1875  QStandardItem * item = _indexModel->itemFromIndex(current);
1876  if(item && item->isEnabled())
1877  {
1878  int index = item->data().toInt();
1879  if(_ui->radioButton_advanced->isChecked() && index >= 6)
1880  {
1881  ++index;
1882  }
1883  _ui->stackedWidget->setCurrentIndex(index);
1884  _ui->scrollArea->horizontalScrollBar()->setValue(0);
1885  _ui->scrollArea->verticalScrollBar()->setValue(0);
1886  }
1887  }
1888 
1889 void PreferencesDialog::closeEvent(QCloseEvent *event)
1890 {
1891  UDEBUG("");
1892  _modifiedParameters.clear();
1896  event->accept();
1897 }
1898 
1899 void PreferencesDialog::closeDialog ( QAbstractButton * button )
1900 {
1901  UDEBUG("");
1902 
1903  QDialogButtonBox::ButtonRole role = _ui->buttonBox_global->buttonRole(button);
1904  switch(role)
1905  {
1906  case QDialogButtonBox::RejectRole:
1907  _modifiedParameters.clear();
1911  this->reject();
1912  break;
1913 
1914  case QDialogButtonBox::AcceptRole:
1915  updateBasicParameter();// make that changes without editing finished signal are updated.
1917  {
1918  if(validateForm())
1919  {
1921  this->accept();
1922  }
1923  }
1924  else
1925  {
1926  this->accept();
1927  }
1928  break;
1929 
1930  default:
1931  break;
1932  }
1933 }
1934 
1935 void PreferencesDialog::resetApply ( QAbstractButton * button )
1936 {
1937  QDialogButtonBox::ButtonRole role = _ui->buttonBox_local->buttonRole(button);
1938  switch(role)
1939  {
1940  case QDialogButtonBox::ApplyRole:
1941  updateBasicParameter();// make that changes without editing finished signal are updated.
1942  if(validateForm())
1943  {
1945  }
1946  break;
1947 
1948  case QDialogButtonBox::ResetRole:
1949  resetSettings(_ui->stackedWidget->currentIndex());
1950  break;
1951 
1952  default:
1953  break;
1954  }
1955 }
1956 
1957 void PreferencesDialog::resetSettings(QGroupBox * groupBox)
1958 {
1959  if(groupBox->objectName() == _ui->groupBox_generalSettingsGui0->objectName())
1960  {
1961  _ui->general_checkBox_imagesKept->setChecked(true);
1962  _ui->general_checkBox_missing_cache_republished->setChecked(true);
1963  _ui->general_checkBox_cloudsKept->setChecked(true);
1964  _ui->checkBox_beep->setChecked(false);
1965  _ui->checkBox_stamps->setChecked(true);
1966  _ui->checkBox_cacheStatistics->setChecked(true);
1967  _ui->checkBox_notifyWhenNewGlobalPathIsReceived->setChecked(false);
1968  _ui->checkBox_verticalLayoutUsed->setChecked(true);
1969  _ui->checkBox_imageRejectedShown->setChecked(true);
1970  _ui->checkBox_imageHighestHypShown->setChecked(false);
1971  _ui->spinBox_odomQualityWarnThr->setValue(50);
1972  _ui->checkBox_odom_onlyInliersShown->setChecked(false);
1973  _ui->radioButton_posteriorGraphView->setChecked(true);
1974  _ui->radioButton_wordsGraphView->setChecked(false);
1975  _ui->radioButton_localizationsGraphView->setChecked(false);
1976  _ui->radioButton_localizationsGraphViewOdomCache->setChecked(false);
1977  _ui->radioButton_nochangeGraphView->setChecked(false);
1978  _ui->checkbox_odomDisabled->setChecked(false);
1979  _ui->checkbox_groundTruthAlign->setChecked(true);
1980  }
1981  else if(groupBox->objectName() == _ui->groupBox_cloudRendering1->objectName())
1982  {
1983  for(int i=0; i<2; ++i)
1984  {
1985  _3dRenderingShowClouds[i]->setChecked(true);
1986  _3dRenderingDecimation[i]->setValue(4);
1987  _3dRenderingMaxDepth[i]->setValue(0.0);
1988  _3dRenderingMinDepth[i]->setValue(0.0);
1989  _3dRenderingRoiRatios[i]->setText("0.0 0.0 0.0 0.0");
1990  _3dRenderingShowScans[i]->setChecked(true);
1991  _3dRenderingShowFeatures[i]->setChecked(i==0?false:true);
1992  _3dRenderingShowFrustums[i]->setChecked(false);
1993 
1994  _3dRenderingDownsamplingScan[i]->setValue(1);
1995  _3dRenderingMaxRange[i]->setValue(0.0);
1996  _3dRenderingMinRange[i]->setValue(0.0);
1997  _3dRenderingVoxelSizeScan[i]->setValue(0.0);
1998  _3dRenderingColorScheme[i]->setValue(0);
1999  _3dRenderingOpacity[i]->setValue(i==0?1.0:0.75);
2000  _3dRenderingPtSize[i]->setValue(i==0?1:2);
2001  _3dRenderingColorSchemeScan[i]->setValue(0);
2002  _3dRenderingOpacityScan[i]->setValue(i==0?1.0:0.5);
2003  _3dRenderingPtSizeScan[i]->setValue(i==0?1:2);
2004  _3dRenderingPtSizeFeatures[i]->setValue(3);
2005  _3dRenderingGravity[i]->setChecked(false);
2006  _3dRenderingGravityLength[i]->setValue(1);
2007  }
2008  _ui->doubleSpinBox_voxel->setValue(0);
2009  _ui->doubleSpinBox_noiseRadius->setValue(0);
2010  _ui->spinBox_noiseMinNeighbors->setValue(5);
2011 
2012  _ui->doubleSpinBox_ceilingFilterHeight->setValue(0);
2013  _ui->doubleSpinBox_floorFilterHeight->setValue(0);
2014  _ui->spinBox_normalKSearch->setValue(10);
2015  _ui->doubleSpinBox_normalRadiusSearch->setValue(0.0);
2016 
2017  _ui->doubleSpinBox_ceilingFilterHeight_scan->setValue(0);
2018  _ui->doubleSpinBox_floorFilterHeight_scan->setValue(0);
2019  _ui->spinBox_normalKSearch_scan->setValue(0);
2020  _ui->doubleSpinBox_normalRadiusSearch_scan->setValue(0.0);
2021 
2022  _ui->checkBox_showGraphs->setChecked(true);
2023  _ui->checkBox_showLabels->setChecked(false);
2024  _ui->checkBox_showFrames->setChecked(false);
2025  _ui->checkBox_showLandmarks->setChecked(true);
2026  _ui->doubleSpinBox_landmarkSize->setValue(0);
2027  _ui->checkBox_showIMUGravity->setChecked(false);
2028  _ui->checkBox_showIMUAcc->setChecked(false);
2029 
2030  _ui->doubleSpinBox_mesh_angleTolerance->setValue(15.0);
2031  _ui->groupBox_organized->setChecked(false);
2032 #if PCL_VERSION_COMPARE(>=, 1, 7, 2)
2033  _ui->checkBox_mesh_quad->setChecked(true);
2034 #else
2035  _ui->checkBox_mesh_quad->setChecked(false);
2036 #endif
2037  _ui->checkBox_mesh_texture->setChecked(false);
2038  _ui->spinBox_mesh_triangleSize->setValue(2);
2039  }
2040  else if(groupBox->objectName() == _ui->groupBox_filtering2->objectName())
2041  {
2042  _ui->radioButton_noFiltering->setChecked(true);
2043  _ui->radioButton_nodeFiltering->setChecked(false);
2044  _ui->radioButton_subtractFiltering->setChecked(false);
2045  _ui->doubleSpinBox_cloudFilterRadius->setValue(0.1);
2046  _ui->doubleSpinBox_cloudFilterAngle->setValue(30);
2047  _ui->spinBox_subtractFilteringMinPts->setValue(5);
2048  _ui->doubleSpinBox_subtractFilteringRadius->setValue(0.02);
2049  _ui->doubleSpinBox_subtractFilteringAngle->setValue(0);
2050  }
2051  else if(groupBox->objectName() == _ui->groupBox_gridMap2->objectName())
2052  {
2053  _ui->doubleSpinBox_map_resolution->setValue(0);
2054  _ui->checkBox_map_shown->setChecked(false);
2055  _ui->doubleSpinBox_map_opacity->setValue(0.75);
2056  _ui->checkBox_elevation_shown->setCheckState(Qt::Unchecked);
2057 
2058  _ui->groupBox_octomap->setChecked(false);
2059  _ui->spinBox_octomap_treeDepth->setValue(16);
2060  _ui->checkBox_octomap_2dgrid->setChecked(true);
2061  _ui->checkBox_octomap_show3dMap->setChecked(true);
2062  _ui->comboBox_octomap_renderingType->setCurrentIndex(0);
2063  _ui->spinBox_octomap_pointSize->setValue(5);
2064  }
2065  else if(groupBox->objectName() == _ui->groupBox_logging1->objectName())
2066  {
2067  _ui->comboBox_loggerLevel->setCurrentIndex(2);
2068  _ui->comboBox_loggerEventLevel->setCurrentIndex(3);
2069  _ui->comboBox_loggerPauseLevel->setCurrentIndex(3);
2070  _ui->checkBox_logger_printTime->setChecked(true);
2071  _ui->checkBox_logger_printThreadId->setChecked(false);
2072  _ui->comboBox_loggerType->setCurrentIndex(1);
2073  for(int i=0; i<_ui->comboBox_loggerFilter->count(); ++i)
2074  {
2075  _ui->comboBox_loggerFilter->setItemChecked(i, false);
2076  }
2077  }
2078  else if(groupBox->objectName() == _ui->groupBox_source0->objectName())
2079  {
2080  _ui->general_doubleSpinBox_imgRate->setValue(0.0);
2081  _ui->source_mirroring->setChecked(false);
2082  _ui->lineEdit_calibrationFile->clear();
2083  _ui->comboBox_sourceType->setCurrentIndex(kSrcRGBD);
2084  _ui->lineEdit_sourceDevice->setText("");
2085  _ui->lineEdit_sourceLocalTransform->setText("0 0 0 0 0 0");
2086 
2087  _ui->source_comboBox_image_type->setCurrentIndex(kSrcUsbDevice-kSrcUsbDevice);
2088  _ui->source_images_spinBox_startPos->setValue(0);
2089  _ui->source_images_spinBox_maxFrames->setValue(0);
2090  _ui->spinBox_usbcam_streamWidth->setValue(0);
2091  _ui->spinBox_usbcam_streamHeight->setValue(0);
2092  _ui->checkBox_rgb_rectify->setChecked(false);
2093  _ui->comboBox_cameraImages_bayerMode->setCurrentIndex(0);
2094 
2095  _ui->source_checkBox_ignoreOdometry->setChecked(false);
2096  _ui->source_checkBox_ignoreGoalDelay->setChecked(true);
2097  _ui->source_checkBox_ignoreGoals->setChecked(true);
2098  _ui->source_checkBox_ignoreLandmarks->setChecked(true);
2099  _ui->source_checkBox_ignoreFeatures->setChecked(true);
2100  _ui->source_checkBox_ignorePriors->setChecked(false);
2101  _ui->source_spinBox_databaseStartId->setValue(0);
2102  _ui->source_spinBox_databaseStopId->setValue(0);
2103  _ui->source_spinBox_database_cameraIndex->setValue(-1);
2104  _ui->source_checkBox_useDbStamps->setChecked(true);
2105 
2106 #ifdef _WIN32
2107  _ui->comboBox_cameraRGBD->setCurrentIndex(kSrcOpenNI2-kSrcRGBD); // openni2
2108 #else
2110  {
2111  _ui->comboBox_cameraRGBD->setCurrentIndex(kSrcFreenect-kSrcRGBD); // freenect
2112  }
2113  else if(CameraOpenNI2::available())
2114  {
2115  _ui->comboBox_cameraRGBD->setCurrentIndex(kSrcOpenNI2-kSrcRGBD); // openni2
2116  }
2117  else
2118  {
2119  _ui->comboBox_cameraRGBD->setCurrentIndex(kSrcOpenNI_PCL-kSrcRGBD); // openni-pcl
2120  }
2121 #endif
2123  {
2124  _ui->comboBox_cameraStereo->setCurrentIndex(kSrcDC1394-kSrcStereo); // dc1394
2125  }
2127  {
2128  _ui->comboBox_cameraStereo->setCurrentIndex(kSrcFlyCapture2-kSrcStereo); // flycapture
2129  }
2130  else
2131  {
2132  _ui->comboBox_cameraStereo->setCurrentIndex(kSrcStereoImages-kSrcStereo); // stereo images
2133  }
2134 
2135  _ui->checkbox_rgbd_colorOnly->setChecked(false);
2136  _ui->spinBox_source_imageDecimation->setValue(1);
2137  _ui->comboBox_source_histogramMethod->setCurrentIndex(0);
2138  _ui->checkbox_source_feature_detection->setChecked(false);
2139  _ui->checkbox_stereo_depthGenerated->setChecked(false);
2140  _ui->checkBox_stereo_exposureCompensation->setChecked(false);
2141  _ui->openni2_autoWhiteBalance->setChecked(true);
2142  _ui->openni2_autoExposure->setChecked(true);
2143  _ui->openni2_exposure->setValue(0);
2144  _ui->openni2_gain->setValue(100);
2145  _ui->openni2_mirroring->setChecked(false);
2146  _ui->openni2_stampsIdsUsed->setChecked(false);
2147  _ui->openni2_hshift->setValue(0);
2148  _ui->openni2_vshift->setValue(0);
2149  _ui->openni2_depth_decimation->setValue(1);
2150  _ui->comboBox_freenect2Format->setCurrentIndex(1);
2151  _ui->doubleSpinBox_freenect2MinDepth->setValue(0.3);
2152  _ui->doubleSpinBox_freenect2MaxDepth->setValue(12.0);
2153  _ui->checkBox_freenect2BilateralFiltering->setChecked(true);
2154  _ui->checkBox_freenect2EdgeAwareFiltering->setChecked(true);
2155  _ui->checkBox_freenect2NoiseFiltering->setChecked(true);
2156  _ui->lineEdit_freenect2Pipeline->setText("");
2157  _ui->comboBox_k4w2Format->setCurrentIndex(1);
2158  _ui->comboBox_realsensePresetRGB->setCurrentIndex(0);
2159  _ui->comboBox_realsensePresetDepth->setCurrentIndex(2);
2160  _ui->checkbox_realsenseOdom->setChecked(false);
2161  _ui->checkbox_realsenseDepthScaledToRGBSize->setChecked(false);
2162  _ui->comboBox_realsenseRGBSource->setCurrentIndex(0);
2163  _ui->checkbox_rs2_emitter->setChecked(true);
2164  _ui->checkbox_rs2_irMode->setChecked(false);
2165  _ui->checkbox_rs2_irDepth->setChecked(true);
2166  _ui->spinBox_rs2_width->setValue(848);
2167  _ui->spinBox_rs2_height->setValue(480);
2168  _ui->spinBox_rs2_rate->setValue(60);
2169  _ui->spinBox_rs2_width_depth->setValue(640);
2170  _ui->spinBox_rs2_height_depth->setValue(480);
2171  _ui->spinBox_rs2_rate_depth->setValue(30);
2172  _ui->checkbox_rs2_globalTimeStync->setChecked(true);
2173  _ui->lineEdit_rs2_jsonFile->clear();
2174  _ui->lineEdit_openniOniPath->clear();
2175  _ui->lineEdit_openni2OniPath->clear();
2176  _ui->comboBox_k4a_rgb_resolution->setCurrentIndex(0);
2177  _ui->comboBox_k4a_framerate->setCurrentIndex(2);
2178  _ui->comboBox_k4a_depth_resolution->setCurrentIndex(2);
2179  _ui->checkbox_k4a_irDepth->setChecked(false);
2180  _ui->lineEdit_k4a_mkv->clear();
2181  _ui->source_checkBox_useMKVStamps->setChecked(true);
2182  _ui->lineEdit_cameraRGBDImages_path_rgb->setText("");
2183  _ui->lineEdit_cameraRGBDImages_path_depth->setText("");
2184  _ui->doubleSpinBox_cameraRGBDImages_scale->setValue(1.0);
2185  _ui->spinBox_cameraRGBDImages_startIndex->setValue(0);
2186  _ui->spinBox_cameraRGBDImages_maxFrames->setValue(0);
2187  _ui->lineEdit_source_distortionModel->setText("");
2188  _ui->groupBox_bilateral->setChecked(false);
2189  _ui->doubleSpinBox_bilateral_sigmaS->setValue(10.0);
2190  _ui->doubleSpinBox_bilateral_sigmaR->setValue(0.1);
2191 
2192  _ui->source_comboBox_image_type->setCurrentIndex(kSrcDC1394-kSrcDC1394);
2193  _ui->lineEdit_cameraStereoImages_path_left->setText("");
2194  _ui->lineEdit_cameraStereoImages_path_right->setText("");
2195  _ui->checkBox_stereo_rectify->setChecked(false);
2196  _ui->spinBox_cameraStereoImages_startIndex->setValue(0);
2197  _ui->spinBox_cameraStereoImages_maxFrames->setValue(0);
2198  _ui->lineEdit_cameraStereoVideo_path->setText("");
2199  _ui->lineEdit_cameraStereoVideo_path_2->setText("");
2200  _ui->spinBox_stereo_right_device->setValue(-1);
2201  _ui->spinBox_stereousbcam_streamWidth->setValue(0);
2202  _ui->spinBox_stereousbcam_streamHeight->setValue(0);
2203  _ui->comboBox_stereoZed_resolution->setCurrentIndex(CameraStereoZed::sdkVersion()<4?3:6);
2204  _ui->comboBox_stereoZed_quality->setCurrentIndex(1);
2205  _ui->checkbox_stereoZed_selfCalibration->setChecked(true);
2206  _ui->comboBox_stereoZed_sensingMode->setCurrentIndex(0);
2207  _ui->spinBox_stereoZed_confidenceThr->setValue(100);
2208  _ui->spinBox_stereoZed_texturenessConfidenceThr->setValue(90);
2209  _ui->lineEdit_zedSvoPath->clear();
2210  _ui->comboBox_stereoZedOC_resolution->setCurrentIndex(3);
2211  _ui->checkbox_stereoMyntEye_rectify->setChecked(false);
2212  _ui->checkbox_stereoMyntEye_depth->setChecked(false);
2213  _ui->checkbox_stereoMyntEye_autoExposure->setChecked(true);
2214  _ui->spinBox_stereoMyntEye_gain->setValue(24);
2215  _ui->spinBox_stereoMyntEye_brightness->setValue(120);
2216  _ui->spinBox_stereoMyntEye_contrast->setValue(116);
2217  _ui->spinBox_stereoMyntEye_irControl->setValue(0);
2218  _ui->comboBox_depthai_resolution->setCurrentIndex(1);
2219  _ui->comboBox_depthai_output_mode->setCurrentIndex(0);
2220  _ui->spinBox_depthai_conf_threshold->setValue(200);
2221  _ui->checkBox_depthai_extended_disparity->setChecked(false);
2222  _ui->comboBox_depthai_subpixel_fractional_bits->setCurrentIndex(2);
2223  _ui->comboBox_depthai_disparity_companding->setCurrentIndex(1);
2224  _ui->spinBox_depthai_lrc_threshold->setValue(5);
2225  _ui->checkBox_depthai_use_spec_translation->setChecked(false);
2226  _ui->doubleSpinBox_depthai_alpha_scaling->setValue(-1);
2227  _ui->checkBox_depthai_imu_published->setChecked(true);
2228  _ui->doubleSpinBox_depthai_dot_intensity->setValue(0.0);
2229  _ui->doubleSpinBox_depthai_flood_intensity->setValue(0.0);
2230  _ui->comboBox_depthai_detect_features->setCurrentIndex(0);
2231  _ui->lineEdit_depthai_blob_path->clear();
2232 
2233  _ui->checkBox_cameraImages_configForEachFrame->setChecked(false);
2234  _ui->checkBox_cameraImages_timestamps->setChecked(false);
2235  _ui->checkBox_cameraImages_syncTimeStamps->setChecked(true);
2236  _ui->lineEdit_cameraImages_timestamps->setText("");
2237  _ui->lineEdit_cameraImages_path_scans->setText("");
2238  _ui->lineEdit_cameraImages_laser_transform->setText("0 0 0 0 0 0");
2239  _ui->spinBox_cameraImages_max_scan_pts->setValue(0);
2240  _ui->lineEdit_cameraImages_odom->setText("");
2241  _ui->comboBox_cameraImages_odomFormat->setCurrentIndex(0);
2242  _ui->lineEdit_cameraImages_gt->setText("");
2243  _ui->comboBox_cameraImages_gtFormat->setCurrentIndex(0);
2244  _ui->doubleSpinBox_maxPoseTimeDiff->setValue(0.02);
2245  _ui->lineEdit_cameraImages_path_imu->setText("");
2246  _ui->lineEdit_cameraImages_imu_transform->setText("0 0 1 0 -1 0 1 0 0");
2247  _ui->spinBox_cameraImages_max_imu_rate->setValue(0);
2248 
2249  _ui->comboBox_odom_sensor->setCurrentIndex(0);
2250  _ui->lineEdit_odom_sensor_extrinsics->setText("-0.000622602 0.0303752 0.031389 -0.00272485 0.00749254 0.0");
2251  _ui->lineEdit_odom_sensor_path_calibration->setText("");
2252  _ui->lineEdit_odomSourceDevice->setText("");
2253  _ui->doubleSpinBox_odom_sensor_time_offset->setValue(0.0);
2254  _ui->doubleSpinBox_odom_sensor_scale_factor->setValue(1);
2255  _ui->doubleSpinBox_odom_sensor_wait_time->setValue(100);
2256  _ui->checkBox_odom_sensor_use_as_gt->setChecked(false);
2257 
2258  _ui->comboBox_imuFilter_strategy->setCurrentIndex(2);
2259  _ui->doubleSpinBox_imuFilterMadgwickGain->setValue(Parameters::defaultImuFilterMadgwickGain());
2260  _ui->doubleSpinBox_imuFilterMadgwickZeta->setValue(Parameters::defaultImuFilterMadgwickZeta());
2261  _ui->doubleSpinBox_imuFilterComplementaryGainAcc->setValue(Parameters::defaultImuFilterComplementaryGainAcc());
2262  _ui->doubleSpinBox_imuFilterComplementaryBiasAlpha->setValue(Parameters::defaultImuFilterComplementaryBiasAlpha());
2263  _ui->checkBox_imuFilterComplementaryDoAdaptiveGain->setChecked(Parameters::defaultImuFilterComplementaryDoAdpativeGain());
2264  _ui->checkBox_imuFilterComplementaryDoBiasEstimation->setChecked(Parameters::defaultImuFilterComplementaryDoBiasEstimation());
2265  _ui->checkBox_imuFilter_baseFrameConversion->setChecked(true);
2266  _ui->checkbox_publishInterIMU->setChecked(false);
2267 
2268  _ui->comboBox_lidar_src->setCurrentIndex(0);
2269  _ui->checkBox_source_scanDeskewing->setChecked(false);
2270  _ui->checkBox_source_scanFromDepth->setChecked(false);
2271  _ui->spinBox_source_scanDownsampleStep->setValue(1);
2272  _ui->doubleSpinBox_source_scanRangeMin->setValue(0);
2273  _ui->doubleSpinBox_source_scanRangeMax->setValue(0);
2274  _ui->doubleSpinBox_source_scanVoxelSize->setValue(0.0f);
2275  _ui->spinBox_source_scanNormalsK->setValue(0);
2276  _ui->doubleSpinBox_source_scanNormalsRadius->setValue(0.0);
2277  _ui->doubleSpinBox_source_scanNormalsForceGroundUp->setValue(0);
2278 
2279  _ui->lineEdit_lidar_local_transform->setText("0 0 0 0 0 0");
2280  _ui->lineEdit_vlp16_pcap_path->clear();
2281  _ui->spinBox_vlp16_ip1->setValue(192);
2282  _ui->spinBox_vlp16_ip2->setValue(168);
2283  _ui->spinBox_vlp16_ip3->setValue(1);
2284  _ui->spinBox_vlp16_ip4->setValue(201);
2285  _ui->spinBox_vlp16_port->setValue(2368);
2286  _ui->checkBox_vlp16_organized->setChecked(false);
2287  _ui->checkBox_vlp16_hostTime->setChecked(true);
2288  _ui->checkBox_vlp16_stamp_last->setChecked(true);
2289 
2290  _ui->groupBox_depthFromScan->setChecked(false);
2291  _ui->groupBox_depthFromScan_fillHoles->setChecked(true);
2292  _ui->radioButton_depthFromScan_vertical->setChecked(true);
2293  _ui->radioButton_depthFromScan_horizontal->setChecked(false);
2294  _ui->checkBox_depthFromScan_fillBorders->setChecked(false);
2295  }
2296  else if(groupBox->objectName() == _ui->groupBox_rtabmap_basic0->objectName())
2297  {
2298  _ui->general_doubleSpinBox_timeThr_2->setValue(Parameters::defaultRtabmapTimeThr());
2299  _ui->general_doubleSpinBox_hardThr_2->setValue(Parameters::defaultRtabmapLoopThr());
2300  _ui->doubleSpinBox_similarityThreshold_2->setValue(Parameters::defaultMemRehearsalSimilarity());
2301  _ui->general_spinBox_imagesBufferSize_2->setValue(Parameters::defaultRtabmapImageBufferSize());
2302  _ui->general_spinBox_maxStMemSize_2->setValue(Parameters::defaultMemSTMSize());
2303  _ui->general_checkBox_publishStats_2->setChecked(Parameters::defaultRtabmapPublishStats());
2304  _ui->general_checkBox_activateRGBD_2->setChecked(Parameters::defaultRGBDEnabled());
2305  _ui->general_checkBox_SLAM_mode_2->setChecked(Parameters::defaultMemIncrementalMemory());
2306  _ui->general_doubleSpinBox_detectionRate_2->setValue(Parameters::defaultRtabmapDetectionRate());
2307  // match the advanced (spin and doubleSpin boxes)
2308  _ui->general_doubleSpinBox_timeThr->setValue(Parameters::defaultRtabmapTimeThr());
2309  _ui->general_doubleSpinBox_hardThr->setValue(Parameters::defaultRtabmapLoopThr());
2310  _ui->doubleSpinBox_similarityThreshold->setValue(Parameters::defaultMemRehearsalSimilarity());
2311  _ui->general_spinBox_imagesBufferSize->setValue(Parameters::defaultRtabmapImageBufferSize());
2312  _ui->general_spinBox_maxStMemSize->setValue(Parameters::defaultMemSTMSize());
2313  _ui->general_doubleSpinBox_detectionRate->setValue(Parameters::defaultRtabmapDetectionRate());
2314  }
2315  else
2316  {
2317  QObjectList children = groupBox->children();
2319  std::string key;
2320  for(int i=0; i<children.size(); ++i)
2321  {
2322  key = children.at(i)->objectName().toStdString();
2323  if(uContains(defaults, key))
2324  {
2325  if(key.compare(Parameters::kRtabmapWorkingDirectory().c_str()) == 0)
2326  {
2327  this->setParameter(key, getDefaultWorkingDirectory().toStdString());
2328  }
2329  else
2330  {
2331  this->setParameter(key, defaults.at(key));
2332  }
2333  if(qobject_cast<const QGroupBox*>(children.at(i)))
2334  {
2335  this->resetSettings((QGroupBox*)children.at(i));
2336  }
2337  }
2338  else if(qobject_cast<const QGroupBox*>(children.at(i)))
2339  {
2340  this->resetSettings((QGroupBox*)children.at(i));
2341  }
2342  else if(qobject_cast<const QStackedWidget*>(children.at(i)))
2343  {
2344  QStackedWidget * stackedWidget = (QStackedWidget*)children.at(i);
2345  for(int j=0; j<stackedWidget->count(); ++j)
2346  {
2347  const QObjectList & children2 = stackedWidget->widget(j)->children();
2348  for(int k=0; k<children2.size(); ++k)
2349  {
2350  if(qobject_cast<QGroupBox *>(children2.at(k)))
2351  {
2352  this->resetSettings((QGroupBox*)children2.at(k));
2353  }
2354  }
2355  }
2356  }
2357  }
2358 
2359  if(groupBox->findChild<QLineEdit*>(_ui->lineEdit_kp_roi->objectName()))
2360  {
2361  this->setupKpRoiPanel();
2362  }
2363 
2364  if(groupBox->objectName() == _ui->groupBox_odometry1->objectName())
2365  {
2366  _ui->odom_registration->setCurrentIndex(3);
2367  _ui->odom_f2m_gravitySigma->setValue(-1);
2368  }
2369  }
2370 }
2371 
2373 {
2374  QList<QGroupBox*> boxes = this->getGroupBoxes();
2375  if(panelNumber >= 0 && panelNumber < boxes.size())
2376  {
2377  this->resetSettings(boxes.at(panelNumber));
2378  }
2379  else if(panelNumber == -1)
2380  {
2381  for(QList<QGroupBox*>::iterator iter = boxes.begin(); iter!=boxes.end(); ++iter)
2382  {
2383  this->resetSettings(*iter);
2384  }
2385  }
2386  else
2387  {
2388  ULOGGER_WARN("panel number and the number of stacked widget doesn't match");
2389  }
2390 
2391 }
2392 
2394 {
2395  return _ui->lineEdit_workingDirectory->text();
2396 }
2397 
2399 {
2400  QString privatePath = QDir::homePath() + "/.rtabmap";
2401  if(!QDir(privatePath).exists())
2402  {
2403  QDir::home().mkdir(".rtabmap");
2404  }
2405  return privatePath + "/rtabmap.ini";
2406 }
2407 
2409 {
2410  return getIniFilePath()+".tmp";
2411 }
2412 
2414 {
2415  QString path = QFileDialog::getOpenFileName(this, tr("Load settings..."), this->getWorkingDirectory(), "*.ini");
2416  if(!path.isEmpty())
2417  {
2418  this->readSettings(path);
2419  }
2420 }
2421 
2422 void PreferencesDialog::readSettings(const QString & filePath)
2423 {
2424  ULOGGER_DEBUG("%s", filePath.toStdString().c_str());
2425  readGuiSettings(filePath);
2426  readCameraSettings(filePath);
2427  if(!readCoreSettings(filePath))
2428  {
2429  _modifiedParameters.clear();
2431 
2432  // only keep GUI settings
2433  QStandardItem * parentItem = _indexModel->invisibleRootItem();
2434  if(parentItem)
2435  {
2436  for(int i=1; i<parentItem->rowCount(); ++i)
2437  {
2438  parentItem->child(i)->setEnabled(false);
2439  }
2440  }
2441  _ui->radioButton_basic->setEnabled(false);
2442  _ui->radioButton_advanced->setEnabled(false);
2443  }
2444  else
2445  {
2446  // enable settings
2447  QStandardItem * parentItem = _indexModel->invisibleRootItem();
2448  if(parentItem)
2449  {
2450  for(int i=0; i<parentItem->rowCount(); ++i)
2451  {
2452  parentItem->child(i)->setEnabled(true);
2453  }
2454  }
2455  _ui->radioButton_basic->setEnabled(true);
2456  _ui->radioButton_advanced->setEnabled(true);
2457  }
2458 }
2459 
2460 void PreferencesDialog::readGuiSettings(const QString & filePath)
2461 {
2462  QString path = getIniFilePath();
2463  if(!filePath.isEmpty())
2464  {
2465  path = filePath;
2466  }
2467  QSettings settings(path, QSettings::IniFormat);
2468  settings.beginGroup("Gui");
2469  settings.beginGroup("General");
2470  _ui->general_checkBox_imagesKept->setChecked(settings.value("imagesKept", _ui->general_checkBox_imagesKept->isChecked()).toBool());
2471  _ui->general_checkBox_missing_cache_republished->setChecked(settings.value("missingRepublished", _ui->general_checkBox_missing_cache_republished->isChecked()).toBool());
2472  _ui->general_checkBox_cloudsKept->setChecked(settings.value("cloudsKept", _ui->general_checkBox_cloudsKept->isChecked()).toBool());
2473  _ui->comboBox_loggerLevel->setCurrentIndex(settings.value("loggerLevel", _ui->comboBox_loggerLevel->currentIndex()).toInt());
2474  _ui->comboBox_loggerEventLevel->setCurrentIndex(settings.value("loggerEventLevel", _ui->comboBox_loggerEventLevel->currentIndex()).toInt());
2475  _ui->comboBox_loggerPauseLevel->setCurrentIndex(settings.value("loggerPauseLevel", _ui->comboBox_loggerPauseLevel->currentIndex()).toInt());
2476  _ui->comboBox_loggerType->setCurrentIndex(settings.value("loggerType", _ui->comboBox_loggerType->currentIndex()).toInt());
2477  _ui->checkBox_logger_printTime->setChecked(settings.value("loggerPrintTime", _ui->checkBox_logger_printTime->isChecked()).toBool());
2478  _ui->checkBox_logger_printThreadId->setChecked(settings.value("loggerPrintThreadId", _ui->checkBox_logger_printThreadId->isChecked()).toBool());
2479  _ui->checkBox_verticalLayoutUsed->setChecked(settings.value("verticalLayoutUsed", _ui->checkBox_verticalLayoutUsed->isChecked()).toBool());
2480  _ui->checkBox_imageRejectedShown->setChecked(settings.value("imageRejectedShown", _ui->checkBox_imageRejectedShown->isChecked()).toBool());
2481  _ui->checkBox_imageHighestHypShown->setChecked(settings.value("imageHighestHypShown", _ui->checkBox_imageHighestHypShown->isChecked()).toBool());
2482  _ui->checkBox_beep->setChecked(settings.value("beep", _ui->checkBox_beep->isChecked()).toBool());
2483  _ui->checkBox_stamps->setChecked(settings.value("figure_time", _ui->checkBox_stamps->isChecked()).toBool());
2484  _ui->checkBox_cacheStatistics->setChecked(settings.value("figure_cache", _ui->checkBox_cacheStatistics->isChecked()).toBool());
2485  _ui->checkBox_notifyWhenNewGlobalPathIsReceived->setChecked(settings.value("notifyNewGlobalPath", _ui->checkBox_notifyWhenNewGlobalPathIsReceived->isChecked()).toBool());
2486  _ui->spinBox_odomQualityWarnThr->setValue(settings.value("odomQualityThr", _ui->spinBox_odomQualityWarnThr->value()).toInt());
2487  _ui->checkBox_odom_onlyInliersShown->setChecked(settings.value("odomOnlyInliersShown", _ui->checkBox_odom_onlyInliersShown->isChecked()).toBool());
2488  _ui->radioButton_posteriorGraphView->setChecked(settings.value("posteriorGraphView", _ui->radioButton_posteriorGraphView->isChecked()).toBool());
2489  _ui->radioButton_wordsGraphView->setChecked(settings.value("wordsGraphView", _ui->radioButton_wordsGraphView->isChecked()).toBool());
2490  _ui->radioButton_localizationsGraphView->setChecked(settings.value("localizationsGraphView", _ui->radioButton_localizationsGraphView->isChecked()).toBool());
2491  _ui->radioButton_localizationsGraphViewOdomCache->setChecked(settings.value("localizationsGraphViewOdomCache", _ui->radioButton_localizationsGraphViewOdomCache->isChecked()).toBool());
2492  _ui->radioButton_nochangeGraphView->setChecked(settings.value("nochangeGraphView", _ui->radioButton_nochangeGraphView->isChecked()).toBool());
2493  _ui->checkbox_odomDisabled->setChecked(settings.value("odomDisabled", _ui->checkbox_odomDisabled->isChecked()).toBool());
2494  _ui->odom_registration->setCurrentIndex(settings.value("odomRegistration", _ui->odom_registration->currentIndex()).toInt());
2495  _ui->odom_f2m_gravitySigma->setValue(settings.value("odomF2MGravitySigma", _ui->odom_f2m_gravitySigma->value()).toDouble());
2496  _ui->checkbox_groundTruthAlign->setChecked(settings.value("gtAlign", _ui->checkbox_groundTruthAlign->isChecked()).toBool());
2497 
2498  for(int i=0; i<2; ++i)
2499  {
2500  _3dRenderingShowClouds[i]->setChecked(settings.value(QString("showClouds%1").arg(i), _3dRenderingShowClouds[i]->isChecked()).toBool());
2501  _3dRenderingDecimation[i]->setValue(settings.value(QString("decimation%1").arg(i), _3dRenderingDecimation[i]->value()).toInt());
2502  _3dRenderingMaxDepth[i]->setValue(settings.value(QString("maxDepth%1").arg(i), _3dRenderingMaxDepth[i]->value()).toDouble());
2503  _3dRenderingMinDepth[i]->setValue(settings.value(QString("minDepth%1").arg(i), _3dRenderingMinDepth[i]->value()).toDouble());
2504  _3dRenderingRoiRatios[i]->setText(settings.value(QString("roiRatios%1").arg(i), _3dRenderingRoiRatios[i]->text()).toString());
2505  _3dRenderingShowScans[i]->setChecked(settings.value(QString("showScans%1").arg(i), _3dRenderingShowScans[i]->isChecked()).toBool());
2506  _3dRenderingShowFeatures[i]->setChecked(settings.value(QString("showFeatures%1").arg(i), _3dRenderingShowFeatures[i]->isChecked()).toBool());
2507  _3dRenderingShowFrustums[i]->setChecked(settings.value(QString("showFrustums%1").arg(i), _3dRenderingShowFrustums[i]->isChecked()).toBool());
2508 
2509  _3dRenderingDownsamplingScan[i]->setValue(settings.value(QString("downsamplingScan%1").arg(i), _3dRenderingDownsamplingScan[i]->value()).toInt());
2510  _3dRenderingMaxRange[i]->setValue(settings.value(QString("maxRange%1").arg(i), _3dRenderingMaxRange[i]->value()).toDouble());
2511  _3dRenderingMinRange[i]->setValue(settings.value(QString("minRange%1").arg(i), _3dRenderingMinRange[i]->value()).toDouble());
2512  _3dRenderingVoxelSizeScan[i]->setValue(settings.value(QString("voxelSizeScan%1").arg(i), _3dRenderingVoxelSizeScan[i]->value()).toDouble());
2513  _3dRenderingColorScheme[i]->setValue(settings.value(QString("colorScheme%1").arg(i), _3dRenderingColorScheme[i]->value()).toInt());
2514  _3dRenderingOpacity[i]->setValue(settings.value(QString("opacity%1").arg(i), _3dRenderingOpacity[i]->value()).toDouble());
2515  _3dRenderingPtSize[i]->setValue(settings.value(QString("ptSize%1").arg(i), _3dRenderingPtSize[i]->value()).toInt());
2516  _3dRenderingColorSchemeScan[i]->setValue(settings.value(QString("colorSchemeScan%1").arg(i), _3dRenderingColorSchemeScan[i]->value()).toInt());
2517  _3dRenderingOpacityScan[i]->setValue(settings.value(QString("opacityScan%1").arg(i), _3dRenderingOpacityScan[i]->value()).toDouble());
2518  _3dRenderingPtSizeScan[i]->setValue(settings.value(QString("ptSizeScan%1").arg(i), _3dRenderingPtSizeScan[i]->value()).toInt());
2519  _3dRenderingPtSizeFeatures[i]->setValue(settings.value(QString("ptSizeFeatures%1").arg(i), _3dRenderingPtSizeFeatures[i]->value()).toInt());
2520  _3dRenderingGravity[i]->setChecked(settings.value(QString("gravityShown%1").arg(i), _3dRenderingGravity[i]->isChecked()).toBool());
2521  _3dRenderingGravityLength[i]->setValue(settings.value(QString("gravityLength%1").arg(i), _3dRenderingGravityLength[i]->value()).toDouble());
2522 
2523  }
2524  _ui->doubleSpinBox_voxel->setValue(settings.value("cloudVoxel", _ui->doubleSpinBox_voxel->value()).toDouble());
2525  _ui->doubleSpinBox_noiseRadius->setValue(settings.value("cloudNoiseRadius", _ui->doubleSpinBox_noiseRadius->value()).toDouble());
2526  _ui->spinBox_noiseMinNeighbors->setValue(settings.value("cloudNoiseMinNeighbors", _ui->spinBox_noiseMinNeighbors->value()).toInt());
2527  _ui->doubleSpinBox_ceilingFilterHeight->setValue(settings.value("cloudCeilingHeight", _ui->doubleSpinBox_ceilingFilterHeight->value()).toDouble());
2528  _ui->doubleSpinBox_floorFilterHeight->setValue(settings.value("cloudFloorHeight", _ui->doubleSpinBox_floorFilterHeight->value()).toDouble());
2529  _ui->spinBox_normalKSearch->setValue(settings.value("normalKSearch", _ui->spinBox_normalKSearch->value()).toInt());
2530  _ui->doubleSpinBox_normalRadiusSearch->setValue(settings.value("normalRadiusSearch", _ui->doubleSpinBox_normalRadiusSearch->value()).toDouble());
2531  _ui->doubleSpinBox_ceilingFilterHeight_scan->setValue(settings.value("scanCeilingHeight", _ui->doubleSpinBox_ceilingFilterHeight_scan->value()).toDouble());
2532  _ui->doubleSpinBox_floorFilterHeight_scan->setValue(settings.value("scanFloorHeight", _ui->doubleSpinBox_floorFilterHeight_scan->value()).toDouble());
2533  _ui->spinBox_normalKSearch_scan->setValue(settings.value("scanNormalKSearch", _ui->spinBox_normalKSearch_scan->value()).toInt());
2534  _ui->doubleSpinBox_normalRadiusSearch_scan->setValue(settings.value("scanNormalRadiusSearch", _ui->doubleSpinBox_normalRadiusSearch_scan->value()).toDouble());
2535 
2536  _ui->checkBox_showGraphs->setChecked(settings.value("showGraphs", _ui->checkBox_showGraphs->isChecked()).toBool());
2537  _ui->checkBox_showLabels->setChecked(settings.value("showLabels", _ui->checkBox_showLabels->isChecked()).toBool());
2538  _ui->checkBox_showFrames->setChecked(settings.value("showFrames", _ui->checkBox_showFrames->isChecked()).toBool());
2539  _ui->checkBox_showLandmarks->setChecked(settings.value("showLandmarks", _ui->checkBox_showLandmarks->isChecked()).toBool());
2540  _ui->doubleSpinBox_landmarkSize->setValue(settings.value("landmarkSize", _ui->doubleSpinBox_landmarkSize->value()).toDouble());
2541  _ui->checkBox_showIMUGravity->setChecked(settings.value("showIMUGravity", _ui->checkBox_showIMUGravity->isChecked()).toBool());
2542  _ui->checkBox_showIMUAcc->setChecked(settings.value("showIMUAcc", _ui->checkBox_showIMUAcc->isChecked()).toBool());
2543 
2544  _ui->radioButton_noFiltering->setChecked(settings.value("noFiltering", _ui->radioButton_noFiltering->isChecked()).toBool());
2545  _ui->radioButton_nodeFiltering->setChecked(settings.value("cloudFiltering", _ui->radioButton_nodeFiltering->isChecked()).toBool());
2546  _ui->doubleSpinBox_cloudFilterRadius->setValue(settings.value("cloudFilteringRadius", _ui->doubleSpinBox_cloudFilterRadius->value()).toDouble());
2547  _ui->doubleSpinBox_cloudFilterAngle->setValue(settings.value("cloudFilteringAngle", _ui->doubleSpinBox_cloudFilterAngle->value()).toDouble());
2548  _ui->radioButton_subtractFiltering->setChecked(settings.value("subtractFiltering", _ui->radioButton_subtractFiltering->isChecked()).toBool());
2549  _ui->spinBox_subtractFilteringMinPts->setValue(settings.value("subtractFilteringMinPts", _ui->spinBox_subtractFilteringMinPts->value()).toInt());
2550  _ui->doubleSpinBox_subtractFilteringRadius->setValue(settings.value("subtractFilteringRadius", _ui->doubleSpinBox_subtractFilteringRadius->value()).toDouble());
2551  _ui->doubleSpinBox_subtractFilteringAngle->setValue(settings.value("subtractFilteringAngle", _ui->doubleSpinBox_subtractFilteringAngle->value()).toDouble());
2552 
2553  _ui->doubleSpinBox_map_resolution->setValue(settings.value("gridUIResolution", _ui->doubleSpinBox_map_resolution->value()).toDouble());
2554  _ui->checkBox_map_shown->setChecked(settings.value("gridMapShown", _ui->checkBox_map_shown->isChecked()).toBool());
2555  _ui->doubleSpinBox_map_opacity->setValue(settings.value("gridMapOpacity", _ui->doubleSpinBox_map_opacity->value()).toDouble());
2556  _ui->checkBox_elevation_shown->setCheckState((Qt::CheckState)settings.value("elevationMapShown", _ui->checkBox_elevation_shown->checkState()).toInt());
2557 
2558  _ui->groupBox_octomap->setChecked(settings.value("octomap", _ui->groupBox_octomap->isChecked()).toBool());
2559  _ui->spinBox_octomap_treeDepth->setValue(settings.value("octomap_depth", _ui->spinBox_octomap_treeDepth->value()).toInt());
2560  _ui->checkBox_octomap_2dgrid->setChecked(settings.value("octomap_2dgrid", _ui->checkBox_octomap_2dgrid->isChecked()).toBool());
2561  _ui->checkBox_octomap_show3dMap->setChecked(settings.value("octomap_3dmap", _ui->checkBox_octomap_show3dMap->isChecked()).toBool());
2562  _ui->comboBox_octomap_renderingType->setCurrentIndex(settings.value("octomap_rendering_type", _ui->comboBox_octomap_renderingType->currentIndex()).toInt());
2563  _ui->spinBox_octomap_pointSize->setValue(settings.value("octomap_point_size", _ui->spinBox_octomap_pointSize->value()).toInt());
2564 
2565  _ui->groupBox_organized->setChecked(settings.value("meshing", _ui->groupBox_organized->isChecked()).toBool());
2566  _ui->doubleSpinBox_mesh_angleTolerance->setValue(settings.value("meshing_angle", _ui->doubleSpinBox_mesh_angleTolerance->value()).toDouble());
2567  _ui->checkBox_mesh_quad->setChecked(settings.value("meshing_quad", _ui->checkBox_mesh_quad->isChecked()).toBool());
2568  _ui->checkBox_mesh_texture->setChecked(settings.value("meshing_texture", _ui->checkBox_mesh_texture->isChecked()).toBool());
2569  _ui->spinBox_mesh_triangleSize->setValue(settings.value("meshing_triangle_size", _ui->spinBox_mesh_triangleSize->value()).toInt());
2570 
2571  settings.endGroup(); // General
2572 
2573  settings.endGroup(); // rtabmap
2574 }
2575 
2576 void PreferencesDialog::readCameraSettings(const QString & filePath)
2577 {
2578  QString path = getIniFilePath();
2579  if(!filePath.isEmpty())
2580  {
2581  path = filePath;
2582  }
2583  QSettings settings(path, QSettings::IniFormat);
2584 
2585  settings.beginGroup("Camera");
2586  _ui->general_doubleSpinBox_imgRate->setValue(settings.value("imgRate", _ui->general_doubleSpinBox_imgRate->value()).toDouble());
2587  _ui->source_mirroring->setChecked(settings.value("mirroring", _ui->source_mirroring->isChecked()).toBool());
2588  _ui->lineEdit_calibrationFile->setText(settings.value("calibrationName", _ui->lineEdit_calibrationFile->text()).toString());
2589  _ui->comboBox_sourceType->setCurrentIndex(settings.value("type", _ui->comboBox_sourceType->currentIndex()).toInt());
2590  _ui->lineEdit_sourceDevice->setText(settings.value("device",_ui->lineEdit_sourceDevice->text()).toString());
2591  _ui->lineEdit_sourceLocalTransform->setText(settings.value("localTransform",_ui->lineEdit_sourceLocalTransform->text()).toString());
2592  _ui->spinBox_source_imageDecimation->setValue(settings.value("imageDecimation",_ui->spinBox_source_imageDecimation->value()).toInt());
2593  _ui->comboBox_source_histogramMethod->setCurrentIndex(settings.value("histogramMethod", _ui->comboBox_source_histogramMethod->currentIndex()).toInt());
2594  _ui->checkbox_source_feature_detection->setChecked(settings.value("featureDetection", _ui->checkbox_source_feature_detection->isChecked()).toBool());
2595  // Backward compatibility
2596  if(_ui->lineEdit_sourceLocalTransform->text().compare("0 0 1 -1 0 0 0 -1 0") == 0)
2597  {
2598  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());
2599  _ui->lineEdit_sourceLocalTransform->setText("0 0 0 0 0 0");
2600  }
2601 
2602  settings.beginGroup("rgbd");
2603  _ui->comboBox_cameraRGBD->setCurrentIndex(settings.value("driver", _ui->comboBox_cameraRGBD->currentIndex()).toInt());
2604  _ui->checkbox_rgbd_colorOnly->setChecked(settings.value("rgbdColorOnly", _ui->checkbox_rgbd_colorOnly->isChecked()).toBool());
2605  _ui->lineEdit_source_distortionModel->setText(settings.value("distortion_model", _ui->lineEdit_source_distortionModel->text()).toString());
2606  _ui->groupBox_bilateral->setChecked(settings.value("bilateral", _ui->groupBox_bilateral->isChecked()).toBool());
2607  _ui->doubleSpinBox_bilateral_sigmaS->setValue(settings.value("bilateral_sigma_s", _ui->doubleSpinBox_bilateral_sigmaS->value()).toDouble());
2608  _ui->doubleSpinBox_bilateral_sigmaR->setValue(settings.value("bilateral_sigma_r", _ui->doubleSpinBox_bilateral_sigmaR->value()).toDouble());
2609  settings.endGroup(); // rgbd
2610 
2611  settings.beginGroup("stereo");
2612  _ui->comboBox_cameraStereo->setCurrentIndex(settings.value("driver", _ui->comboBox_cameraStereo->currentIndex()).toInt());
2613  _ui->checkbox_stereo_depthGenerated->setChecked(settings.value("depthGenerated", _ui->checkbox_stereo_depthGenerated->isChecked()).toBool());
2614  _ui->checkBox_stereo_exposureCompensation->setChecked(settings.value("exposureCompensation", _ui->checkBox_stereo_exposureCompensation->isChecked()).toBool());
2615  settings.endGroup(); // stereo
2616 
2617  settings.beginGroup("rgb");
2618  _ui->source_comboBox_image_type->setCurrentIndex(settings.value("driver", _ui->source_comboBox_image_type->currentIndex()).toInt());
2619  _ui->checkBox_rgb_rectify->setChecked(settings.value("rectify",_ui->checkBox_rgb_rectify->isChecked()).toBool());
2620  settings.endGroup(); // rgb
2621 
2622  settings.beginGroup("Openni");
2623  _ui->lineEdit_openniOniPath->setText(settings.value("oniPath", _ui->lineEdit_openniOniPath->text()).toString());
2624  settings.endGroup(); // Openni
2625 
2626  settings.beginGroup("Openni2");
2627  _ui->openni2_autoWhiteBalance->setChecked(settings.value("autoWhiteBalance", _ui->openni2_autoWhiteBalance->isChecked()).toBool());
2628  _ui->openni2_autoExposure->setChecked(settings.value("autoExposure", _ui->openni2_autoExposure->isChecked()).toBool());
2629  _ui->openni2_exposure->setValue(settings.value("exposure", _ui->openni2_exposure->value()).toInt());
2630  _ui->openni2_gain->setValue(settings.value("gain", _ui->openni2_gain->value()).toInt());
2631  _ui->openni2_mirroring->setChecked(settings.value("mirroring", _ui->openni2_mirroring->isChecked()).toBool());
2632  _ui->openni2_stampsIdsUsed->setChecked(settings.value("stampsIdsUsed", _ui->openni2_stampsIdsUsed->isChecked()).toBool());
2633  _ui->lineEdit_openni2OniPath->setText(settings.value("oniPath", _ui->lineEdit_openni2OniPath->text()).toString());
2634  _ui->openni2_hshift->setValue(settings.value("hshift", _ui->openni2_hshift->value()).toInt());
2635  _ui->openni2_vshift->setValue(settings.value("vshift", _ui->openni2_vshift->value()).toInt());
2636  _ui->openni2_depth_decimation->setValue(settings.value("depthDecimation", _ui->openni2_depth_decimation->value()).toInt());
2637  settings.endGroup(); // Openni2
2638 
2639  settings.beginGroup("Freenect2");
2640  _ui->comboBox_freenect2Format->setCurrentIndex(settings.value("format", _ui->comboBox_freenect2Format->currentIndex()).toInt());
2641  _ui->doubleSpinBox_freenect2MinDepth->setValue(settings.value("minDepth", _ui->doubleSpinBox_freenect2MinDepth->value()).toDouble());
2642  _ui->doubleSpinBox_freenect2MaxDepth->setValue(settings.value("maxDepth", _ui->doubleSpinBox_freenect2MaxDepth->value()).toDouble());
2643  _ui->checkBox_freenect2BilateralFiltering->setChecked(settings.value("bilateralFiltering", _ui->checkBox_freenect2BilateralFiltering->isChecked()).toBool());
2644  _ui->checkBox_freenect2EdgeAwareFiltering->setChecked(settings.value("edgeAwareFiltering", _ui->checkBox_freenect2EdgeAwareFiltering->isChecked()).toBool());
2645  _ui->checkBox_freenect2NoiseFiltering->setChecked(settings.value("noiseFiltering", _ui->checkBox_freenect2NoiseFiltering->isChecked()).toBool());
2646  _ui->lineEdit_freenect2Pipeline->setText(settings.value("pipeline", _ui->lineEdit_freenect2Pipeline->text()).toString());
2647  settings.endGroup(); // Freenect2
2648 
2649  settings.beginGroup("K4W2");
2650  _ui->comboBox_k4w2Format->setCurrentIndex(settings.value("format", _ui->comboBox_k4w2Format->currentIndex()).toInt());
2651  settings.endGroup(); // K4W2
2652 
2653  settings.beginGroup("K4A");
2654  _ui->comboBox_k4a_rgb_resolution->setCurrentIndex(settings.value("rgb_resolution", _ui->comboBox_k4a_rgb_resolution->currentIndex()).toInt());
2655  _ui->comboBox_k4a_framerate->setCurrentIndex(settings.value("framerate", _ui->comboBox_k4a_framerate->currentIndex()).toInt());
2656  _ui->comboBox_k4a_depth_resolution->setCurrentIndex(settings.value("depth_resolution", _ui->comboBox_k4a_depth_resolution->currentIndex()).toInt());
2657  _ui->checkbox_k4a_irDepth->setChecked(settings.value("ir", _ui->checkbox_k4a_irDepth->isChecked()).toBool());
2658  _ui->lineEdit_k4a_mkv->setText(settings.value("mkvPath", _ui->lineEdit_k4a_mkv->text()).toString());
2659  _ui->source_checkBox_useMKVStamps->setChecked(settings.value("useMkvStamps", _ui->source_checkBox_useMKVStamps->isChecked()).toBool());
2660  settings.endGroup(); // K4A
2661 
2662  settings.beginGroup("RealSense");
2663  _ui->comboBox_realsensePresetRGB->setCurrentIndex(settings.value("presetRGB", _ui->comboBox_realsensePresetRGB->currentIndex()).toInt());
2664  _ui->comboBox_realsensePresetDepth->setCurrentIndex(settings.value("presetDepth", _ui->comboBox_realsensePresetDepth->currentIndex()).toInt());
2665  _ui->checkbox_realsenseOdom->setChecked(settings.value("odom", _ui->checkbox_realsenseOdom->isChecked()).toBool());
2666  _ui->checkbox_realsenseDepthScaledToRGBSize->setChecked(settings.value("depthScaled", _ui->checkbox_realsenseDepthScaledToRGBSize->isChecked()).toBool());
2667  _ui->comboBox_realsenseRGBSource->setCurrentIndex(settings.value("rgbSource", _ui->comboBox_realsenseRGBSource->currentIndex()).toInt());
2668  settings.endGroup(); // RealSense
2669 
2670  settings.beginGroup("RealSense2");
2671  _ui->checkbox_rs2_emitter->setChecked(settings.value("emitter", _ui->checkbox_rs2_emitter->isChecked()).toBool());
2672  _ui->checkbox_rs2_irMode->setChecked(settings.value("ir", _ui->checkbox_rs2_irMode->isChecked()).toBool());
2673  _ui->checkbox_rs2_irDepth->setChecked(settings.value("irdepth", _ui->checkbox_rs2_irDepth->isChecked()).toBool());
2674  _ui->spinBox_rs2_width->setValue(settings.value("width", _ui->spinBox_rs2_width->value()).toInt());
2675  _ui->spinBox_rs2_height->setValue(settings.value("height", _ui->spinBox_rs2_height->value()).toInt());
2676  _ui->spinBox_rs2_rate->setValue(settings.value("rate", _ui->spinBox_rs2_rate->value()).toInt());
2677  _ui->spinBox_rs2_width_depth->setValue(settings.value("width_depth", _ui->spinBox_rs2_width_depth->value()).toInt());
2678  _ui->spinBox_rs2_height_depth->setValue(settings.value("height_depth", _ui->spinBox_rs2_height_depth->value()).toInt());
2679  _ui->spinBox_rs2_rate_depth->setValue(settings.value("rate_depth", _ui->spinBox_rs2_rate_depth->value()).toInt());
2680  _ui->checkbox_rs2_globalTimeStync->setChecked(settings.value("global_time_sync", _ui->checkbox_rs2_globalTimeStync->isChecked()).toBool());
2681  _ui->lineEdit_rs2_jsonFile->setText(settings.value("json_preset", _ui->lineEdit_rs2_jsonFile->text()).toString());
2682  settings.endGroup(); // RealSense
2683 
2684  settings.beginGroup("RGBDImages");
2685  _ui->lineEdit_cameraRGBDImages_path_rgb->setText(settings.value("path_rgb", _ui->lineEdit_cameraRGBDImages_path_rgb->text()).toString());
2686  _ui->lineEdit_cameraRGBDImages_path_depth->setText(settings.value("path_depth", _ui->lineEdit_cameraRGBDImages_path_depth->text()).toString());
2687  _ui->doubleSpinBox_cameraRGBDImages_scale->setValue(settings.value("scale", _ui->doubleSpinBox_cameraRGBDImages_scale->value()).toDouble());
2688  _ui->spinBox_cameraRGBDImages_startIndex->setValue(settings.value("start_index", _ui->spinBox_cameraRGBDImages_startIndex->value()).toInt());
2689  _ui->spinBox_cameraRGBDImages_maxFrames->setValue(settings.value("max_frames", _ui->spinBox_cameraRGBDImages_maxFrames->value()).toInt());
2690  settings.endGroup(); // RGBDImages
2691 
2692  settings.beginGroup("StereoImages");
2693  _ui->lineEdit_cameraStereoImages_path_left->setText(settings.value("path_left", _ui->lineEdit_cameraStereoImages_path_left->text()).toString());
2694  _ui->lineEdit_cameraStereoImages_path_right->setText(settings.value("path_right", _ui->lineEdit_cameraStereoImages_path_right->text()).toString());
2695  _ui->checkBox_stereo_rectify->setChecked(settings.value("rectify",_ui->checkBox_stereo_rectify->isChecked()).toBool());
2696  _ui->spinBox_cameraStereoImages_startIndex->setValue(settings.value("start_index",_ui->spinBox_cameraStereoImages_startIndex->value()).toInt());
2697  _ui->spinBox_cameraStereoImages_maxFrames->setValue(settings.value("max_frames",_ui->spinBox_cameraStereoImages_maxFrames->value()).toInt());
2698  settings.endGroup(); // StereoImages
2699 
2700  settings.beginGroup("StereoVideo");
2701  _ui->lineEdit_cameraStereoVideo_path->setText(settings.value("path", _ui->lineEdit_cameraStereoVideo_path->text()).toString());
2702  _ui->lineEdit_cameraStereoVideo_path_2->setText(settings.value("path2", _ui->lineEdit_cameraStereoVideo_path_2->text()).toString());
2703  _ui->spinBox_stereo_right_device->setValue(settings.value("device2", _ui->spinBox_stereo_right_device->value()).toInt());
2704  _ui->spinBox_stereousbcam_streamWidth->setValue(settings.value("width", _ui->spinBox_stereousbcam_streamWidth->value()).toInt());
2705  _ui->spinBox_stereousbcam_streamHeight->setValue(settings.value("height", _ui->spinBox_stereousbcam_streamHeight->value()).toInt());
2706  settings.endGroup(); // StereoVideo
2707 
2708  settings.beginGroup("StereoZed");
2709  _ui->comboBox_stereoZed_resolution->setCurrentIndex(settings.value("resolution", _ui->comboBox_stereoZed_resolution->currentIndex()).toInt());
2710  _ui->comboBox_stereoZed_quality->setCurrentIndex(settings.value("quality", _ui->comboBox_stereoZed_quality->currentIndex()).toInt());
2711  _ui->checkbox_stereoZed_selfCalibration->setChecked(settings.value("self_calibration", _ui->checkbox_stereoZed_selfCalibration->isChecked()).toBool());
2712  _ui->comboBox_stereoZed_sensingMode->setCurrentIndex(settings.value("sensing_mode", _ui->comboBox_stereoZed_sensingMode->currentIndex()).toInt());
2713  _ui->spinBox_stereoZed_confidenceThr->setValue(settings.value("confidence_thr", _ui->spinBox_stereoZed_confidenceThr->value()).toInt());
2714  _ui->spinBox_stereoZed_texturenessConfidenceThr->setValue(settings.value("textureness_confidence_thr", _ui->spinBox_stereoZed_texturenessConfidenceThr->value()).toInt());
2715  _ui->lineEdit_zedSvoPath->setText(settings.value("svo_path", _ui->lineEdit_zedSvoPath->text()).toString());
2716  settings.endGroup(); // StereoZed
2717 
2718  settings.beginGroup("MyntEye");
2719  _ui->checkbox_stereoMyntEye_rectify->setChecked(settings.value("rectify", _ui->checkbox_stereoMyntEye_rectify->isChecked()).toBool());
2720  _ui->checkbox_stereoMyntEye_depth->setChecked(settings.value("depth", _ui->checkbox_stereoMyntEye_depth->isChecked()).toBool());
2721  _ui->checkbox_stereoMyntEye_autoExposure->setChecked(settings.value("auto_exposure", _ui->checkbox_stereoMyntEye_autoExposure->isChecked()).toBool());
2722  _ui->spinBox_stereoMyntEye_gain->setValue(settings.value("gain", _ui->spinBox_stereoMyntEye_gain->value()).toInt());
2723  _ui->spinBox_stereoMyntEye_brightness->setValue(settings.value("brightness", _ui->spinBox_stereoMyntEye_brightness->value()).toInt());
2724  _ui->spinBox_stereoMyntEye_contrast->setValue(settings.value("contrast", _ui->spinBox_stereoMyntEye_contrast->value()).toInt());
2725  _ui->spinBox_stereoMyntEye_irControl->setValue(settings.value("ir_control", _ui->spinBox_stereoMyntEye_irControl->value()).toInt());
2726  settings.endGroup(); // MyntEye
2727 
2728  settings.beginGroup("DepthAI");
2729  _ui->comboBox_depthai_resolution->setCurrentIndex(settings.value("resolution", _ui->comboBox_depthai_resolution->currentIndex()).toInt());
2730  _ui->comboBox_depthai_output_mode->setCurrentIndex(settings.value("output_mode", _ui->comboBox_depthai_output_mode->currentIndex()).toInt());
2731  _ui->spinBox_depthai_conf_threshold->setValue(settings.value("conf_threshold", _ui->spinBox_depthai_conf_threshold->value()).toInt());
2732  _ui->spinBox_depthai_lrc_threshold->setValue(settings.value("lrc_threshold", _ui->spinBox_depthai_lrc_threshold->value()).toInt());
2733  _ui->checkBox_depthai_extended_disparity->setChecked(settings.value("extended_disparity", _ui->checkBox_depthai_extended_disparity->isChecked()).toBool());
2734  _ui->comboBox_depthai_subpixel_fractional_bits->setCurrentIndex(settings.value("subpixel_fractional_bits", _ui->comboBox_depthai_subpixel_fractional_bits->currentIndex()).toInt());
2735  _ui->comboBox_depthai_disparity_companding->setCurrentIndex(settings.value("companding", _ui->comboBox_depthai_disparity_companding->currentIndex()).toInt());
2736  _ui->checkBox_depthai_use_spec_translation->setChecked(settings.value("use_spec_translation", _ui->checkBox_depthai_use_spec_translation->isChecked()).toBool());
2737  _ui->doubleSpinBox_depthai_alpha_scaling->setValue(settings.value("alpha_scaling", _ui->doubleSpinBox_depthai_alpha_scaling->value()).toDouble());
2738  _ui->checkBox_depthai_imu_published->setChecked(settings.value("imu_published", _ui->checkBox_depthai_imu_published->isChecked()).toBool());
2739  _ui->doubleSpinBox_depthai_dot_intensity->setValue(settings.value("dot_intensity", _ui->doubleSpinBox_depthai_dot_intensity->value()).toDouble());
2740  _ui->doubleSpinBox_depthai_flood_intensity->setValue(settings.value("flood_intensity", _ui->doubleSpinBox_depthai_flood_intensity->value()).toDouble());
2741  _ui->comboBox_depthai_detect_features->setCurrentIndex(settings.value("detect_features", _ui->comboBox_depthai_detect_features->currentIndex()).toInt());
2742  _ui->lineEdit_depthai_blob_path->setText(settings.value("blob_path", _ui->lineEdit_depthai_blob_path->text()).toString());
2743  settings.endGroup(); // DepthAI
2744 
2745  settings.beginGroup("Images");
2746  _ui->source_images_lineEdit_path->setText(settings.value("path", _ui->source_images_lineEdit_path->text()).toString());
2747  _ui->source_images_spinBox_startPos->setValue(settings.value("startPos",_ui->source_images_spinBox_startPos->value()).toInt());
2748  _ui->source_images_spinBox_maxFrames->setValue(settings.value("maxFrames",_ui->source_images_spinBox_maxFrames->value()).toInt());
2749  _ui->comboBox_cameraImages_bayerMode->setCurrentIndex(settings.value("bayerMode",_ui->comboBox_cameraImages_bayerMode->currentIndex()).toInt());
2750 
2751  _ui->checkBox_cameraImages_configForEachFrame->setChecked(settings.value("config_each_frame",_ui->checkBox_cameraImages_configForEachFrame->isChecked()).toBool());
2752  _ui->checkBox_cameraImages_timestamps->setChecked(settings.value("filenames_as_stamps",_ui->checkBox_cameraImages_timestamps->isChecked()).toBool());
2753  _ui->checkBox_cameraImages_syncTimeStamps->setChecked(settings.value("sync_stamps",_ui->checkBox_cameraImages_syncTimeStamps->isChecked()).toBool());
2754  _ui->lineEdit_cameraImages_timestamps->setText(settings.value("stamps", _ui->lineEdit_cameraImages_timestamps->text()).toString());
2755  _ui->lineEdit_cameraImages_path_scans->setText(settings.value("path_scans", _ui->lineEdit_cameraImages_path_scans->text()).toString());
2756  _ui->lineEdit_cameraImages_laser_transform->setText(settings.value("scan_transform", _ui->lineEdit_cameraImages_laser_transform->text()).toString());
2757  _ui->spinBox_cameraImages_max_scan_pts->setValue(settings.value("scan_max_pts", _ui->spinBox_cameraImages_max_scan_pts->value()).toInt());
2758  _ui->lineEdit_cameraImages_odom->setText(settings.value("odom_path", _ui->lineEdit_cameraImages_odom->text()).toString());
2759  _ui->comboBox_cameraImages_odomFormat->setCurrentIndex(settings.value("odom_format", _ui->comboBox_cameraImages_odomFormat->currentIndex()).toInt());
2760  _ui->lineEdit_cameraImages_gt->setText(settings.value("gt_path", _ui->lineEdit_cameraImages_gt->text()).toString());
2761  _ui->comboBox_cameraImages_gtFormat->setCurrentIndex(settings.value("gt_format", _ui->comboBox_cameraImages_gtFormat->currentIndex()).toInt());
2762  _ui->doubleSpinBox_maxPoseTimeDiff->setValue(settings.value("max_pose_time_diff", _ui->doubleSpinBox_maxPoseTimeDiff->value()).toDouble());
2763 
2764  _ui->lineEdit_cameraImages_path_imu->setText(settings.value("imu_path", _ui->lineEdit_cameraImages_path_imu->text()).toString());
2765  _ui->lineEdit_cameraImages_imu_transform->setText(settings.value("imu_local_transform", _ui->lineEdit_cameraImages_imu_transform->text()).toString());
2766  _ui->spinBox_cameraImages_max_imu_rate->setValue(settings.value("imu_rate", _ui->spinBox_cameraImages_max_imu_rate->value()).toInt());
2767  settings.endGroup(); // images
2768 
2769  settings.beginGroup("OdomSensor");
2770  _ui->comboBox_odom_sensor->setCurrentIndex(settings.value("odom_sensor", _ui->comboBox_odom_sensor->currentIndex()).toInt());
2771  _ui->lineEdit_odom_sensor_extrinsics->setText(settings.value("odom_sensor_extrinsics", _ui->lineEdit_odom_sensor_extrinsics->text()).toString());
2772  _ui->lineEdit_odom_sensor_path_calibration->setText(settings.value("odom_sensor_calibration_path", _ui->lineEdit_odom_sensor_path_calibration->text()).toString());
2773  _ui->lineEdit_odomSourceDevice->setText(settings.value("odom_sensor_device", _ui->lineEdit_odomSourceDevice->text()).toString());
2774  _ui->doubleSpinBox_odom_sensor_time_offset->setValue(settings.value("odom_sensor_offset_time", _ui->doubleSpinBox_odom_sensor_time_offset->value()).toDouble());
2775  _ui->doubleSpinBox_odom_sensor_scale_factor->setValue(settings.value("odom_sensor_scale_factor", _ui->doubleSpinBox_odom_sensor_scale_factor->value()).toDouble());
2776  _ui->doubleSpinBox_odom_sensor_wait_time->setValue(settings.value("odom_sensor_wait_time", _ui->doubleSpinBox_odom_sensor_wait_time->value()).toDouble());
2777  _ui->checkBox_odom_sensor_use_as_gt->setChecked(settings.value("odom_sensor_odom_as_gt", _ui->checkBox_odom_sensor_use_as_gt->isChecked()).toBool());
2778  settings.endGroup(); // OdomSensor
2779 
2780  settings.beginGroup("UsbCam");
2781  _ui->spinBox_usbcam_streamWidth->setValue(settings.value("width", _ui->spinBox_usbcam_streamWidth->value()).toInt());
2782  _ui->spinBox_usbcam_streamHeight->setValue(settings.value("height", _ui->spinBox_usbcam_streamHeight->value()).toInt());
2783  settings.endGroup(); // UsbCam
2784 
2785  settings.beginGroup("Video");
2786  _ui->source_video_lineEdit_path->setText(settings.value("path", _ui->source_video_lineEdit_path->text()).toString());
2787  settings.endGroup(); // video
2788 
2789  settings.beginGroup("IMU");
2790  _ui->comboBox_imuFilter_strategy->setCurrentIndex(settings.value("strategy", _ui->comboBox_imuFilter_strategy->currentIndex()).toInt());
2791  _ui->doubleSpinBox_imuFilterMadgwickGain->setValue(settings.value("madgwick_gain", _ui->doubleSpinBox_imuFilterMadgwickGain->value()).toDouble());
2792  _ui->doubleSpinBox_imuFilterMadgwickZeta->setValue(settings.value("madgwick_zeta", _ui->doubleSpinBox_imuFilterMadgwickZeta->value()).toDouble());
2793  _ui->doubleSpinBox_imuFilterComplementaryGainAcc->setValue(settings.value("complementary_gain_acc", _ui->doubleSpinBox_imuFilterComplementaryGainAcc->value()).toDouble());
2794  _ui->doubleSpinBox_imuFilterComplementaryBiasAlpha->setValue(settings.value("complementary_bias_alpha", _ui->doubleSpinBox_imuFilterComplementaryBiasAlpha->value()).toDouble());
2795  _ui->checkBox_imuFilterComplementaryDoAdaptiveGain->setChecked(settings.value("complementary_adaptive_gain", _ui->checkBox_imuFilterComplementaryDoAdaptiveGain->isChecked()).toBool());
2796  _ui->checkBox_imuFilterComplementaryDoBiasEstimation->setChecked(settings.value("complementary_biais_estimation", _ui->checkBox_imuFilterComplementaryDoBiasEstimation->isChecked()).toBool());
2797  _ui->checkBox_imuFilter_baseFrameConversion->setChecked(settings.value("base_frame_conversion", _ui->checkBox_imuFilter_baseFrameConversion->isChecked()).toBool());
2798  _ui->checkbox_publishInterIMU->setChecked(settings.value("publish_inter_imu", _ui->checkbox_publishInterIMU->isChecked()).toBool());
2799  settings.endGroup();//IMU
2800 
2801  settings.beginGroup("Scan");
2802  _ui->comboBox_lidar_src->setCurrentIndex(settings.value("source", _ui->comboBox_lidar_src->currentIndex()).toInt());
2803  _ui->checkBox_source_scanDeskewing->setChecked(settings.value("deskewing", _ui->checkBox_source_scanDeskewing->isChecked()).toBool());
2804  _ui->checkBox_source_scanFromDepth->setChecked(settings.value("fromDepth", _ui->checkBox_source_scanFromDepth->isChecked()).toBool());
2805  _ui->spinBox_source_scanDownsampleStep->setValue(settings.value("downsampleStep", _ui->spinBox_source_scanDownsampleStep->value()).toInt());
2806  _ui->doubleSpinBox_source_scanRangeMin->setValue(settings.value("rangeMin", _ui->doubleSpinBox_source_scanRangeMin->value()).toDouble());
2807  _ui->doubleSpinBox_source_scanRangeMax->setValue(settings.value("rangeMax", _ui->doubleSpinBox_source_scanRangeMax->value()).toDouble());
2808  _ui->doubleSpinBox_source_scanVoxelSize->setValue(settings.value("voxelSize", _ui->doubleSpinBox_source_scanVoxelSize->value()).toDouble());
2809  _ui->spinBox_source_scanNormalsK->setValue(settings.value("normalsK", _ui->spinBox_source_scanNormalsK->value()).toInt());
2810  _ui->doubleSpinBox_source_scanNormalsRadius->setValue(settings.value("normalsRadius", _ui->doubleSpinBox_source_scanNormalsRadius->value()).toDouble());
2811  _ui->doubleSpinBox_source_scanNormalsForceGroundUp->setValue(settings.value("normalsUpF", _ui->doubleSpinBox_source_scanNormalsForceGroundUp->value()).toDouble());
2812  settings.endGroup();//Scan
2813 
2814  settings.beginGroup("DepthFromScan");
2815  _ui->groupBox_depthFromScan->setChecked(settings.value("depthFromScan", _ui->groupBox_depthFromScan->isChecked()).toBool());
2816  _ui->groupBox_depthFromScan_fillHoles->setChecked(settings.value("depthFromScanFillHoles", _ui->groupBox_depthFromScan_fillHoles->isChecked()).toBool());
2817  _ui->radioButton_depthFromScan_vertical->setChecked(settings.value("depthFromScanVertical", _ui->radioButton_depthFromScan_vertical->isChecked()).toBool());
2818  _ui->radioButton_depthFromScan_horizontal->setChecked(settings.value("depthFromScanHorizontal", _ui->radioButton_depthFromScan_horizontal->isChecked()).toBool());
2819  _ui->checkBox_depthFromScan_fillBorders->setChecked(settings.value("depthFromScanFillBorders", _ui->checkBox_depthFromScan_fillBorders->isChecked()).toBool());
2820  settings.endGroup();
2821 
2822  settings.beginGroup("Database");
2823  _ui->source_database_lineEdit_path->setText(settings.value("path",_ui->source_database_lineEdit_path->text()).toString());
2824  _ui->source_checkBox_ignoreOdometry->setChecked(settings.value("ignoreOdometry", _ui->source_checkBox_ignoreOdometry->isChecked()).toBool());
2825  _ui->source_checkBox_ignoreGoalDelay->setChecked(settings.value("ignoreGoalDelay", _ui->source_checkBox_ignoreGoalDelay->isChecked()).toBool());
2826  _ui->source_checkBox_ignoreGoals->setChecked(settings.value("ignoreGoals", _ui->source_checkBox_ignoreGoals->isChecked()).toBool());
2827  _ui->source_checkBox_ignoreLandmarks->setChecked(settings.value("ignoreLandmarks", _ui->source_checkBox_ignoreLandmarks->isChecked()).toBool());
2828  _ui->source_checkBox_ignoreFeatures->setChecked(settings.value("ignoreFeatures", _ui->source_checkBox_ignoreFeatures->isChecked()).toBool());
2829  _ui->source_checkBox_ignorePriors->setChecked(settings.value("ignorePriors", _ui->source_checkBox_ignorePriors->isChecked()).toBool());
2830  _ui->source_spinBox_databaseStartId->setValue(settings.value("startId", _ui->source_spinBox_databaseStartId->value()).toInt());
2831  _ui->source_spinBox_databaseStopId->setValue(settings.value("stopId", _ui->source_spinBox_databaseStopId->value()).toInt());
2832  _ui->source_spinBox_database_cameraIndex->setValue(settings.value("cameraIndex", _ui->source_spinBox_database_cameraIndex->value()).toInt());
2833  _ui->source_checkBox_useDbStamps->setChecked(settings.value("useDatabaseStamps", _ui->source_checkBox_useDbStamps->isChecked()).toBool());
2834  settings.endGroup(); // Database
2835 
2836  settings.endGroup(); // Camera
2837 
2838  settings.beginGroup("Lidar");
2839 
2840  settings.beginGroup("VLP16");
2841  _ui->lineEdit_lidar_local_transform->setText(settings.value("localTransform",_ui->lineEdit_lidar_local_transform->text()).toString());
2842  _ui->lineEdit_vlp16_pcap_path->setText(settings.value("pcapPath",_ui->lineEdit_vlp16_pcap_path->text()).toString());
2843  _ui->spinBox_vlp16_ip1->setValue(settings.value("ip1", _ui->spinBox_vlp16_ip1->value()).toInt());
2844  _ui->spinBox_vlp16_ip2->setValue(settings.value("ip2", _ui->spinBox_vlp16_ip2->value()).toInt());
2845  _ui->spinBox_vlp16_ip3->setValue(settings.value("ip3", _ui->spinBox_vlp16_ip3->value()).toInt());
2846  _ui->spinBox_vlp16_ip4->setValue(settings.value("ip4", _ui->spinBox_vlp16_ip4->value()).toInt());
2847  _ui->spinBox_vlp16_port->setValue(settings.value("port", _ui->spinBox_vlp16_port->value()).toInt());
2848  _ui->checkBox_vlp16_organized->setChecked(settings.value("organized", _ui->checkBox_vlp16_organized->isChecked()).toBool());
2849  _ui->checkBox_vlp16_hostTime->setChecked(settings.value("hostTime", _ui->checkBox_vlp16_hostTime->isChecked()).toBool());
2850  _ui->checkBox_vlp16_stamp_last->setChecked(settings.value("stampLast", _ui->checkBox_vlp16_stamp_last->isChecked()).toBool());
2851  settings.endGroup(); // VLP16
2852 
2853  settings.endGroup(); // Lidar
2854 
2855  _calibrationDialog->loadSettings(settings, "CalibrationDialog");
2856 
2857 }
2858 
2860 {
2862 }
2863 
2864 bool PreferencesDialog::readCoreSettings(const QString & filePath)
2865 {
2866  QString path = getIniFilePath();
2867  if(!filePath.isEmpty())
2868  {
2869  path = filePath;
2870  }
2871 
2872  UDEBUG("%s", path.toStdString().c_str());
2873 
2874  if(!QFile::exists(path))
2875  {
2876  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));
2877  }
2878 
2879  ParametersMap parameters;
2880  Parameters::readINI(path.toStdString(), parameters);
2881 
2882  for(rtabmap::ParametersMap::const_iterator iter = parameters.begin(); iter!=parameters.end(); ++iter)
2883  {
2884  std::string value = iter->second;
2885  if(iter->first.compare(Parameters::kRtabmapWorkingDirectory()) == 0)
2886  {
2887  if(value.empty())
2888  {
2889  UWARN("Reading config: Working directory is empty. Keeping old one (\"%s\").",
2890  this->getWorkingDirectory().toStdString().c_str());
2891  value = this->getWorkingDirectory().toStdString();
2892  }
2893 
2894  // The directory should exist if not the default one
2895  if(!QDir(value.c_str()).exists() && value.compare(getDefaultWorkingDirectory().toStdString()) != 0)
2896  {
2897  if(QDir(this->getWorkingDirectory().toStdString().c_str()).exists())
2898  {
2899  UWARN("Reading config: Not existing working directory \"%s\". Keeping old one (\"%s\").",
2900  value.c_str(),
2901  this->getWorkingDirectory().toStdString().c_str());
2902  value = this->getWorkingDirectory().toStdString();
2903  }
2904  else
2905  {
2906  std::string defaultWorkingDir = getDefaultWorkingDirectory().toStdString();
2907  UWARN("Reading config: Not existing working directory \"%s\". Using default one (\"%s\").",
2908  value.c_str(),
2909  defaultWorkingDir.c_str());
2910  value = defaultWorkingDir;
2911  }
2912  }
2913  }
2914 
2915  //backward compatibility
2916  if(iter->first.compare(Parameters::kIcpStrategy()) == 0)
2917  {
2918  if(value.compare("true") == 0)
2919  {
2920  value = "1";
2921  }
2922  else if(value.compare("false") == 0)
2923  {
2924  value = "0";
2925  }
2926  }
2927 
2928  this->setParameter(iter->first, value);
2929  }
2930 
2931  // Add information about the working directory if not in the config file
2932  if(parameters.find(Parameters::kRtabmapWorkingDirectory()) == parameters.end())
2933  {
2934  if(!_initialized)
2935  {
2936  QMessageBox::information(this,
2937  tr("Working directory"),
2938  tr("RTAB-Map needs a working directory to put the database.\n\n"
2939  "By default, the directory \"%1\" is used.\n\n"
2940  "The working directory can be changed any time in the "
2941  "preferences menu.").arg(getDefaultWorkingDirectory()));
2942  }
2943  this->setParameter(Parameters::kRtabmapWorkingDirectory(), getDefaultWorkingDirectory().toStdString());
2944  UDEBUG("key.toStdString()=%s", getDefaultWorkingDirectory().toStdString().c_str());
2945  }
2946 
2947  return true;
2948 }
2949 
2951 {
2952  QString path = QFileDialog::getSaveFileName(this, tr("Save settings..."), this->getWorkingDirectory()+QDir::separator()+"config.ini", "*.ini");
2953  if(!path.isEmpty())
2954  {
2958  return true;
2959  }
2960  return false;
2961 }
2962 
2964 {
2965  int button = QMessageBox::warning(this,
2966  tr("Reset settings..."),
2967  tr("This will reset all settings. Restore all settings to default without saving them first?"),
2968  QMessageBox::Cancel | QMessageBox::Yes | QMessageBox::Save,
2969  QMessageBox::Cancel);
2970  if(button == QMessageBox::Yes ||
2971  (button == QMessageBox::Save && saveConfigTo()))
2972  {
2973  this->resetSettings(-1);
2974 
2976  }
2977 }
2978 
2979 void PreferencesDialog::loadPreset(const std::string & presetHexHeader)
2980 {
2982  if(!presetHexHeader.empty())
2983  {
2984  Parameters::readINIStr(uHex2Str(presetHexHeader), parameters);
2985  }
2986 
2987  // Reset 3D rendering panel
2988  this->resetSettings(1);
2989  // Update parameters
2990  parameters.erase(Parameters::kRtabmapWorkingDirectory());
2991  for(ParametersMap::iterator iter=parameters.begin(); iter!=parameters.end(); ++iter)
2992  {
2993  this->setParameter(iter->first, iter->second);
2994  }
2995 }
2996 
2998 {
2999  if(sender() == _ui->pushButton_presets_camera_tof_icp)
3000  {
3001  loadPreset(CAMERA_TOF_ICP_INI);
3002  }
3003  else if(sender() == _ui->pushButton_presets_lidar_3d_icp)
3004  {
3005  loadPreset(LIDAR3D_ICP_INI);
3006  }
3007  else
3008  {
3009  UERROR("Unknown sender!");
3010  return;
3011  }
3012  QMessageBox::information(this,
3013  tr("Preset"),
3014  tr("Loaded \"%1\" preset!").arg(((QPushButton*)sender())->text()),
3015  QMessageBox::Ok);
3016 }
3017 
3018 void PreferencesDialog::writeSettings(const QString & filePath)
3019 {
3020  writeGuiSettings(filePath);
3021  writeCameraSettings(filePath);
3022  writeCoreSettings(filePath);
3023 
3024  UDEBUG("_obsoletePanels=%d modified parameters=%d", (int)_obsoletePanels, (int)_modifiedParameters.size());
3025 
3026  if(_modifiedParameters.size())
3027  {
3029  }
3030 
3031  if(_obsoletePanels)
3032  {
3034  }
3035 
3036  for(ParametersMap::iterator iter = _modifiedParameters.begin(); iter!=_modifiedParameters.end(); ++iter)
3037  {
3038  if (_parameters.at(iter->first).compare(iter->second) != 0)
3039  {
3040  bool different = true;
3041  if (Parameters::getType(iter->first).compare("double") == 0 ||
3042  Parameters::getType(iter->first).compare("float") == 0)
3043  {
3044  if (uStr2Double(_parameters.at(iter->first)) == uStr2Double(iter->second))
3045  {
3046  different = false;
3047  }
3048  }
3049  if (different)
3050  {
3051  UINFO("modified %s = %s->%s", iter->first.c_str(), _parameters.at(iter->first).c_str(), iter->second.c_str());
3052  }
3053  }
3054  }
3055 
3056  uInsert(_parameters, _modifiedParameters); // update cached parameters
3057  _modifiedParameters.clear();
3059 }
3060 
3061 void PreferencesDialog::writeGuiSettings(const QString & filePath) const
3062 {
3063  QString path = getIniFilePath();
3064  if(!filePath.isEmpty())
3065  {
3066  path = filePath;
3067  }
3068  QSettings settings(path, QSettings::IniFormat);
3069  settings.beginGroup("Gui");
3070 
3071  settings.beginGroup("General");
3072  settings.remove("");
3073  settings.setValue("imagesKept", _ui->general_checkBox_imagesKept->isChecked());
3074  settings.setValue("missingRepublished", _ui->general_checkBox_missing_cache_republished->isChecked());
3075  settings.setValue("cloudsKept", _ui->general_checkBox_cloudsKept->isChecked());
3076  settings.setValue("loggerLevel", _ui->comboBox_loggerLevel->currentIndex());
3077  settings.setValue("loggerEventLevel", _ui->comboBox_loggerEventLevel->currentIndex());
3078  settings.setValue("loggerPauseLevel", _ui->comboBox_loggerPauseLevel->currentIndex());
3079  settings.setValue("loggerType", _ui->comboBox_loggerType->currentIndex());
3080  settings.setValue("loggerPrintTime", _ui->checkBox_logger_printTime->isChecked());
3081  settings.setValue("loggerPrintThreadId", _ui->checkBox_logger_printThreadId->isChecked());
3082  settings.setValue("verticalLayoutUsed", _ui->checkBox_verticalLayoutUsed->isChecked());
3083  settings.setValue("imageRejectedShown", _ui->checkBox_imageRejectedShown->isChecked());
3084  settings.setValue("imageHighestHypShown", _ui->checkBox_imageHighestHypShown->isChecked());
3085  settings.setValue("beep", _ui->checkBox_beep->isChecked());
3086  settings.setValue("figure_time", _ui->checkBox_stamps->isChecked());
3087  settings.setValue("figure_cache", _ui->checkBox_cacheStatistics->isChecked());
3088  settings.setValue("notifyNewGlobalPath", _ui->checkBox_notifyWhenNewGlobalPathIsReceived->isChecked());
3089  settings.setValue("odomQualityThr", _ui->spinBox_odomQualityWarnThr->value());
3090  settings.setValue("odomOnlyInliersShown", _ui->checkBox_odom_onlyInliersShown->isChecked());
3091  settings.setValue("posteriorGraphView", _ui->radioButton_posteriorGraphView->isChecked());
3092  settings.setValue("wordsGraphView", _ui->radioButton_wordsGraphView->isChecked());
3093  settings.setValue("localizationsGraphView", _ui->radioButton_localizationsGraphView->isChecked());
3094  settings.setValue("localizationsGraphViewOdomCache", _ui->radioButton_localizationsGraphViewOdomCache->isChecked());
3095  settings.setValue("nochangeGraphView", _ui->radioButton_nochangeGraphView->isChecked());
3096  settings.setValue("odomDisabled", _ui->checkbox_odomDisabled->isChecked());
3097  settings.setValue("odomRegistration", _ui->odom_registration->currentIndex());
3098  settings.setValue("odomF2MGravitySigma", _ui->odom_f2m_gravitySigma->value());
3099  settings.setValue("gtAlign", _ui->checkbox_groundTruthAlign->isChecked());
3100 
3101  for(int i=0; i<2; ++i)
3102  {
3103  settings.setValue(QString("showClouds%1").arg(i), _3dRenderingShowClouds[i]->isChecked());
3104  settings.setValue(QString("decimation%1").arg(i), _3dRenderingDecimation[i]->value());
3105  settings.setValue(QString("maxDepth%1").arg(i), _3dRenderingMaxDepth[i]->value());
3106  settings.setValue(QString("minDepth%1").arg(i), _3dRenderingMinDepth[i]->value());
3107  settings.setValue(QString("roiRatios%1").arg(i), _3dRenderingRoiRatios[i]->text());
3108  settings.setValue(QString("showScans%1").arg(i), _3dRenderingShowScans[i]->isChecked());
3109  settings.setValue(QString("showFeatures%1").arg(i), _3dRenderingShowFeatures[i]->isChecked());
3110  settings.setValue(QString("showFrustums%1").arg(i), _3dRenderingShowFrustums[i]->isChecked());
3111 
3112  settings.setValue(QString("downsamplingScan%1").arg(i), _3dRenderingDownsamplingScan[i]->value());
3113  settings.setValue(QString("maxRange%1").arg(i), _3dRenderingMaxRange[i]->value());
3114  settings.setValue(QString("minRange%1").arg(i), _3dRenderingMinRange[i]->value());
3115  settings.setValue(QString("voxelSizeScan%1").arg(i), _3dRenderingVoxelSizeScan[i]->value());
3116  settings.setValue(QString("colorScheme%1").arg(i), _3dRenderingColorScheme[i]->value());
3117  settings.setValue(QString("opacity%1").arg(i), _3dRenderingOpacity[i]->value());
3118  settings.setValue(QString("ptSize%1").arg(i), _3dRenderingPtSize[i]->value());
3119  settings.setValue(QString("colorSchemeScan%1").arg(i), _3dRenderingColorSchemeScan[i]->value());
3120  settings.setValue(QString("opacityScan%1").arg(i), _3dRenderingOpacityScan[i]->value());
3121  settings.setValue(QString("ptSizeScan%1").arg(i), _3dRenderingPtSizeScan[i]->value());
3122  settings.setValue(QString("ptSizeFeatures%1").arg(i), _3dRenderingPtSizeFeatures[i]->value());
3123  settings.setValue(QString("gravityShown%1").arg(i), _3dRenderingGravity[i]->isChecked());
3124  settings.setValue(QString("gravityLength%1").arg(i), _3dRenderingGravityLength[i]->value());
3125  }
3126  settings.setValue("cloudVoxel", _ui->doubleSpinBox_voxel->value());
3127  settings.setValue("cloudNoiseRadius", _ui->doubleSpinBox_noiseRadius->value());
3128  settings.setValue("cloudNoiseMinNeighbors", _ui->spinBox_noiseMinNeighbors->value());
3129  settings.setValue("cloudCeilingHeight", _ui->doubleSpinBox_ceilingFilterHeight->value());
3130  settings.setValue("cloudFloorHeight", _ui->doubleSpinBox_floorFilterHeight->value());
3131  settings.setValue("normalKSearch", _ui->spinBox_normalKSearch->value());
3132  settings.setValue("normalRadiusSearch", _ui->doubleSpinBox_normalRadiusSearch->value());
3133  settings.setValue("scanCeilingHeight", _ui->doubleSpinBox_ceilingFilterHeight_scan->value());
3134  settings.setValue("scanFloorHeight", _ui->doubleSpinBox_floorFilterHeight_scan->value());
3135  settings.setValue("scanNormalKSearch", _ui->spinBox_normalKSearch_scan->value());
3136  settings.setValue("scanNormalRadiusSearch", _ui->doubleSpinBox_normalRadiusSearch_scan->value());
3137 
3138  settings.setValue("showGraphs", _ui->checkBox_showGraphs->isChecked());
3139  settings.setValue("showLabels", _ui->checkBox_showLabels->isChecked());
3140  settings.setValue("showFrames", _ui->checkBox_showFrames->isChecked());
3141  settings.setValue("showLandmarks", _ui->checkBox_showLandmarks->isChecked());
3142  settings.setValue("landmarkSize", _ui->doubleSpinBox_landmarkSize->value());
3143  settings.setValue("showIMUGravity", _ui->checkBox_showIMUGravity->isChecked());
3144  settings.setValue("showIMUAcc", _ui->checkBox_showIMUAcc->isChecked());
3145 
3146 
3147  settings.setValue("noFiltering", _ui->radioButton_noFiltering->isChecked());
3148  settings.setValue("cloudFiltering", _ui->radioButton_nodeFiltering->isChecked());
3149  settings.setValue("cloudFilteringRadius", _ui->doubleSpinBox_cloudFilterRadius->value());
3150  settings.setValue("cloudFilteringAngle", _ui->doubleSpinBox_cloudFilterAngle->value());
3151  settings.setValue("subtractFiltering", _ui->radioButton_subtractFiltering->isChecked());
3152  settings.setValue("subtractFilteringMinPts", _ui->spinBox_subtractFilteringMinPts->value());
3153  settings.setValue("subtractFilteringRadius", _ui->doubleSpinBox_subtractFilteringRadius->value());
3154  settings.setValue("subtractFilteringAngle", _ui->doubleSpinBox_subtractFilteringAngle->value());
3155 
3156  settings.setValue("gridUIResolution", _ui->doubleSpinBox_map_resolution->value());
3157  settings.setValue("gridMapShown", _ui->checkBox_map_shown->isChecked());
3158  settings.setValue("gridMapOpacity", _ui->doubleSpinBox_map_opacity->value());
3159  settings.setValue("elevationMapShown", _ui->checkBox_elevation_shown->checkState());
3160 
3161 
3162  settings.setValue("octomap", _ui->groupBox_octomap->isChecked());
3163  settings.setValue("octomap_depth", _ui->spinBox_octomap_treeDepth->value());
3164  settings.setValue("octomap_2dgrid", _ui->checkBox_octomap_2dgrid->isChecked());
3165  settings.setValue("octomap_3dmap", _ui->checkBox_octomap_show3dMap->isChecked());
3166  settings.setValue("octomap_rendering_type", _ui->comboBox_octomap_renderingType->currentIndex());
3167  settings.setValue("octomap_point_size", _ui->spinBox_octomap_pointSize->value());
3168 
3169 
3170  settings.setValue("meshing", _ui->groupBox_organized->isChecked());
3171  settings.setValue("meshing_angle", _ui->doubleSpinBox_mesh_angleTolerance->value());
3172  settings.setValue("meshing_quad", _ui->checkBox_mesh_quad->isChecked());
3173  settings.setValue("meshing_texture", _ui->checkBox_mesh_texture->isChecked());
3174  settings.setValue("meshing_triangle_size", _ui->spinBox_mesh_triangleSize->value());
3175 
3176  settings.endGroup(); // General
3177 
3178  settings.endGroup(); // rtabmap
3179 }
3180 
3181 void PreferencesDialog::writeCameraSettings(const QString & filePath) const
3182 {
3183  QString path = getIniFilePath();
3184  if(!filePath.isEmpty())
3185  {
3186  path = filePath;
3187  }
3188  QSettings settings(path, QSettings::IniFormat);
3189 
3190  settings.beginGroup("Camera");
3191  settings.remove("");
3192  settings.setValue("imgRate", _ui->general_doubleSpinBox_imgRate->value());
3193  settings.setValue("mirroring", _ui->source_mirroring->isChecked());
3194  settings.setValue("calibrationName", _ui->lineEdit_calibrationFile->text());
3195  settings.setValue("type", _ui->comboBox_sourceType->currentIndex());
3196  settings.setValue("device", _ui->lineEdit_sourceDevice->text());
3197  settings.setValue("localTransform", _ui->lineEdit_sourceLocalTransform->text());
3198  settings.setValue("imageDecimation", _ui->spinBox_source_imageDecimation->value());
3199  settings.setValue("histogramMethod", _ui->comboBox_source_histogramMethod->currentIndex());
3200  settings.setValue("featureDetection", _ui->checkbox_source_feature_detection->isChecked());
3201 
3202  settings.beginGroup("rgbd");
3203  settings.setValue("driver", _ui->comboBox_cameraRGBD->currentIndex());
3204  settings.setValue("rgbdColorOnly", _ui->checkbox_rgbd_colorOnly->isChecked());
3205  settings.setValue("distortion_model", _ui->lineEdit_source_distortionModel->text());
3206  settings.setValue("bilateral", _ui->groupBox_bilateral->isChecked());
3207  settings.setValue("bilateral_sigma_s", _ui->doubleSpinBox_bilateral_sigmaS->value());
3208  settings.setValue("bilateral_sigma_r", _ui->doubleSpinBox_bilateral_sigmaR->value());
3209  settings.endGroup(); // rgbd
3210 
3211  settings.beginGroup("stereo");
3212  settings.setValue("driver", _ui->comboBox_cameraStereo->currentIndex());
3213  settings.setValue("depthGenerated", _ui->checkbox_stereo_depthGenerated->isChecked());
3214  settings.setValue("exposureCompensation", _ui->checkBox_stereo_exposureCompensation->isChecked());
3215  settings.endGroup(); // stereo
3216 
3217  settings.beginGroup("rgb");
3218  settings.setValue("driver", _ui->source_comboBox_image_type->currentIndex());
3219  settings.setValue("rectify", _ui->checkBox_rgb_rectify->isChecked());
3220  settings.endGroup(); // rgb
3221 
3222  settings.beginGroup("Openni");
3223  settings.setValue("oniPath", _ui->lineEdit_openniOniPath->text());
3224  settings.endGroup(); // Openni
3225 
3226  settings.beginGroup("Openni2");
3227  settings.setValue("autoWhiteBalance", _ui->openni2_autoWhiteBalance->isChecked());
3228  settings.setValue("autoExposure", _ui->openni2_autoExposure->isChecked());
3229  settings.setValue("exposure", _ui->openni2_exposure->value());
3230  settings.setValue("gain", _ui->openni2_gain->value());
3231  settings.setValue("mirroring", _ui->openni2_mirroring->isChecked());
3232  settings.setValue("stampsIdsUsed", _ui->openni2_stampsIdsUsed->isChecked());
3233  settings.setValue("oniPath", _ui->lineEdit_openni2OniPath->text());
3234  settings.setValue("hshift", _ui->openni2_hshift->value());
3235  settings.setValue("vshift", _ui->openni2_vshift->value());
3236  settings.setValue("depthDecimation", _ui->openni2_depth_decimation->value());
3237  settings.endGroup(); // Openni2
3238 
3239  settings.beginGroup("Freenect2");
3240  settings.setValue("format", _ui->comboBox_freenect2Format->currentIndex());
3241  settings.setValue("minDepth", _ui->doubleSpinBox_freenect2MinDepth->value());
3242  settings.setValue("maxDepth", _ui->doubleSpinBox_freenect2MaxDepth->value());
3243  settings.setValue("bilateralFiltering", _ui->checkBox_freenect2BilateralFiltering->isChecked());
3244  settings.setValue("edgeAwareFiltering", _ui->checkBox_freenect2EdgeAwareFiltering->isChecked());
3245  settings.setValue("noiseFiltering", _ui->checkBox_freenect2NoiseFiltering->isChecked());
3246  settings.setValue("pipeline", _ui->lineEdit_freenect2Pipeline->text());
3247  settings.endGroup(); // Freenect2
3248 
3249  settings.beginGroup("K4W2");
3250  settings.setValue("format", _ui->comboBox_k4w2Format->currentIndex());
3251  settings.endGroup(); // K4W2
3252 
3253  settings.beginGroup("K4A");
3254  settings.setValue("rgb_resolution", _ui->comboBox_k4a_rgb_resolution->currentIndex());
3255  settings.setValue("framerate", _ui->comboBox_k4a_framerate->currentIndex());
3256  settings.setValue("depth_resolution", _ui->comboBox_k4a_depth_resolution->currentIndex());
3257  settings.setValue("ir", _ui->checkbox_k4a_irDepth->isChecked());
3258  settings.setValue("mkvPath", _ui->lineEdit_k4a_mkv->text());
3259  settings.setValue("useMkvStamps", _ui->source_checkBox_useMKVStamps->isChecked());
3260  settings.endGroup(); // K4A
3261 
3262  settings.beginGroup("RealSense");
3263  settings.setValue("presetRGB", _ui->comboBox_realsensePresetRGB->currentIndex());
3264  settings.setValue("presetDepth", _ui->comboBox_realsensePresetDepth->currentIndex());
3265  settings.setValue("odom", _ui->checkbox_realsenseOdom->isChecked());
3266  settings.setValue("depthScaled", _ui->checkbox_realsenseDepthScaledToRGBSize->isChecked());
3267  settings.setValue("rgbSource", _ui->comboBox_realsenseRGBSource->currentIndex());
3268  settings.endGroup(); // RealSense
3269 
3270  settings.beginGroup("RealSense2");
3271  settings.setValue("emitter", _ui->checkbox_rs2_emitter->isChecked());
3272  settings.setValue("ir", _ui->checkbox_rs2_irMode->isChecked());
3273  settings.setValue("irdepth", _ui->checkbox_rs2_irDepth->isChecked());
3274  settings.setValue("width", _ui->spinBox_rs2_width->value());
3275  settings.setValue("height", _ui->spinBox_rs2_height->value());
3276  settings.setValue("rate", _ui->spinBox_rs2_rate->value());
3277  settings.setValue("width_depth", _ui->spinBox_rs2_width_depth->value());
3278  settings.setValue("height_depth", _ui->spinBox_rs2_height_depth->value());
3279  settings.setValue("rate_depth", _ui->spinBox_rs2_rate_depth->value());
3280  settings.setValue("global_time_sync", _ui->checkbox_rs2_globalTimeStync->isChecked());
3281  settings.setValue("json_preset", _ui->lineEdit_rs2_jsonFile->text());
3282  settings.endGroup(); // RealSense2
3283 
3284  settings.beginGroup("RGBDImages");
3285  settings.setValue("path_rgb", _ui->lineEdit_cameraRGBDImages_path_rgb->text());
3286  settings.setValue("path_depth", _ui->lineEdit_cameraRGBDImages_path_depth->text());
3287  settings.setValue("scale", _ui->doubleSpinBox_cameraRGBDImages_scale->value());
3288  settings.setValue("start_index", _ui->spinBox_cameraRGBDImages_startIndex->value());
3289  settings.setValue("max_frames", _ui->spinBox_cameraRGBDImages_maxFrames->value());
3290  settings.endGroup(); // RGBDImages
3291 
3292  settings.beginGroup("StereoImages");
3293  settings.setValue("path_left", _ui->lineEdit_cameraStereoImages_path_left->text());
3294  settings.setValue("path_right", _ui->lineEdit_cameraStereoImages_path_right->text());
3295  settings.setValue("rectify", _ui->checkBox_stereo_rectify->isChecked());
3296  settings.setValue("start_index", _ui->spinBox_cameraStereoImages_startIndex->value());
3297  settings.setValue("max_frames", _ui->spinBox_cameraStereoImages_maxFrames->value());
3298  settings.endGroup(); // StereoImages
3299 
3300  settings.beginGroup("StereoVideo");
3301  settings.setValue("path", _ui->lineEdit_cameraStereoVideo_path->text());
3302  settings.setValue("path2", _ui->lineEdit_cameraStereoVideo_path_2->text());
3303  settings.setValue("device2", _ui->spinBox_stereo_right_device->value());
3304  settings.setValue("width", _ui->spinBox_stereousbcam_streamWidth->value());
3305  settings.setValue("height", _ui->spinBox_stereousbcam_streamHeight->value());
3306  settings.endGroup(); // StereoVideo
3307 
3308  settings.beginGroup("StereoZed");
3309  settings.setValue("resolution", _ui->comboBox_stereoZed_resolution->currentIndex());
3310  settings.setValue("quality", _ui->comboBox_stereoZed_quality->currentIndex());
3311  settings.setValue("self_calibration", _ui->checkbox_stereoZed_selfCalibration->isChecked());
3312  settings.setValue("sensing_mode", _ui->comboBox_stereoZed_sensingMode->currentIndex());
3313  settings.setValue("confidence_thr", _ui->spinBox_stereoZed_confidenceThr->value());
3314  settings.setValue("textureness_confidence_thr", _ui->spinBox_stereoZed_texturenessConfidenceThr->value());
3315  settings.setValue("svo_path", _ui->lineEdit_zedSvoPath->text());
3316  settings.endGroup(); // StereoZed
3317 
3318  settings.beginGroup("MyntEye");
3319  settings.setValue("rectify", _ui->checkbox_stereoMyntEye_rectify->isChecked());
3320  settings.setValue("depth", _ui->checkbox_stereoMyntEye_depth->isChecked());
3321  settings.setValue("auto_exposure", _ui->checkbox_stereoMyntEye_autoExposure->isChecked());
3322  settings.setValue("gain", _ui->spinBox_stereoMyntEye_gain->value());
3323  settings.setValue("brightness", _ui->spinBox_stereoMyntEye_brightness->value());
3324  settings.setValue("contrast", _ui->spinBox_stereoMyntEye_contrast->value());
3325  settings.setValue("ir_control", _ui->spinBox_stereoMyntEye_irControl->value());
3326  settings.endGroup(); // MyntEye
3327 
3328  settings.beginGroup("DepthAI");
3329  settings.setValue("resolution", _ui->comboBox_depthai_resolution->currentIndex());
3330  settings.setValue("output_mode", _ui->comboBox_depthai_output_mode->currentIndex());
3331  settings.setValue("conf_threshold", _ui->spinBox_depthai_conf_threshold->value());
3332  settings.setValue("lrc_threshold", _ui->spinBox_depthai_lrc_threshold->value());
3333  settings.setValue("extended_disparity", _ui->checkBox_depthai_extended_disparity->isChecked());
3334  settings.setValue("subpixel_fractional_bits", _ui->comboBox_depthai_subpixel_fractional_bits->currentIndex());
3335  settings.setValue("companding", _ui->comboBox_depthai_disparity_companding->currentIndex());
3336  settings.setValue("use_spec_translation", _ui->checkBox_depthai_use_spec_translation->isChecked());
3337  settings.setValue("alpha_scaling", _ui->doubleSpinBox_depthai_alpha_scaling->value());
3338  settings.setValue("imu_published", _ui->checkBox_depthai_imu_published->isChecked());
3339  settings.setValue("dot_intensity", _ui->doubleSpinBox_depthai_dot_intensity->value());
3340  settings.setValue("flood_intensity", _ui->doubleSpinBox_depthai_flood_intensity->value());
3341  settings.setValue("detect_features", _ui->comboBox_depthai_detect_features->currentIndex());
3342  settings.setValue("blob_path", _ui->lineEdit_depthai_blob_path->text());
3343  settings.endGroup(); // DepthAI
3344 
3345  settings.beginGroup("Images");
3346  settings.setValue("path", _ui->source_images_lineEdit_path->text());
3347  settings.setValue("startPos", _ui->source_images_spinBox_startPos->value());
3348  settings.setValue("maxFrames", _ui->source_images_spinBox_maxFrames->value());
3349  settings.setValue("bayerMode", _ui->comboBox_cameraImages_bayerMode->currentIndex());
3350  settings.setValue("config_each_frame", _ui->checkBox_cameraImages_configForEachFrame->isChecked());
3351  settings.setValue("filenames_as_stamps", _ui->checkBox_cameraImages_timestamps->isChecked());
3352  settings.setValue("sync_stamps", _ui->checkBox_cameraImages_syncTimeStamps->isChecked());
3353  settings.setValue("stamps", _ui->lineEdit_cameraImages_timestamps->text());
3354  settings.setValue("path_scans", _ui->lineEdit_cameraImages_path_scans->text());
3355  settings.setValue("scan_transform", _ui->lineEdit_cameraImages_laser_transform->text());
3356  settings.setValue("scan_max_pts", _ui->spinBox_cameraImages_max_scan_pts->value());
3357  settings.setValue("odom_path", _ui->lineEdit_cameraImages_odom->text());
3358  settings.setValue("odom_format", _ui->comboBox_cameraImages_odomFormat->currentIndex());
3359  settings.setValue("gt_path", _ui->lineEdit_cameraImages_gt->text());
3360  settings.setValue("gt_format", _ui->comboBox_cameraImages_gtFormat->currentIndex());
3361  settings.setValue("max_pose_time_diff", _ui->doubleSpinBox_maxPoseTimeDiff->value());
3362  settings.setValue("imu_path", _ui->lineEdit_cameraImages_path_imu->text());
3363  settings.setValue("imu_local_transform", _ui->lineEdit_cameraImages_imu_transform->text());
3364  settings.setValue("imu_rate", _ui->spinBox_cameraImages_max_imu_rate->value());
3365  settings.endGroup(); // images
3366 
3367  settings.beginGroup("OdomSensor");
3368  settings.setValue("odom_sensor", _ui->comboBox_odom_sensor->currentIndex());
3369  settings.setValue("odom_sensor_extrinsics", _ui->lineEdit_odom_sensor_extrinsics->text());
3370  settings.setValue("odom_sensor_calibration_path", _ui->lineEdit_odom_sensor_path_calibration->text());
3371  settings.setValue("odom_sensor_device", _ui->lineEdit_odomSourceDevice->text());
3372  settings.setValue("odom_sensor_offset_time", _ui->doubleSpinBox_odom_sensor_time_offset->value());
3373  settings.setValue("odom_sensor_scale_factor", _ui->doubleSpinBox_odom_sensor_scale_factor->value());
3374  settings.setValue("odom_sensor_wait_time", _ui->doubleSpinBox_odom_sensor_wait_time->value());
3375  settings.setValue("odom_sensor_odom_as_gt", _ui->checkBox_odom_sensor_use_as_gt->isChecked());
3376  settings.endGroup(); // OdomSensor
3377 
3378  settings.beginGroup("UsbCam");
3379  settings.setValue("width", _ui->spinBox_usbcam_streamWidth->value());
3380  settings.setValue("height", _ui->spinBox_usbcam_streamHeight->value());
3381  settings.endGroup(); // UsbCam
3382 
3383  settings.beginGroup("Video");
3384  settings.setValue("path", _ui->source_video_lineEdit_path->text());
3385  settings.endGroup(); // video
3386 
3387  settings.beginGroup("IMU");
3388  settings.setValue("strategy", _ui->comboBox_imuFilter_strategy->currentIndex());
3389  settings.setValue("madgwick_gain", _ui->doubleSpinBox_imuFilterMadgwickGain->value());
3390  settings.setValue("madgwick_zeta", _ui->doubleSpinBox_imuFilterMadgwickZeta->value());
3391  settings.setValue("complementary_gain_acc", _ui->doubleSpinBox_imuFilterComplementaryGainAcc->value());
3392  settings.setValue("complementary_bias_alpha", _ui->doubleSpinBox_imuFilterComplementaryBiasAlpha->value());
3393  settings.setValue("complementary_adaptive_gain", _ui->checkBox_imuFilterComplementaryDoAdaptiveGain->isChecked());
3394  settings.setValue("complementary_biais_estimation", _ui->checkBox_imuFilterComplementaryDoBiasEstimation->isChecked());
3395  settings.setValue("base_frame_conversion", _ui->checkBox_imuFilter_baseFrameConversion->isChecked());
3396  settings.setValue("publish_inter_imu", _ui->checkbox_publishInterIMU->isChecked());
3397  settings.endGroup();//IMU
3398 
3399  settings.beginGroup("Scan");
3400  settings.setValue("source", _ui->comboBox_lidar_src->currentIndex());
3401  settings.setValue("deskewing", _ui->checkBox_source_scanDeskewing->isChecked());
3402  settings.setValue("fromDepth", _ui->checkBox_source_scanFromDepth->isChecked());
3403  settings.setValue("downsampleStep", _ui->spinBox_source_scanDownsampleStep->value());
3404  settings.setValue("rangeMin", _ui->doubleSpinBox_source_scanRangeMin->value());
3405  settings.setValue("rangeMax", _ui->doubleSpinBox_source_scanRangeMax->value());
3406  settings.setValue("voxelSize", _ui->doubleSpinBox_source_scanVoxelSize->value());
3407  settings.setValue("normalsK", _ui->spinBox_source_scanNormalsK->value());
3408  settings.setValue("normalsRadius", _ui->doubleSpinBox_source_scanNormalsRadius->value());
3409  settings.setValue("normalsUpF", _ui->doubleSpinBox_source_scanNormalsForceGroundUp->value());
3410  settings.endGroup();
3411 
3412  settings.beginGroup("DepthFromScan");
3413  settings.setValue("depthFromScan", _ui->groupBox_depthFromScan->isChecked());
3414  settings.setValue("depthFromScanFillHoles", _ui->groupBox_depthFromScan_fillHoles->isChecked());
3415  settings.setValue("depthFromScanVertical", _ui->radioButton_depthFromScan_vertical->isChecked());
3416  settings.setValue("depthFromScanHorizontal", _ui->radioButton_depthFromScan_horizontal->isChecked());
3417  settings.setValue("depthFromScanFillBorders", _ui->checkBox_depthFromScan_fillBorders->isChecked());
3418  settings.endGroup();
3419 
3420  settings.beginGroup("Database");
3421  settings.setValue("path", _ui->source_database_lineEdit_path->text());
3422  settings.setValue("ignoreOdometry", _ui->source_checkBox_ignoreOdometry->isChecked());
3423  settings.setValue("ignoreGoalDelay", _ui->source_checkBox_ignoreGoalDelay->isChecked());
3424  settings.setValue("ignoreGoals", _ui->source_checkBox_ignoreGoals->isChecked());
3425  settings.setValue("ignoreLandmarks", _ui->source_checkBox_ignoreLandmarks->isChecked());
3426  settings.setValue("ignoreFeatures", _ui->source_checkBox_ignoreFeatures->isChecked());
3427  settings.setValue("ignorePriors", _ui->source_checkBox_ignorePriors->isChecked());
3428  settings.setValue("startId", _ui->source_spinBox_databaseStartId->value());
3429  settings.setValue("stopId", _ui->source_spinBox_databaseStopId->value());
3430  settings.setValue("cameraIndex", _ui->source_spinBox_database_cameraIndex->value());
3431  settings.setValue("useDatabaseStamps", _ui->source_checkBox_useDbStamps->isChecked());
3432  settings.endGroup(); // Database
3433 
3434  settings.endGroup(); // Camera
3435 
3436  settings.beginGroup("Lidar");
3437 
3438  settings.beginGroup("VLP16");
3439  settings.setValue("localTransform",_ui->lineEdit_lidar_local_transform->text());
3440  settings.setValue("pcapPath",_ui->lineEdit_vlp16_pcap_path->text());
3441  settings.setValue("ip1", _ui->spinBox_vlp16_ip1->value());
3442  settings.setValue("ip2", _ui->spinBox_vlp16_ip2->value());
3443  settings.setValue("ip3", _ui->spinBox_vlp16_ip3->value());
3444  settings.setValue("ip4", _ui->spinBox_vlp16_ip4->value());
3445  settings.setValue("port", _ui->spinBox_vlp16_port->value());
3446  settings.setValue("organized", _ui->checkBox_vlp16_organized->isChecked());
3447  settings.setValue("hostTime", _ui->checkBox_vlp16_hostTime->isChecked());
3448  settings.setValue("stampLast", _ui->checkBox_vlp16_stamp_last->isChecked());
3449  settings.endGroup(); // VLP16
3450 
3451  settings.endGroup(); // Lidar
3452 
3453  _calibrationDialog->saveSettings(settings, "CalibrationDialog");
3454 }
3455 
3456 void PreferencesDialog::writeCoreSettings(const QString & filePath) const
3457 {
3458  QString path = getIniFilePath();
3459  if(!filePath.isEmpty())
3460  {
3461  path = filePath;
3462  }
3463 
3464  Parameters::writeINI(path.toStdString(), this->getAllParameters());
3465 }
3466 
3468 {
3469 #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)))
3470 #ifndef RTABMAP_NONFREE
3471  // verify that SURF/SIFT cannot be selected if not built with OpenCV nonfree module
3472  // BOW dictionary type
3473  if(_ui->comboBox_detector_strategy->currentIndex() <= 1 || _ui->comboBox_detector_strategy->currentIndex() == 12)
3474  {
3475  QMessageBox::warning(this, tr("Parameter warning"),
3476  tr("Selected feature type (SURF/SIFT) is not available. RTAB-Map is not built "
3477  "with the nonfree module from OpenCV. ORB is set instead for the bag-of-words dictionary."));
3478  _ui->comboBox_detector_strategy->setCurrentIndex(Feature2D::kFeatureOrb);
3479  }
3480  // BOW Reextract features type
3481  if(_ui->vis_feature_detector->currentIndex() <= 1 || _ui->vis_feature_detector->currentIndex() == 12)
3482  {
3483  QMessageBox::warning(this, tr("Parameter warning"),
3484  tr("Selected feature type (SURF/SIFT) is not available. RTAB-Map is not built "
3485  "with the nonfree module from OpenCV. Fast/Brief is set instead for the re-extraction "
3486  "of features on loop closure."));
3487  _ui->vis_feature_detector->setCurrentIndex(Feature2D::kFeatureFastBrief);
3488  }
3489 #endif
3490 #else //>= 4.4.0 >= 3.4.11
3491 #ifndef RTABMAP_NONFREE
3492  // verify that SURF cannot be selected if not built with OpenCV nonfree module
3493  // BOW dictionary type
3494  if(_ui->comboBox_detector_strategy->currentIndex() < 1 || _ui->comboBox_detector_strategy->currentIndex() == 12)
3495  {
3496  QMessageBox::warning(this, tr("Parameter warning"),
3497  tr("Selected feature type (SURF) is not available. RTAB-Map is not built "
3498  "with the nonfree module from OpenCV. SIFT is set instead for the bag-of-words dictionary."));
3499  _ui->comboBox_detector_strategy->setCurrentIndex(Feature2D::kFeatureSift);
3500  }
3501  // BOW Reextract features type
3502  if(_ui->vis_feature_detector->currentIndex() < 1 || _ui->vis_feature_detector->currentIndex() == 12)
3503  {
3504  QMessageBox::warning(this, tr("Parameter warning"),
3505  tr("Selected feature type (SURF) is not available. RTAB-Map is not built "
3506  "with the nonfree module from OpenCV. Fast/Brief is set instead for the re-extraction "
3507  "of features on loop closure."));
3508  _ui->vis_feature_detector->setCurrentIndex(Feature2D::kFeatureFastBrief);
3509  }
3510 #endif
3511 #endif
3512 
3513 #if CV_MAJOR_VERSION < 3
3514  if (_ui->comboBox_detector_strategy->currentIndex() == Feature2D::kFeatureKaze)
3515  {
3516 #ifdef RTABMAP_NONFREE
3517  QMessageBox::warning(this, tr("Parameter warning"),
3518  tr("Selected feature type (KAZE) is not available on OpenCV2. SURF is set instead "
3519  "for the bag-of-words dictionary."));
3520  _ui->comboBox_detector_strategy->setCurrentIndex(Feature2D::kFeatureSurf);
3521 #else
3522  QMessageBox::warning(this, tr("Parameter warning"),
3523  tr("Selected feature type (KAZE) is not available on OpenCV2. ORB is set instead "
3524  "for the bag-of-words dictionary."));
3525  _ui->comboBox_detector_strategy->setCurrentIndex(Feature2D::kFeatureOrb);
3526 #endif
3527  }
3528  if (_ui->vis_feature_detector->currentIndex() == Feature2D::kFeatureKaze)
3529  {
3530 #ifdef RTABMAP_NONFREE
3531  QMessageBox::warning(this, tr("Parameter warning"),
3532  tr("Selected feature type (KAZE) is not available on OpenCV2. SURF is set instead "
3533  "for the re-extraction of features on loop closure."));
3534  _ui->vis_feature_detector->setCurrentIndex(Feature2D::kFeatureSurf);
3535 #else
3536  QMessageBox::warning(this, tr("Parameter warning"),
3537  tr("Selected feature type (KAZE) is not available on OpenCV2. ORB is set instead "
3538  "for the re-extraction of features on loop closure."));
3539  _ui->vis_feature_detector->setCurrentIndex(Feature2D::kFeatureOrb);
3540 #endif
3541  }
3542 #endif
3543 
3544 #ifndef RTABMAP_ORB_OCTREE
3545  if (_ui->comboBox_detector_strategy->currentIndex() == Feature2D::kFeatureOrbOctree)
3546  {
3547  QMessageBox::warning(this, tr("Parameter warning"),
3548  tr("Selected feature type (ORB Octree) is not available. ORB is set instead "
3549  "for the bag-of-words dictionary."));
3550  _ui->comboBox_detector_strategy->setCurrentIndex(Feature2D::kFeatureOrb);
3551  }
3552  if (_ui->vis_feature_detector->currentIndex() == Feature2D::kFeatureOrbOctree)
3553  {
3554  QMessageBox::warning(this, tr("Parameter warning"),
3555  tr("Selected feature type (ORB Octree) is not available on OpenCV2. ORB is set instead "
3556  "for the re-extraction of features on loop closure."));
3557  _ui->vis_feature_detector->setCurrentIndex(Feature2D::kFeatureOrb);
3558  }
3559 #endif
3560 
3561  // optimization strategy
3562  if(_ui->graphOptimization_type->currentIndex() == 0 && !Optimizer::isAvailable(Optimizer::kTypeTORO))
3563  {
3565  {
3566  QMessageBox::warning(this, tr("Parameter warning"),
3567  tr("Selected graph optimization strategy (TORO) is not available. RTAB-Map is not built "
3568  "with TORO. GTSAM is set instead for graph optimization strategy."));
3569  _ui->graphOptimization_type->setCurrentIndex(Optimizer::kTypeGTSAM);
3570  }
3571 #ifndef RTABMAP_ORB_SLAM
3573  {
3574  QMessageBox::warning(this, tr("Parameter warning"),
3575  tr("Selected graph optimization strategy (TORO) is not available. RTAB-Map is not built "
3576  "with TORO. g2o is set instead for graph optimization strategy."));
3577  _ui->graphOptimization_type->setCurrentIndex(Optimizer::kTypeG2O);
3578  }
3579 #endif
3580  }
3581 #ifdef RTABMAP_ORB_SLAM
3582  if(_ui->graphOptimization_type->currentIndex() == 1)
3583 #else
3584  if(_ui->graphOptimization_type->currentIndex() == 1 && !Optimizer::isAvailable(Optimizer::kTypeG2O))
3585 #endif
3586  {
3588  {
3589  QMessageBox::warning(this, tr("Parameter warning"),
3590  tr("Selected graph optimization strategy (g2o) is not available. RTAB-Map is not built "
3591  "with g2o. GTSAM is set instead for graph optimization strategy."));
3592  _ui->graphOptimization_type->setCurrentIndex(Optimizer::kTypeGTSAM);
3593  }
3595  {
3596  QMessageBox::warning(this, tr("Parameter warning"),
3597  tr("Selected graph optimization strategy (g2o) is not available. RTAB-Map is not built "
3598  "with g2o. TORO is set instead for graph optimization strategy."));
3599  _ui->graphOptimization_type->setCurrentIndex(Optimizer::kTypeTORO);
3600  }
3601  }
3602  if(_ui->graphOptimization_type->currentIndex() == 2 && !Optimizer::isAvailable(Optimizer::kTypeGTSAM))
3603  {
3604 #ifndef RTABMAP_ORB_SLAM
3606  {
3607  QMessageBox::warning(this, tr("Parameter warning"),
3608  tr("Selected graph optimization strategy (GTSAM) is not available. RTAB-Map is not built "
3609  "with GTSAM. g2o is set instead for graph optimization strategy."));
3610  _ui->graphOptimization_type->setCurrentIndex(Optimizer::kTypeG2O);
3611  }
3612  else
3613 #endif
3615  {
3616  QMessageBox::warning(this, tr("Parameter warning"),
3617  tr("Selected graph optimization strategy (GTSAM) is not available. RTAB-Map is not built "
3618  "with GTSAM. TORO is set instead for graph optimization strategy."));
3619  _ui->graphOptimization_type->setCurrentIndex(Optimizer::kTypeTORO);
3620  }
3621  }
3622 
3623  // Registration bundle adjustment strategy
3624  if(_ui->loopClosure_bundle->currentIndex() == 1 && !Optimizer::isAvailable(Optimizer::kTypeG2O))
3625  {
3626  QMessageBox::warning(this, tr("Parameter warning"),
3627  tr("Selected visual registration bundle adjustment optimization strategy (g2o) is not available. RTAB-Map is not built "
3628  "with g2o. Bundle adjustment is disabled."));
3629  _ui->loopClosure_bundle->setCurrentIndex(0);
3630  }
3631  if(_ui->loopClosure_bundle->currentIndex() == 2 && !Optimizer::isAvailable(Optimizer::kTypeCVSBA))
3632  {
3633  QMessageBox::warning(this, tr("Parameter warning"),
3634  tr("Selected visual registration bundle adjustment optimization strategy (cvsba) is not available. RTAB-Map is not built "
3635  "with cvsba. Bundle adjustment is disabled."));
3636  _ui->loopClosure_bundle->setCurrentIndex(0);
3637  }
3638  if(_ui->loopClosure_bundle->currentIndex() == 3 && !Optimizer::isAvailable(Optimizer::kTypeCeres))
3639  {
3640  QMessageBox::warning(this, tr("Parameter warning"),
3641  tr("Selected visual registration bundle adjustment optimization strategy (Ceres) is not available. RTAB-Map is not built "
3642  "with cERES. Bundle adjustment is disabled."));
3643  _ui->loopClosure_bundle->setCurrentIndex(0);
3644  }
3645 
3646  // Local bundle adjustment strategy for odometry F2M
3647  if(_ui->odom_f2m_bundleStrategy->currentIndex() == 1 && !Optimizer::isAvailable(Optimizer::kTypeG2O))
3648  {
3649  QMessageBox::warning(this, tr("Parameter warning"),
3650  tr("Selected odometry local bundle adjustment optimization strategy (g2o) is not available. RTAB-Map is not built "
3651  "with g2o. Bundle adjustment is disabled."));
3652  _ui->odom_f2m_bundleStrategy->setCurrentIndex(0);
3653  }
3654  if(_ui->odom_f2m_bundleStrategy->currentIndex() == 2 && !Optimizer::isAvailable(Optimizer::kTypeCVSBA))
3655  {
3656  QMessageBox::warning(this, tr("Parameter warning"),
3657  tr("Selected odometry local bundle adjustment optimization strategy (cvsba) is not available. RTAB-Map is not built "
3658  "with cvsba. Bundle adjustment is disabled."));
3659  _ui->odom_f2m_bundleStrategy->setCurrentIndex(0);
3660  }
3661  if(_ui->odom_f2m_bundleStrategy->currentIndex() == 3 && !Optimizer::isAvailable(Optimizer::kTypeCeres))
3662  {
3663  QMessageBox::warning(this, tr("Parameter warning"),
3664  tr("Selected odometry local bundle adjustment optimization strategy (Ceres) is not available. RTAB-Map is not built "
3665  "with Ceres. Bundle adjustment is disabled."));
3666  _ui->odom_f2m_bundleStrategy->setCurrentIndex(0);
3667  }
3668 
3669  // verify that Robust and Reject threshold are not set at the same time
3670  if(_ui->graphOptimization_robust->isChecked() && _ui->graphOptimization_maxError->value()>0.0)
3671  {
3672  QMessageBox::warning(this, tr("Parameter warning"),
3673  tr("Robust graph optimization and maximum optimization error threshold cannot be "
3674  "both used at the same time. Disabling robust optimization."));
3675  _ui->graphOptimization_robust->setChecked(false);
3676  }
3677 
3678  //verify binary features and nearest neighbor
3679  // BOW dictionary type
3680  if(_ui->comboBox_dictionary_strategy->currentIndex() == VWDictionary::kNNFlannLSH && _ui->comboBox_detector_strategy->currentIndex() <= 1)
3681  {
3682  QMessageBox::warning(this, tr("Parameter warning"),
3683  tr("With the selected feature type (SURF or SIFT), parameter \"Visual word->Nearest Neighbor\" "
3684  "cannot be LSH (used for binary descriptor). KD-tree is set instead for the bag-of-words dictionary."));
3685  _ui->comboBox_dictionary_strategy->setCurrentIndex(VWDictionary::kNNFlannKdTree);
3686  }
3687 
3688  // BOW Reextract features type
3689  if(_ui->reextract_nn->currentIndex() == VWDictionary::kNNFlannLSH && _ui->vis_feature_detector->currentIndex() <= 1)
3690  {
3691  QMessageBox::warning(this, tr("Parameter warning"),
3692  tr("With the selected feature type (SURF or SIFT), parameter \"Visual word->Nearest Neighbor\" "
3693  "cannot be LSH (used for binary descriptor). KD-tree is set instead for the re-extraction "
3694  "of features on loop closure."));
3695  _ui->reextract_nn->setCurrentIndex(VWDictionary::kNNFlannKdTree);
3696  }
3697 
3698  if(_ui->doubleSpinBox_freenect2MinDepth->value() >= _ui->doubleSpinBox_freenect2MaxDepth->value())
3699  {
3700  QMessageBox::warning(this, tr("Parameter warning"),
3701  tr("Freenect2 minimum depth (%1 m) should be lower than maximum depth (%2 m). Setting maximum depth to %3 m.")
3702  .arg(_ui->doubleSpinBox_freenect2MinDepth->value())
3703  .arg(_ui->doubleSpinBox_freenect2MaxDepth->value())
3704  .arg(_ui->doubleSpinBox_freenect2MaxDepth->value()+1));
3705  _ui->doubleSpinBox_freenect2MaxDepth->setValue(_ui->doubleSpinBox_freenect2MaxDepth->value()+1);
3706  }
3707 
3708  if(_ui->surf_doubleSpinBox_maxDepth->value() > 0.0 &&
3709  _ui->surf_doubleSpinBox_minDepth->value() >= _ui->surf_doubleSpinBox_maxDepth->value())
3710  {
3711  QMessageBox::warning(this, tr("Parameter warning"),
3712  tr("Visual word minimum depth (%1 m) should be lower than maximum depth (%2 m). Setting maximum depth to %3 m.")
3713  .arg(_ui->surf_doubleSpinBox_minDepth->value())
3714  .arg(_ui->surf_doubleSpinBox_maxDepth->value())
3715  .arg(_ui->surf_doubleSpinBox_maxDepth->value()+1));
3716  _ui->doubleSpinBox_freenect2MinDepth->setValue(0);
3717  }
3718 
3719  if(_ui->loopClosure_bowMaxDepth->value() > 0.0 &&
3720  _ui->loopClosure_bowMinDepth->value() >= _ui->loopClosure_bowMaxDepth->value())
3721  {
3722  QMessageBox::warning(this, tr("Parameter warning"),
3723  tr("Visual registration word minimum depth (%1 m) should be lower than maximum depth (%2 m). Setting maximum depth to %3 m.")
3724  .arg(_ui->loopClosure_bowMinDepth->value())
3725  .arg(_ui->loopClosure_bowMaxDepth->value())
3726  .arg(_ui->loopClosure_bowMaxDepth->value()+1));
3727  _ui->loopClosure_bowMinDepth->setValue(0);
3728  }
3729 
3730  if(_ui->fastThresholdMax->value() < _ui->fastThresholdMin->value())
3731  {
3732  QMessageBox::warning(this, tr("Parameter warning"),
3733  tr("FAST minimum threshold cannot be lower than maximum threshold. Setting minimum to 1."));
3734  _ui->fastThresholdMin->setValue(1);
3735  }
3736  if(_ui->fastThreshold->value() > _ui->fastThresholdMax->value())
3737  {
3738  QMessageBox::warning(this, tr("Parameter warning"),
3739  tr("FAST threshold cannot be higher than maximum threshold. Maximum value set to current threshold."));
3740  _ui->fastThresholdMax->setValue(_ui->fastThreshold->value());
3741  }
3742  if(_ui->fastThreshold->value() < _ui->fastThresholdMin->value())
3743  {
3744  QMessageBox::warning(this, tr("Parameter warning"),
3745  tr("FAST threshold cannot be lower than minimum threshold. Minimum value set to current threshold."));
3746  _ui->fastThresholdMin->setValue(_ui->fastThreshold->value());
3747  }
3748 
3749  if(_ui->checkbox_odomDisabled->isChecked() &&
3750  _ui->general_checkBox_SLAM_mode->isChecked() &&
3751  _ui->general_checkBox_activateRGBD->isChecked())
3752  {
3753  QMessageBox::warning(this, tr("Parameter warning"),
3754  tr("Odometry is disabled but incremental RGB-D SLAM is activated! Re-enabling odometry."));
3755  _ui->checkbox_odomDisabled->setChecked(false);
3756  }
3757 
3758 #if CV_MAJOR_VERSION < 3 || (CV_MAJOR_VERSION == 3 && (CV_MINOR_VERSION <4 || (CV_MINOR_VERSION ==4 && CV_SUBMINOR_VERSION<2)))
3759  if(_ui->ArucoDictionary->currentIndex()>=17)
3760  {
3761  QMessageBox::warning(this, tr("Parameter warning"),
3762  tr("ArUco dictionary: cannot select AprilTag dictionary, OpenCV version should be at least 3.4.2. Setting back to 0."));
3763  _ui->ArucoDictionary->setCurrentIndex(0);
3764  }
3765 #endif
3766 
3767  return true;
3768 }
3769 
3771 {
3772  return tr("Reading parameters from the configuration file...");
3773 }
3774 
3775 void PreferencesDialog::showEvent ( QShowEvent * event )
3776 {
3777  if(_monitoringState)
3778  {
3779  // In monitoring state, you cannot change remote paths
3780  _ui->lineEdit_dictionaryPath->setEnabled(false);
3781  _ui->toolButton_dictionaryPath->setEnabled(false);
3782  _ui->label_dictionaryPath->setEnabled(false);
3783 
3784  _ui->groupBox_source0->setEnabled(false);
3785  _ui->groupBox_odometry1->setEnabled(false);
3786 
3787  this->setWindowTitle(tr("Preferences [Monitoring mode]"));
3788  }
3789  else
3790  {
3791  _ui->lineEdit_dictionaryPath->setEnabled(true);
3792  _ui->toolButton_dictionaryPath->setEnabled(true);
3793  _ui->label_dictionaryPath->setEnabled(true);
3794 
3795  _ui->groupBox_source0->setEnabled(true);
3796  _ui->groupBox_odometry1->setEnabled(true);
3797 
3798  this->setWindowTitle(tr("Preferences"));
3799  }
3800 
3801  // setup logger filter
3802  std::map<std::string, unsigned long> threads = ULogger::getRegisteredThreads();
3803  std::vector<std::string> threadsChecked = this->getGeneralLoggerThreads();
3804  std::set<std::string> threadsCheckedSet(threadsChecked.begin(), threadsChecked.end());
3805  _ui->comboBox_loggerFilter->clear();
3806  for(std::map<std::string, unsigned long>::iterator iter=threads.begin(); iter!=threads.end(); ++iter)
3807  {
3808  if(threadsCheckedSet.find(iter->first.c_str()) != threadsCheckedSet.end())
3809  {
3810  _ui->comboBox_loggerFilter->addItem(QString(iter->first.c_str()), QVariant(true));
3811  }
3812  else
3813  {
3814  _ui->comboBox_loggerFilter->addItem(QString(iter->first.c_str()), QVariant(false));
3815  }
3816  }
3817 
3818  this->readSettingsBegin();
3819 }
3820 
3822 {
3823  _progressDialog->setLabelText(this->getParamMessage());
3824  _progressDialog->show();
3825 
3826  // this will let the MainThread to display the progress dialog before reading the parameters...
3827  QTimer::singleShot(10, this, SLOT(readSettingsEnd()));
3828 }
3829 
3831 {
3832  QApplication::processEvents();
3833 
3835 
3836  _progressDialog->setValue(1);
3837  if(this->isVisible())
3838  {
3839  _progressDialog->setLabelText(tr("Setup dialog..."));
3840 
3841  this->updatePredictionPlot();
3842  this->setupKpRoiPanel();
3843  }
3844 
3845  _progressDialog->setValue(2); // this will make closing...
3846 }
3847 
3848 void PreferencesDialog::saveWindowGeometry(const QWidget * window)
3849 {
3850  if(!window->objectName().isEmpty() && !window->isMaximized())
3851  {
3852  QSettings settings(getIniFilePath(), QSettings::IniFormat);
3853  settings.beginGroup("Gui");
3854  settings.beginGroup(window->objectName());
3855  settings.setValue("geometry", window->saveGeometry());
3856  settings.endGroup(); // "windowName"
3857  settings.endGroup(); // rtabmap
3858 
3859  QSettings settingsTmp(getTmpIniFilePath(), QSettings::IniFormat);
3860  settingsTmp.beginGroup("Gui");
3861  settingsTmp.beginGroup(window->objectName());
3862  settingsTmp.setValue("geometry", window->saveGeometry());
3863  settingsTmp.endGroup(); // "windowName"
3864  settingsTmp.endGroup(); // rtabmap
3865  }
3866 }
3867 
3869 {
3870  if(!window->objectName().isEmpty())
3871  {
3872  QByteArray bytes;
3873  QSettings settings(getIniFilePath(), QSettings::IniFormat);
3874  settings.beginGroup("Gui");
3875  settings.beginGroup(window->objectName());
3876  bytes = settings.value("geometry", QByteArray()).toByteArray();
3877  if(!bytes.isEmpty())
3878  {
3879  window->restoreGeometry(bytes);
3880  }
3881  settings.endGroup(); // "windowName"
3882  settings.endGroup(); // rtabmap
3883 
3884  QSettings settingsTmp(getTmpIniFilePath(), QSettings::IniFormat);
3885  settingsTmp.beginGroup("Gui");
3886  settingsTmp.beginGroup(window->objectName());
3887  settingsTmp.setValue("geometry", window->saveGeometry());
3888  settingsTmp.endGroup(); // "windowName"
3889  settingsTmp.endGroup(); // rtabmap
3890  }
3891 }
3892 
3893 void PreferencesDialog::saveMainWindowState(const QMainWindow * mainWindow)
3894 {
3895  if(!mainWindow->objectName().isEmpty())
3896  {
3897  saveWindowGeometry(mainWindow);
3898 
3899  QSettings settings(getIniFilePath(), QSettings::IniFormat);
3900  settings.beginGroup("Gui");
3901  settings.beginGroup(mainWindow->objectName());
3902  settings.setValue("state", mainWindow->saveState());
3903  settings.setValue("maximized", mainWindow->isMaximized());
3904  settings.setValue("status_bar", mainWindow->statusBar()->isVisible());
3905  settings.endGroup(); // "MainWindow"
3906  settings.endGroup(); // rtabmap
3907 
3908  QSettings settingsTmp(getTmpIniFilePath(), QSettings::IniFormat);
3909  settingsTmp.beginGroup("Gui");
3910  settingsTmp.beginGroup(mainWindow->objectName());
3911  settingsTmp.setValue("state", mainWindow->saveState());
3912  settingsTmp.setValue("maximized", mainWindow->isMaximized());
3913  settingsTmp.setValue("status_bar", mainWindow->statusBar()->isVisible());
3914  settingsTmp.endGroup(); // "MainWindow"
3915  settingsTmp.endGroup(); // rtabmap
3916  }
3917 }
3918 
3919 void PreferencesDialog::loadMainWindowState(QMainWindow * mainWindow, bool & maximized, bool & statusBarShown)
3920 {
3921  if(!mainWindow->objectName().isEmpty())
3922  {
3923  loadWindowGeometry(mainWindow);
3924 
3925  QByteArray bytes;
3926  QSettings settings(getIniFilePath(), QSettings::IniFormat);
3927  settings.beginGroup("Gui");
3928  settings.beginGroup(mainWindow->objectName());
3929  bytes = settings.value("state", QByteArray()).toByteArray();
3930  if(!bytes.isEmpty())
3931  {
3932  mainWindow->restoreState(bytes);
3933  }
3934  maximized = settings.value("maximized", false).toBool();
3935  statusBarShown = settings.value("status_bar", false).toBool();
3936  mainWindow->statusBar()->setVisible(statusBarShown);
3937  settings.endGroup(); // "MainWindow"
3938  settings.endGroup(); // rtabmap
3939 
3940  QSettings settingsTmp(getTmpIniFilePath(), QSettings::IniFormat);
3941  settingsTmp.beginGroup("Gui");
3942  settingsTmp.beginGroup(mainWindow->objectName());
3943  settingsTmp.setValue("state", mainWindow->saveState());
3944  settingsTmp.setValue("maximized", maximized);
3945  settingsTmp.setValue("status_bar", statusBarShown);
3946  settingsTmp.endGroup(); // "MainWindow"
3947  settingsTmp.endGroup(); // rtabmap
3948  }
3949 }
3950 
3951 void PreferencesDialog::saveWidgetState(const QWidget * widget)
3952 {
3953  if(!widget->objectName().isEmpty())
3954  {
3955  QSettings settings(getIniFilePath(), QSettings::IniFormat);
3956  settings.beginGroup("Gui");
3957  settings.beginGroup(widget->objectName());
3958 
3959  QSettings settingsTmp(getTmpIniFilePath(), QSettings::IniFormat);
3960  settingsTmp.beginGroup("Gui");
3961  settingsTmp.beginGroup(widget->objectName());
3962 
3963  const CloudViewer * cloudViewer = qobject_cast<const CloudViewer*>(widget);
3964  const ImageView * imageView = qobject_cast<const ImageView*>(widget);
3965  const ExportCloudsDialog * exportCloudsDialog = qobject_cast<const ExportCloudsDialog*>(widget);
3966  const ExportBundlerDialog * exportBundlerDialog = qobject_cast<const ExportBundlerDialog*>(widget);
3967  const PostProcessingDialog * postProcessingDialog = qobject_cast<const PostProcessingDialog *>(widget);
3968  const GraphViewer * graphViewer = qobject_cast<const GraphViewer *>(widget);
3969  const CalibrationDialog * calibrationDialog = qobject_cast<const CalibrationDialog *>(widget);
3970  const DepthCalibrationDialog * depthCalibrationDialog = qobject_cast<const DepthCalibrationDialog *>(widget);
3971 
3972  if(cloudViewer)
3973  {
3974  cloudViewer->saveSettings(settings);
3975  cloudViewer->saveSettings(settingsTmp);
3976  }
3977  else if(imageView)
3978  {
3979  imageView->saveSettings(settings);
3980  imageView->saveSettings(settingsTmp);
3981  }
3982  else if(exportCloudsDialog)
3983  {
3984  exportCloudsDialog->saveSettings(settings);
3985  exportCloudsDialog->saveSettings(settingsTmp);
3986  }
3987  else if(exportBundlerDialog)
3988  {
3989  exportBundlerDialog->saveSettings(settings);
3990  exportBundlerDialog->saveSettings(settingsTmp);
3991  }
3992  else if(postProcessingDialog)
3993  {
3994  postProcessingDialog->saveSettings(settings);
3995  postProcessingDialog->saveSettings(settingsTmp);
3996  }
3997  else if(graphViewer)
3998  {
3999  graphViewer->saveSettings(settings);
4000  graphViewer->saveSettings(settingsTmp);
4001  }
4002  else if(calibrationDialog)
4003  {
4004  calibrationDialog->saveSettings(settings);
4005  calibrationDialog->saveSettings(settingsTmp);
4006  }
4007  else if(depthCalibrationDialog)
4008  {
4009  depthCalibrationDialog->saveSettings(settings);
4010  depthCalibrationDialog->saveSettings(settingsTmp);
4011  }
4012  else
4013  {
4014  UERROR("Widget \"%s\" cannot be exported in config file.", widget->objectName().toStdString().c_str());
4015  }
4016 
4017  settings.endGroup(); // "name"
4018  settings.endGroup(); // Gui
4019  settingsTmp.endGroup();
4020  settingsTmp.endGroup();
4021  }
4022 }
4023 
4025 {
4026  if(!widget->objectName().isEmpty())
4027  {
4028  QByteArray bytes;
4029  QSettings settings(getIniFilePath(), QSettings::IniFormat);
4030  settings.beginGroup("Gui");
4031  settings.beginGroup(widget->objectName());
4032 
4033  QSettings settingsTmp(getTmpIniFilePath(), QSettings::IniFormat);
4034  settingsTmp.beginGroup("Gui");
4035  settingsTmp.beginGroup(widget->objectName());
4036 
4037  CloudViewer * cloudViewer = qobject_cast<CloudViewer*>(widget);
4038  ImageView * imageView = qobject_cast<ImageView*>(widget);
4039  ExportCloudsDialog * exportCloudsDialog = qobject_cast<ExportCloudsDialog*>(widget);
4040  ExportBundlerDialog * exportBundlerDialog = qobject_cast<ExportBundlerDialog*>(widget);
4041  PostProcessingDialog * postProcessingDialog = qobject_cast<PostProcessingDialog *>(widget);
4042  GraphViewer * graphViewer = qobject_cast<GraphViewer *>(widget);
4043  CalibrationDialog * calibrationDialog = qobject_cast<CalibrationDialog *>(widget);
4044  DepthCalibrationDialog * depthCalibrationDialog = qobject_cast<DepthCalibrationDialog *>(widget);
4045 
4046  if(cloudViewer)
4047  {
4048  cloudViewer->loadSettings(settings);
4049  cloudViewer->saveSettings(settingsTmp);
4050  }
4051  else if(imageView)
4052  {
4053  imageView->loadSettings(settings);
4054  imageView->saveSettings(settingsTmp);
4055  }
4056  else if(exportCloudsDialog)
4057  {
4058  exportCloudsDialog->loadSettings(settings);
4059  exportCloudsDialog->saveSettings(settingsTmp);
4060  }
4061  else if(exportBundlerDialog)
4062  {
4063  exportBundlerDialog->loadSettings(settings);
4064  exportBundlerDialog->saveSettings(settingsTmp);
4065  }
4066  else if(postProcessingDialog)
4067  {
4068  postProcessingDialog->loadSettings(settings);
4069  postProcessingDialog->saveSettings(settingsTmp);
4070  }
4071  else if(graphViewer)
4072  {
4073  graphViewer->loadSettings(settings);
4074  graphViewer->saveSettings(settingsTmp);
4075  }
4076  else if(calibrationDialog)
4077  {
4078  calibrationDialog->loadSettings(settings);
4079  calibrationDialog->saveSettings(settingsTmp);
4080  }
4081  else if(depthCalibrationDialog)
4082  {
4083  depthCalibrationDialog->loadSettings(settings);
4084  depthCalibrationDialog->saveSettings(settingsTmp);
4085  }
4086  else
4087  {
4088  UERROR("Widget \"%s\" cannot be loaded from config file.", widget->objectName().toStdString().c_str());
4089  }
4090 
4091  settings.endGroup(); //"name"
4092  settings.endGroup(); // Gui
4093  settingsTmp.endGroup(); //"name"
4094  settingsTmp.endGroup(); // Gui
4095  }
4096 }
4097 
4098 
4099 void PreferencesDialog::saveCustomConfig(const QString & section, const QString & key, const QString & value)
4100 {
4101  QSettings settings(getIniFilePath(), QSettings::IniFormat);
4102  settings.beginGroup("Gui");
4103  settings.beginGroup(section);
4104  settings.setValue(key, value);
4105  settings.endGroup(); // "section"
4106  settings.endGroup(); // rtabmap
4107 
4108  QSettings settingsTmp(getTmpIniFilePath(), QSettings::IniFormat);
4109  settingsTmp.beginGroup("Gui");
4110  settingsTmp.beginGroup(section);
4111  settingsTmp.setValue(key, value);
4112  settingsTmp.endGroup(); // "section"
4113  settingsTmp.endGroup(); // rtabmap
4114 }
4115 
4116 QString PreferencesDialog::loadCustomConfig(const QString & section, const QString & key)
4117 {
4118  QString value;
4119  QSettings settings(getIniFilePath(), QSettings::IniFormat);
4120  settings.beginGroup("Gui");
4121  settings.beginGroup(section);
4122  value = settings.value(key, QString()).toString();
4123  settings.endGroup(); // "section"
4124  settings.endGroup(); // rtabmap
4125 
4126  QSettings settingsTmp(getTmpIniFilePath(), QSettings::IniFormat);
4127  settingsTmp.beginGroup("Gui");
4128  settingsTmp.beginGroup(section);
4129  settingsTmp.setValue(key, value);
4130  settingsTmp.endGroup(); // "section"
4131  settingsTmp.endGroup(); // rtabmap
4132 
4133  return value;
4134 }
4135 
4137 {
4138  if(_parameters.size() != Parameters::getDefaultParameters().size())
4139  {
4140  UWARN("%d vs %d (Is PreferencesDialog::init() called?)", (int)_parameters.size(), (int)Parameters::getDefaultParameters().size());
4141  }
4142  ParametersMap parameters = _parameters;
4143  uInsert(parameters, _modifiedParameters);
4144 
4145  return parameters;
4146 }
4147 
4148 std::string PreferencesDialog::getParameter(const std::string & key) const
4149 {
4150  if(_modifiedParameters.find(key) != _modifiedParameters.end())
4151  {
4152  return _modifiedParameters.at(key);
4153  }
4154 
4155  UASSERT(_parameters.find(key) != _parameters.end());
4156  return _parameters.at(key);
4157 }
4158 
4159 void PreferencesDialog::updateParameters(const ParametersMap & parameters, bool setOtherParametersToDefault)
4160 {
4161  if(parameters.size())
4162  {
4163  for(rtabmap::ParametersMap::const_iterator iter = parameters.begin(); iter!=parameters.end(); ++iter)
4164  {
4165  this->setParameter(iter->first, iter->second);
4166  }
4167  if(setOtherParametersToDefault)
4168  {
4169  for(ParametersMap::const_iterator iter=Parameters::getDefaultParameters().begin();
4171  ++iter)
4172  {
4173  if(parameters.find(iter->first) == parameters.end() &&
4174  iter->first.compare(Parameters::kRtabmapWorkingDirectory())!=0)
4175  {
4176  this->setParameter(iter->first, iter->second);
4177  }
4178  }
4179  }
4180  if(!this->isVisible())
4181  {
4183  }
4184  }
4185 }
4186 
4188 {
4189  Src previousCameraSrc = getSourceDriver();
4190  Src previousLidarSrc = getLidarSourceDriver();
4191 
4192  if(_ui->comboBox_imuFilter_strategy->currentIndex()==0)
4193  {
4194  _ui->comboBox_imuFilter_strategy->setCurrentIndex(2);
4195  }
4196  _3dRenderingRoiRatios[0]->setText("0.0 0.0 0.0 0.0");
4197  _3dRenderingRoiRatios[1]->setText("0.0 0.0 0.0 0.0");
4198 
4199  if(src >= kSrcRGBD && src<kSrcStereo)
4200  {
4201  _ui->comboBox_sourceType->setCurrentIndex(0);
4202  _ui->comboBox_cameraRGBD->setCurrentIndex(src - kSrcRGBD);
4203  if(src == kSrcOpenNI_PCL)
4204  {
4205  _ui->lineEdit_openniOniPath->clear();
4206  }
4207  else if(src == kSrcOpenNI2)
4208  {
4209  _ui->lineEdit_openni2OniPath->clear();
4210  }
4211  else if (src == kSrcK4A)
4212  {
4213  _ui->lineEdit_k4a_mkv->clear();
4214  _3dRenderingRoiRatios[0]->setText("0.05 0.05 0.05 0.05");
4215  _3dRenderingRoiRatios[1]->setText("0.05 0.05 0.05 0.05");
4216  }
4217  else if (src == kSrcRealSense2)
4218  {
4219  if(variant > 0) // L515
4220  {
4221  _ui->spinBox_rs2_width->setValue(1280);
4222  _ui->spinBox_rs2_height->setValue(720);
4223  _ui->spinBox_rs2_rate->setValue(30);
4224  _ui->checkbox_rs2_irMode->setChecked(false);
4225  _ui->checkbox_rs2_emitter->setChecked(true);
4226  }
4227  else // D400
4228  {
4229  _ui->spinBox_rs2_width->setValue(848);
4230  _ui->spinBox_rs2_height->setValue(480);
4231  _ui->spinBox_rs2_rate->setValue(60);
4232  _ui->checkbox_rs2_irMode->setChecked(true);
4233  _ui->checkbox_rs2_emitter->setChecked(false);
4234  }
4235  }
4236  }
4237  else if(src >= kSrcStereo && src<kSrcRGB)
4238  {
4239  _ui->comboBox_sourceType->setCurrentIndex(1);
4240  _ui->comboBox_cameraStereo->setCurrentIndex(src - kSrcStereo);
4241 
4242  if(src == kSrcStereoZed) // Zedm, Zed2
4243  {
4244  // disable IMU filtering (zed sends already quaternion)
4245  _ui->comboBox_imuFilter_strategy->setCurrentIndex(0);
4246  }
4247  else if(src == kSrcStereoDepthAI) // OAK-D-Pro (variant==2), OAK-D (variant==1), OAK-D Lite (variant==0)
4248  {
4249  _ui->checkBox_depthai_imu_published->setChecked(variant >= 1);
4250  _ui->comboBox_depthai_resolution->setCurrentIndex(variant >= 1?1:3);
4251  _ui->comboBox_depthai_output_mode->setCurrentIndex(variant==2?2:0);
4252  _ui->doubleSpinBox_depthai_dot_intensity->setValue(variant==2?1:0);
4253  }
4254  }
4255  else if(src >= kSrcRGB && src<kSrcDatabase)
4256  {
4257  _ui->comboBox_sourceType->setCurrentIndex(2);
4258  _ui->source_comboBox_image_type->setCurrentIndex(src - kSrcRGB);
4259  }
4260  else if(src == kSrcDatabase)
4261  {
4262  _ui->comboBox_sourceType->setCurrentIndex(3);
4263  }
4264  else if(src >= kSrcLidar)
4265  {
4266  _ui->comboBox_lidar_src->setCurrentIndex(kSrcLidarVLP16 - kSrcLidar + 1);
4267  }
4268 
4269  if(previousCameraSrc == kSrcUndef && src < kSrcDatabase &&
4270  QMessageBox::question(this, tr("Camera Source..."),
4271  tr("Do you want to use default camera settings?"),
4272  QMessageBox::Yes | QMessageBox::No, QMessageBox::Yes) == QMessageBox::Yes)
4273  {
4274  loadPreset("");
4275  _ui->comboBox_lidar_src->setCurrentIndex(0); // Set Lidar to None;
4276  _ui->comboBox_odom_sensor->setCurrentIndex(0); // Set odom sensor to None
4277  }
4278  else if(previousLidarSrc== kSrcUndef && src >= kSrcLidar &&
4279  QMessageBox::question(this, tr("LiDAR Source..."),
4280  tr("Do you want to use \"LiDAR 3D ICP\" preset?"),
4281  QMessageBox::Yes | QMessageBox::No, QMessageBox::Yes) == QMessageBox::Yes)
4282  {
4283  loadPreset(LIDAR3D_ICP_INI);
4284  _ui->comboBox_sourceType->setCurrentIndex(4); // Set camera to None;
4285  _ui->comboBox_odom_sensor->setCurrentIndex(0); // Set odom sensor to No
4286  }
4287 
4288  if(validateForm())
4289  {
4290  // Even if there is no change, MainWindow should be notified
4292 
4294  }
4295  else
4296  {
4297  this->readSettingsBegin();
4298  }
4299 }
4300 
4301 bool sortCallback(const std::string & a, const std::string & b)
4302 {
4303  return uStrNumCmp(a,b) < 0;
4304 }
4305 
4307 {
4308  QString dir = _ui->source_database_lineEdit_path->text();
4309  if(dir.isEmpty())
4310  {
4311  dir = getWorkingDirectory();
4312  }
4313  QStringList paths = QFileDialog::getOpenFileNames(this, tr("Select file"), dir, tr("RTAB-Map database files (*.db)"));
4314  if(paths.size())
4315  {
4316  int r = QMessageBox::question(this, tr("Odometry in database..."), tr("Use odometry saved in database (if some saved)?"), QMessageBox::Yes | QMessageBox::No, QMessageBox::Yes);
4317  _ui->source_checkBox_ignoreOdometry->setChecked(r != QMessageBox::Yes);
4318 
4319  if (_ui->general_doubleSpinBox_detectionRate->value() != 0 && _ui->general_spinBox_imagesBufferSize->value() != 0)
4320  {
4321  r = QMessageBox::question(this, tr("Detection rate..."),
4322  tr("Do you want to process all frames? \n\nClicking \"Yes\" will set "
4323  "RTAB-Map's detection rate (%1 Hz) and buffer size (%2) to 0 to make "
4324  "sure that all frames are processed.")
4325  .arg(_ui->general_doubleSpinBox_detectionRate->value())
4326  .arg(_ui->general_spinBox_imagesBufferSize->value()),
4327  QMessageBox::Yes | QMessageBox::No, QMessageBox::Yes);
4328  if (r == QMessageBox::Yes)
4329  {
4330  _ui->general_doubleSpinBox_detectionRate->setValue(0.0);
4331  _ui->general_spinBox_imagesBufferSize->setValue(0);
4332  }
4333  }
4334 
4335  if(paths.size() > 1)
4336  {
4337  std::vector<std::string> vFileNames(paths.size());
4338  for(int i=0; i<paths.size(); ++i)
4339  {
4340  vFileNames[i] = paths[i].toStdString();
4341  }
4342  std::sort(vFileNames.begin(), vFileNames.end(), sortCallback);
4343  for(int i=0; i<paths.size(); ++i)
4344  {
4345  paths[i] = vFileNames[i].c_str();
4346  }
4347  }
4348 
4349  _ui->source_database_lineEdit_path->setText(paths.size()==1?paths.front():paths.join(";"));
4350  _ui->source_spinBox_databaseStartId->setValue(0);
4351  _ui->source_spinBox_databaseStopId->setValue(0);
4352  _ui->source_spinBox_database_cameraIndex->setValue(-1);
4353  }
4354 }
4355 
4357 {
4358  DatabaseViewer * viewer = new DatabaseViewer(getIniFilePath(), this);
4359  viewer->setWindowModality(Qt::WindowModal);
4360  viewer->setAttribute(Qt::WA_DeleteOnClose, true);
4361  viewer->showCloseButton();
4362  if(viewer->openDatabase(_ui->source_database_lineEdit_path->text()))
4363  {
4364  viewer->show();
4365  }
4366  else
4367  {
4368  delete viewer;
4369  }
4370 }
4371 
4373 {
4374  if(!_ui->lineEdit_source_distortionModel->text().isEmpty() &&
4375  QFileInfo(_ui->lineEdit_source_distortionModel->text()).exists())
4376  {
4378  model.load(_ui->lineEdit_source_distortionModel->text().toStdString());
4379  if(model.isValid())
4380  {
4381  cv::Mat img = model.visualize();
4382  QString name = QFileInfo(_ui->lineEdit_source_distortionModel->text()).baseName()+".png";
4383  cv::imwrite(name.toStdString(), img);
4384  QDesktopServices::openUrl(QUrl::fromLocalFile(name));
4385  }
4386  else
4387  {
4388  QMessageBox::warning(this, tr("Distortion Model"), tr("Model loaded from \"%1\" is not valid!").arg(_ui->lineEdit_source_distortionModel->text()));
4389  }
4390  }
4391  else
4392  {
4393  QMessageBox::warning(this, tr("Distortion Model"), tr("File \"%1\" doesn't exist!").arg(_ui->lineEdit_source_distortionModel->text()));
4394  }
4395 }
4396 
4398 {
4399  QString dir = _ui->lineEdit_calibrationFile->text();
4400  if(dir.isEmpty())
4401  {
4402  dir = getWorkingDirectory()+"/camera_info";
4403  }
4404  else if(!dir.contains('.'))
4405  {
4406  dir = getWorkingDirectory()+"/camera_info/"+dir;
4407  }
4408  QString path = QFileDialog::getOpenFileName(this, tr("Select file"), dir, tr("Calibration file (*.yaml)"));
4409  if(path.size())
4410  {
4411  _ui->lineEdit_calibrationFile->setText(path);
4412  }
4413 }
4414 
4416 {
4417  QString dir = _ui->lineEdit_odom_sensor_path_calibration->text();
4418  if(dir.isEmpty())
4419  {
4420  dir = getWorkingDirectory()+"/camera_info";
4421  }
4422  else if(!dir.contains('.'))
4423  {
4424  dir = getWorkingDirectory()+"/camera_info/"+dir;
4425  }
4426  QString path = QFileDialog::getOpenFileName(this, tr("Select file"), dir, tr("Calibration file (*.yaml)"));
4427  if(path.size())
4428  {
4429  _ui->lineEdit_odom_sensor_path_calibration->setText(path);
4430  }
4431 }
4432 
4434 {
4435  QString dir = _ui->lineEdit_cameraImages_timestamps->text();
4436  if(dir.isEmpty())
4437  {
4438  dir = getWorkingDirectory();
4439  }
4440  QString path = QFileDialog::getOpenFileName(this, tr("Select file"), dir, tr("Timestamps file (*.txt)"));
4441  if(path.size())
4442  {
4443  _ui->lineEdit_cameraImages_timestamps->setText(path);
4444  }
4445 }
4446 
4448 {
4449  QString dir = _ui->lineEdit_cameraRGBDImages_path_rgb->text();
4450  if(dir.isEmpty())
4451  {
4452  dir = getWorkingDirectory();
4453  }
4454  QString path = QFileDialog::getExistingDirectory(this, tr("Select RGB images directory"), dir);
4455  if(path.size())
4456  {
4457  _ui->lineEdit_cameraRGBDImages_path_rgb->setText(path);
4458  }
4459 }
4460 
4461 
4463 {
4464  QString dir = _ui->lineEdit_cameraImages_path_scans->text();
4465  if(dir.isEmpty())
4466  {
4467  dir = getWorkingDirectory();
4468  }
4469  QString path = QFileDialog::getExistingDirectory(this, tr("Select scans directory"), dir);
4470  if(path.size())
4471  {
4472  _ui->lineEdit_cameraImages_path_scans->setText(path);
4473  }
4474 }
4475 
4477 {
4478  QString dir = _ui->lineEdit_cameraImages_path_imu->text();
4479  if(dir.isEmpty())
4480  {
4481  dir = getWorkingDirectory();
4482  }
4483  QString path = QFileDialog::getOpenFileName(this, tr("Select file "), dir, tr("EuRoC IMU file (*.csv)"));
4484  if(path.size())
4485  {
4486  _ui->lineEdit_cameraImages_path_imu->setText(path);
4487  }
4488 }
4489 
4490 
4492 {
4493  QString dir = _ui->lineEdit_cameraRGBDImages_path_depth->text();
4494  if(dir.isEmpty())
4495  {
4496  dir = getWorkingDirectory();
4497  }
4498  QString path = QFileDialog::getExistingDirectory(this, tr("Select depth images directory"), dir);
4499  if(path.size())
4500  {
4501  _ui->lineEdit_cameraRGBDImages_path_depth->setText(path);
4502  }
4503 }
4504 
4506 {
4507  QString dir = _ui->lineEdit_cameraImages_odom->text();
4508  if(dir.isEmpty())
4509  {
4510  dir = getWorkingDirectory();
4511  }
4512  QString path = QFileDialog::getOpenFileName(this, tr("Select file"), dir, tr("Odometry (*.txt *.log *.toro *.g2o *.csv)"));
4513  if(path.size())
4514  {
4515  QStringList list;
4516  for(int i=0; i<_ui->comboBox_cameraImages_odomFormat->count(); ++i)
4517  {
4518  list.push_back(_ui->comboBox_cameraImages_odomFormat->itemText(i));
4519  }
4520  QString item = QInputDialog::getItem(this, tr("Odometry Format"), tr("Format:"), list, _ui->comboBox_cameraImages_odomFormat->currentIndex(), false);
4521  if(!item.isEmpty())
4522  {
4523  _ui->lineEdit_cameraImages_odom->setText(path);
4524  _ui->comboBox_cameraImages_odomFormat->setCurrentIndex(_ui->comboBox_cameraImages_odomFormat->findText(item));
4525  }
4526  }
4527 }
4528 
4530 {
4531  QString dir = _ui->lineEdit_cameraImages_gt->text();
4532  if(dir.isEmpty())
4533  {
4534  dir = getWorkingDirectory();
4535  }
4536  QString path = QFileDialog::getOpenFileName(this, tr("Select file"), dir, tr("Ground Truth (*.txt *.log *.toro *.g2o *.csv)"));
4537  if(path.size())
4538  {
4539  QStringList list;
4540  for(int i=0; i<_ui->comboBox_cameraImages_gtFormat->count(); ++i)
4541  {
4542  list.push_back(_ui->comboBox_cameraImages_gtFormat->itemText(i));
4543  }
4544  QString item = QInputDialog::getItem(this, tr("Ground Truth Format"), tr("Format:"), list, _ui->comboBox_cameraImages_gtFormat->currentIndex(), false);
4545  if(!item.isEmpty())
4546  {
4547  _ui->lineEdit_cameraImages_gt->setText(path);
4548  _ui->comboBox_cameraImages_gtFormat->setCurrentIndex(_ui->comboBox_cameraImages_gtFormat->findText(item));
4549  }
4550  }
4551 }
4552 
4554 {
4555  QString dir = _ui->lineEdit_cameraStereoImages_path_left->text();
4556  if(dir.isEmpty())
4557  {
4558  dir = getWorkingDirectory();
4559  }
4560  QString path = QFileDialog::getExistingDirectory(this, tr("Select left images directory"), dir);
4561  if(path.size())
4562  {
4563  _ui->lineEdit_cameraStereoImages_path_left->setText(path);
4564  }
4565 }
4566 
4568 {
4569  QString dir = _ui->lineEdit_cameraStereoImages_path_right->text();
4570  if(dir.isEmpty())
4571  {
4572  dir = getWorkingDirectory();
4573  }
4574  QString path = QFileDialog::getExistingDirectory(this, tr("Select right images directory"), dir);
4575  if(path.size())
4576  {
4577  _ui->lineEdit_cameraStereoImages_path_right->setText(path);
4578  }
4579 }
4580 
4582 {
4583  QString dir = _ui->source_images_lineEdit_path->text();
4584  if(dir.isEmpty())
4585  {
4586  dir = getWorkingDirectory();
4587  }
4588  QString path = QFileDialog::getExistingDirectory(this, tr("Select images directory"), _ui->source_images_lineEdit_path->text());
4589  if(!path.isEmpty())
4590  {
4591  _ui->source_images_lineEdit_path->setText(path);
4592  _ui->source_images_spinBox_startPos->setValue(0);
4593  _ui->source_images_spinBox_maxFrames->setValue(0);
4594  }
4595 }
4596 
4598 {
4599  QString dir = _ui->source_video_lineEdit_path->text();
4600  if(dir.isEmpty())
4601  {
4602  dir = getWorkingDirectory();
4603  }
4604  QString path = QFileDialog::getOpenFileName(this, tr("Select file"), dir, tr("Videos (*.avi *.mpg *.mp4 *.mov *.mkv)"));
4605  if(!path.isEmpty())
4606  {
4607  _ui->source_video_lineEdit_path->setText(path);
4608  }
4609 }
4610 
4612 {
4613  QString dir = _ui->lineEdit_cameraStereoVideo_path->text();
4614  if(dir.isEmpty())
4615  {
4616  dir = getWorkingDirectory();
4617  }
4618  QString path = QFileDialog::getOpenFileName(this, tr("Select file"), dir, tr("Videos (*.avi *.mpg *.mp4 *.mov *.mkv)"));
4619  if(!path.isEmpty())
4620  {
4621  _ui->lineEdit_cameraStereoVideo_path->setText(path);
4622  }
4623 }
4624 
4626 {
4627  QString dir = _ui->lineEdit_cameraStereoVideo_path_2->text();
4628  if(dir.isEmpty())
4629  {
4630  dir = getWorkingDirectory();
4631  }
4632  QString path = QFileDialog::getOpenFileName(this, tr("Select file"), dir, tr("Videos (*.avi *.mpg *.mp4 *.mov *.mkv)"));
4633  if(!path.isEmpty())
4634  {
4635  _ui->lineEdit_cameraStereoVideo_path_2->setText(path);
4636  }
4637 }
4638 
4640 {
4641  QString dir = _ui->lineEdit_source_distortionModel->text();
4642  if(dir.isEmpty())
4643  {
4644  dir = getWorkingDirectory();
4645  }
4646  QString path = QFileDialog::getOpenFileName(this, tr("Select file"), dir, tr("Distortion model (*.bin *.txt)"));
4647  if(!path.isEmpty())
4648  {
4649  _ui->lineEdit_source_distortionModel->setText(path);
4650  }
4651 }
4652 
4654 {
4655  QString dir = _ui->lineEdit_openniOniPath->text();
4656  if(dir.isEmpty())
4657  {
4658  dir = getWorkingDirectory();
4659  }
4660  QString path = QFileDialog::getOpenFileName(this, tr("Select file"), dir, tr("OpenNI (*.oni)"));
4661  if(!path.isEmpty())
4662  {
4663  _ui->lineEdit_openniOniPath->setText(path);
4664  }
4665 }
4666 
4668 {
4669  QString dir = _ui->lineEdit_openni2OniPath->text();
4670  if(dir.isEmpty())
4671  {
4672  dir = getWorkingDirectory();
4673  }
4674  QString path = QFileDialog::getOpenFileName(this, tr("Select file"), dir, tr("OpenNI (*.oni)"));
4675  if(!path.isEmpty())
4676  {
4677  _ui->lineEdit_openni2OniPath->setText(path);
4678  }
4679 }
4680 
4682 {
4683  QString dir = _ui->lineEdit_k4a_mkv->text();
4684  if (dir.isEmpty())
4685  {
4686  dir = getWorkingDirectory();
4687  }
4688  QString path = QFileDialog::getOpenFileName(this, tr("Select file"), dir, tr("K4A recording (*.mkv)"));
4689  if (!path.isEmpty())
4690  {
4691  _ui->lineEdit_k4a_mkv->setText(path);
4692  }
4693 }
4694 
4696 {
4697  QString dir = _ui->lineEdit_zedSvoPath->text();
4698  if(dir.isEmpty())
4699  {
4700  dir = getWorkingDirectory();
4701  }
4702  QString path = QFileDialog::getOpenFileName(this, tr("Select file"), dir, tr("ZED (*.svo)"));
4703  if(!path.isEmpty())
4704  {
4705  _ui->lineEdit_zedSvoPath->setText(path);
4706  }
4707 }
4708 
4710 {
4711  QString dir = _ui->lineEdit_rs2_jsonFile->text();
4712  if(dir.isEmpty())
4713  {
4714  dir = getWorkingDirectory();
4715  }
4716  QString path = QFileDialog::getOpenFileName(this, tr("Select RealSense2 preset"), dir, tr("JSON (*.json)"));
4717  if(path.size())
4718  {
4719  _ui->lineEdit_rs2_jsonFile->setText(path);
4720  }
4721 }
4722 
4724 {
4725  QString dir = _ui->lineEdit_depthai_blob_path->text();
4726  if(dir.isEmpty())
4727  {
4728  dir = getWorkingDirectory();
4729  }
4730  QString path = QFileDialog::getOpenFileName(this, tr("Select file"), dir, tr("MyriadX blob (*.blob)"));
4731  if(path.size())
4732  {
4733  _ui->lineEdit_depthai_blob_path->setText(path);
4734  }
4735 }
4736 
4738 {
4739  QString dir = _ui->lineEdit_vlp16_pcap_path->text();
4740  if (dir.isEmpty())
4741  {
4742  dir = getWorkingDirectory();
4743  }
4744  QString path = QFileDialog::getOpenFileName(this, tr("Select file"), dir, tr("Velodyne recording (*.pcap)"));
4745  if (!path.isEmpty())
4746  {
4747  _ui->lineEdit_vlp16_pcap_path->setText(path);
4748  }
4749 }
4750 
4751 void PreferencesDialog::setParameter(const std::string & key, const std::string & value)
4752 {
4753  UDEBUG("%s=%s", key.c_str(), value.c_str());
4754  QWidget * obj = _ui->stackedWidget->findChild<QWidget*>(key.c_str());
4755  if(obj)
4756  {
4758 
4759  QSpinBox * spin = qobject_cast<QSpinBox *>(obj);
4760  QDoubleSpinBox * doubleSpin = qobject_cast<QDoubleSpinBox *>(obj);
4761  QComboBox * combo = qobject_cast<QComboBox *>(obj);
4762  QCheckBox * check = qobject_cast<QCheckBox *>(obj);
4763  QRadioButton * radio = qobject_cast<QRadioButton *>(obj);
4764  QLineEdit * lineEdit = qobject_cast<QLineEdit *>(obj);
4765  QGroupBox * groupBox = qobject_cast<QGroupBox *>(obj);
4766  bool ok;
4767  if(spin)
4768  {
4769  spin->setValue(QString(value.c_str()).toInt(&ok));
4770  if(!ok)
4771  {
4772  UERROR("Conversion failed from \"%s\" for parameter %s", value.c_str(), key.c_str());
4773  }
4774  }
4775  else if(doubleSpin)
4776  {
4777  doubleSpin->setValue(QString(value.c_str()).toDouble(&ok));
4778  if(!ok)
4779  {
4780  UERROR("Conversion failed from \"%s\" for parameter %s", value.c_str(), key.c_str());
4781  }
4782  }
4783  else if(combo)
4784  {
4785  //backward compatibility
4786  std::string valueCpy = value;
4787  if( key.compare(Parameters::kIcpStrategy()) == 0 ||
4788  key.compare(Parameters::kGridSensor()) == 0)
4789  {
4790  if(value.compare("true") == 0)
4791  {
4792  valueCpy = "1";
4793  }
4794  else if(value.compare("false") == 0)
4795  {
4796  valueCpy = "0";
4797  }
4798  }
4799 
4800  int valueInt = QString(valueCpy.c_str()).toInt(&ok);
4801  if(!ok)
4802  {
4803  UERROR("Conversion failed from \"%s\" for parameter %s", valueCpy.c_str(), key.c_str());
4804  }
4805  else
4806  {
4807 #ifndef RTABMAP_NONFREE
4808  if(valueInt == 0 &&
4809  (combo->objectName().toStdString().compare(Parameters::kKpDetectorStrategy()) == 0 ||
4810  combo->objectName().toStdString().compare(Parameters::kVisFeatureType()) == 0))
4811  {
4812  UWARN("Trying to set \"%s\" to SURF but RTAB-Map isn't built "
4813  "with the nonfree module from OpenCV. Keeping default combo value: %s.",
4814  combo->objectName().toStdString().c_str(),
4815  combo->currentText().toStdString().c_str());
4816  ok = false;
4817  }
4818 #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)))
4819  if(valueInt == 1 &&
4820  (combo->objectName().toStdString().compare(Parameters::kKpDetectorStrategy()) == 0 ||
4821  combo->objectName().toStdString().compare(Parameters::kVisFeatureType()) == 0))
4822  {
4823  UWARN("Trying to set \"%s\" to SIFT but RTAB-Map isn't built "
4824  "with the nonfree module from OpenCV. Keeping default combo value: %s.",
4825  combo->objectName().toStdString().c_str(),
4826  combo->currentText().toStdString().c_str());
4827  ok = false;
4828  }
4829 #endif
4830 #endif
4831 #ifndef RTABMAP_ORB_SLAM
4833 #endif
4834  {
4835  if(valueInt==1 && combo->objectName().toStdString().compare(Parameters::kOptimizerStrategy()) == 0)
4836  {
4837  UWARN("Trying to set \"%s\" to g2o but RTAB-Map isn't built "
4838  "with g2o. Keeping default combo value: %s.",
4839  combo->objectName().toStdString().c_str(),
4840  combo->currentText().toStdString().c_str());
4841  ok = false;
4842  }
4843  }
4845  {
4846  if(valueInt==2 && combo->objectName().toStdString().compare(Parameters::kOptimizerStrategy()) == 0)
4847  {
4848  UWARN("Trying to set \"%s\" to GTSAM but RTAB-Map isn't built "
4849  "with GTSAM. Keeping default combo value: %s.",
4850  combo->objectName().toStdString().c_str(),
4851  combo->currentText().toStdString().c_str());
4852  ok = false;
4853  }
4854  }
4855  if(ok)
4856  {
4857  combo->setCurrentIndex(valueInt);
4858  }
4859  }
4860 
4861  }
4862  else if(check)
4863  {
4864  _ui->checkBox_useOdomFeatures->blockSignals(true);
4865  check->setChecked(uStr2Bool(value.c_str()));
4866  _ui->checkBox_useOdomFeatures->blockSignals(false);
4867  }
4868  else if(radio)
4869  {
4870  radio->setChecked(uStr2Bool(value.c_str()));
4871  }
4872  else if(lineEdit)
4873  {
4874  lineEdit->setText(value.c_str());
4875  }
4876  else if(groupBox)
4877  {
4878  groupBox->setChecked(uStr2Bool(value.c_str()));
4879  }
4880  else
4881  {
4882  ULOGGER_WARN("QObject called %s can't be cast to a supported widget", key.c_str());
4883  }
4884  }
4885  else
4886  {
4887  ULOGGER_WARN("Can't find the related QObject for parameter %s", key.c_str());
4888  }
4889 }
4890 
4892 {
4893  if(sender())
4894  {
4895  this->addParameter(sender(), value);
4896  }
4897  else
4898  {
4899  ULOGGER_ERROR("This slot must be triggered by a signal, not a direct call...");
4900  }
4901 }
4902 
4904 {
4905  if(sender())
4906  {
4907  this->addParameter(sender(), value);
4908  }
4909  else
4910  {
4911  ULOGGER_ERROR("This slot must be triggered by a signal, not a direct call...");
4912  }
4913 }
4914 
4916 {
4917  if(sender())
4918  {
4919  this->addParameter(sender(), value);
4920  }
4921  else
4922  {
4923  ULOGGER_ERROR("This slot must be triggered by a signal, not a direct call...");
4924  }
4925 }
4926 
4927 void PreferencesDialog::addParameter(const QString & value)
4928 {
4929  if(sender())
4930  {
4931  this->addParameter(sender(), value);
4932  }
4933  else
4934  {
4935  ULOGGER_ERROR("This slot must be triggered by a signal, not a direct call...");
4936  }
4937 }
4938 
4939 void PreferencesDialog::addParameter(const QObject * object, int value)
4940 {
4941  if(object)
4942  {
4943  const QComboBox * comboBox = qobject_cast<const QComboBox*>(object);
4944  const QSpinBox * spinbox = qobject_cast<const QSpinBox*>(object);
4945  if(comboBox || spinbox)
4946  {
4947  // Add parameter
4948  UDEBUG("modify param %s=%s", object->objectName().toStdString().c_str(), uNumber2Str(value).c_str());
4949  uInsert(_modifiedParameters, rtabmap::ParametersPair(object->objectName().toStdString(), QString::number(value).toStdString()));
4950  }
4951  else
4952  {
4953  UWARN("Undefined object \"%s\"", object->objectName().toStdString().c_str());
4954  }
4955 
4956  }
4957  else
4958  {
4959  ULOGGER_ERROR("Object is null");
4960  }
4961 }
4962 
4963 void PreferencesDialog::addParameter(const QObject * object, bool value)
4964 {
4965  if(object)
4966  {
4967  const QCheckBox * checkbox = qobject_cast<const QCheckBox*>(object);
4968  const QRadioButton * radio = qobject_cast<const QRadioButton*>(object);
4969  const QGroupBox * groupBox = qobject_cast<const QGroupBox*>(object);
4970  if(checkbox || radio || groupBox)
4971  {
4972  // Add parameter
4973  UDEBUG("modify param %s=%s", object->objectName().toStdString().c_str(), uBool2Str(value).c_str());
4974  uInsert(_modifiedParameters, rtabmap::ParametersPair(object->objectName().toStdString(), uBool2Str(value)));
4975  }
4976  else
4977  {
4978  UWARN("Undefined object \"%s\"", object->objectName().toStdString().c_str());
4979  }
4980 
4981  }
4982  else
4983  {
4984  ULOGGER_ERROR("Object is null");
4985  }
4986 }
4987 
4988 void PreferencesDialog::addParameter(const QObject * object, double value)
4989 {
4990  if(object)
4991  {
4992  UDEBUG("modify param %s=%f", object->objectName().toStdString().c_str(), value);
4993  uInsert(_modifiedParameters, rtabmap::ParametersPair(object->objectName().toStdString(), QString::number(value).toStdString()));
4994  }
4995  else
4996  {
4997  ULOGGER_ERROR("Object is null");
4998  }
4999 }
5000 
5001 void PreferencesDialog::addParameter(const QObject * object, const QString & value)
5002 {
5003  if(object)
5004  {
5005  UDEBUG("modify param %s=%s", object->objectName().toStdString().c_str(), value.toStdString().c_str());
5006  uInsert(_modifiedParameters, rtabmap::ParametersPair(object->objectName().toStdString(), value.toStdString()));
5007  }
5008  else
5009  {
5010  ULOGGER_ERROR("Object is null");
5011  }
5012 }
5013 
5014 void PreferencesDialog::addParameters(const QObjectList & children)
5015 {
5016  //ULOGGER_DEBUG("PreferencesDialog::addParameters(QGroupBox) box %s has %d children", box->objectName().toStdString().c_str(), children.size());
5017  for(int i=0; i<children.size(); ++i)
5018  {
5019  const QSpinBox * spin = qobject_cast<const QSpinBox *>(children[i]);
5020  const QDoubleSpinBox * doubleSpin = qobject_cast<const QDoubleSpinBox *>(children[i]);
5021  const QComboBox * combo = qobject_cast<const QComboBox *>(children[i]);
5022  const QCheckBox * check = qobject_cast<const QCheckBox *>(children[i]);
5023  const QRadioButton * radio = qobject_cast<const QRadioButton *>(children[i]);
5024  const QLineEdit * lineEdit = qobject_cast<const QLineEdit *>(children[i]);
5025  const QGroupBox * groupBox = qobject_cast<const QGroupBox *>(children[i]);
5026  const QStackedWidget * stackedWidget = qobject_cast<const QStackedWidget *>(children[i]);
5027  if(spin)
5028  {
5029  this->addParameter(spin, spin->value());
5030  }
5031  else if(doubleSpin)
5032  {
5033  this->addParameter(doubleSpin, doubleSpin->value());
5034  }
5035  else if(combo)
5036  {
5037  this->addParameter(combo, combo->currentIndex());
5038  }
5039  else if(check)
5040  {
5041  this->addParameter(check, check->isChecked());
5042  }
5043  else if(radio)
5044  {
5045  this->addParameter(radio, radio->isChecked());
5046  }
5047  else if(lineEdit)
5048  {
5049  this->addParameter(lineEdit, lineEdit->text());
5050  }
5051  else if(groupBox)
5052  {
5053  if(groupBox->isCheckable())
5054  {
5055  this->addParameter(groupBox, groupBox->isChecked());
5056  }
5057  else
5058  {
5059  this->addParameters(groupBox);
5060  }
5061  }
5062  else if(stackedWidget)
5063  {
5064  this->addParameters(stackedWidget);
5065  }
5066  }
5067 }
5068 
5069 void PreferencesDialog::addParameters(const QStackedWidget * stackedWidget, int panel)
5070 {
5071  if(stackedWidget)
5072  {
5073  if(panel == -1)
5074  {
5075  for(int i=0; i<stackedWidget->count(); ++i)
5076  {
5077  const QObjectList & children = stackedWidget->widget(i)->children();
5078  addParameters(children);
5079  }
5080  }
5081  else
5082  {
5083  UASSERT(panel<stackedWidget->count());
5084  const QObjectList & children = stackedWidget->widget(panel)->children();
5085  addParameters(children);
5086  }
5087  }
5088 }
5089 
5090 void PreferencesDialog::addParameters(const QGroupBox * box)
5091 {
5092  if(box)
5093  {
5094  const QObjectList & children = box->children();
5095  addParameters(children);
5096  }
5097 }
5098 
5100 {
5101  UDEBUG("");
5102 
5103  // This method is used to update basic/advanced referred parameters, see above editingFinished()
5104 
5105  // basic to advanced (advanced to basic must be done by connecting signal valueChanged())
5106  if(sender() == _ui->general_doubleSpinBox_timeThr_2)
5107  {
5108  _ui->general_doubleSpinBox_timeThr->setValue(_ui->general_doubleSpinBox_timeThr_2->value());
5109  }
5110  else if(sender() == _ui->general_doubleSpinBox_hardThr_2)
5111  {
5112  _ui->general_doubleSpinBox_hardThr->setValue(_ui->general_doubleSpinBox_hardThr_2->value());
5113  }
5114  else if(sender() == _ui->general_doubleSpinBox_detectionRate_2)
5115  {
5116  _ui->general_doubleSpinBox_detectionRate->setValue(_ui->general_doubleSpinBox_detectionRate_2->value());
5117  }
5118  else if(sender() == _ui->general_spinBox_imagesBufferSize_2)
5119  {
5120  _ui->general_spinBox_imagesBufferSize->setValue(_ui->general_spinBox_imagesBufferSize_2->value());
5121  }
5122  else if(sender() == _ui->general_spinBox_maxStMemSize_2)
5123  {
5124  _ui->general_spinBox_maxStMemSize->setValue(_ui->general_spinBox_maxStMemSize_2->value());
5125  }
5126  else if(sender() == _ui->groupBox_publishing)
5127  {
5128  _ui->general_checkBox_publishStats_2->setChecked(_ui->groupBox_publishing->isChecked());
5129  }
5130  else if(sender() == _ui->general_checkBox_publishStats_2)
5131  {
5132  _ui->groupBox_publishing->setChecked(_ui->general_checkBox_publishStats_2->isChecked());
5133  }
5134  else if(sender() == _ui->doubleSpinBox_similarityThreshold_2)
5135  {
5136  _ui->doubleSpinBox_similarityThreshold->setValue(_ui->doubleSpinBox_similarityThreshold_2->value());
5137  }
5138  else if(sender() == _ui->general_checkBox_activateRGBD)
5139  {
5140  _ui->general_checkBox_activateRGBD_2->blockSignals(true);
5141  _ui->general_checkBox_activateRGBD_2->setChecked(_ui->general_checkBox_activateRGBD->isChecked());
5142  _ui->general_checkBox_activateRGBD_2->blockSignals(false);
5143  }
5144  else if(sender() == _ui->general_checkBox_activateRGBD_2)
5145  {
5146  _ui->general_checkBox_activateRGBD->blockSignals(true);
5147  _ui->general_checkBox_activateRGBD->setChecked(_ui->general_checkBox_activateRGBD_2->isChecked());
5148  addParameter(_ui->general_checkBox_activateRGBD, _ui->general_checkBox_activateRGBD->isChecked());
5149  _ui->general_checkBox_activateRGBD->blockSignals(false);
5150  }
5151  else if(sender() == _ui->general_checkBox_SLAM_mode)
5152  {
5153  _ui->general_checkBox_SLAM_mode_2->blockSignals(true);
5154  _ui->general_checkBox_SLAM_mode_2->setChecked(_ui->general_checkBox_SLAM_mode->isChecked());
5155  _ui->general_checkBox_SLAM_mode_2->blockSignals(false);
5156  }
5157  else if(sender() == _ui->general_checkBox_SLAM_mode_2)
5158  {
5159  _ui->general_checkBox_SLAM_mode->blockSignals(true);
5160  _ui->general_checkBox_SLAM_mode->setChecked(_ui->general_checkBox_SLAM_mode_2->isChecked());
5161  addParameter(_ui->general_checkBox_SLAM_mode, _ui->general_checkBox_SLAM_mode->isChecked());
5162  _ui->general_checkBox_SLAM_mode->blockSignals(false);
5163  }
5164  else
5165  {
5166  //update all values (only those using editingFinished signal)
5167  _ui->general_doubleSpinBox_timeThr->setValue(_ui->general_doubleSpinBox_timeThr_2->value());
5168  _ui->general_doubleSpinBox_hardThr->setValue(_ui->general_doubleSpinBox_hardThr_2->value());
5169  _ui->general_doubleSpinBox_detectionRate->setValue(_ui->general_doubleSpinBox_detectionRate_2->value());
5170  _ui->general_spinBox_imagesBufferSize->setValue(_ui->general_spinBox_imagesBufferSize_2->value());
5171  _ui->general_spinBox_maxStMemSize->setValue(_ui->general_spinBox_maxStMemSize_2->value());
5172  _ui->doubleSpinBox_similarityThreshold->setValue(_ui->doubleSpinBox_similarityThreshold_2->value());
5173  }
5174 }
5175 
5177 {
5178  ULOGGER_DEBUG("");
5180 }
5181 
5183 {
5184  ULOGGER_DEBUG("");
5186 }
5187 
5189 {
5190  ULOGGER_DEBUG("");
5192 }
5193 
5195 {
5196  ULOGGER_DEBUG("");
5198 }
5199 
5201 {
5202  ULOGGER_DEBUG("");
5204 }
5205 
5207 {
5208  QList<QGroupBox*> boxes;
5209  for(int i=0; i<_ui->stackedWidget->count(); ++i)
5210  {
5211  QGroupBox * gb = 0;
5212  const QObjectList & children = _ui->stackedWidget->widget(i)->children();
5213  for(int j=0; j<children.size(); ++j)
5214  {
5215  if((gb = qobject_cast<QGroupBox *>(children.at(j))))
5216  {
5217  //ULOGGER_DEBUG("PreferencesDialog::setupTreeView() index(%d) Added %s, box name=%s", i, gb->title().toStdString().c_str(), gb->objectName().toStdString().c_str());
5218  break;
5219  }
5220  }
5221  if(gb)
5222  {
5223  boxes.append(gb);
5224  }
5225  else
5226  {
5227  ULOGGER_ERROR("A QGroupBox must be included in the first level of children in stacked widget, index=%d", i);
5228  }
5229  }
5230  return boxes;
5231 }
5232 
5234 {
5235  QStringList values = _ui->lineEdit_bayes_predictionLC->text().simplified().split(' ');
5236  if(values.size() < 2)
5237  {
5238  UERROR("Error parsing prediction (must have at least 2 items) : %s",
5239  _ui->lineEdit_bayes_predictionLC->text().toStdString().c_str());
5240  return;
5241  }
5242  QVector<qreal> dataX((values.size()-2)*2 + 1);
5243  QVector<qreal> dataY((values.size()-2)*2 + 1);
5244  double value;
5245  double sum = 0;
5246  int lvl = 1;
5247  bool ok = false;
5248  bool error = false;
5249  int loopClosureIndex = (dataX.size()-1)/2;
5250  for(int i=0; i<values.size(); ++i)
5251  {
5252  value = values.at(i).toDouble(&ok);
5253  if(!ok)
5254  {
5255  UERROR("Error parsing prediction : \"%s\"", values.at(i).toStdString().c_str());
5256  error = true;
5257  }
5258  sum+=value;
5259  if(i==0)
5260  {
5261  //do nothing
5262  }
5263  else if(i == 1)
5264  {
5265  dataY[loopClosureIndex] = value;
5266  dataX[loopClosureIndex] = 0;
5267  }
5268  else
5269  {
5270  dataY[loopClosureIndex-lvl] = value;
5271  dataX[loopClosureIndex-lvl] = -lvl;
5272  dataY[loopClosureIndex+lvl] = value;
5273  dataX[loopClosureIndex+lvl] = lvl;
5274  ++lvl;
5275  }
5276  }
5277 
5278  _ui->label_prediction_sum->setNum(sum);
5279  if(error)
5280  {
5281  _ui->label_prediction_sum->setText(QString("<font color=#FF0000>") + _ui->label_prediction_sum->text() + "</font>");
5282  }
5283  else if(sum == 1.0)
5284  {
5285  _ui->label_prediction_sum->setText(QString("<font color=#00FF00>") + _ui->label_prediction_sum->text() + "</font>");
5286  }
5287  else if(sum > 1.0)
5288  {
5289  _ui->label_prediction_sum->setText(QString("<font color=#FFa500>") + _ui->label_prediction_sum->text() + "</font>");
5290  }
5291  else
5292  {
5293  _ui->label_prediction_sum->setText(QString("<font color=#000000>") + _ui->label_prediction_sum->text() + "</font>");
5294  }
5295 
5296  _ui->predictionPlot->removeCurves();
5297  _ui->predictionPlot->addCurve(new UPlotCurve("Prediction", dataX, dataY, _ui->predictionPlot));
5298 }
5299 
5301 {
5302  QStringList strings = _ui->lineEdit_kp_roi->text().split(' ');
5303  if(strings.size()!=4)
5304  {
5305  UERROR("ROI must have 4 values (%s)", _ui->lineEdit_kp_roi->text().toStdString().c_str());
5306  return;
5307  }
5308  _ui->doubleSpinBox_kp_roi0->setValue(strings[0].toDouble()*100.0);
5309  _ui->doubleSpinBox_kp_roi1->setValue(strings[1].toDouble()*100.0);
5310  _ui->doubleSpinBox_kp_roi2->setValue(strings[2].toDouble()*100.0);
5311  _ui->doubleSpinBox_kp_roi3->setValue(strings[3].toDouble()*100.0);
5312 }
5313 
5315 {
5316  QStringList strings;
5317  strings.append(QString::number(_ui->doubleSpinBox_kp_roi0->value()/100.0));
5318  strings.append(QString::number(_ui->doubleSpinBox_kp_roi1->value()/100.0));
5319  strings.append(QString::number(_ui->doubleSpinBox_kp_roi2->value()/100.0));
5320  strings.append(QString::number(_ui->doubleSpinBox_kp_roi3->value()/100.0));
5321  _ui->lineEdit_kp_roi->setText(strings.join(" "));
5322 }
5323 
5325 {
5326  Src driver = this->getSourceDriver();
5327  _ui->checkbox_stereo_depthGenerated->setVisible(
5329  _ui->comboBox_stereoZed_quality->currentIndex() == 0);
5330  _ui->label_stereo_depthGenerated->setVisible(
5332  _ui->comboBox_stereoZed_quality->currentIndex() == 0);
5333 
5334  _ui->checkBox_stereo_rectify->setEnabled(
5335  _ui->comboBox_cameraStereo->currentIndex() == kSrcStereoImages - kSrcStereo ||
5336  _ui->comboBox_cameraStereo->currentIndex() == kSrcStereoUsb - kSrcStereo ||
5337  _ui->comboBox_cameraStereo->currentIndex() == kSrcStereoTara - kSrcStereo ||
5338  _ui->comboBox_cameraStereo->currentIndex() == kSrcStereoVideo - kSrcStereo ||
5339  _ui->comboBox_cameraStereo->currentIndex() == kSrcDC1394 - kSrcStereo ||
5340  _ui->comboBox_cameraStereo->currentIndex() == kSrcStereoRealSense2 - kSrcStereo);
5341  _ui->checkBox_stereo_rectify->setVisible(_ui->checkBox_stereo_rectify->isEnabled());
5342  _ui->label_stereo_rectify->setVisible(_ui->checkBox_stereo_rectify->isEnabled());
5343 }
5344 
5346 {
5347  _ui->groupBox_pymatcher->setVisible(_ui->reextract_nn->currentIndex() == 6);
5348  _ui->groupBox_gms->setVisible(_ui->reextract_nn->currentIndex() == 7);
5349 }
5350 
5352 {
5353  _ui->groupBox_pydescriptor->setVisible(_ui->comboBox_globalDescriptorExtractor->currentIndex() == 1);
5354 }
5355 
5357 {
5358  if(index == 11) // FLOAM -> LOAM
5359  {
5360  _ui->stackedWidget_odometryType->setCurrentIndex(7);
5361  }
5362  else
5363  {
5364  _ui->stackedWidget_odometryType->setCurrentIndex(index);
5365  }
5366  _ui->groupBox_odomF2M->setVisible(index==0);
5367  _ui->groupBox_odomF2F->setVisible(index==1);
5368  _ui->groupBox_odomFovis->setVisible(index==2);
5369  _ui->groupBox_odomViso2->setVisible(index==3);
5370  _ui->groupBox_odomDVO->setVisible(index==4);
5371  _ui->groupBox_odomORBSLAM->setVisible(index==5);
5372  _ui->groupBox_odomOKVIS->setVisible(index==6);
5373  _ui->groupBox_odomLOAM->setVisible(index==7);
5374  _ui->groupBox_odomMSCKF->setVisible(index==8);
5375  _ui->groupBox_odomVINS->setVisible(index==9);
5376  _ui->groupBox_odomOpenVINS->setVisible(index==10);
5377  _ui->groupBox_odomOpen3D->setVisible(index==12);
5378 }
5379 
5381 {
5382  if(this->isVisible() && _ui->checkBox_useOdomFeatures->isChecked())
5383  {
5384  int r = QMessageBox::question(this, tr("Using odometry features for vocabulary..."),
5385  tr("Do you want to match vocabulary feature parameters "
5386  "with corresponding ones used for odometry?"), QMessageBox::Yes | QMessageBox::No, QMessageBox::Yes);
5387 
5388  if(r == QMessageBox::Yes)
5389  {
5390  _ui->comboBox_detector_strategy->setCurrentIndex(_ui->vis_feature_detector->currentIndex());
5391  _ui->surf_doubleSpinBox_maxDepth->setValue(_ui->loopClosure_bowMaxDepth->value());
5392  _ui->surf_doubleSpinBox_minDepth->setValue(_ui->loopClosure_bowMinDepth->value());
5393  _ui->surf_spinBox_wordsPerImageTarget->setValue(_ui->reextract_maxFeatures->value());
5394  _ui->checkBox_kp_ssc->setChecked(_ui->checkBox_visSSC->isChecked());
5395  _ui->spinBox_KPGridRows->setValue(_ui->reextract_gridrows->value());
5396  _ui->spinBox_KPGridCols->setValue(_ui->reextract_gridcols->value());
5397  _ui->lineEdit_kp_roi->setText(_ui->loopClosure_roi->text());
5398  _ui->subpix_winSize_kp->setValue(_ui->subpix_winSize->value());
5399  _ui->subpix_iterations_kp->setValue(_ui->subpix_iterations->value());
5400  _ui->subpix_eps_kp->setValue(_ui->subpix_eps->value());
5401  }
5402  }
5403 }
5404 
5406 {
5407  QString directory = QFileDialog::getExistingDirectory(this, tr("Working directory"), _ui->lineEdit_workingDirectory->text());
5408  if(!directory.isEmpty())
5409  {
5410  ULOGGER_DEBUG("New working directory = %s", directory.toStdString().c_str());
5411  _ui->lineEdit_workingDirectory->setText(directory);
5412  }
5413 }
5414 
5416 {
5417  QString path;
5418  if(_ui->lineEdit_dictionaryPath->text().isEmpty())
5419  {
5420  path = QFileDialog::getOpenFileName(this, tr("Dictionary"), this->getWorkingDirectory(), tr("Dictionary (*.txt *.db)"));
5421  }
5422  else
5423  {
5424  path = QFileDialog::getOpenFileName(this, tr("Dictionary"), _ui->lineEdit_dictionaryPath->text(), tr("Dictionary (*.txt *.db)"));
5425  }
5426  if(!path.isEmpty())
5427  {
5428  _ui->lineEdit_dictionaryPath->setText(path);
5429  }
5430 }
5431 
5433 {
5434  QString path;
5435  if(_ui->lineEdit_OdomORBSLAMVocPath->text().isEmpty())
5436  {
5437  path = QFileDialog::getOpenFileName(this, tr("ORBSLAM Vocabulary"), this->getWorkingDirectory(), tr("Vocabulary (*.txt)"));
5438  }
5439  else
5440  {
5441  path = QFileDialog::getOpenFileName(this, tr("ORBSLAM Vocabulary"), _ui->lineEdit_OdomORBSLAMVocPath->text(), tr("Vocabulary (*.txt)"));
5442  }
5443  if(!path.isEmpty())
5444  {
5445  _ui->lineEdit_OdomORBSLAMVocPath->setText(path);
5446  }
5447 }
5448 
5450 {
5451  QString path;
5452  if(_ui->lineEdit_OdomOkvisPath->text().isEmpty())
5453  {
5454  path = QFileDialog::getOpenFileName(this, tr("OKVIS Config"), this->getWorkingDirectory(), tr("OKVIS config (*.yaml)"));
5455  }
5456  else
5457  {
5458  path = QFileDialog::getOpenFileName(this, tr("OKVIS Config"), _ui->lineEdit_OdomOkvisPath->text(), tr("OKVIS config (*.yaml)"));
5459  }
5460  if(!path.isEmpty())
5461  {
5462  _ui->lineEdit_OdomOkvisPath->setText(path);
5463  }
5464 }
5465 
5467 {
5468  QString path;
5469  if(_ui->lineEdit_OdomVinsPath->text().isEmpty())
5470  {
5471  path = QFileDialog::getOpenFileName(this, tr("VINS-Fusion Config"), this->getWorkingDirectory(), tr("VINS-Fusion config (*.yaml)"));
5472  }
5473  else
5474  {
5475  path = QFileDialog::getOpenFileName(this, tr("VINS-Fusion Config"), _ui->lineEdit_OdomVinsPath->text(), tr("VINS-Fusion config (*.yaml)"));
5476  }
5477  if(!path.isEmpty())
5478  {
5479  _ui->lineEdit_OdomVinsPath->setText(path);
5480  }
5481 }
5482 
5484 {
5485  QString path;
5486  if(_ui->lineEdit_OdomOpenVINSLeftMaskPath->text().isEmpty())
5487  {
5488  path = QFileDialog::getOpenFileName(this, tr("Select Left Mask"), this->getWorkingDirectory(), tr("Image mask (*.jpg *.png)"));
5489  }
5490  else
5491  {
5492  path = QFileDialog::getOpenFileName(this, tr("Select Left Mask"), _ui->lineEdit_OdomOpenVINSLeftMaskPath->text(), tr("Image mask (*.jpg *.png)"));
5493  }
5494  if(!path.isEmpty())
5495  {
5496  _ui->lineEdit_OdomOpenVINSLeftMaskPath->setText(path);
5497  }
5498 }
5499 
5501 {
5502  QString path;
5503  if(_ui->lineEdit_OdomOpenVINSRightMaskPath->text().isEmpty())
5504  {
5505  path = QFileDialog::getOpenFileName(this, tr("Select Right Mask"), this->getWorkingDirectory(), tr("Image mask (*.jpg *.png)"));
5506  }
5507  else
5508  {
5509  path = QFileDialog::getOpenFileName(this, tr("Select Right Mask"), _ui->lineEdit_OdomOpenVINSRightMaskPath->text(), tr("Image mask (*.jpg *.png)"));
5510  }
5511  if(!path.isEmpty())
5512  {
5513  _ui->lineEdit_OdomOpenVINSRightMaskPath->setText(path);
5514  }
5515 }
5516 
5518 {
5519  QString path;
5520  if(_ui->lineEdit_IcpPMConfigPath->text().isEmpty())
5521  {
5522  path = QFileDialog::getOpenFileName(this, tr("Select file"), this->getWorkingDirectory(), tr("libpointmatcher (*.yaml)"));
5523  }
5524  else
5525  {
5526  path = QFileDialog::getOpenFileName(this, tr("Select file"), _ui->lineEdit_IcpPMConfigPath->text(), tr("libpointmatcher (*.yaml)"));
5527  }
5528  if(!path.isEmpty())
5529  {
5530  _ui->lineEdit_IcpPMConfigPath->setText(path);
5531  }
5532 }
5533 
5535 {
5536  QString path;
5537  if(_ui->lineEdit_sptorch_path->text().isEmpty())
5538  {
5539  path = QFileDialog::getOpenFileName(this, tr("Select file"), this->getWorkingDirectory(), tr("SuperPoint weights (*.pt)"));
5540  }
5541  else
5542  {
5543  path = QFileDialog::getOpenFileName(this, tr("Select file"), _ui->lineEdit_sptorch_path->text(), tr("SuperPoint weights (*.pt)"));
5544  }
5545  if(!path.isEmpty())
5546  {
5547  _ui->lineEdit_sptorch_path->setText(path);
5548  }
5549 }
5550 
5552 {
5553  QString path;
5554  if(_ui->lineEdit_pymatcher_path->text().isEmpty())
5555  {
5556  path = QFileDialog::getOpenFileName(this, tr("Select file"), this->getWorkingDirectory(), tr("Python wrapper (*.py)"));
5557  }
5558  else
5559  {
5560  path = QFileDialog::getOpenFileName(this, tr("Select file"), _ui->lineEdit_pymatcher_path->text(), tr("Python wrapper (*.py)"));
5561  }
5562  if(!path.isEmpty())
5563  {
5564  _ui->lineEdit_pymatcher_path->setText(path);
5565  }
5566 }
5567 
5569 {
5570  QString path;
5571  if(_ui->lineEdit_pymatcher_model->text().isEmpty())
5572  {
5573  path = QFileDialog::getOpenFileName(this, tr("Select file"), this->getWorkingDirectory(), tr("PyTorch model (*.pth *.pt)"));
5574  }
5575  else
5576  {
5577  path = QFileDialog::getOpenFileName(this, tr("Select file"), _ui->lineEdit_pymatcher_model->text(), tr("PyTorch model (*.pth *.pt)"));
5578  }
5579  if(!path.isEmpty())
5580  {
5581  _ui->lineEdit_pymatcher_model->setText(path);
5582  }
5583 }
5584 
5586 {
5587  QString path;
5588  if(_ui->lineEdit_pydescriptor_path->text().isEmpty())
5589  {
5590  path = QFileDialog::getOpenFileName(this, tr("Select file"), this->getWorkingDirectory(), tr("Python wrapper (*.py)"));
5591  }
5592  else
5593  {
5594  path = QFileDialog::getOpenFileName(this, tr("Select file"), _ui->lineEdit_pydescriptor_path->text(), tr("Python wrapper (*.py)"));
5595  }
5596  if(!path.isEmpty())
5597  {
5598  _ui->lineEdit_pydescriptor_path->setText(path);
5599  }
5600 }
5602 {
5603  QString path;
5604  if(_ui->lineEdit_pydetector_path->text().isEmpty())
5605  {
5606  path = QFileDialog::getOpenFileName(this, tr("Select file"), this->getWorkingDirectory(), tr("Python wrapper (*.py)"));
5607  }
5608  else
5609  {
5610  path = QFileDialog::getOpenFileName(this, tr("Select file"), _ui->lineEdit_pydetector_path->text(), tr("Python wrapper (*.py)"));
5611  }
5612  if(!path.isEmpty())
5613  {
5614  _ui->lineEdit_pydetector_path->setText(path);
5615  }
5616 }
5617 
5619 {
5620  _ui->stackedWidget_src->setVisible(_ui->comboBox_sourceType->currentIndex() != 4); // Not Camera None
5621  _ui->frame_camera_sensor->setVisible(_ui->comboBox_sourceType->currentIndex() != 4); // Not Camera None
5622 
5623  _ui->groupBox_sourceRGBD->setVisible(_ui->comboBox_sourceType->currentIndex() == 0);
5624  _ui->groupBox_sourceStereo->setVisible(_ui->comboBox_sourceType->currentIndex() == 1);
5625  _ui->groupBox_sourceRGB->setVisible(_ui->comboBox_sourceType->currentIndex() == 2);
5626  _ui->groupBox_sourceDatabase->setVisible(_ui->comboBox_sourceType->currentIndex() == 3);
5627 
5628  _ui->stackedWidget_rgbd->setVisible(_ui->comboBox_sourceType->currentIndex() == 0 &&
5629  (_ui->comboBox_cameraRGBD->currentIndex() == kSrcOpenNI2-kSrcRGBD ||
5630  _ui->comboBox_cameraRGBD->currentIndex() == kSrcFreenect2-kSrcRGBD ||
5631  _ui->comboBox_cameraRGBD->currentIndex() == kSrcK4W2 - kSrcRGBD ||
5632  _ui->comboBox_cameraRGBD->currentIndex() == kSrcK4A - kSrcRGBD ||
5633  _ui->comboBox_cameraRGBD->currentIndex() == kSrcRealSense - kSrcRGBD ||
5634  _ui->comboBox_cameraRGBD->currentIndex() == kSrcRGBDImages-kSrcRGBD ||
5635  _ui->comboBox_cameraRGBD->currentIndex() == kSrcOpenNI_PCL-kSrcRGBD ||
5636  _ui->comboBox_cameraRGBD->currentIndex() == kSrcRealSense2-kSrcRGBD ||
5637  _ui->comboBox_cameraRGBD->currentIndex() == kSrcSeerSense-kSrcRGBD));
5638  _ui->groupBox_openni2->setVisible(_ui->comboBox_sourceType->currentIndex() == 0 && _ui->comboBox_cameraRGBD->currentIndex() == kSrcOpenNI2-kSrcRGBD);
5639  _ui->groupBox_freenect2->setVisible(_ui->comboBox_sourceType->currentIndex() == 0 && _ui->comboBox_cameraRGBD->currentIndex() == kSrcFreenect2-kSrcRGBD);
5640  _ui->groupBox_k4w2->setVisible(_ui->comboBox_sourceType->currentIndex() == 0 && _ui->comboBox_cameraRGBD->currentIndex() == kSrcK4W2 - kSrcRGBD);
5641  _ui->groupBox_k4a->setVisible(_ui->comboBox_sourceType->currentIndex() == 0 && _ui->comboBox_cameraRGBD->currentIndex() == kSrcK4A - kSrcRGBD);
5642  _ui->groupBox_realsense->setVisible(_ui->comboBox_sourceType->currentIndex() == 0 && _ui->comboBox_cameraRGBD->currentIndex() == kSrcRealSense - kSrcRGBD);
5643  _ui->groupBox_realsense2->setVisible(_ui->comboBox_sourceType->currentIndex() == 0 && _ui->comboBox_cameraRGBD->currentIndex() == kSrcRealSense2 - kSrcRGBD);
5644  _ui->groupBox_cameraRGBDImages->setVisible(_ui->comboBox_sourceType->currentIndex() == 0 && _ui->comboBox_cameraRGBD->currentIndex() == kSrcRGBDImages-kSrcRGBD);
5645  _ui->groupBox_openni->setVisible(_ui->comboBox_sourceType->currentIndex() == 0 && _ui->comboBox_cameraRGBD->currentIndex() == kSrcOpenNI_PCL - kSrcRGBD);
5646 
5647  _ui->stackedWidget_stereo->setVisible(_ui->comboBox_sourceType->currentIndex() == 1 &&
5648  (_ui->comboBox_cameraStereo->currentIndex() == kSrcStereoVideo-kSrcStereo ||
5649  _ui->comboBox_cameraStereo->currentIndex() == kSrcStereoImages-kSrcStereo ||
5650  _ui->comboBox_cameraStereo->currentIndex() == kSrcStereoZed - kSrcStereo ||
5651  _ui->comboBox_cameraStereo->currentIndex() == kSrcStereoUsb - kSrcStereo ||
5652  _ui->comboBox_cameraStereo->currentIndex() == kSrcStereoMyntEye - kSrcStereo ||
5653  _ui->comboBox_cameraStereo->currentIndex() == kSrcStereoZedOC - kSrcStereo ||
5654  _ui->comboBox_cameraStereo->currentIndex() == kSrcStereoDepthAI - kSrcStereo));
5655  _ui->groupBox_cameraStereoImages->setVisible(_ui->comboBox_sourceType->currentIndex() == 1 && _ui->comboBox_cameraStereo->currentIndex() == kSrcStereoImages-kSrcStereo);
5656  _ui->groupBox_cameraStereoVideo->setVisible(_ui->comboBox_sourceType->currentIndex() == 1 && _ui->comboBox_cameraStereo->currentIndex() == kSrcStereoVideo - kSrcStereo);
5657  _ui->groupBox_cameraStereoUsb->setVisible(_ui->comboBox_sourceType->currentIndex() == 1 && _ui->comboBox_cameraStereo->currentIndex() == kSrcStereoUsb - kSrcStereo);
5658  _ui->groupBox_cameraStereoZed->setVisible(_ui->comboBox_sourceType->currentIndex() == 1 && _ui->comboBox_cameraStereo->currentIndex() == kSrcStereoZed - kSrcStereo);
5659  _ui->groupBox_cameraMyntEye->setVisible(_ui->comboBox_sourceType->currentIndex() == 1 && _ui->comboBox_cameraStereo->currentIndex() == kSrcStereoMyntEye - kSrcStereo);
5660  _ui->groupBox_cameraStereoZedOC->setVisible(_ui->comboBox_sourceType->currentIndex() == 1 && _ui->comboBox_cameraStereo->currentIndex() == kSrcStereoZedOC - kSrcStereo);
5661  _ui->groupBox_cameraDepthAI->setVisible(_ui->comboBox_sourceType->currentIndex() == 1 && _ui->comboBox_cameraStereo->currentIndex() == kSrcStereoDepthAI - kSrcStereo);
5662 
5663  _ui->stackedWidget_image->setVisible(_ui->comboBox_sourceType->currentIndex() == 2 &&
5664  (_ui->source_comboBox_image_type->currentIndex() == kSrcImages-kSrcRGB ||
5665  _ui->source_comboBox_image_type->currentIndex() == kSrcVideo-kSrcRGB ||
5666  _ui->source_comboBox_image_type->currentIndex() == kSrcUsbDevice-kSrcRGB));
5667  _ui->source_groupBox_images->setVisible(_ui->comboBox_sourceType->currentIndex() == 2 && _ui->source_comboBox_image_type->currentIndex() == kSrcImages-kSrcRGB);
5668  _ui->source_groupBox_video->setVisible(_ui->comboBox_sourceType->currentIndex() == 2 && _ui->source_comboBox_image_type->currentIndex() == kSrcVideo-kSrcRGB);
5669  _ui->source_groupBox_usbcam->setVisible(_ui->comboBox_sourceType->currentIndex() == 2 && _ui->source_comboBox_image_type->currentIndex() == kSrcUsbDevice-kSrcRGB);
5670 
5671  _ui->groupBox_sourceImages_optional->setVisible(
5672  (_ui->comboBox_sourceType->currentIndex() == 0 && _ui->comboBox_cameraRGBD->currentIndex() == kSrcRGBDImages-kSrcRGBD) ||
5673  (_ui->comboBox_sourceType->currentIndex() == 1 && _ui->comboBox_cameraStereo->currentIndex() == kSrcStereoImages-kSrcStereo) ||
5674  (_ui->comboBox_sourceType->currentIndex() == 2 && _ui->source_comboBox_image_type->currentIndex() == kSrcImages-kSrcRGB));
5675 
5676  _ui->groupBox_depthImageFiltering->setEnabled(
5677  _ui->comboBox_sourceType->currentIndex() == 0 || // RGBD
5678  _ui->comboBox_sourceType->currentIndex() == 3); // Database
5679  _ui->groupBox_depthImageFiltering->setVisible(_ui->groupBox_depthImageFiltering->isEnabled());
5680 
5681  _ui->groupBox_depthFromScan->setVisible(_ui->comboBox_sourceType->currentIndex() == 2 && _ui->source_comboBox_image_type->currentIndex() == kSrcImages-kSrcRGB);
5682 
5683  // Odom Sensor Group
5684  _ui->frame_visual_odometry_sensor->setVisible(getOdomSourceDriver() != kSrcUndef); // Not Lidar None
5685  _ui->groupBox_odom_sensor->setVisible(_ui->comboBox_sourceType->currentIndex() != 3); // Don't show when database is selected
5686 
5687  // Lidar Sensor Group
5688  _ui->comboBox_lidar_src->setEnabled(_ui->comboBox_sourceType->currentIndex() != 3); // Disable if database input
5689  if(!_ui->comboBox_lidar_src->isEnabled() && _ui->comboBox_lidar_src->currentIndex() != 0)
5690  {
5691  _ui->comboBox_lidar_src->setCurrentIndex(0); // Set to none
5692  }
5693  _ui->checkBox_source_scanFromDepth->setEnabled(_ui->comboBox_sourceType->currentIndex() <= 1 || _ui->comboBox_sourceType->currentIndex() == 3);
5694  _ui->label_source_scanFromDepth->setEnabled(_ui->checkBox_source_scanFromDepth->isEnabled());
5695  if(!_ui->checkBox_source_scanFromDepth->isEnabled())
5696  {
5697  _ui->checkBox_source_scanFromDepth->setChecked(false);
5698  }
5699  _ui->stackedWidget_lidar_src->setVisible(_ui->comboBox_lidar_src->currentIndex() > 0);
5700  _ui->groupBox_vlp16->setVisible(_ui->comboBox_lidar_src->currentIndex()-1 == kSrcLidarVLP16-kSrcLidar);
5701  _ui->frame_lidar_sensor->setVisible(_ui->comboBox_lidar_src->currentIndex() > 0 || _ui->checkBox_source_scanFromDepth->isChecked()); // Not Lidar None or database input
5702  _ui->pushButton_test_lidar->setEnabled(_ui->comboBox_lidar_src->currentIndex() > 0);
5703 
5704  // IMU group
5705  _ui->groupBox_imuFiltering->setEnabled(
5706  (_ui->comboBox_sourceType->currentIndex() == 0 && _ui->comboBox_cameraRGBD->currentIndex() == kSrcRGBDImages-kSrcRGBD) ||
5707  (_ui->comboBox_sourceType->currentIndex() == 1 && _ui->comboBox_cameraStereo->currentIndex() == kSrcStereoImages-kSrcStereo) ||
5708  (_ui->comboBox_sourceType->currentIndex() == 2 && _ui->source_comboBox_image_type->currentIndex() == kSrcImages-kSrcRGB) ||
5709  (_ui->comboBox_sourceType->currentIndex() == 0 && _ui->comboBox_cameraRGBD->currentIndex() == kSrcFreenect - kSrcRGBD) || //Kinect360
5710  (_ui->comboBox_sourceType->currentIndex() == 0 && _ui->comboBox_cameraRGBD->currentIndex() == kSrcK4A - kSrcRGBD) || //K4A
5711  (_ui->comboBox_sourceType->currentIndex() == 0 && _ui->comboBox_cameraRGBD->currentIndex() == kSrcRealSense2 - kSrcRGBD) || //D435i
5712  (_ui->comboBox_sourceType->currentIndex() == 0 && _ui->comboBox_cameraRGBD->currentIndex() == kSrcSeerSense - kSrcRGBD) ||
5713  (_ui->comboBox_sourceType->currentIndex() == 1 && _ui->comboBox_cameraStereo->currentIndex() == kSrcStereoRealSense2 - kSrcStereo) || //T265
5714  (_ui->comboBox_sourceType->currentIndex() == 1 && _ui->comboBox_cameraStereo->currentIndex() == kSrcStereoZed - kSrcStereo) || // ZEDm, ZED2
5715  (_ui->comboBox_sourceType->currentIndex() == 1 && _ui->comboBox_cameraStereo->currentIndex() == kSrcStereoMyntEye - kSrcStereo) || // MYNT EYE S
5716  (_ui->comboBox_sourceType->currentIndex() == 1 && _ui->comboBox_cameraStereo->currentIndex() == kSrcStereoZedOC - kSrcStereo) ||
5717  (_ui->comboBox_sourceType->currentIndex() == 1 && _ui->comboBox_cameraStereo->currentIndex() == kSrcStereoDepthAI - kSrcStereo));
5718  _ui->frame_imu_filtering->setVisible(getIMUFilteringStrategy() > 0); // Not None
5719  _ui->stackedWidget_imuFilter->setVisible(_ui->comboBox_imuFilter_strategy->currentIndex() > 0);
5720  _ui->groupBox_madgwickfilter->setVisible(_ui->comboBox_imuFilter_strategy->currentIndex() == 1);
5721  _ui->groupBox_complementaryfilter->setVisible(_ui->comboBox_imuFilter_strategy->currentIndex() == 2);
5722  _ui->groupBox_imuFiltering->setVisible(_ui->groupBox_imuFiltering->isEnabled());
5723 }
5724 
5725 /*** GETTERS ***/
5726 //General
5728 {
5729  return _ui->comboBox_loggerLevel->currentIndex();
5730 }
5732 {
5733  return _ui->comboBox_loggerEventLevel->currentIndex();
5734 }
5736 {
5737  return _ui->comboBox_loggerPauseLevel->currentIndex();
5738 }
5740 {
5741  return _ui->comboBox_loggerType->currentIndex();
5742 }
5744 {
5745  return _ui->checkBox_logger_printTime->isChecked();
5746 }
5748 {
5749  return _ui->checkBox_logger_printThreadId->isChecked();
5750 }
5751 std::vector<std::string> PreferencesDialog::getGeneralLoggerThreads() const
5752 {
5753  std::vector<std::string> threads;
5754  for(int i=0; i<_ui->comboBox_loggerFilter->count(); ++i)
5755  {
5756  if(_ui->comboBox_loggerFilter->itemData(i).toBool())
5757  {
5758  threads.push_back(_ui->comboBox_loggerFilter->itemText(i).toStdString());
5759  }
5760  }
5761  return threads;
5762 }
5764 {
5765  return _ui->checkBox_verticalLayoutUsed->isChecked();
5766 }
5768 {
5769  return _ui->checkBox_imageRejectedShown->isChecked();
5770 }
5772 {
5773  return _ui->checkBox_imageHighestHypShown->isChecked();
5774 }
5776 {
5777  return _ui->checkBox_beep->isChecked();
5778 }
5780 {
5781  return _ui->checkBox_stamps->isChecked();
5782 }
5784 {
5785  return _ui->checkBox_cacheStatistics->isChecked();
5786 }
5788 {
5789  return _ui->checkBox_notifyWhenNewGlobalPathIsReceived->isChecked();
5790 }
5792 {
5793  return _ui->spinBox_odomQualityWarnThr->value();
5794 }
5796 {
5797  return _ui->checkBox_odom_onlyInliersShown->isChecked();
5798 }
5800 {
5801  return _ui->radioButton_posteriorGraphView->isChecked();
5802 }
5804 {
5805  return _ui->radioButton_wordsGraphView->isChecked();
5806 }
5808 {
5809  return _ui->radioButton_localizationsGraphView->isChecked();
5810 }
5812 {
5813  return _ui->radioButton_localizationsGraphViewOdomCache->isChecked();
5814 }
5816 {
5817  return _ui->checkbox_odomDisabled->isChecked();
5818 }
5820 {
5821  return _ui->checkBox_odom_sensor_use_as_gt->isChecked();
5822 }
5824 {
5825  return _ui->odom_registration->currentIndex();
5826 }
5828 {
5829  return _ui->odom_f2m_gravitySigma->value();
5830 }
5832 {
5833  return _ui->checkbox_groundTruthAlign->isChecked();
5834 }
5835 
5837 {
5838  UASSERT(index >= 0 && index <= 1);
5839  return _3dRenderingShowClouds[index]->isChecked();
5840 }
5842 {
5843 #ifdef RTABMAP_OCTOMAP
5844  return _ui->groupBox_octomap->isChecked();
5845 #endif
5846  return false;
5847 }
5849 {
5850 #ifdef RTABMAP_OCTOMAP
5851  return _ui->groupBox_octomap->isChecked() && _ui->checkBox_octomap_show3dMap->isChecked();
5852 #endif
5853  return false;
5854 }
5856 {
5857  return _ui->comboBox_octomap_renderingType->currentIndex();
5858 }
5860 {
5861 #ifdef RTABMAP_OCTOMAP
5862  return _ui->groupBox_octomap->isChecked() && _ui->checkBox_octomap_2dgrid->isChecked();
5863 #endif
5864  return false;
5865 }
5867 {
5868  return _ui->spinBox_octomap_treeDepth->value();
5869 }
5871 {
5872  return _ui->spinBox_octomap_pointSize->value();
5873 }
5874 
5876 {
5877  return _ui->doubleSpinBox_voxel->value();
5878 }
5880 {
5881  return _ui->doubleSpinBox_noiseRadius->value();
5882 }
5884 {
5885  return _ui->spinBox_noiseMinNeighbors->value();
5886 }
5888 {
5889  return _ui->doubleSpinBox_ceilingFilterHeight->value();
5890 }
5892 {
5893  return _ui->doubleSpinBox_floorFilterHeight->value();
5894 }
5896 {
5897  return _ui->spinBox_normalKSearch->value();
5898 }
5900 {
5901  return _ui->doubleSpinBox_normalRadiusSearch->value();
5902 }
5904 {
5905  return _ui->doubleSpinBox_ceilingFilterHeight_scan->value();
5906 }
5908 {
5909  return _ui->doubleSpinBox_floorFilterHeight_scan->value();
5910 }
5912 {
5913  return _ui->spinBox_normalKSearch_scan->value();
5914 }
5916 {
5917  return _ui->doubleSpinBox_normalRadiusSearch_scan->value();
5918 }
5919 
5921 {
5922  return _ui->checkBox_showGraphs->isChecked();
5923 }
5925 {
5926  return _ui->checkBox_showLabels->isChecked();
5927 }
5929 {
5930  return _ui->checkBox_showFrames->isChecked();
5931 }
5933 {
5934  return _ui->checkBox_showLandmarks->isChecked();
5935 }
5937 {
5938  return _ui->doubleSpinBox_landmarkSize->value();
5939 }
5941 {
5942  UASSERT(index >= 0 && index <= 1);
5943  return _3dRenderingGravity[index]->isChecked();
5944 }
5946 {
5947  UASSERT(index >= 0 && index <= 1);
5948  return _3dRenderingGravityLength[index]->value();
5949 }
5951 {
5952  return _ui->checkBox_showIMUAcc->isChecked();
5953 }
5955 {
5956  return _ui->RGBDMarkerDetection->isChecked();
5957 }
5959 {
5960  return _ui->ArucoMarkerLength->value();
5961 }
5963 {
5964  return _ui->groupBox_organized->isChecked();
5965 }
5967 {
5968  return _ui->doubleSpinBox_mesh_angleTolerance->value()*M_PI/180.0;
5969 }
5971 {
5972  return _ui->checkBox_mesh_quad->isChecked();
5973 }
5975 {
5976  return _ui->checkBox_mesh_texture->isChecked();
5977 }
5979 {
5980  return _ui->spinBox_mesh_triangleSize->value();
5981 }
5983 {
5984  UASSERT(index >= 0 && index <= 1);
5985  return _3dRenderingDecimation[index]->value()==0?1:_3dRenderingDecimation[index]->value();
5986 }
5988 {
5989  UASSERT(index >= 0 && index <= 1);
5990  return _3dRenderingMaxDepth[index]->value();
5991 }
5993 {
5994  UASSERT(index >= 0 && index <= 1);
5995  return _3dRenderingMinDepth[index]->value();
5996 }
5997 std::vector<float> PreferencesDialog::getCloudRoiRatios(int index) const
5998 {
5999  UASSERT(index >= 0 && index <= 1);
6000  std::vector<float> roiRatios;
6001  if(!_3dRenderingRoiRatios[index]->text().isEmpty())
6002  {
6003  QStringList values = _3dRenderingRoiRatios[index]->text().split(' ');
6004  if(values.size() == 4)
6005  {
6006  roiRatios.resize(4);
6007  for(int i=0; i<values.size(); ++i)
6008  {
6009  roiRatios[i] = uStr2Float(values[i].toStdString().c_str());
6010  }
6011  }
6012  }
6013  return roiRatios;
6014 }
6016 {
6017  UASSERT(index >= 0 && index <= 1);
6018  return _3dRenderingColorScheme[index]->value();
6019 }
6020 double PreferencesDialog::getCloudOpacity(int index) const
6021 {
6022  UASSERT(index >= 0 && index <= 1);
6023  return _3dRenderingOpacity[index]->value();
6024 }
6026 {
6027  UASSERT(index >= 0 && index <= 1);
6028  return _3dRenderingPtSize[index]->value();
6029 }
6030 
6031 bool PreferencesDialog::isScansShown(int index) const
6032 {
6033  UASSERT(index >= 0 && index <= 1);
6034  return _3dRenderingShowScans[index]->isChecked();
6035 }
6037 {
6038  UASSERT(index >= 0 && index <= 1);
6039  return _3dRenderingDownsamplingScan[index]->value();
6040 }
6041 double PreferencesDialog::getScanMaxRange(int index) const
6042 {
6043  UASSERT(index >= 0 && index <= 1);
6044  return _3dRenderingMaxRange[index]->value();
6045 }
6046 double PreferencesDialog::getScanMinRange(int index) const
6047 {
6048  UASSERT(index >= 0 && index <= 1);
6049  return _3dRenderingMinRange[index]->value();
6050 }
6052 {
6053  UASSERT(index >= 0 && index <= 1);
6054  return _3dRenderingVoxelSizeScan[index]->value();
6055 }
6057 {
6058  UASSERT(index >= 0 && index <= 1);
6059  return _3dRenderingColorSchemeScan[index]->value();
6060 }
6061 double PreferencesDialog::getScanOpacity(int index) const
6062 {
6063  UASSERT(index >= 0 && index <= 1);
6064  return _3dRenderingOpacityScan[index]->value();
6065 }
6067 {
6068  UASSERT(index >= 0 && index <= 1);
6069  return _3dRenderingPtSizeScan[index]->value();
6070 }
6071 
6073 {
6074  UASSERT(index >= 0 && index <= 1);
6075  return _3dRenderingShowFeatures[index]->isChecked();
6076 }
6078 {
6079  UASSERT(index >= 0 && index <= 1);
6080  return _3dRenderingShowFrustums[index]->isEnabled() && _3dRenderingShowFrustums[index]->isChecked();
6081 }
6083 {
6084  UASSERT(index >= 0 && index <= 1);
6085  return _3dRenderingPtSizeFeatures[index]->value();
6086 }
6087 
6089 {
6090  return _ui->radioButton_nodeFiltering->isChecked();
6091 }
6093 {
6094  return _ui->radioButton_subtractFiltering->isChecked();
6095 }
6097 {
6098  return _ui->doubleSpinBox_cloudFilterRadius->value();
6099 }
6101 {
6102  return _ui->doubleSpinBox_cloudFilterAngle->value();
6103 }
6105 {
6106  return _ui->spinBox_subtractFilteringMinPts->value();
6107 }
6109 {
6110  return _ui->doubleSpinBox_subtractFilteringRadius->value();
6111 }
6113 {
6114  return _ui->doubleSpinBox_subtractFilteringAngle->value()*M_PI/180.0;
6115 }
6117 {
6118  return _ui->doubleSpinBox_map_resolution->value();
6119 }
6121 {
6122  return _ui->checkBox_map_shown->isChecked();
6123 }
6125 {
6126  return _ui->checkBox_elevation_shown->checkState();
6127 }
6129 {
6130  return _ui->comboBox_grid_sensor->currentIndex();
6131 }
6133 {
6134  return _ui->checkBox_grid_projMapFrame->isChecked();
6135 }
6137 {
6138  return _ui->doubleSpinBox_grid_maxGroundAngle->value()*M_PI/180.0;
6139 }
6141 {
6142  return _ui->doubleSpinBox_grid_maxGroundHeight->value();
6143 }
6145 {
6146  return _ui->spinBox_grid_minClusterSize->value();
6147 }
6149 {
6150  return _ui->doubleSpinBox_grid_maxObstacleHeight->value();
6151 }
6153 {
6154  return _ui->checkBox_grid_flatObstaclesDetected->isChecked();
6155 }
6157 {
6158  return _ui->doubleSpinBox_map_opacity->value();
6159 }
6160 
6161 
6162 // Source
6164 {
6165  return _ui->general_doubleSpinBox_imgRate->value();
6166 }
6168 {
6169  return _ui->source_mirroring->isChecked();
6170 }
6172 {
6173  int index = _ui->comboBox_sourceType->currentIndex();
6174  if(index == 0)
6175  {
6176  return kSrcRGBD;
6177  }
6178  else if(index == 1)
6179  {
6180  return kSrcStereo;
6181  }
6182  else if(index == 2)
6183  {
6184  return kSrcRGB;
6185  }
6186  else if(index == 3)
6187  {
6188  return kSrcDatabase;
6189  }
6190  return kSrcUndef;
6191 }
6193 {
6195  if(type==kSrcRGBD)
6196  {
6197  return (PreferencesDialog::Src)(_ui->comboBox_cameraRGBD->currentIndex()+kSrcRGBD);
6198  }
6199  else if(type==kSrcStereo)
6200  {
6201  return (PreferencesDialog::Src)(_ui->comboBox_cameraStereo->currentIndex()+kSrcStereo);
6202  }
6203  else if(type==kSrcRGB)
6204  {
6205  return (PreferencesDialog::Src)(_ui->source_comboBox_image_type->currentIndex()+kSrcRGB);
6206  }
6207  else if(type==kSrcDatabase)
6208  {
6209  return kSrcDatabase;
6210  }
6211  return kSrcUndef;
6212 }
6214 {
6216  if(type==kSrcRGBD)
6217  {
6218  return _ui->comboBox_cameraRGBD->currentText();
6219  }
6220  else if(type==kSrcStereo)
6221  {
6222  return _ui->comboBox_cameraStereo->currentText();
6223  }
6224  else if(type==kSrcRGB)
6225  {
6226  return _ui->source_comboBox_image_type->currentText();
6227  }
6228  else if(type==kSrcDatabase)
6229  {
6230  return "Database";
6231  }
6232  return "";
6233 }
6234 
6236 {
6237  return _ui->lineEdit_sourceDevice->text();
6238 }
6239 
6241 {
6242  if(_ui->comboBox_odom_sensor->currentIndex() == 1)
6243  {
6244  //RealSense2
6245  return kSrcStereoRealSense2;
6246  }
6247  else if(_ui->comboBox_odom_sensor->currentIndex() == 2)
6248  {
6249  //Zed SDK
6250  return kSrcStereoZed;
6251  }
6252  else if(_ui->comboBox_odom_sensor->currentIndex() == 3)
6253  {
6254  //XVisio SDK
6255  return kSrcSeerSense;
6256  }
6257  else if(_ui->comboBox_odom_sensor->currentIndex() != 0)
6258  {
6259  UERROR("Not implemented!");
6260  }
6261  return kSrcUndef;
6262 }
6263 
6265 {
6266  if(_ui->comboBox_lidar_src->currentIndex() == 0)
6267  {
6268  return kSrcUndef;
6269  }
6270  return (PreferencesDialog::Src)(_ui->comboBox_lidar_src->currentIndex()-1 + kSrcLidar);
6271 }
6272 
6274 {
6275  Transform t = Transform::fromString(_ui->lineEdit_sourceLocalTransform->text().replace("PI_2", QString::number(3.141592/2.0)).toStdString());
6276  if(t.isNull())
6277  {
6278  return Transform::getIdentity();
6279  }
6280  return t;
6281 }
6282 
6284 {
6285  Transform t = Transform::fromString(_ui->lineEdit_cameraImages_laser_transform->text().replace("PI_2", QString::number(3.141592/2.0)).toStdString());
6286  if(t.isNull())
6287  {
6288  return Transform::getIdentity();
6289  }
6290  return t;
6291 }
6292 
6294 {
6295  return _ui->lineEdit_cameraImages_path_imu->text();
6296 }
6298 {
6299  Transform t = Transform::fromString(_ui->lineEdit_cameraImages_imu_transform->text().replace("PI_2", QString::number(3.141592/2.0)).toStdString());
6300  if(t.isNull())
6301  {
6302  return Transform::getIdentity();
6303  }
6304  return t;
6305 }
6307 {
6308  return _ui->spinBox_cameraImages_max_imu_rate->value();
6309 }
6310 
6312 {
6313  return _ui->source_checkBox_useDbStamps->isChecked();
6314 }
6316 {
6317  return _ui->checkbox_rgbd_colorOnly->isChecked();
6318 }
6320 {
6321  return _ui->comboBox_imuFilter_strategy->currentIndex();
6322 }
6324 {
6325  return _ui->checkBox_imuFilter_baseFrameConversion->isChecked();
6326 }
6328 {
6329  return _ui->groupBox_depthImageFiltering->isEnabled();
6330 }
6332 {
6333  return _ui->lineEdit_source_distortionModel->text();
6334 }
6336 {
6337  return _ui->groupBox_bilateral->isChecked();
6338 }
6340 {
6341  return _ui->doubleSpinBox_bilateral_sigmaS->value();
6342 }
6344 {
6345  return _ui->doubleSpinBox_bilateral_sigmaR->value();
6346 }
6348 {
6349  return _ui->spinBox_source_imageDecimation->value();
6350 }
6352 {
6353  return _ui->comboBox_source_histogramMethod->currentIndex();
6354 }
6356 {
6357  return _ui->checkbox_source_feature_detection->isChecked();
6358 }
6360 {
6361  return _ui->checkbox_stereo_depthGenerated->isChecked();
6362 }
6364 {
6365  return _ui->checkBox_stereo_exposureCompensation->isChecked();
6366 }
6368 {
6369  return _ui->checkBox_source_scanFromDepth->isChecked();
6370 }
6372 {
6373  return _ui->checkBox_source_scanDeskewing->isChecked();
6374 }
6376 {
6377  return _ui->spinBox_source_scanDownsampleStep->value();
6378 }
6380 {
6381  return _ui->doubleSpinBox_source_scanRangeMin->value();
6382 }
6384 {
6385  return _ui->doubleSpinBox_source_scanRangeMax->value();
6386 }
6388 {
6389  return _ui->doubleSpinBox_source_scanVoxelSize->value();
6390 }
6392 {
6393  return _ui->spinBox_source_scanNormalsK->value();
6394 }
6396 {
6397  return _ui->doubleSpinBox_source_scanNormalsRadius->value();
6398 }
6400 {
6401  return _ui->doubleSpinBox_source_scanNormalsForceGroundUp->value();
6402 }
6403 
6404 Camera * PreferencesDialog::createCamera(bool useRawImages, bool useColor)
6405 {
6406  return createCamera(
6407  this->getSourceDriver(),
6408  _ui->lineEdit_sourceDevice->text(),
6409  _ui->lineEdit_calibrationFile->text(),
6410  useRawImages,
6411  useColor,
6412  false,
6413  false);
6414 }
6415 
6417  Src driver,
6418  const QString & device,
6419  const QString & calibrationPath,
6420  bool useRawImages,
6421  bool useColor,
6422  bool odomOnly,
6423  bool odomSensorExtrinsicsCalib)
6424 {
6425  if(odomOnly && !(driver == kSrcStereoRealSense2 || driver == kSrcStereoZed || driver == kSrcSeerSense))
6426  {
6427  QMessageBox::warning(this, tr("Odometry Sensor"),
6428  tr("Driver %1 cannot support odometry only mode.").arg(driver), QMessageBox::Ok);
6429  return 0;
6430  }
6431 
6432  UDEBUG("");
6433  Camera * camera = 0;
6434  if(driver == PreferencesDialog::kSrcOpenNI_PCL)
6435  {
6436  if(useRawImages)
6437  {
6438  QMessageBox::warning(this, tr("Calibration"),
6439  tr("Using raw images for \"OpenNI\" driver is not yet supported. "
6440  "Factory calibration loaded from OpenNI is used."), QMessageBox::Ok);
6441  return 0;
6442  }
6443  else
6444  {
6445  camera = new CameraOpenni(
6446  _ui->lineEdit_openniOniPath->text().isEmpty()?device.toStdString():_ui->lineEdit_openniOniPath->text().toStdString(),
6447  this->getGeneralInputRate(),
6448  this->getSourceLocalTransform());
6449  }
6450  }
6451  else if(driver == PreferencesDialog::kSrcOpenNI2)
6452  {
6453  camera = new CameraOpenNI2(
6454  _ui->lineEdit_openni2OniPath->text().isEmpty()?device.toStdString():_ui->lineEdit_openni2OniPath->text().toStdString(),
6456  this->getGeneralInputRate(),
6457  this->getSourceLocalTransform());
6458  }
6459  else if(driver == PreferencesDialog::kSrcFreenect)
6460  {
6461  camera = new CameraFreenect(
6462  device.isEmpty()?0:atoi(device.toStdString().c_str()),
6464  this->getGeneralInputRate(),
6465  this->getSourceLocalTransform());
6466  }
6467  else if(driver == PreferencesDialog::kSrcOpenNI_CV ||
6469  {
6470  if(useRawImages)
6471  {
6472  QMessageBox::warning(this, tr("Calibration"),
6473  tr("Using raw images for \"OpenNI\" driver is not yet supported. "
6474  "Factory calibration loaded from OpenNI is used."), QMessageBox::Ok);
6475  return 0;
6476  }
6477  else
6478  {
6479  camera = new CameraOpenNICV(
6481  this->getGeneralInputRate(),
6482  this->getSourceLocalTransform());
6483  }
6484  }
6485  else if(driver == kSrcFreenect2)
6486  {
6487  camera = new CameraFreenect2(
6488  device.isEmpty()?0:atoi(device.toStdString().c_str()),
6489  useRawImages?CameraFreenect2::kTypeColorIR:(CameraFreenect2::Type)_ui->comboBox_freenect2Format->currentIndex(),
6490  this->getGeneralInputRate(),
6491  this->getSourceLocalTransform(),
6492  _ui->doubleSpinBox_freenect2MinDepth->value(),
6493  _ui->doubleSpinBox_freenect2MaxDepth->value(),
6494  _ui->checkBox_freenect2BilateralFiltering->isChecked(),
6495  _ui->checkBox_freenect2EdgeAwareFiltering->isChecked(),
6496  _ui->checkBox_freenect2NoiseFiltering->isChecked(),
6497  _ui->lineEdit_freenect2Pipeline->text().toStdString());
6498  }
6499  else if (driver == kSrcK4W2)
6500  {
6501  camera = new CameraK4W2(
6502  device.isEmpty() ? 0 : atoi(device.toStdString().c_str()),
6503  (CameraK4W2::Type)_ui->comboBox_k4w2Format->currentIndex(),
6504  this->getGeneralInputRate(),
6505  this->getSourceLocalTransform());
6506  }
6507  else if (driver == kSrcK4A)
6508  {
6509  if (!_ui->lineEdit_k4a_mkv->text().isEmpty())
6510  {
6511  // playback
6512  camera = new CameraK4A(
6513  _ui->lineEdit_k4a_mkv->text().toStdString().c_str(),
6514  _ui->source_checkBox_useMKVStamps->isChecked() ? -1 : this->getGeneralInputRate(),
6515  this->getSourceLocalTransform());
6516  }
6517  else
6518  {
6519  camera = new CameraK4A(
6520  device.isEmpty() ? 0 : atoi(device.toStdString().c_str()),
6521  this->getGeneralInputRate(),
6522  this->getSourceLocalTransform());
6523  }
6524 
6525  ((CameraK4A*)camera)->setIRDepthFormat(_ui->checkbox_k4a_irDepth->isChecked());
6526  ((CameraK4A*)camera)->setPreferences(_ui->comboBox_k4a_rgb_resolution->currentIndex(),
6527  _ui->comboBox_k4a_framerate->currentIndex(),
6528  _ui->comboBox_k4a_depth_resolution->currentIndex());
6529  }
6530  else if (driver == kSrcRealSense)
6531  {
6532  if(useRawImages && _ui->comboBox_realsenseRGBSource->currentIndex()!=2)
6533  {
6534  QMessageBox::warning(this, tr("Calibration"),
6535  tr("Using raw images for \"RealSense\" driver is not yet supported for color and infrared streams. "
6536  "Factory calibration loaded from RealSense is used."), QMessageBox::Ok);
6537  return 0;
6538  }
6539  else
6540  {
6541  camera = new CameraRealSense(
6542  device.isEmpty() ? 0 : atoi(device.toStdString().c_str()),
6543  _ui->comboBox_realsensePresetRGB->currentIndex(),
6544  _ui->comboBox_realsensePresetDepth->currentIndex(),
6545  _ui->checkbox_realsenseOdom->isChecked(),
6546  this->getGeneralInputRate(),
6547  this->getSourceLocalTransform());
6548  ((CameraRealSense*)camera)->setDepthScaledToRGBSize(_ui->checkbox_realsenseDepthScaledToRGBSize->isChecked());
6549  ((CameraRealSense*)camera)->setRGBSource((CameraRealSense::RGBSource)_ui->comboBox_realsenseRGBSource->currentIndex());
6550  }
6551  }
6552  else if (driver == kSrcRealSense2 || driver == kSrcStereoRealSense2)
6553  {
6554  if(driver == kSrcRealSense2 && useRawImages)
6555  {
6556  QMessageBox::warning(this, tr("Calibration"),
6557  tr("Using raw images for \"RealSense\" driver is not yet supported. "
6558  "Factory calibration loaded from RealSense2 is used."), QMessageBox::Ok);
6559  return 0;
6560  }
6561  else
6562  {
6563  camera = new CameraRealSense2(
6564  device.isEmpty()&&driver == kSrcStereoRealSense2?"T265":device.toStdString(),
6565  this->getGeneralInputRate(),
6566  this->getSourceLocalTransform());
6568  _ui->checkbox_publishInterIMU->isChecked(),
6569  _ui->checkbox_publishInterIMU->isChecked() && getIMUFilteringStrategy()>0?
6571  if(driver == kSrcStereoRealSense2)
6572  {
6573  ((CameraRealSense2*)camera)->setImagesRectified((_ui->checkBox_stereo_rectify->isEnabled() && _ui->checkBox_stereo_rectify->isChecked()) && !useRawImages);
6574  ((CameraRealSense2*)camera)->setOdomProvided(getOdomSourceDriver() == kSrcStereoRealSense2 || odomOnly, odomOnly, odomSensorExtrinsicsCalib);
6575  }
6576  else
6577  {
6578  ((CameraRealSense2*)camera)->setEmitterEnabled(_ui->checkbox_rs2_emitter->isChecked());
6579  ((CameraRealSense2*)camera)->setIRFormat(_ui->checkbox_rs2_irMode->isChecked(), _ui->checkbox_rs2_irDepth->isChecked());
6580  ((CameraRealSense2*)camera)->setResolution(_ui->spinBox_rs2_width->value(), _ui->spinBox_rs2_height->value(), _ui->spinBox_rs2_rate->value());
6581  ((CameraRealSense2*)camera)->setDepthResolution(_ui->spinBox_rs2_width_depth->value(), _ui->spinBox_rs2_height_depth->value(), _ui->spinBox_rs2_rate_depth->value());
6582  ((CameraRealSense2*)camera)->setGlobalTimeSync(_ui->checkbox_rs2_globalTimeStync->isChecked());
6583  ((CameraRealSense2*)camera)->setDualMode(getOdomSourceDriver() == kSrcStereoRealSense2, Transform::fromString(_ui->lineEdit_odom_sensor_extrinsics->text().toStdString()));
6584  ((CameraRealSense2*)camera)->setJsonConfig(_ui->lineEdit_rs2_jsonFile->text().toStdString());
6585  }
6586  }
6587  }
6588  else if (driver == kSrcStereoMyntEye)
6589  {
6590  if(driver == kSrcStereoMyntEye && useRawImages)
6591  {
6592  QMessageBox::warning(this, tr("Calibration"),
6593  tr("Using raw images for \"MyntEye\" driver is not yet supported. "
6594  "Factory calibration loaded from MyntEye is used."), QMessageBox::Ok);
6595  return 0;
6596  }
6597  else
6598  {
6599  camera = new CameraMyntEye(
6600  device.toStdString(),
6601  _ui->checkbox_stereoMyntEye_rectify->isChecked(),
6602  _ui->checkbox_stereoMyntEye_depth->isChecked(),
6603  this->getGeneralInputRate(),
6604  this->getSourceLocalTransform());
6605  ((CameraMyntEye*)camera)->publishInterIMU(_ui->checkbox_publishInterIMU->isChecked());
6606  if(_ui->checkbox_stereoMyntEye_autoExposure->isChecked())
6607  {
6608  ((CameraMyntEye*)camera)->setAutoExposure();
6609  }
6610  else
6611  {
6612  ((CameraMyntEye*)camera)->setManualExposure(
6613  _ui->spinBox_stereoMyntEye_gain->value(),
6614  _ui->spinBox_stereoMyntEye_brightness->value(),
6615  _ui->spinBox_stereoMyntEye_contrast->value());
6616  }
6617  ((CameraMyntEye*)camera)->setIrControl(
6618  _ui->spinBox_stereoMyntEye_irControl->value());
6619  }
6620  }
6621  else if(driver == kSrcRGBDImages)
6622  {
6623  camera = new CameraRGBDImages(
6624  _ui->lineEdit_cameraRGBDImages_path_rgb->text().append(QDir::separator()).toStdString(),
6625  _ui->lineEdit_cameraRGBDImages_path_depth->text().append(QDir::separator()).toStdString(),
6626  _ui->doubleSpinBox_cameraRGBDImages_scale->value(),
6627  this->getGeneralInputRate(),
6628  this->getSourceLocalTransform());
6629  ((CameraRGBDImages*)camera)->setStartIndex(_ui->spinBox_cameraRGBDImages_startIndex->value());
6630  ((CameraRGBDImages*)camera)->setMaxFrames(_ui->spinBox_cameraRGBDImages_maxFrames->value());
6631  ((CameraRGBDImages*)camera)->setBayerMode(_ui->comboBox_cameraImages_bayerMode->currentIndex()-1);
6632  ((CameraRGBDImages*)camera)->setOdometryPath(_ui->lineEdit_cameraImages_odom->text().toStdString(), _ui->comboBox_cameraImages_odomFormat->currentIndex());
6633  ((CameraRGBDImages*)camera)->setGroundTruthPath(_ui->lineEdit_cameraImages_gt->text().toStdString(), _ui->comboBox_cameraImages_gtFormat->currentIndex());
6634  ((CameraRGBDImages*)camera)->setMaxPoseTimeDiff(_ui->doubleSpinBox_maxPoseTimeDiff->value());
6635  ((CameraRGBDImages*)camera)->setScanPath(
6636  _ui->lineEdit_cameraImages_path_scans->text().isEmpty()?"":_ui->lineEdit_cameraImages_path_scans->text().append(QDir::separator()).toStdString(),
6637  _ui->spinBox_cameraImages_max_scan_pts->value(),
6638  this->getLaserLocalTransform());
6639  ((CameraRGBDImages*)camera)->setTimestamps(
6640  _ui->checkBox_cameraImages_timestamps->isChecked(),
6641  _ui->lineEdit_cameraImages_timestamps->text().toStdString(),
6642  _ui->checkBox_cameraImages_syncTimeStamps->isChecked());
6643  ((CameraRGBDImages*)camera)->setConfigForEachFrame(_ui->checkBox_cameraImages_configForEachFrame->isChecked());
6644  }
6645  else if(driver == kSrcDC1394)
6646  {
6647  camera = new CameraStereoDC1394(
6648  this->getGeneralInputRate(),
6649  this->getSourceLocalTransform());
6650  }
6651  else if(driver == kSrcFlyCapture2)
6652  {
6653  if(useRawImages)
6654  {
6655  QMessageBox::warning(this, tr("Calibration"),
6656  tr("Using raw images for \"FlyCapture2\" driver is not yet supported. "
6657  "Factory calibration loaded from FlyCapture2 is used."), QMessageBox::Ok);
6658  return 0;
6659  }
6660  else
6661  {
6663  this->getGeneralInputRate(),
6664  this->getSourceLocalTransform());
6665  }
6666  }
6667  else if(driver == kSrcStereoImages)
6668  {
6669  camera = new CameraStereoImages(
6670  _ui->lineEdit_cameraStereoImages_path_left->text().append(QDir::separator()).toStdString(),
6671  _ui->lineEdit_cameraStereoImages_path_right->text().append(QDir::separator()).toStdString(),
6672  (_ui->checkBox_stereo_rectify->isEnabled() && _ui->checkBox_stereo_rectify->isChecked()) && !useRawImages,
6673  this->getGeneralInputRate(),
6674  this->getSourceLocalTransform());
6675  ((CameraStereoImages*)camera)->setStartIndex(_ui->spinBox_cameraStereoImages_startIndex->value());
6676  ((CameraStereoImages*)camera)->setMaxFrames(_ui->spinBox_cameraStereoImages_maxFrames->value());
6677  ((CameraStereoImages*)camera)->setBayerMode(_ui->comboBox_cameraImages_bayerMode->currentIndex()-1);
6678  ((CameraStereoImages*)camera)->setOdometryPath(_ui->lineEdit_cameraImages_odom->text().toStdString(), _ui->comboBox_cameraImages_odomFormat->currentIndex());
6679  ((CameraStereoImages*)camera)->setGroundTruthPath(_ui->lineEdit_cameraImages_gt->text().toStdString(), _ui->comboBox_cameraImages_gtFormat->currentIndex());
6680  ((CameraStereoImages*)camera)->setMaxPoseTimeDiff(_ui->doubleSpinBox_maxPoseTimeDiff->value());
6681  ((CameraStereoImages*)camera)->setScanPath(
6682  _ui->lineEdit_cameraImages_path_scans->text().isEmpty()?"":_ui->lineEdit_cameraImages_path_scans->text().append(QDir::separator()).toStdString(),
6683  _ui->spinBox_cameraImages_max_scan_pts->value(),
6684  this->getLaserLocalTransform());
6685  ((CameraStereoImages*)camera)->setTimestamps(
6686  _ui->checkBox_cameraImages_timestamps->isChecked(),
6687  _ui->lineEdit_cameraImages_timestamps->text().toStdString(),
6688  _ui->checkBox_cameraImages_syncTimeStamps->isChecked());
6689  ((CameraRGBDImages*)camera)->setConfigForEachFrame(_ui->checkBox_cameraImages_configForEachFrame->isChecked());
6690 
6691  }
6692  else if (driver == kSrcStereoUsb)
6693  {
6694  if(_ui->spinBox_stereo_right_device->value()>=0)
6695  {
6696  camera = new CameraStereoVideo(
6697  device.isEmpty() ? 0 : atoi(device.toStdString().c_str()),
6698  _ui->spinBox_stereo_right_device->value(),
6699  (_ui->checkBox_stereo_rectify->isEnabled() && _ui->checkBox_stereo_rectify->isChecked()) && !useRawImages,
6700  this->getGeneralInputRate(),
6701  this->getSourceLocalTransform());
6702  }
6703  else
6704  {
6705  camera = new CameraStereoVideo(
6706  device.isEmpty() ? 0 : atoi(device.toStdString().c_str()),
6707  (_ui->checkBox_stereo_rectify->isEnabled() && _ui->checkBox_stereo_rectify->isChecked()) && !useRawImages,
6708  this->getGeneralInputRate(),
6709  this->getSourceLocalTransform());
6710  }
6711  ((CameraStereoVideo*)camera)->setResolution(_ui->spinBox_stereousbcam_streamWidth->value(), _ui->spinBox_stereousbcam_streamHeight->value());
6712  }
6713  else if(driver == kSrcStereoVideo)
6714  {
6715  if(!_ui->lineEdit_cameraStereoVideo_path_2->text().isEmpty())
6716  {
6717  // left and right videos
6718  camera = new CameraStereoVideo(
6719  _ui->lineEdit_cameraStereoVideo_path->text().toStdString(),
6720  _ui->lineEdit_cameraStereoVideo_path_2->text().toStdString(),
6721  (_ui->checkBox_stereo_rectify->isEnabled() && _ui->checkBox_stereo_rectify->isChecked()) && !useRawImages,
6722  this->getGeneralInputRate(),
6723  this->getSourceLocalTransform());
6724  }
6725  else
6726  {
6727  // side-by-side video
6728  camera = new CameraStereoVideo(
6729  _ui->lineEdit_cameraStereoVideo_path->text().toStdString(),
6730  (_ui->checkBox_stereo_rectify->isEnabled() && _ui->checkBox_stereo_rectify->isChecked()) && !useRawImages,
6731  this->getGeneralInputRate(),
6732  this->getSourceLocalTransform());
6733  }
6734  }
6735 
6736  else if (driver == kSrcStereoTara)
6737  {
6738 
6739  camera = new CameraStereoTara(
6740  device.isEmpty()?0:atoi(device.toStdString().c_str()),
6741  (_ui->checkBox_stereo_rectify->isEnabled() && _ui->checkBox_stereo_rectify->isChecked()) && !useRawImages,
6742  this->getGeneralInputRate(),
6743  this->getSourceLocalTransform());
6744 
6745  }
6746  else if (driver == kSrcStereoZed)
6747  {
6748  UDEBUG("ZED");
6749  if(!_ui->lineEdit_zedSvoPath->text().isEmpty())
6750  {
6751  camera = new CameraStereoZed(
6752  _ui->lineEdit_zedSvoPath->text().toStdString(),
6753  _ui->comboBox_stereoZed_quality->currentIndex(),
6754  _ui->comboBox_stereoZed_sensingMode->currentIndex(),
6755  _ui->spinBox_stereoZed_confidenceThr->value(),
6757  this->getGeneralInputRate(),
6758  this->getSourceLocalTransform(),
6759  _ui->checkbox_stereoZed_selfCalibration->isChecked(),
6760  _ui->loopClosure_bowForce2D->isChecked(),
6761  _ui->spinBox_stereoZed_texturenessConfidenceThr->value());
6762  }
6763  else
6764  {
6765  camera = new CameraStereoZed(
6766  device.isEmpty()?0:atoi(device.toStdString().c_str()),
6767  _ui->comboBox_stereoZed_resolution->currentIndex(),
6768  // depth should be enabled for zed vo to work
6769  _ui->comboBox_stereoZed_quality->currentIndex()==0&&odomOnly?1:_ui->comboBox_stereoZed_quality->currentIndex(),
6770  _ui->comboBox_stereoZed_sensingMode->currentIndex(),
6771  _ui->spinBox_stereoZed_confidenceThr->value(),
6772  getOdomSourceDriver() == kSrcStereoZed || odomOnly,
6773  this->getGeneralInputRate(),
6774  this->getSourceLocalTransform(),
6775  _ui->checkbox_stereoZed_selfCalibration->isChecked(),
6776  _ui->loopClosure_bowForce2D->isChecked(),
6777  _ui->spinBox_stereoZed_texturenessConfidenceThr->value());
6778  }
6779  camera->setInterIMUPublishing(
6780  _ui->checkbox_publishInterIMU->isChecked(),
6781  _ui->checkbox_publishInterIMU->isChecked() && getIMUFilteringStrategy()>0?
6783  }
6784  else if (driver == kSrcStereoZedOC)
6785  {
6786  UDEBUG("ZEDOC");
6787  camera = new CameraStereoZedOC(
6788  device.isEmpty()?-1:atoi(device.toStdString().c_str()),
6789  _ui->comboBox_stereoZedOC_resolution->currentIndex(),
6790  this->getGeneralInputRate(),
6791  this->getSourceLocalTransform());
6792  }
6793  else if (driver == kSrcStereoDepthAI)
6794  {
6795  UDEBUG("DepthAI");
6796  camera = new CameraDepthAI(
6797  device.toStdString().c_str(),
6798  _ui->comboBox_depthai_resolution->currentIndex(),
6799  this->getGeneralInputRate(),
6800  this->getSourceLocalTransform());
6801  ((CameraDepthAI*)camera)->setOutputMode(_ui->comboBox_depthai_output_mode->currentIndex());
6802  ((CameraDepthAI*)camera)->setDepthProfile(_ui->spinBox_depthai_conf_threshold->value(), _ui->spinBox_depthai_lrc_threshold->value());
6803  ((CameraDepthAI*)camera)->setExtendedDisparity(_ui->checkBox_depthai_extended_disparity->isChecked());
6804  ((CameraDepthAI*)camera)->setSubpixelMode(_ui->comboBox_depthai_subpixel_fractional_bits->currentIndex()!=0, _ui->comboBox_depthai_subpixel_fractional_bits->currentIndex()==2?4:_ui->comboBox_depthai_subpixel_fractional_bits->currentIndex()==3?5:3);
6805  ((CameraDepthAI*)camera)->setCompanding(_ui->comboBox_depthai_disparity_companding->currentIndex()!=0, _ui->comboBox_depthai_disparity_companding->currentIndex()==1?64:96);
6806  ((CameraDepthAI*)camera)->setRectification(_ui->checkBox_depthai_use_spec_translation->isChecked(), _ui->doubleSpinBox_depthai_alpha_scaling->value(), !useRawImages);
6807  ((CameraDepthAI*)camera)->setIMU(_ui->checkBox_depthai_imu_published->isChecked(), _ui->checkbox_publishInterIMU->isChecked());
6808  ((CameraDepthAI*)camera)->setIrIntensity(_ui->doubleSpinBox_depthai_dot_intensity->value(), _ui->doubleSpinBox_depthai_flood_intensity->value());
6809  ((CameraDepthAI*)camera)->setDetectFeatures(_ui->comboBox_depthai_detect_features->currentIndex());
6810  ((CameraDepthAI*)camera)->setBlobPath(_ui->lineEdit_depthai_blob_path->text().toStdString());
6811  if(_ui->comboBox_depthai_detect_features->currentIndex() == 1)
6812  {
6813  ((CameraDepthAI*)camera)->setGFTTDetector(_ui->checkBox_GFTT_useHarrisDetector->isChecked(), _ui->doubleSpinBox_GFTT_minDistance->value(), _ui->reextract_maxFeatures->value());
6814  }
6815  else if(_ui->comboBox_depthai_detect_features->currentIndex() >= 2)
6816  {
6817  ((CameraDepthAI*)camera)->setSuperPointDetector(_ui->doubleSpinBox_sptorch_threshold->value(), _ui->checkBox_sptorch_nms->isChecked(), _ui->spinBox_sptorch_minDistance->value());
6818  }
6819  }
6820  else if (driver == kSrcSeerSense)
6821  {
6822  UDEBUG("SeerSense");
6823  camera = new CameraSeerSense(
6824  getOdomSourceDriver() == kSrcSeerSense || odomOnly,
6825  this->getGeneralInputRate(),
6826  this->getSourceLocalTransform());
6827  camera->setInterIMUPublishing(
6828  _ui->checkbox_publishInterIMU->isChecked(),
6829  _ui->checkbox_publishInterIMU->isChecked() && getIMUFilteringStrategy()>0?
6831  }
6832  else if(driver == kSrcUsbDevice)
6833  {
6834  camera = new CameraVideo(
6835  device.isEmpty()?0:atoi(device.toStdString().c_str()),
6836  (_ui->checkBox_rgb_rectify->isEnabled() && _ui->checkBox_rgb_rectify->isChecked()) && !useRawImages,
6837  this->getGeneralInputRate(),
6838  this->getSourceLocalTransform());
6839  ((CameraVideo*)camera)->setResolution(_ui->spinBox_usbcam_streamWidth->value(), _ui->spinBox_usbcam_streamHeight->value());
6840  }
6841  else if(driver == kSrcVideo)
6842  {
6843  camera = new CameraVideo(
6844  _ui->source_video_lineEdit_path->text().toStdString(),
6845  (_ui->checkBox_rgb_rectify->isEnabled() && _ui->checkBox_rgb_rectify->isChecked()) && !useRawImages,
6846  this->getGeneralInputRate(),
6847  this->getSourceLocalTransform());
6848  }
6849  else if(driver == kSrcImages)
6850  {
6851  camera = new CameraImages(
6852  _ui->source_images_lineEdit_path->text().toStdString(),
6853  this->getGeneralInputRate(),
6854  this->getSourceLocalTransform());
6855 
6856  ((CameraImages*)camera)->setStartIndex(_ui->source_images_spinBox_startPos->value());
6857  ((CameraImages*)camera)->setMaxFrames(_ui->source_images_spinBox_maxFrames->value());
6858  ((CameraImages*)camera)->setImagesRectified((_ui->checkBox_rgb_rectify->isEnabled() && _ui->checkBox_rgb_rectify->isChecked()) && !useRawImages);
6859 
6860  ((CameraImages*)camera)->setBayerMode(_ui->comboBox_cameraImages_bayerMode->currentIndex()-1);
6861  ((CameraImages*)camera)->setOdometryPath(
6862  _ui->lineEdit_cameraImages_odom->text().toStdString(),
6863  _ui->comboBox_cameraImages_odomFormat->currentIndex());
6864  ((CameraImages*)camera)->setGroundTruthPath(
6865  _ui->lineEdit_cameraImages_gt->text().toStdString(),
6866  _ui->comboBox_cameraImages_gtFormat->currentIndex());
6867  ((CameraImages*)camera)->setMaxPoseTimeDiff(_ui->doubleSpinBox_maxPoseTimeDiff->value());
6868  ((CameraImages*)camera)->setScanPath(
6869  _ui->lineEdit_cameraImages_path_scans->text().isEmpty()?"":_ui->lineEdit_cameraImages_path_scans->text().append(QDir::separator()).toStdString(),
6870  _ui->spinBox_cameraImages_max_scan_pts->value(),
6871  this->getLaserLocalTransform());
6872  ((CameraImages*)camera)->setDepthFromScan(
6873  _ui->groupBox_depthFromScan->isChecked(),
6874  !_ui->groupBox_depthFromScan_fillHoles->isChecked()?0:_ui->radioButton_depthFromScan_vertical->isChecked()?1:-1,
6875  _ui->checkBox_depthFromScan_fillBorders->isChecked());
6876  ((CameraImages*)camera)->setTimestamps(
6877  _ui->checkBox_cameraImages_timestamps->isChecked(),
6878  _ui->lineEdit_cameraImages_timestamps->text().toStdString(),
6879  _ui->checkBox_cameraImages_syncTimeStamps->isChecked());
6880  ((CameraRGBDImages*)camera)->setConfigForEachFrame(_ui->checkBox_cameraImages_configForEachFrame->isChecked());
6881  }
6882  else if(driver == kSrcDatabase)
6883  {
6884  camera = new DBReader(_ui->source_database_lineEdit_path->text().toStdString(),
6885  _ui->source_checkBox_useDbStamps->isChecked()?-1:this->getGeneralInputRate(),
6886  _ui->source_checkBox_ignoreOdometry->isChecked(),
6887  _ui->source_checkBox_ignoreGoalDelay->isChecked(),
6888  _ui->source_checkBox_ignoreGoals->isChecked(),
6889  _ui->source_spinBox_databaseStartId->value(),
6890  _ui->source_spinBox_database_cameraIndex->value(),
6891  _ui->source_spinBox_databaseStopId->value(),
6892  !_ui->general_checkBox_createIntermediateNodes->isChecked(),
6893  _ui->source_checkBox_ignoreLandmarks->isChecked(),
6894  _ui->source_checkBox_ignoreFeatures->isChecked(),
6895  0,
6896  -1,
6897  _ui->source_checkBox_ignorePriors->isChecked());
6898  }
6899  else
6900  {
6901  UFATAL("Source driver undefined (%d)!", driver);
6902  }
6903 
6904  if(camera)
6905  {
6906  UDEBUG("Init");
6907  QString dir = this->getCameraInfoDir();
6908  QString calibrationFile = calibrationPath;
6909  if(!(driver >= kSrcRGB && driver <= kSrcVideo))
6910  {
6911  calibrationFile.remove("_left.yaml").remove("_right.yaml").remove("_pose.yaml").remove("_rgb.yaml").remove("_depth.yaml");
6912  }
6913  QString name = QFileInfo(calibrationFile.remove(".yaml")).fileName();
6914  if(!calibrationPath.isEmpty())
6915  {
6916  QDir d = QFileInfo(calibrationPath).dir();
6917  QString tmp = calibrationPath;
6918  if(!tmp.remove(QFileInfo(calibrationPath).baseName()).isEmpty())
6919  {
6920  dir = d.absolutePath();
6921  }
6922  }
6923 
6924  UDEBUG("useRawImages=%d dir=%s", useRawImages?1:0, dir.toStdString().c_str());
6925  // don't set calibration folder if we want raw images
6926  if(!camera->init(useRawImages?"":dir.toStdString(), name.toStdString()))
6927  {
6928  UWARN("init camera failed... ");
6929  QMessageBox::warning(this,
6930  tr("RTAB-Map"),
6931  tr("Camera initialization failed..."));
6932  delete camera;
6933  camera = 0;
6934  }
6935  else
6936  {
6937  //should be after initialization
6938  if(driver == kSrcOpenNI2)
6939  {
6940  ((CameraOpenNI2*)camera)->setAutoWhiteBalance(_ui->openni2_autoWhiteBalance->isChecked());
6941  ((CameraOpenNI2*)camera)->setAutoExposure(_ui->openni2_autoExposure->isChecked());
6942  ((CameraOpenNI2*)camera)->setMirroring(_ui->openni2_mirroring->isChecked());
6943  ((CameraOpenNI2*)camera)->setOpenNI2StampsAndIDsUsed(_ui->openni2_stampsIdsUsed->isChecked());
6945  {
6946  ((CameraOpenNI2*)camera)->setExposure(_ui->openni2_exposure->value());
6947  ((CameraOpenNI2*)camera)->setGain(_ui->openni2_gain->value());
6948  }
6949  ((CameraOpenNI2*)camera)->setIRDepthShift(_ui->openni2_hshift->value(), _ui->openni2_vshift->value());
6950  ((CameraOpenNI2*)camera)->setMirroring(_ui->openni2_mirroring->isChecked());
6951  ((CameraOpenNI2*)camera)->setDepthDecimation(_ui->openni2_depth_decimation->value());
6952  }
6953  }
6954  }
6955 
6956  UDEBUG("");
6957  return camera;
6958 }
6959 
6960 SensorCapture * PreferencesDialog::createOdomSensor(Transform & extrinsics, double & timeOffset, float & scaleFactor, double & waitTime)
6961 {
6962  Src driver = getOdomSourceDriver();
6963  if(driver != kSrcUndef)
6964  {
6965  if(driver == getSourceDriver() &&
6966  _ui->lineEdit_odomSourceDevice->text().compare(_ui->lineEdit_sourceDevice->text()) == 0)
6967  {
6968  QMessageBox::warning(this, tr("Odometry Sensor"),
6969  tr("Cannot create an odometry sensor with same driver than camera AND with same "
6970  "device. Change device ID of the odometry or camera sensor. To use odometry option "
6971  "from a single camera, look at the parameters of that driver to enable it, "
6972  "then disable odometry sensor. "), QMessageBox::Ok);
6973  return 0;
6974  }
6975 
6976  extrinsics = Transform::fromString(_ui->lineEdit_odom_sensor_extrinsics->text().replace("PI_2", QString::number(3.141592/2.0)).toStdString());
6977  timeOffset = _ui->doubleSpinBox_odom_sensor_time_offset->value()/1000.0;
6978  scaleFactor = (float)_ui->doubleSpinBox_odom_sensor_scale_factor->value();
6979  waitTime = _ui->doubleSpinBox_odom_sensor_wait_time->value()/1000.0;
6980 
6981  return createCamera(driver, _ui->lineEdit_odomSourceDevice->text(), _ui->lineEdit_odom_sensor_path_calibration->text(), false, true, true, false);
6982  }
6983  return 0;
6984 }
6985 
6987 {
6988  Lidar * lidar = 0;
6989  Src driver = getLidarSourceDriver();
6990  if(driver == kSrcLidarVLP16)
6991  {
6992 #if PCL_VERSION_COMPARE(>=, 1, 8, 0)
6993  Transform localTransform = Transform::fromString(_ui->lineEdit_lidar_local_transform->text().replace("PI_2", QString::number(3.141592/2.0)).toStdString());
6994  if(localTransform.isNull())
6995  {
6996  UWARN("Failed to parse lidar local transfor string \"%s\"!",
6997  _ui->lineEdit_lidar_local_transform->text().toStdString().c_str());
6998  localTransform = Transform::getIdentity();
6999  }
7000  if(!_ui->lineEdit_vlp16_pcap_path->text().isEmpty())
7001  {
7002  // PCAP mode
7003  lidar = new LidarVLP16(
7004  _ui->lineEdit_vlp16_pcap_path->text().toStdString(),
7005  _ui->checkBox_vlp16_organized->isChecked(),
7006  _ui->checkBox_vlp16_stamp_last->isChecked(),
7007  this->getGeneralInputRate(),
7008  localTransform);
7009  }
7010  else
7011  {
7012  // Connect to sensor
7013 
7014  lidar = new LidarVLP16(
7015  boost::asio::ip::address_v4::from_string(uFormat("%ld.%ld.%ld.%ld",
7016  (size_t)_ui->spinBox_vlp16_ip1->value(),
7017  (size_t)_ui->spinBox_vlp16_ip2->value(),
7018  (size_t)_ui->spinBox_vlp16_ip3->value(),
7019  (size_t)_ui->spinBox_vlp16_ip4->value())),
7020  _ui->spinBox_vlp16_port->value(),
7021  _ui->checkBox_vlp16_organized->isChecked(),
7022  _ui->checkBox_vlp16_hostTime->isChecked(),
7023  _ui->checkBox_vlp16_stamp_last->isChecked(),
7024  this->getGeneralInputRate(),
7025  localTransform);
7026 
7027  }
7028  if(!lidar->init())
7029  {
7030  UWARN("init lidar failed... ");
7031  QMessageBox::warning(this,
7032  tr("RTAB-Map"),
7033  tr("Lidar initialization failed..."));
7034  delete lidar;
7035  lidar = 0;
7036  }
7037 #else
7038  UWARN("Lidar cannot be used with rtabmap built with PCL < 1.8... ");
7039  QMessageBox::warning(this,
7040  tr("RTAB-Map"),
7041  tr("Lidar initialization failed..."));
7042 #endif
7043  }
7044  return lidar;
7045 }
7046 
7048 {
7049  return _ui->groupBox_publishing->isChecked();
7050 }
7052 {
7053  return _ui->general_doubleSpinBox_hardThr->value();
7054 }
7056 {
7057  return _ui->general_doubleSpinBox_vp->value();
7058 }
7060 {
7061  return _ui->doubleSpinBox_similarityThreshold->value();
7062 }
7064 {
7065  return _ui->odom_strategy->currentIndex();
7066 }
7068 {
7069  return _ui->odom_dataBufferSize->value();
7070 }
7071 
7073 {
7074  return (this->getWorkingDirectory().isEmpty()?".":this->getWorkingDirectory())+"/camera_info";
7075 }
7076 
7078 {
7079  return _ui->general_checkBox_imagesKept->isChecked();
7080 }
7082 {
7083  return _ui->general_checkBox_missing_cache_republished->isChecked();
7084 }
7086 {
7087  return _ui->general_checkBox_cloudsKept->isChecked();
7088 }
7090 {
7091  return _ui->general_doubleSpinBox_timeThr->value();
7092 }
7094 {
7095  return _ui->general_doubleSpinBox_detectionRate->value();
7096 }
7098 {
7099  return _ui->general_checkBox_SLAM_mode->isChecked();
7100 }
7102 {
7103  return _ui->general_checkBox_activateRGBD->isChecked();
7104 }
7106 {
7107  return _ui->surf_spinBox_wordsPerImageTarget->value();
7108 }
7110 {
7111  return _ui->graphOptimization_priorsIgnored->isChecked();
7112 }
7113 
7114 /*** SETTERS ***/
7116 {
7117  ULOGGER_DEBUG("imgRate=%2.2f", value);
7118  if(_ui->general_doubleSpinBox_imgRate->value() != value)
7119  {
7120  _ui->general_doubleSpinBox_imgRate->setValue(value);
7121  if(validateForm())
7122  {
7124  }
7125  else
7126  {
7127  this->readSettingsBegin();
7128  }
7129  }
7130 }
7131 
7133 {
7134  ULOGGER_DEBUG("detectionRate=%2.2f", value);
7135  if(_ui->general_doubleSpinBox_detectionRate->value() != value)
7136  {
7137  _ui->general_doubleSpinBox_detectionRate->setValue(value);
7138  if(validateForm())
7139  {
7141  }
7142  else
7143  {
7144  this->readSettingsBegin();
7145  }
7146  }
7147 }
7148 
7150 {
7151  ULOGGER_DEBUG("timeLimit=%fs", value);
7152  if(_ui->general_doubleSpinBox_timeThr->value() != value)
7153  {
7154  _ui->general_doubleSpinBox_timeThr->setValue(value);
7155  if(validateForm())
7156  {
7158  }
7159  else
7160  {
7161  this->readSettingsBegin();
7162  }
7163  }
7164 }
7165 
7167 {
7168  ULOGGER_DEBUG("slam mode=%s", enabled?"true":"false");
7169  if(_ui->general_checkBox_SLAM_mode->isChecked() != enabled)
7170  {
7171  _ui->general_checkBox_SLAM_mode->setChecked(enabled);
7172  if(validateForm())
7173  {
7175  }
7176  else
7177  {
7178  this->readSettingsBegin();
7179  }
7180  }
7181 }
7182 
7184 {
7185  Camera * camera = this->createCamera();
7186  if(!camera)
7187  {
7188  return;
7189  }
7190 
7191  ParametersMap parameters = this->getAllParameters();
7192  IMUThread * imuThread = 0;
7193  if((this->getSourceDriver() == kSrcStereoImages ||
7194  this->getSourceDriver() == kSrcRGBDImages ||
7195  this->getSourceDriver() == kSrcImages) &&
7196  !_ui->lineEdit_cameraImages_path_imu->text().isEmpty())
7197  {
7198  imuThread = new IMUThread(_ui->spinBox_cameraImages_max_imu_rate->value(), this->getIMULocalTransform());
7199  if(getIMUFilteringStrategy()>0)
7200  {
7202  }
7203  if(!imuThread->init(_ui->lineEdit_cameraImages_path_imu->text().toStdString()))
7204  {
7205  QMessageBox::warning(this, tr("Source IMU Path"),
7206  tr("Initialization of IMU data has failed! Path=%1.").arg(_ui->lineEdit_cameraImages_path_imu->text()), QMessageBox::Ok);
7207  delete camera;
7208  delete imuThread;
7209  return;
7210  }
7211  }
7212 
7213  if(getOdomRegistrationApproach() < 3)
7214  {
7215  uInsert(parameters, ParametersPair(Parameters::kRegStrategy(), uNumber2Str(getOdomRegistrationApproach())));
7216  }
7217 
7218  int odomStrategy = Parameters::defaultOdomStrategy();
7219  Parameters::parse(parameters, Parameters::kOdomStrategy(), odomStrategy);
7220  if(odomStrategy != 1)
7221  {
7222  // Only Frame To Frame supports all VisCorType
7223  parameters.erase(Parameters::kVisCorType());
7224  }
7225 
7226  Odometry * odometry = Odometry::create(parameters);
7227 
7228  OdometryThread odomThread(
7229  odometry, // take ownership of odometry
7230  _ui->odom_dataBufferSize->value());
7231  odomThread.registerToEventsManager();
7232 
7233  OdometryViewer * odomViewer = new OdometryViewer(10,
7234  _ui->spinBox_decimation_odom->value(),
7235  0.0f,
7236  _ui->doubleSpinBox_maxDepth_odom->value(),
7237  this->getOdomQualityWarnThr(),
7238  this,
7239  this->getAllParameters());
7240  odomViewer->setWindowTitle(tr("Odometry viewer"));
7241  odomViewer->resize(1280, 480+QPushButton().minimumHeight());
7242  odomViewer->registerToEventsManager();
7243 
7244  SensorCaptureThread cameraThread(camera, this->getAllParameters()); // take ownership of camera
7245  cameraThread.setMirroringEnabled(isSourceMirroring());
7246  cameraThread.setColorOnly(_ui->checkbox_rgbd_colorOnly->isChecked());
7247  cameraThread.setImageDecimation(_ui->spinBox_source_imageDecimation->value());
7248  cameraThread.setHistogramMethod(_ui->comboBox_source_histogramMethod->currentIndex());
7249  if(_ui->checkbox_source_feature_detection->isChecked())
7250  {
7251  cameraThread.enableFeatureDetection(this->getAllParameters());
7252  }
7253  cameraThread.setStereoToDepth(_ui->checkbox_stereo_depthGenerated->isChecked());
7254  cameraThread.setStereoExposureCompensation(_ui->checkBox_stereo_exposureCompensation->isChecked());
7255  cameraThread.setScanParameters(
7256  _ui->checkBox_source_scanFromDepth->isChecked(),
7257  _ui->spinBox_source_scanDownsampleStep->value(),
7258  _ui->doubleSpinBox_source_scanRangeMin->value(),
7259  _ui->doubleSpinBox_source_scanRangeMax->value(),
7260  _ui->doubleSpinBox_source_scanVoxelSize->value(),
7261  _ui->spinBox_source_scanNormalsK->value(),
7262  _ui->doubleSpinBox_source_scanNormalsRadius->value(),
7263  (float)_ui->doubleSpinBox_source_scanNormalsForceGroundUp->value(),
7264  _ui->checkBox_source_scanDeskewing->isChecked());
7265  if(_ui->comboBox_imuFilter_strategy->currentIndex()>0 && dynamic_cast<DBReader*>(camera) == 0)
7266  {
7267  cameraThread.enableIMUFiltering(_ui->comboBox_imuFilter_strategy->currentIndex()-1, this->getAllParameters(), _ui->checkBox_imuFilter_baseFrameConversion->isChecked());
7268  }
7270  {
7271  if(_ui->groupBox_bilateral->isChecked())
7272  {
7273  cameraThread.enableBilateralFiltering(
7274  _ui->doubleSpinBox_bilateral_sigmaS->value(),
7275  _ui->doubleSpinBox_bilateral_sigmaR->value());
7276  }
7277  if(!_ui->lineEdit_source_distortionModel->text().isEmpty())
7278  {
7279  cameraThread.setDistortionModel(_ui->lineEdit_source_distortionModel->text().toStdString());
7280  }
7281  }
7282 
7283  UEventsManager::createPipe(&cameraThread, &odomThread, "SensorEvent");
7284  if(imuThread)
7285  {
7286  UEventsManager::createPipe(imuThread, &odomThread, "IMUEvent");
7287  }
7288  UEventsManager::createPipe(&odomThread, odomViewer, "OdometryEvent");
7289  UEventsManager::createPipe(odomViewer, &odomThread, "OdometryResetEvent");
7290 
7291  odomThread.start();
7292  cameraThread.start();
7293 
7294  if(imuThread)
7295  {
7296  imuThread->start();
7297  }
7298 
7299  odomViewer->exec();
7300  delete odomViewer;
7301 
7302  if(imuThread)
7303  {
7304  imuThread->join(true);
7305  delete imuThread;
7306  }
7307  cameraThread.join(true);
7308  odomThread.join(true);
7309 }
7310 
7312 {
7313  CameraViewer * window = new CameraViewer(this, this->getAllParameters());
7314  window->setWindowTitle(tr("Camera viewer"));
7315  window->resize(1280, 480+QPushButton().minimumHeight());
7316  window->registerToEventsManager();
7317 
7318  Camera * camera = this->createCamera();
7319  if(camera)
7320  {
7321  SensorCaptureThread cameraThread(camera, this->getAllParameters());
7322  cameraThread.setMirroringEnabled(isSourceMirroring());
7323  cameraThread.setColorOnly(_ui->checkbox_rgbd_colorOnly->isChecked());
7324  cameraThread.setImageDecimation(_ui->spinBox_source_imageDecimation->value());
7325  cameraThread.setHistogramMethod(_ui->comboBox_source_histogramMethod->currentIndex());
7326  if(_ui->checkbox_source_feature_detection->isChecked())
7327  {
7328  cameraThread.enableFeatureDetection(this->getAllParameters());
7329  }
7330  cameraThread.setStereoToDepth(_ui->checkbox_stereo_depthGenerated->isChecked());
7331  cameraThread.setStereoExposureCompensation(_ui->checkBox_stereo_exposureCompensation->isChecked());
7332  cameraThread.setScanParameters(
7333  _ui->checkBox_source_scanFromDepth->isChecked(),
7334  _ui->spinBox_source_scanDownsampleStep->value(),
7335  _ui->doubleSpinBox_source_scanRangeMin->value(),
7336  _ui->doubleSpinBox_source_scanRangeMax->value(),
7337  _ui->doubleSpinBox_source_scanVoxelSize->value(),
7338  _ui->spinBox_source_scanNormalsK->value(),
7339  _ui->doubleSpinBox_source_scanNormalsRadius->value(),
7340  (float)_ui->doubleSpinBox_source_scanNormalsForceGroundUp->value(),
7341  _ui->checkBox_source_scanDeskewing->isChecked());
7342  if(_ui->comboBox_imuFilter_strategy->currentIndex()>0 && dynamic_cast<DBReader*>(camera) == 0)
7343  {
7344  cameraThread.enableIMUFiltering(_ui->comboBox_imuFilter_strategy->currentIndex()-1, this->getAllParameters(), _ui->checkBox_imuFilter_baseFrameConversion->isChecked());
7345  }
7347  {
7348  if(_ui->groupBox_bilateral->isChecked())
7349  {
7350  cameraThread.enableBilateralFiltering(
7351  _ui->doubleSpinBox_bilateral_sigmaS->value(),
7352  _ui->doubleSpinBox_bilateral_sigmaR->value());
7353  }
7354  if(!_ui->lineEdit_source_distortionModel->text().isEmpty())
7355  {
7356  cameraThread.setDistortionModel(_ui->lineEdit_source_distortionModel->text().toStdString());
7357  }
7358  }
7359  UEventsManager::createPipe(&cameraThread, window, "SensorEvent");
7360 
7361  cameraThread.start();
7362  window->exec();
7363  delete window;
7364  cameraThread.join(true);
7365  }
7366  else
7367  {
7368  delete window;
7369  }
7370 }
7371 
7373 {
7374  if(this->getSourceType() == kSrcDatabase)
7375  {
7376  QMessageBox::warning(this,
7377  tr("Calibration"),
7378  tr("Cannot calibrate database source!"));
7379  return;
7380  }
7381 
7382  if(!this->getCameraInfoDir().isEmpty())
7383  {
7384  QDir dir(this->getCameraInfoDir());
7385  if (!dir.exists())
7386  {
7387  UINFO("Creating camera_info directory: \"%s\"", this->getCameraInfoDir().toStdString().c_str());
7388  if(!dir.mkpath(this->getCameraInfoDir()))
7389  {
7390  UWARN("Could create camera_info directory: \"%s\"", this->getCameraInfoDir().toStdString().c_str());
7391  }
7392  }
7393  }
7394 
7395  Src driver = this->getSourceDriver();
7397  {
7398  // 3 steps calibration: RGB -> IR -> Extrinsic
7399  QMessageBox::StandardButton button = QMessageBox::question(this, tr("Calibration"),
7400  tr("With \"%1\" driver, Color and IR cameras cannot be streamed at the "
7401  "same time. A 3-steps calibration is required (Color -> IR -> extrinsics). We will "
7402  "start with the Color camera calibration. Do you want to continue?").arg(this->getSourceDriverStr()),
7403  QMessageBox::Yes | QMessageBox::No | QMessageBox::Ignore, QMessageBox::Yes);
7404 
7405  if(button == QMessageBox::Yes || button == QMessageBox::Ignore)
7406  {
7408 
7409  Camera * camera = 0;
7410 
7411  // Step 1: RGB
7412  if(button != QMessageBox::Ignore)
7413  {
7414  camera = this->createCamera(true, true); // RAW color
7415  if(!camera)
7416  {
7417  return;
7418  }
7419 
7420  _calibrationDialog->setStereoMode(false); // this forces restart
7421  _calibrationDialog->setCameraName(QString(camera->getSerial().c_str())+"_rgb");
7423  SensorCaptureThread cameraThread(camera, this->getAllParameters());
7424  UEventsManager::createPipe(&cameraThread, _calibrationDialog, "SensorEvent");
7425  cameraThread.start();
7426  _calibrationDialog->exec();
7428  cameraThread.join(true);
7429  camera = 0;
7430  }
7431 
7432  button = QMessageBox::question(this, tr("Calibration"),
7433  tr("We will now calibrate the IR camera. Hide the IR projector with a Post-It and "
7434  "make sure you have enough ambient IR light (e.g., external IR source or sunlight!) to see the "
7435  "checkerboard with the IR camera. Do you want to continue?"),
7436  QMessageBox::Yes | QMessageBox::No | QMessageBox::Ignore, QMessageBox::Yes);
7437  if(button == QMessageBox::Yes || button == QMessageBox::Ignore)
7438  {
7439  // Step 2: IR
7440  if(button != QMessageBox::Ignore)
7441  {
7442  camera = this->createCamera(true, false); // RAW ir
7443  if(!camera)
7444  {
7445  return;
7446  }
7447 
7448  _calibrationDialog->setStereoMode(false); // this forces restart
7449  _calibrationDialog->setCameraName(QString(camera->getSerial().c_str())+"_depth");
7451  SensorCaptureThread cameraThread(camera, this->getAllParameters());
7452  UEventsManager::createPipe(&cameraThread, _calibrationDialog, "SensorEvent");
7453  cameraThread.start();
7454  _calibrationDialog->exec();
7456  cameraThread.join(true);
7457  camera = 0;
7458  }
7459 
7460  button = QMessageBox::question(this, tr("Calibration"),
7461  tr("We will now calibrate the extrinsics. Important: Make sure "
7462  "the cameras and the checkerboard don't move and that both "
7463  "cameras can see the checkerboard. We will repeat this "
7464  "multiple times. Each time, you will have to move the camera (or "
7465  "checkerboard) for a different point of view. Do you want to "
7466  "continue?"),
7467  QMessageBox::Yes | QMessageBox::No, QMessageBox::Yes);
7468 
7469  bool ok = false;
7470  int totalSamples = 0;
7471  if(button == QMessageBox::Yes)
7472  {
7473  totalSamples = QInputDialog::getInt(this, tr("Calibration"), tr("Samples: "), 1, 1, 99, 1, &ok);
7474  }
7475 
7476  if(ok)
7477  {
7478  int count = 0;
7479  _calibrationDialog->setStereoMode(true, "depth", "rgb"); // this forces restart
7481  _calibrationDialog->setModal(true);
7483  _calibrationDialog->show();
7484  CameraModel irModel;
7485  CameraModel rgbModel;
7486  std::string serial;
7487  for(;count < totalSamples && button == QMessageBox::Yes; )
7488  {
7489  // Step 3: Extrinsics
7490  camera = this->createCamera(false, true); // Rectified color
7491  if(!camera)
7492  {
7493  return;
7494  }
7495  SensorData rgbData = camera->takeData();
7496  UASSERT(rgbData.cameraModels().size() == 1);
7497  rgbModel = rgbData.cameraModels()[0];
7498  delete camera;
7499  camera = this->createCamera(false, false); // Rectified ir
7500  if(!camera)
7501  {
7502  return;
7503  }
7504  SensorData irData = camera->takeData();
7505  serial = camera->getSerial();
7506  UASSERT(irData.cameraModels().size() == 1);
7507  irModel = irData.cameraModels()[0];
7508  delete camera;
7509 
7510  if(!rgbData.imageRaw().empty() && !irData.imageRaw().empty())
7511  {
7512  // assume rgb sensor is on right (e.g., Kinect, Xtion Live Pro)
7513  int pair = _calibrationDialog->getStereoPairs();
7514  _calibrationDialog->processImages(irData.imageRaw(), rgbData.imageRaw(), serial.c_str());
7515  if(_calibrationDialog->getStereoPairs() - pair > 0)
7516  {
7517  ++count;
7518  if(count < totalSamples)
7519  {
7520  button = QMessageBox::question(this, tr("Calibration"),
7521  tr("A stereo pair has been taken (total=%1/%2). Move the checkerboard or "
7522  "camera to another position. Press \"Yes\" when you are ready "
7523  "for the next capture.").arg(count).arg(totalSamples),
7524  QMessageBox::Yes | QMessageBox::Abort, QMessageBox::Yes);
7525  }
7526  }
7527  else
7528  {
7529  button = QMessageBox::question(this, tr("Calibration"),
7530  tr("Could not detect the checkerboard on both images or "
7531  "the point of view didn't change enough. Try again?"),
7532  QMessageBox::Yes | QMessageBox::No, QMessageBox::Yes);
7533  }
7534  }
7535  else
7536  {
7537  button = QMessageBox::question(this, tr("Calibration"),
7538  tr("Failed to start the camera. Try again?"), QMessageBox::Yes | QMessageBox::No, QMessageBox::Yes);
7539  }
7540  }
7541  if(count == totalSamples && button == QMessageBox::Yes)
7542  {
7543  StereoCameraModel stereoModel = _calibrationDialog->stereoCalibration(irModel, rgbModel, true);
7544  stereoModel.setName(stereoModel.name(), "depth", "rgb");
7545  if(stereoModel.stereoTransform().isNull())
7546  {
7547  QMessageBox::warning(this, tr("Calibration"),
7548  tr("Extrinsic calibration has failed! Look on the terminal "
7549  "for possible error messages. Make sure corresponding calibration files exist "
7550  "in \"%1\" folder for camera \"%2\" or calibration name set. If not, re-do "
7551  "step 1 and 2 and make sure to export the calibration files.").arg(this->getCameraInfoDir()).arg(serial.c_str()), QMessageBox::Ok);
7552  }
7553  else if(stereoModel.saveStereoTransform(this->getCameraInfoDir().toStdString()))
7554  {
7555  QMessageBox::information(this, tr("Calibration"),
7556  tr("Calibration is completed! Extrinsics have been saved to \"%1/%2_pose.yaml\"").arg(this->getCameraInfoDir()).arg(stereoModel.name().c_str()), QMessageBox::Ok);
7557  }
7558  }
7559  }
7560  }
7561  }
7562  }
7563  else // standard calibration
7564  {
7565  Camera * camera = this->createCamera(true);
7566  if(!camera)
7567  {
7568  return;
7569  }
7570 
7571  bool freenect2 = driver == kSrcFreenect2;
7572  bool rgbDepth = freenect2 || (driver==kSrcStereoDepthAI && _ui->comboBox_depthai_output_mode->currentIndex() == 2);
7573  _calibrationDialog->setStereoMode(this->getSourceType() != kSrcRGB && driver != kSrcRealSense, rgbDepth?"rgb":"left", rgbDepth?"depth":"right"); // RGB+Depth or left+right
7576  if(driver == kSrcStereoRealSense2)
7578  if(driver == kSrcStereoDepthAI)
7582 
7583  SensorCaptureThread cameraThread(camera, this->getAllParameters());
7584  UEventsManager::createPipe(&cameraThread, _calibrationDialog, "SensorEvent");
7585 
7586  cameraThread.start();
7587 
7588  _calibrationDialog->exec();
7590 
7591  cameraThread.join(true);
7592  }
7594 }
7595 
7597 {
7599  if(_createCalibrationDialog->exec() == QMessageBox::Accepted)
7600  {
7601  _ui->lineEdit_calibrationFile->setText(_createCalibrationDialog->cameraName());
7602  }
7603 }
7604 
7606 {
7607  if(this->getSourceType() == kSrcDatabase)
7608  {
7609  QMessageBox::warning(this,
7610  tr("Calibration"),
7611  tr("Cannot calibrate database source!"));
7612  return;
7613  }
7614 
7615  if(!this->getCameraInfoDir().isEmpty())
7616  {
7617  QDir dir(this->getCameraInfoDir());
7618  if (!dir.exists())
7619  {
7620  UINFO("Creating camera_info directory: \"%s\"", this->getCameraInfoDir().toStdString().c_str());
7621  if(!dir.mkpath(this->getCameraInfoDir()))
7622  {
7623  UWARN("Could create camera_info directory: \"%s\"", this->getCameraInfoDir().toStdString().c_str());
7624  }
7625  }
7626  }
7627 
7628  Src odomDriver = getOdomSourceDriver();
7629  if(odomDriver == kSrcUndef)
7630  {
7631  QMessageBox::warning(this,
7632  tr("Calibration"),
7633  tr("No odometry sensor selected!"));
7634  return;
7635  }
7636 
7637 
7638  // 3 steps calibration: RGB -> IR -> Extrinsic
7639  QMessageBox::StandardButton button = QMessageBox::question(this, tr("Calibration"),
7640  tr("We will calibrate the extrinsics. Important: Make sure "
7641  "the cameras and the checkerboard don't move and that both "
7642  "cameras can see the checkerboard. We will repeat this "
7643  "multiple times. Each time, you will have to move the camera (or "
7644  "checkerboard) for a different point of view. Do you want to "
7645  "continue?"),
7646  QMessageBox::Yes | QMessageBox::No, QMessageBox::Yes);
7647 
7648  if(button == QMessageBox::Yes)
7649  {
7651 
7652  bool ok = false;
7653  int totalSamples = 0;
7654  if(button == QMessageBox::Yes)
7655  {
7656  QDialog dialog(this);
7657  QFormLayout form(&dialog);
7658 
7659  // Add the lineEdits with their respective labels
7660  QSpinBox * samples = new QSpinBox(&dialog);
7661  samples->setMinimum(1);
7662  samples->setMaximum(99);
7663  samples->setValue(1);
7664  QSpinBox * boardWidth = new QSpinBox(&dialog);
7665  boardWidth->setMinimum(2);
7666  boardWidth->setMaximum(99);
7667  boardWidth->setValue(_calibrationDialog->boardWidth());
7668  QSpinBox * boardHeight = new QSpinBox(&dialog);
7669  boardHeight->setMinimum(2);
7670  boardHeight->setMaximum(99);
7671  boardHeight->setValue(_calibrationDialog->boardHeight());
7672  QDoubleSpinBox * squareSize = new QDoubleSpinBox(&dialog);
7673  squareSize->setDecimals(4);
7674  squareSize->setMinimum(0.0001);
7675  squareSize->setMaximum(9);
7676  squareSize->setValue(_calibrationDialog->squareSize());
7677  squareSize->setSuffix(" m");
7678  form.addRow("Samples: ", samples);
7679  form.addRow("Checkerboard Width: ", boardWidth);
7680  form.addRow("Checkerboard Height: ", boardHeight);
7681  form.addRow("Checkerboard Square Size: ", squareSize);
7682 
7683  // Add some standard buttons (Cancel/Ok) at the bottom of the dialog
7684  QDialogButtonBox buttonBox(QDialogButtonBox::Ok | QDialogButtonBox::Cancel,
7685  Qt::Horizontal, &dialog);
7686  form.addRow(&buttonBox);
7687  QObject::connect(&buttonBox, SIGNAL(accepted()), &dialog, SLOT(accept()));
7688  QObject::connect(&buttonBox, SIGNAL(rejected()), &dialog, SLOT(reject()));
7689 
7690  // Show the dialog as modal
7691  if (dialog.exec() == QDialog::Accepted) {
7692  _calibrationDialog->setBoardWidth(boardWidth->value());
7693  _calibrationDialog->setBoardHeight(boardHeight->value());
7694  _calibrationDialog->setSquareSize(squareSize->value());
7695  totalSamples = samples->value();
7696  ok = true;
7697  }
7698  }
7699 
7700  if(ok)
7701  {
7702  int count = 0;
7703  _calibrationDialog->setStereoMode(true, "camera", "odom_sensor"); // this forces restart
7705  _calibrationDialog->setModal(true);
7707  _calibrationDialog->show();
7708 
7709  CameraModel cameraModel;
7710  CameraModel odomSensorModel;
7711  std::string serial;
7712  for(;count < totalSamples && button == QMessageBox::Yes; )
7713  {
7714  // Step 3: Extrinsics
7715  Camera * camera = this->createCamera(
7716  odomDriver,
7717  _ui->lineEdit_odomSourceDevice->text(),
7718  _ui->lineEdit_odom_sensor_path_calibration->text(),
7719  false, true, false, true); // Odom sensor
7720  if(!camera)
7721  {
7722  return;
7723  }
7724  else if(!camera->isCalibrated())
7725  {
7726  QMessageBox::warning(_calibrationDialog, tr("Calibration"),
7727  tr("Odom sensor is not calibrated. Camera and odometry sensor should be individually calibrated (intrinsics) before calibrating the extrinsics between them. Aborting..."), QMessageBox::Ok);
7728  delete camera;
7729  return;
7730  }
7731  SensorData odomSensorData = camera->takeData();
7732  if(odomSensorData.cameraModels().size() == 1) {
7733  odomSensorModel = odomSensorData.cameraModels()[0];
7734  }
7735  else if(odomSensorData.stereoCameraModels().size() == 1) {
7736  odomSensorModel = odomSensorData.stereoCameraModels()[0].left();
7737  }
7738  delete camera;
7739 
7740  int currentIndex = _ui->comboBox_odom_sensor->currentIndex();
7741  _ui->comboBox_odom_sensor->setCurrentIndex(0);
7742  camera = this->createCamera(false, true); // Camera
7743  _ui->comboBox_odom_sensor->setCurrentIndex(currentIndex);
7744  if(!camera)
7745  {
7746  return;
7747  }
7748  else if(!camera->isCalibrated())
7749  {
7750  QMessageBox::warning(_calibrationDialog, tr("Calibration"),
7751  tr("Odom sensor is not calibrated. Camera and odometry sensor should be individually calibrated (intrinsics) before calibrating the extrinsics between them. Aborting..."), QMessageBox::Ok);
7752  delete camera;
7753  return;
7754  }
7755  SensorData camData = camera->takeData();
7756  serial = camera->getSerial();
7757  if(camData.cameraModels().size() == 1) {
7758  cameraModel = camData.cameraModels()[0];
7759  }
7760  else if(camData.stereoCameraModels().size() == 1) {
7761  cameraModel = camData.stereoCameraModels()[0].left();
7762  }
7763  delete camera;
7764 
7765  if(!odomSensorData.imageRaw().empty() && !camData.imageRaw().empty())
7766  {
7767  int pair = _calibrationDialog->getStereoPairs();
7768  _calibrationDialog->processImages(camData.imageRaw(), odomSensorData.imageRaw(), serial.c_str());
7769  if(_calibrationDialog->getStereoPairs() - pair > 0)
7770  {
7771  ++count;
7772  if(count < totalSamples)
7773  {
7774  button = QMessageBox::question(_calibrationDialog, tr("Calibration"),
7775  tr("A stereo pair has been taken (total=%1/%2). Move the checkerboard or "
7776  "camera to another position. Press \"Yes\" when you are ready "
7777  "for the next capture.").arg(count).arg(totalSamples),
7778  QMessageBox::Yes | QMessageBox::Abort, QMessageBox::Yes);
7779  }
7780  }
7781  else
7782  {
7783  button = QMessageBox::question(_calibrationDialog, tr("Calibration"),
7784  tr("Could not detect the checkerboard on both images or "
7785  "the point of view didn't change enough. Try again?"),
7786  QMessageBox::Yes | QMessageBox::No, QMessageBox::Yes);
7787  }
7788  }
7789  else
7790  {
7791  button = QMessageBox::question(_calibrationDialog, tr("Calibration"),
7792  tr("Failed to start the camera. Try again?"), QMessageBox::Yes | QMessageBox::No, QMessageBox::Yes);
7793  }
7794  }
7795  if(count == totalSamples && button == QMessageBox::Yes)
7796  {
7797  // Assume cameras are already rectified!
7798  cameraModel = CameraModel("camera", cameraModel.imageSize(), cameraModel.K(), cv::Mat::zeros(1,5,CV_64FC1), cv::Mat(), cv::Mat(), cameraModel.localTransform());
7799  odomSensorModel = CameraModel("odom_sensor", odomSensorModel.imageSize(), odomSensorModel.K(), cv::Mat::zeros(1,5,CV_64FC1), cv::Mat(), cv::Mat(), odomSensorModel.localTransform());
7800 
7801  StereoCameraModel stereoModel = _calibrationDialog->stereoCalibration(cameraModel, odomSensorModel, true);
7802  stereoModel.setName(stereoModel.name(), "camera", "odom_sensor");
7803  if(stereoModel.stereoTransform().isNull())
7804  {
7805  QMessageBox::warning(_calibrationDialog, tr("Calibration"),
7806  tr("Extrinsic calibration has failed! Look on the terminal "
7807  "for possible error messages."), QMessageBox::Ok);
7808  std::cout << "stereoModel: " << stereoModel << std::endl;
7809  }
7810  else
7811  {
7812  UINFO("Odom sensor local transform (pose to left cam): %s", odomSensorModel.localTransform().prettyPrint().c_str());
7813  UINFO("Extrinsics (odom left cam to camera left cam): %s", stereoModel.stereoTransform().prettyPrint().c_str());
7814 
7815  Transform t = odomSensorModel.localTransform() * stereoModel.stereoTransform() * CameraModel::opticalRotation().inverse();
7816  UINFO("Odom sensor frame to camera frame: %s", t.prettyPrint().c_str());
7817 
7818  float x,y,z,roll,pitch,yaw;
7819  t.getTranslationAndEulerAngles(x, y, z, roll, pitch, yaw);
7820  _ui->lineEdit_odom_sensor_extrinsics->setText(QString("%1 %2 %3 %4 %5 %6")
7821  .arg(x).arg(y).arg(z)
7822  .arg(roll).arg(pitch).arg(yaw));
7823  QMessageBox::information(_calibrationDialog, tr("Calibration"),
7824  tr("Calibration is completed! Extrinsics have been computed: %1. "
7825  "You can close the calibration dialog.").arg(t.prettyPrint().c_str()), QMessageBox::Ok);
7826  }
7827  }
7828  }
7829  }
7830 }
7831 
7833 {
7834  CameraViewer * window = new CameraViewer(this, this->getAllParameters());
7835  window->setWindowTitle(tr("Lidar viewer"));
7836  window->setWindowFlags(Qt::Window);
7837  window->resize(1280, 480+QPushButton().minimumHeight());
7838  window->registerToEventsManager();
7839  window->setDecimation(1);
7840 
7841  Lidar * lidar = this->createLidar();
7842  if(lidar)
7843  {
7844  SensorCaptureThread lidarThread(lidar, this->getAllParameters());
7845  lidarThread.setScanParameters(
7846  _ui->checkBox_source_scanFromDepth->isChecked(),
7847  _ui->spinBox_source_scanDownsampleStep->value(),
7848  _ui->doubleSpinBox_source_scanRangeMin->value(),
7849  _ui->doubleSpinBox_source_scanRangeMax->value(),
7850  _ui->doubleSpinBox_source_scanVoxelSize->value(),
7851  _ui->spinBox_source_scanNormalsK->value(),
7852  _ui->doubleSpinBox_source_scanNormalsRadius->value(),
7853  (float)_ui->doubleSpinBox_source_scanNormalsForceGroundUp->value(),
7854  _ui->checkBox_source_scanDeskewing->isChecked());
7855 
7856  UEventsManager::createPipe(&lidarThread, window, "SensorEvent");
7857 
7858  lidarThread.start();
7859  window->exec();
7860  delete window;
7861  lidarThread.join(true);
7862  }
7863  else
7864  {
7865  delete window;
7866  }
7867 }
7868 
7869 }
7870 
rtabmap::PreferencesDialog::changeOdometryVINSConfigPath
void changeOdometryVINSConfigPath()
Definition: PreferencesDialog.cpp:5466
rtabmap::PreferencesDialog::selectSourceDistortionModel
void selectSourceDistortionModel()
Definition: PreferencesDialog.cpp:4639
rtabmap::Optimizer::isAvailable
static bool isAvailable(Optimizer::Type type)
Definition: Optimizer.cpp:47
rtabmap::SensorData
Definition: SensorData.h:51
rtabmap::PreferencesDialog::beepOnPause
bool beepOnPause() const
Definition: PreferencesDialog.cpp:5775
rtabmap::SensorCaptureThread
Definition: SensorCaptureThread.h:58
check
check
rtabmap::PreferencesDialog::isVerticalLayoutUsed
bool isVerticalLayoutUsed() const
Definition: PreferencesDialog.cpp:5763
rtabmap::PreferencesDialog::clicked
void clicked(const QModelIndex &current, const QModelIndex &previous)
Definition: PreferencesDialog.cpp:1873
rtabmap::CalibrationDialog::setProgressVisibility
void setProgressVisibility(bool visible)
Definition: CalibrationDialog.cpp:328
rtabmap::ParametersPair
std::pair< std::string, std::string > ParametersPair
Definition: Parameters.h:44
rtabmap::PreferencesDialog::selectSourceRGBDImagesPathDepth
void selectSourceRGBDImagesPathDepth()
Definition: PreferencesDialog.cpp:4491
rtabmap::PreferencesDialog::_parameters
rtabmap::ParametersMap _parameters
Definition: PreferencesDialog.h:451
rtabmap::CalibrationDialog::loadSettings
void loadSettings(QSettings &settings, const QString &group="")
Definition: CalibrationDialog.cpp:200
rtabmap::PreferencesDialog::isCloudFiltering
bool isCloudFiltering() const
Definition: PreferencesDialog.cpp:6088
CreateSimpleCalibrationDialog.h
rtabmap::DatabaseViewer
Definition: DatabaseViewer.h:68
rtabmap::PreferencesDialog::getOdomStrategy
int getOdomStrategy() const
Definition: PreferencesDialog.cpp:7063
rtabmap::PreferencesDialog::getGridMapSensor
int getGridMapSensor() const
Definition: PreferencesDialog.cpp:6128
rtabmap::SensorCapture::getSerial
virtual std::string getSerial() const =0
rtabmap::Odometry::create
static Odometry * create(const ParametersMap &parameters=ParametersMap())
Definition: Odometry.cpp:58
rtabmap::CalibrationDialog::setSwitchedImages
void setSwitchedImages(bool switched)
Definition: CalibrationDialog.cpp:333
rtabmap::CameraImages
Definition: CameraImages.h:39
rtabmap::PreferencesDialog::settingsChanged
void settingsChanged(PreferencesDialog::PANEL_FLAGS)
rtabmap::PreferencesDialog::kPanelLogging
@ kPanelLogging
Definition: PreferencesDialog.h:77
rtabmap::PreferencesDialog::getCloudColorScheme
int getCloudColorScheme(int index) const
Definition: PreferencesDialog.cpp:6015
rtabmap::CalibrationDialog::setRationalModel
void setRationalModel()
Definition: CalibrationDialog.cpp:348
UINFO
#define UINFO(...)
rtabmap::PreferencesDialog::getSourceScanForceGroundNormalsUp
double getSourceScanForceGroundNormalsUp() const
Definition: PreferencesDialog.cpp:6399
rtabmap::PreferencesDialog::loadCustomConfig
QString loadCustomConfig(const QString &section, const QString &key)
Definition: PreferencesDialog.cpp:4116
name
rtabmap::PreferencesDialog::makeObsoleteCloudRenderingPanel
void makeObsoleteCloudRenderingPanel()
Definition: PreferencesDialog.cpp:5182
rtabmap::StereoCameraModel
Definition: StereoCameraModel.h:35
rtabmap::PreferencesDialog::setupTreeView
void setupTreeView()
Definition: PreferencesDialog.cpp:1714
rtabmap::PreferencesDialog::getIMUGravityLength
double getIMUGravityLength(int index) const
Definition: PreferencesDialog.cpp:5945
ImageView.h
rtabmap::PreferencesDialog::getIMURate
int getIMURate() const
Definition: PreferencesDialog.cpp:6306
rtabmap::CameraStereoTara
Definition: CameraStereoTara.h:43
rtabmap::PreferencesDialog::isSourceRGBDColorOnly
bool isSourceRGBDColorOnly() const
Definition: PreferencesDialog.cpp:6315
rtabmap::PreferencesDialog::setParameter
void setParameter(const std::string &key, const std::string &value)
Definition: PreferencesDialog.cpp:4751
clams::DiscreteDepthDistortionModel
Definition: discrete_depth_distortion_model.h:68
rtabmap::PreferencesDialog::selectOdomSensorCalibrationPath
void selectOdomSensorCalibrationPath()
Definition: PreferencesDialog.cpp:4415
rtabmap::CameraStereoVideo
Definition: CameraStereoVideo.h:36
SensorCaptureThread.h
rtabmap::IMUThread::init
bool init(const std::string &path)
Definition: IMUThread.cpp:54
rtabmap::PreferencesDialog::kSrcUsbDevice
@ kSrcUsbDevice
Definition: PreferencesDialog.h:116
glm::yaw
GLM_FUNC_DECL T yaw(detail::tquat< T, P > const &x)
bytes
rtabmap::SensorCaptureThread::setScanParameters
RTABMAP_DEPRECATED void setScanParameters(bool fromDepth, int downsampleStep, float rangeMin, float rangeMax, float voxelSize, int normalsK, float normalsRadius, bool forceGroundNormalsUp, bool deskewing)
Definition: SensorCaptureThread.cpp:262
rtabmap::CameraDepthAI
Definition: CameraDepthAI.h:44
rtabmap::Parameters::readINIStr
static void readINIStr(const std::string &configContent, ParametersMap &parameters, bool modifiedOnly=false)
Definition: Parameters.cpp:1280
rtabmap::PreferencesDialog::_3dRenderingGravityLength
QVector< QDoubleSpinBox * > _3dRenderingGravityLength
Definition: PreferencesDialog.h:483
rtabmap::PreferencesDialog::selectVlp16PcapPath
void selectVlp16PcapPath()
Definition: PreferencesDialog.cpp:4737
rtabmap::PreferencesDialog::updateOdometryStackedIndex
void updateOdometryStackedIndex(int index)
Definition: PreferencesDialog.cpp:5356
rtabmap::PreferencesDialog::selectSourceDatabase
void selectSourceDatabase()
Definition: PreferencesDialog.cpp:4306
arg::arg
constexpr arg(const char *name=nullptr)
rtabmap::CameraStereoFlyCapture2::available
static bool available()
Definition: CameraStereoFlyCapture2.cpp:68
rtabmap::PreferencesDialog::isRGBDMode
bool isRGBDMode() const
Definition: PreferencesDialog.cpp:7101
rtabmap::PreferencesDialog::isSourceStereoExposureCompensation
bool isSourceStereoExposureCompensation() const
Definition: PreferencesDialog.cpp:6363
discrete_depth_distortion_model.h
rtabmap::OdometryThread
Definition: OdometryThread.h:41
rtabmap::PreferencesDialog::selectSourceStereoImagesPathRight
void selectSourceStereoImagesPathRight()
Definition: PreferencesDialog.cpp:4567
gtsam::Values::size
size_t size() const
rtabmap::PreferencesDialog::getSourceType
PreferencesDialog::Src getSourceType() const
Definition: PreferencesDialog.cpp:6171
rtabmap::PreferencesDialog::isSourceFeatureDetection
bool isSourceFeatureDetection() const
Definition: PreferencesDialog.cpp:6355
rtabmap::PreferencesDialog::kPanelCalibration
@ kPanelCalibration
Definition: PreferencesDialog.h:79
rtabmap::CameraOpenNI2::exposureGainAvailable
static bool exposureGainAvailable()
Definition: CameraOpenNI2.cpp:51
rtabmap::PreferencesDialog::getSimThr
double getSimThr() const
Definition: PreferencesDialog.cpp:7059
rtabmap::CloudViewer::saveSettings
void saveSettings(QSettings &settings, const QString &group="") const
Definition: CloudViewer.cpp:415
IMUThread.h
rtabmap::CameraFreenect::available
static bool available()
Definition: CameraFreenect.cpp:284
b
Array< int, 3, 1 > b
UEventsHandler::registerToEventsManager
void registerToEventsManager()
Definition: UEventsHandler.cpp:29
rtabmap::CreateSimpleCalibrationDialog
Definition: CreateSimpleCalibrationDialog.h:40
rtabmap::PreferencesDialog::getIMUPath
QString getIMUPath() const
Definition: PreferencesDialog.cpp:6293
rtabmap::PreferencesDialog::isOctomapUpdated
bool isOctomapUpdated() const
Definition: PreferencesDialog.cpp:5841
rtabmap::PreferencesDialog::isCloudMeshingTexture
bool isCloudMeshingTexture() const
Definition: PreferencesDialog.cpp:5974
rtabmap::CalibrationDialog::getStereoPairs
int getStereoPairs() const
Definition: CalibrationDialog.h:65
list
rtabmap::PreferencesDialog::_calibrationDialog
CalibrationDialog * _calibrationDialog
Definition: PreferencesDialog.h:460
rtabmap::PreferencesDialog::getLaserLocalTransform
Transform getLaserLocalTransform() const
Definition: PreferencesDialog.cpp:6283
Horizontal
Horizontal
rtabmap::Optimizer::kTypeGTSAM
@ kTypeGTSAM
Definition: Optimizer.h:68
rtabmap::PreferencesDialog::validateForm
bool validateForm()
Definition: PreferencesDialog.cpp:3467
rtabmap::CameraRealSense::available
static bool available()
Definition: CameraRealSense.cpp:47
rtabmap::PreferencesDialog::resetConfig
void resetConfig()
Definition: PreferencesDialog.cpp:2963
rtabmap::ExportCloudsDialog
Definition: ExportCloudsDialog.h:54
rtabmap::CameraStereoDC1394::available
static bool available()
Definition: CameraStereoDC1394.cpp:317
rtabmap::PreferencesDialog::_3dRenderingColorScheme
QVector< QSpinBox * > _3dRenderingColorScheme
Definition: PreferencesDialog.h:468
rtabmap::CameraK4W2::available
static bool available()
Definition: CameraK4W2.cpp:53
rtabmap::PreferencesDialog::projMaxGroundHeight
double projMaxGroundHeight() const
Definition: PreferencesDialog.cpp:6140
rtabmap::PreferencesDialog::getSubtractFilteringAngle
double getSubtractFilteringAngle() const
Definition: PreferencesDialog.cpp:6112
rtabmap::PreferencesDialog::isRelocalizationColorOdomCacheGraphView
bool isRelocalizationColorOdomCacheGraphView() const
Definition: PreferencesDialog.cpp:5811
rtabmap::CameraViewer
Definition: CameraViewer.h:49
VWDictionary.h
rtabmap::PreferencesDialog::projMapFrame
bool projMapFrame() const
Definition: PreferencesDialog.cpp:6132
rtabmap::PreferencesDialog::getAllParameters
rtabmap::ParametersMap getAllParameters() const
Definition: PreferencesDialog.cpp:4136
LoopClosureViewer.h
rtabmap::PreferencesDialog::getParameter
std::string getParameter(const std::string &key) const
Definition: PreferencesDialog.cpp:4148
LidarVLP16.h
rtabmap::PreferencesDialog::changeDictionaryPath
void changeDictionaryPath()
Definition: PreferencesDialog.cpp:5415
rtabmap::PreferencesDialog::kSrcStereoMyntEye
@ kSrcStereoMyntEye
Definition: PreferencesDialog.h:111
rtabmap::PreferencesDialog::resetSettings
void resetSettings(int panelNumber)
Definition: PreferencesDialog.cpp:2372
OdometryThread.h
rtabmap::PreferencesDialog::changeIcpPMConfigPath
void changeIcpPMConfigPath()
Definition: PreferencesDialog.cpp:5517
rtabmap::IMUThread
Definition: IMUThread.h:49
rtabmap::ExportCloudsDialog::loadSettings
void loadSettings(QSettings &settings, const QString &group="")
Definition: ExportCloudsDialog.cpp:533
rtabmap::CameraFreenect::kTypeIRDepth
@ kTypeIRDepth
Definition: CameraFreenect.h:49
rtabmap::PreferencesDialog::isFramesShown
bool isFramesShown() const
Definition: PreferencesDialog.cpp:5928
rtabmap::PreferencesDialog::getSourceScanNormalsRadius
double getSourceScanNormalsRadius() const
Definition: PreferencesDialog.cpp:6395
rtabmap::PreferencesDialog::makeObsoleteCalibrationPanel
void makeObsoleteCalibrationPanel()
Definition: PreferencesDialog.cpp:5200
rtabmap::PreferencesDialog::getGeneralLoggerPrintTime
bool getGeneralLoggerPrintTime() const
Definition: PreferencesDialog.cpp:5743
rtabmap::Transform::getIdentity
static Transform getIdentity()
Definition: Transform.cpp:411
this
this
rtabmap::CameraModel
Definition: CameraModel.h:38
rtabmap::PreferencesDialog::addParameter
void addParameter(int value)
Definition: PreferencesDialog.cpp:4891
uStr2Bool
bool UTILITE_EXPORT uStr2Bool(const char *str)
Definition: UConversion.cpp:170
rtabmap::PreferencesDialog::kSrcLidar
@ kSrcLidar
Definition: PreferencesDialog.h:122
rtabmap::CameraFreenect2::kTypeColorIR
@ kTypeColorIR
Definition: CameraFreenect2.h:58
rtabmap::CalibrationDialog::boardHeight
int boardHeight() const
Definition: CalibrationDialog.cpp:392
rtabmap::PreferencesDialog::kSrcRGBDImages
@ kSrcRGBDImages
Definition: PreferencesDialog.h:96
rtabmap::PreferencesDialog::isGraphsShown
bool isGraphsShown() const
Definition: PreferencesDialog.cpp:5920
rtabmap::PreferencesDialog::selectSourceSvoPath
void selectSourceSvoPath()
Definition: PreferencesDialog.cpp:4695
rtabmap::PreferencesDialog::loadPreset
void loadPreset()
Definition: PreferencesDialog.cpp:2997
rtabmap::PreferencesDialog::_3dRenderingDecimation
QVector< QSpinBox * > _3dRenderingDecimation
Definition: PreferencesDialog.h:464
rtabmap::PreferencesDialog::Src
Src
Definition: PreferencesDialog.h:85
UThread::join
void join(bool killFirst=false)
Definition: UThread.cpp:85
rtabmap::CameraFreenect2::Type
Type
Definition: CameraFreenect2.h:52
rtabmap::PreferencesDialog::getScanNormalRadiusSearch
double getScanNormalRadiusSearch() const
Definition: PreferencesDialog.cpp:5915
rtabmap::PreferencesDialog::isOctomap2dGrid
bool isOctomap2dGrid() const
Definition: PreferencesDialog.cpp:5859
rtabmap::PreferencesDialog::isTimeUsedInFigures
bool isTimeUsedInFigures() const
Definition: PreferencesDialog.cpp:5779
rtabmap::PreferencesDialog::isFrustumsShown
bool isFrustumsShown(int index) const
Definition: PreferencesDialog.cpp:6077
rtabmap::PreferencesDialog::loadMainWindowState
void loadMainWindowState(QMainWindow *mainWindow, bool &maximized, bool &statusBarShown)
Definition: PreferencesDialog.cpp:3919
count
Index count
rtabmap::PreferencesDialog::updateFeatureMatchingVisibility
void updateFeatureMatchingVisibility()
Definition: PreferencesDialog.cpp:5345
PostProcessingDialog.h
rtabmap::SensorCaptureThread::setColorOnly
void setColorOnly(bool colorOnly)
Definition: SensorCaptureThread.h:125
rtabmap::PreferencesDialog::_3dRenderingPtSizeScan
QVector< QSpinBox * > _3dRenderingPtSizeScan
Definition: PreferencesDialog.h:478
rtabmap::OptimizerG2O::isCholmodAvailable
static bool isCholmodAvailable()
Definition: OptimizerG2O.cpp:135
rtabmap::CameraMyntEye
Definition: CameraMyntEye.h:47
rtabmap::PreferencesDialog::makeObsoleteLoggingPanel
void makeObsoleteLoggingPanel()
Definition: PreferencesDialog.cpp:5188
rtabmap::PreferencesDialog::createLidar
Lidar * createLidar()
Definition: PreferencesDialog.cpp:6986
rtabmap::PreferencesDialog::getScanMaxRange
double getScanMaxRange(int index) const
Definition: PreferencesDialog.cpp:6041
CameraViewer.h
rtabmap::PreferencesDialog::selectSourceDepthaiBlobPath
void selectSourceDepthaiBlobPath()
Definition: PreferencesDialog.cpp:4723
CameraRGBD.h
rtabmap_netvlad.img
img
Definition: rtabmap_netvlad.py:78
rtabmap::PreferencesDialog::writeCameraSettings
virtual void writeCameraSettings(const QString &filePath=QString()) const
Definition: PreferencesDialog.cpp:3181
rtabmap::PreferencesDialog::kSrcRealSense2
@ kSrcRealSense2
Definition: PreferencesDialog.h:98
rtabmap::PreferencesDialog::init
void init(const QString &iniFilePath="")
Definition: PreferencesDialog.cpp:1678
rtabmap::CameraStereoTara::available
static bool available()
Definition: CameraStereoTara.cpp:45
type
rtabmap::PreferencesDialog::getOdomRegistrationApproach
int getOdomRegistrationApproach() const
Definition: PreferencesDialog.cpp:5823
rtabmap::DatabaseViewer::showCloseButton
void showCloseButton(bool visible=true)
Definition: DatabaseViewer.cpp:534
rtabmap::CalibrationDialog::boardWidth
int boardWidth() const
Definition: CalibrationDialog.cpp:388
rtabmap::PreferencesDialog::kSrcStereoTara
@ kSrcStereoTara
Definition: PreferencesDialog.h:109
CameraStereo.h
rtabmap::PreferencesDialog::getBilateralSigmaR
double getBilateralSigmaR() const
Definition: PreferencesDialog.cpp:6343
rtabmap::PreferencesDialog::_indexModel
QStandardItemModel * _indexModel
Definition: PreferencesDialog.h:453
rtabmap::PreferencesDialog::changePyMatcherPath
void changePyMatcherPath()
Definition: PreferencesDialog.cpp:5551
DBReader.h
rtabmap::PreferencesDialog::updateGlobalDescriptorVisibility
void updateGlobalDescriptorVisibility()
Definition: PreferencesDialog.cpp:5351
rtabmap::PreferencesDialog::kPanelDummy
@ kPanelDummy
Definition: PreferencesDialog.h:74
rtabmap::PreferencesDialog::_3dRenderingShowScans
QVector< QCheckBox * > _3dRenderingShowScans
Definition: PreferencesDialog.h:471
rtabmap::PreferencesDialog::isPriorIgnored
bool isPriorIgnored() const
Definition: PreferencesDialog.cpp:7109
y
Matrix3f y
rtabmap::PreferencesDialog::getGeneralLoggerType
int getGeneralLoggerType() const
Definition: PreferencesDialog.cpp:5739
rtabmap::PreferencesDialog::isCloudMeshing
bool isCloudMeshing() const
Definition: PreferencesDialog.cpp:5962
rtabmap::PreferencesDialog::isIMUAccShown
bool isIMUAccShown() const
Definition: PreferencesDialog.cpp:5950
rtabmap::Transform::fromString
static Transform fromString(const std::string &string)
Definition: Transform.cpp:475
uStr2Double
double UTILITE_EXPORT uStr2Double(const std::string &str)
Definition: UConversion.cpp:147
rtabmap::CameraModel::K
cv::Mat K() const
Definition: CameraModel.h:110
rtabmap::PreferencesDialog::changeOdometryOKVISConfigPath
void changeOdometryOKVISConfigPath()
Definition: PreferencesDialog.cpp:5449
rtabmap::PreferencesDialog::updateParameters
void updateParameters(const ParametersMap &parameters, bool setOtherParametersToDefault=false)
Definition: PreferencesDialog.cpp:4159
rtabmap::PreferencesDialog::isMarkerDetection
bool isMarkerDetection() const
Definition: PreferencesDialog.cpp:5954
rtabmap::PreferencesDialog::_3dRenderingOpacity
QVector< QDoubleSpinBox * > _3dRenderingOpacity
Definition: PreferencesDialog.h:469
rtabmap::PreferencesDialog::changeWorkingDirectory
void changeWorkingDirectory()
Definition: PreferencesDialog.cpp:5405
rtabmap::PreferencesDialog::getBilateralSigmaS
double getBilateralSigmaS() const
Definition: PreferencesDialog.cpp:6339
rtabmap::PreferencesDialog::getScanPointSize
int getScanPointSize(int index) const
Definition: PreferencesDialog.cpp:6066
rtabmap::PreferencesDialog::getSubtractFilteringMinPts
int getSubtractFilteringMinPts() const
Definition: PreferencesDialog.cpp:6104
rtabmap::PreferencesDialog::kSrcOpenNI2
@ kSrcOpenNI2
Definition: PreferencesDialog.h:93
rtabmap::PreferencesDialog::kSrcVideo
@ kSrcVideo
Definition: PreferencesDialog.h:118
rtabmap::PreferencesDialog::getMarkerLength
double getMarkerLength() const
Definition: PreferencesDialog.cpp:5958
rtabmap::CameraK4W2::Type
Type
Definition: CameraK4W2.h:50
rtabmap::ParametersMap
std::map< std::string, std::string > ParametersMap
Definition: Parameters.h:43
rtabmap::PreferencesDialog::getVoxel
double getVoxel() const
Definition: PreferencesDialog.cpp:5875
rtabmap::PreferencesDialog::readCoreSettings
virtual bool readCoreSettings(const QString &filePath=QString())
Definition: PreferencesDialog.cpp:2864
box
box
rtabmap::Feature2D::kFeatureSift
@ kFeatureSift
Definition: Features2d.h:110
rtabmap::PreferencesDialog::getCloudFilteringRadius
double getCloudFilteringRadius() const
Definition: PreferencesDialog.cpp:6096
rtabmap::PreferencesDialog::getSourceHistogramMethod
int getSourceHistogramMethod() const
Definition: PreferencesDialog.cpp:6351
rtabmap::PreferencesDialog::getOdomQualityWarnThr
int getOdomQualityWarnThr() const
Definition: PreferencesDialog.cpp:5791
rtabmap::PreferencesDialog::getIMULocalTransform
Transform getIMULocalTransform() const
Definition: PreferencesDialog.cpp:6297
ULOGGER_DEBUG
#define ULOGGER_DEBUG(...)
Definition: ULogger.h:53
rtabmap::Optimizer::kTypeCVSBA
@ kTypeCVSBA
Definition: Optimizer.h:70
rtabmap::PreferencesDialog::getOctomapRenderingType
int getOctomapRenderingType() const
Definition: PreferencesDialog.cpp:5855
rtabmap::Transform::isNull
bool isNull() const
Definition: Transform.cpp:107
rtabmap::SensorData::cameraModels
const std::vector< CameraModel > & cameraModels() const
Definition: SensorData.h:240
rtabmap::PreferencesDialog::getCameraInfoDir
QString getCameraInfoDir() const
Definition: PreferencesDialog.cpp:7072
rtabmap::ImageView::saveSettings
void saveSettings(QSettings &settings, const QString &group="") const
Definition: ImageView.cpp:288
rtabmap::PreferencesDialog::kSrcStereo
@ kSrcStereo
Definition: PreferencesDialog.h:102
rtabmap::CameraStereoZedOC::available
static bool available()
Definition: CameraStereoZedOC.cpp:499
rtabmap::CameraFreenect2::available
static bool available()
Definition: CameraFreenect2.cpp:45
rtabmap::PreferencesDialog::isImagesKept
bool isImagesKept() const
Definition: PreferencesDialog.cpp:7077
rtabmap::PreferencesDialog::getOdomBufferSize
int getOdomBufferSize() const
Definition: PreferencesDialog.cpp:7067
rtabmap::Feature2D::kFeatureFastBrief
@ kFeatureFastBrief
Definition: Features2d.h:113
GraphViewer.h
rtabmap::IMUFilter::create
static IMUFilter * create(const ParametersMap &parameters=ParametersMap())
Definition: IMUFilter.cpp:38
rtabmap::PreferencesDialog::getLidarSourceDriver
PreferencesDialog::Src getLidarSourceDriver() const
Definition: PreferencesDialog.cpp:6264
rtabmap::PreferencesDialog::getSourceLocalTransform
Transform getSourceLocalTransform() const
Definition: PreferencesDialog.cpp:6273
rtabmap::IMUFilter::Type
Type
Definition: IMUFilter.h:40
rtabmap::Parameters::parse
static bool parse(const ParametersMap &parameters, const std::string &key, bool &value)
Definition: Parameters.cpp:500
rtabmap::SensorData::stereoCameraModels
const std::vector< StereoCameraModel > & stereoCameraModels() const
Definition: SensorData.h:241
rtabmap::SensorCaptureThread::setDistortionModel
void setDistortionModel(const std::string &path)
Definition: SensorCaptureThread.cpp:196
rtabmap::PreferencesDialog::getCloudRoiRatios
std::vector< float > getCloudRoiRatios(int index) const
Definition: PreferencesDialog.cpp:5997
rtabmap::PreferencesDialog::selectSourceMKVPath
void selectSourceMKVPath()
Definition: PreferencesDialog.cpp:4681
rtabmap::ImageView::loadSettings
void loadSettings(QSettings &settings, const QString &group="")
Definition: ImageView.cpp:317
rtabmap::PreferencesDialog::getNormalKSearch
int getNormalKSearch() const
Definition: PreferencesDialog.cpp:5895
rtabmap::CameraK4A
Definition: CameraK4A.h:43
rtabmap::PreferencesDialog::_initialized
bool _initialized
Definition: PreferencesDialog.h:454
rtabmap::PreferencesDialog::getTmpIniFilePath
virtual QString getTmpIniFilePath() const
Definition: PreferencesDialog.cpp:2408
rtabmap::PreferencesDialog::saveConfigTo
bool saveConfigTo()
Definition: PreferencesDialog.cpp:2950
ULogger::getRegisteredThreads
static std::map< std::string, unsigned long > getRegisteredThreads()
Definition: ULogger.cpp:247
rtabmap::CameraFreenect
Definition: CameraFreenect.h:44
Parameters.h
rtabmap::PreferencesDialog::kSrcStereoDepthAI
@ kSrcStereoDepthAI
Definition: PreferencesDialog.h:113
rtabmap::PreferencesDialog::changeOdometryORBSLAMVocabulary
void changeOdometryORBSLAMVocabulary()
Definition: PreferencesDialog.cpp:5432
odometry
Pose2 odometry(2.0, 0.0, 0.0)
Odometry.h
rtabmap::PreferencesDialog::kSrcImages
@ kSrcImages
Definition: PreferencesDialog.h:117
rtabmap::CloudViewer
Definition: CloudViewer.h:79
rtabmap::PreferencesDialog::kSrcStereoZedOC
@ kSrcStereoZedOC
Definition: PreferencesDialog.h:112
rtabmap::PreferencesDialog::kSrcStereoUsb
@ kSrcStereoUsb
Definition: PreferencesDialog.h:108
rtabmap::Camera::isCalibrated
virtual bool isCalibrated() const =0
rtabmap::Camera::setInterIMUPublishing
void setInterIMUPublishing(bool enabled, IMUFilter *filter=0)
Definition: Camera.cpp:55
uInsert
void uInsert(std::map< K, V > &map, const std::pair< K, V > &pair)
Definition: UStl.h:441
rtabmap::ExportBundlerDialog::loadSettings
void loadSettings(QSettings &settings, const QString &group="")
Definition: ExportBundlerDialog.cpp:107
rtabmap::PreferencesDialog::getDefaultWorkingDirectory
virtual QString getDefaultWorkingDirectory() const
Definition: PreferencesDialog.cpp:2859
rtabmap::PreferencesDialog::~PreferencesDialog
virtual ~PreferencesDialog()
Definition: PreferencesDialog.cpp:1672
rtabmap::SensorCapture::init
virtual bool init(const std::string &calibrationFolder=".", const std::string &cameraName="")=0
rtabmap::SensorCaptureThread::enableIMUFiltering
void enableIMUFiltering(int filteringStrategy=1, const ParametersMap &parameters=ParametersMap(), bool baseFrameConversion=false)
Definition: SensorCaptureThread.cpp:224
rtabmap::PreferencesDialog::saveSettings
void saveSettings()
Definition: PreferencesDialog.cpp:1709
rtabmap::Parameters::getDefaultParameters
static const ParametersMap & getDefaultParameters()
Definition: Parameters.h:896
rtabmap::PreferencesDialog::testCamera
void testCamera()
Definition: PreferencesDialog.cpp:7311
uContains
bool uContains(const std::list< V > &list, const V &value)
Definition: UStl.h:407
gtsam::Values::at
const ValueType at(Key j) const
rtabmap::DepthCalibrationDialog
Definition: DepthCalibrationDialog.h:49
UFATAL
#define UFATAL(...)
rtabmap::PreferencesDialog::getCloudMaxDepth
double getCloudMaxDepth(int index) const
Definition: PreferencesDialog.cpp:5987
rtabmap::CloudViewer::loadSettings
void loadSettings(QSettings &settings, const QString &group="")
Definition: CloudViewer.cpp:480
rtabmap::PreferencesDialog::isBilateralFiltering
bool isBilateralFiltering() const
Definition: PreferencesDialog.cpp:6335
rtabmap::PreferencesDialog::isSourceStereoDepthGenerated
bool isSourceStereoDepthGenerated() const
Definition: PreferencesDialog.cpp:6359
rtabmap::PreferencesDialog::getCloudOpacity
double getCloudOpacity(int index) const
Definition: PreferencesDialog.cpp:6020
rtabmap::PreferencesDialog::isScansShown
bool isScansShown(int index) const
Definition: PreferencesDialog.cpp:6031
rtabmap::ExportBundlerDialog
Definition: ExportBundlerDialog.h:42
samples
set noclip points set clip one set noclip two set bar set border lt lw set xdata set ydata set zdata set x2data set y2data set boxwidth set dummy y set format x g set format y g set format x2 g set format y2 g set format z g set angles radians set nogrid set key title set key left top Right noreverse box linetype linewidth samplen spacing width set nolabel set noarrow set nologscale set logscale x set set pointsize set encoding default set nopolar set noparametric set set samples
rtabmap::PreferencesDialog::getGroupBoxes
QList< QGroupBox * > getGroupBoxes()
Definition: PreferencesDialog.cpp:5206
rtabmap::PreferencesDialog::imageRejectedShown
bool imageRejectedShown() const
Definition: PreferencesDialog.cpp:5767
rtabmap::PreferencesDialog::_3dRenderingDownsamplingScan
QVector< QSpinBox * > _3dRenderingDownsamplingScan
Definition: PreferencesDialog.h:472
uHex2Str
std::string UTILITE_EXPORT uHex2Str(const std::string &hex)
Definition: UConversion.cpp:250
rtabmap::PreferencesDialog::getFeaturesPointSize
int getFeaturesPointSize(int index) const
Definition: PreferencesDialog.cpp:6082
rtabmap::Transform::prettyPrint
std::string prettyPrint() const
Definition: Transform.cpp:326
uStrNumCmp
int uStrNumCmp(const std::string &a, const std::string &b)
Definition: UStl.h:717
rtabmap::CameraFreenect2
Definition: CameraFreenect2.h:46
rtabmap::PreferencesDialog::landmarkVisSize
double landmarkVisSize() const
Definition: PreferencesDialog.cpp:5936
rtabmap::CameraStereoImages
Definition: CameraStereoImages.h:39
rtabmap::CameraOpenNI2
Definition: CameraOpenNI2.h:42
rtabmap::PreferencesDialog::selectSourceImagesStamps
void selectSourceImagesStamps()
Definition: PreferencesDialog.cpp:4433
rtabmap::Feature2D::kFeatureOrb
@ kFeatureOrb
Definition: Features2d.h:111
j
std::ptrdiff_t j
rtabmap::PreferencesDialog::projMaxObstaclesHeight
double projMaxObstaclesHeight() const
Definition: PreferencesDialog.cpp:6148
rtabmap::DepthCalibrationDialog::loadSettings
void loadSettings(QSettings &settings, const QString &group="")
Definition: DepthCalibrationDialog.cpp:127
rtabmap::PreferencesDialog::getSourceScanDownsampleStep
int getSourceScanDownsampleStep() const
Definition: PreferencesDialog.cpp:6375
rtabmap::GraphViewer
Definition: GraphViewer.h:52
rtabmap::PreferencesDialog::isMissingCacheRepublished
bool isMissingCacheRepublished() const
Definition: PreferencesDialog.cpp:7081
rtabmap::PreferencesDialog::_3dRenderingColorSchemeScan
QVector< QSpinBox * > _3dRenderingColorSchemeScan
Definition: PreferencesDialog.h:476
uNumber2Str
std::string UTILITE_EXPORT uNumber2Str(unsigned int number)
Definition: UConversion.cpp:91
rtabmap::PreferencesDialog::_3dRenderingShowClouds
QVector< QCheckBox * > _3dRenderingShowClouds
Definition: PreferencesDialog.h:463
rtabmap::PreferencesDialog::isCloudsShown
bool isCloudsShown(int index) const
Definition: PreferencesDialog.cpp:5836
rtabmap::PreferencesDialog::projMaxGroundAngle
double projMaxGroundAngle() const
Definition: PreferencesDialog.cpp:6136
rtabmap::PreferencesDialog::getScanFloorFilteringHeight
double getScanFloorFilteringHeight() const
Definition: PreferencesDialog.cpp:5907
rtabmap::CameraDepthAI::available
static bool available()
Definition: CameraDepthAI.cpp:39
rtabmap::CameraSeerSense::available
static bool available()
Definition: CameraSeerSense.cpp:6
rtabmap::PreferencesDialog::selectSourceImagesPathGt
void selectSourceImagesPathGt()
Definition: PreferencesDialog.cpp:4529
UConversion.h
Some conversion functions.
rtabmap::PreferencesDialog::getVpThr
double getVpThr() const
Definition: PreferencesDialog.cpp:7055
rtabmap::PreferencesDialog::getScanCeilingFilteringHeight
double getScanCeilingFilteringHeight() const
Definition: PreferencesDialog.cpp:5903
rtabmap::CameraRealSense2
Definition: CameraRealSense2.h:54
rtabmap::PreferencesDialog::isOdomDisabled
bool isOdomDisabled() const
Definition: PreferencesDialog.cpp:5815
rtabmap::PreferencesDialog::getDetectionRate
float getDetectionRate() const
Definition: PreferencesDialog.cpp:7093
CalibrationDialog.h
rtabmap::PreferencesDialog::getIniFilePath
virtual QString getIniFilePath() const
Definition: PreferencesDialog.cpp:2398
CloudViewer.h
UEventsManager::createPipe
static void createPipe(const UEventsSender *sender, const UEventsHandler *receiver, const std::string &eventName)
Definition: UEventsManager.cpp:67
rtabmap::PreferencesDialog::getSubtractFilteringRadius
double getSubtractFilteringRadius() const
Definition: PreferencesDialog.cpp:6108
rtabmap::PreferencesDialog::getGeneralInputRate
double getGeneralInputRate() const
Definition: PreferencesDialog.cpp:6163
rtabmap::PreferencesDialog::_modifiedParameters
rtabmap::ParametersMap _modifiedParameters
Definition: PreferencesDialog.h:450
rtabmap::CameraStereoZedOC
Definition: CameraStereoZedOC.h:47
rtabmap::CreateSimpleCalibrationDialog::cameraName
const QString & cameraName() const
Definition: CreateSimpleCalibrationDialog.h:53
rtabmap::PreferencesDialog::getWorkingDirectory
QString getWorkingDirectory() const
Definition: PreferencesDialog.cpp:2393
rtabmap_superglue.device
string device
Definition: rtabmap_superglue.py:21
rtabmap::PreferencesDialog::_ui
Ui_preferencesDialog * _ui
Definition: PreferencesDialog.h:452
rtabmap::CalibrationDialog::setFisheyeModel
void setFisheyeModel()
Definition: CalibrationDialog.cpp:338
rtabmap::PreferencesDialog::getCloudVoxelSizeScan
double getCloudVoxelSizeScan(int index) const
Definition: PreferencesDialog.cpp:6051
rtabmap::PreferencesDialog::kPanelAll
@ kPanelAll
Definition: PreferencesDialog.h:80
rtabmap::CalibrationDialog::processImages
void processImages(const cv::Mat &imageLeft, const cv::Mat &imageRight, const QString &cameraName)
Definition: CalibrationDialog.cpp:633
rtabmap::PreferencesDialog::readSettings
void readSettings(const QString &filePath=QString())
Definition: PreferencesDialog.cpp:2422
rtabmap::PreferencesDialog::isSourceDatabaseStampsUsed
bool isSourceDatabaseStampsUsed() const
Definition: PreferencesDialog.cpp:6311
rtabmap::PreferencesDialog::writeCoreSettings
virtual void writeCoreSettings(const QString &filePath=QString()) const
Definition: PreferencesDialog.cpp:3456
rtabmap::PreferencesDialog::getNormalRadiusSearch
double getNormalRadiusSearch() const
Definition: PreferencesDialog.cpp:5899
arg
rtabmap::PreferencesDialog::kSrcK4A
@ kSrcK4A
Definition: PreferencesDialog.h:99
rtabmap::PreferencesDialog::isCloudMeshingQuad
bool isCloudMeshingQuad() const
Definition: PreferencesDialog.cpp:5970
rtabmap::PreferencesDialog::resetApply
void resetApply(QAbstractButton *button)
Definition: PreferencesDialog.cpp:1935
Optimizer.h
rtabmap::PreferencesDialog::setSLAMMode
void setSLAMMode(bool enabled)
Definition: PreferencesDialog.cpp:7166
rtabmap::PreferencesDialog::isLabelsShown
bool isLabelsShown() const
Definition: PreferencesDialog.cpp:5924
rtabmap::PreferencesDialog::readCameraSettings
virtual void readCameraSettings(const QString &filePath=QString())
Definition: PreferencesDialog.cpp:2576
rtabmap::PreferencesDialog::getCloudMeshingTriangleSize
int getCloudMeshingTriangleSize()
Definition: PreferencesDialog.cpp:5978
rtabmap::PreferencesDialog::setCurrentPanelToSource
void setCurrentPanelToSource()
Definition: PreferencesDialog.cpp:1695
rtabmap::PreferencesDialog::selectSourceImagesPathIMU
void selectSourceImagesPathIMU()
Definition: PreferencesDialog.cpp:4476
rtabmap::PreferencesDialog::updateKpROI
void updateKpROI()
Definition: PreferencesDialog.cpp:5314
rtabmap::SensorCaptureThread::setStereoExposureCompensation
void setStereoExposureCompensation(bool enabled)
Definition: SensorCaptureThread.h:124
rtabmap::SensorCaptureThread::enableFeatureDetection
void enableFeatureDetection(const ParametersMap &parameters=ParametersMap())
Definition: SensorCaptureThread.cpp:237
rtabmap::SensorCapture::takeData
SensorData takeData(SensorCaptureInfo *info=0)
Definition: SensorCapture.cpp:64
rtabmap::CameraStereoZed::sdkVersion
static int sdkVersion()
Definition: CameraStereoZed.cpp:245
rtabmap::CalibrationDialog::stereoCalibration
StereoCameraModel stereoCalibration(const CameraModel &left, const CameraModel &right, bool ignoreStereoRectification, QTextStream *logStream=0) const
Definition: CalibrationDialog.cpp:1636
UEventsHandler::unregisterFromEventsManager
void unregisterFromEventsManager()
Definition: UEventsHandler.cpp:33
rtabmap::CalibrationDialog::setSquareSize
void setSquareSize(double size)
Definition: CalibrationDialog.cpp:441
rtabmap::PreferencesDialog::selectCalibrationPath
void selectCalibrationPath()
Definition: PreferencesDialog.cpp:4397
rtabmap::StereoCameraModel::setName
void setName(const std::string &name, const std::string &leftSuffix="left", const std::string &rightSuffix="right")
Definition: StereoCameraModel.cpp:163
rtabmap::PreferencesDialog::isFeaturesShown
bool isFeaturesShown(int index) const
Definition: PreferencesDialog.cpp:6072
rtabmap::PreferencesDialog::kSrcStereoVideo
@ kSrcStereoVideo
Definition: PreferencesDialog.h:106
rtabmap::PreferencesDialog::PreferencesDialog
PreferencesDialog(QWidget *parent=0)
Definition: PreferencesDialog.cpp:113
rtabmap::PreferencesDialog::isSourceScanFromDepth
bool isSourceScanFromDepth() const
Definition: PreferencesDialog.cpp:6367
object
rtabmap::PreferencesDialog::makeObsoleteGeneralPanel
void makeObsoleteGeneralPanel()
Definition: PreferencesDialog.cpp:5176
rtabmap::SensorCaptureThread::setMirroringEnabled
void setMirroringEnabled(bool enabled)
Definition: SensorCaptureThread.h:123
UASSERT
#define UASSERT(condition)
d
d
DepthCalibrationDialog.h
rtabmap::PreferencesDialog::useOdomFeatures
void useOdomFeatures()
Definition: PreferencesDialog.cpp:5380
rtabmap::GraphViewer::loadSettings
void loadSettings(QSettings &settings, const QString &group="")
Definition: GraphViewer.cpp:1304
rtabmap::PreferencesDialog::updatePredictionPlot
void updatePredictionPlot()
Definition: PreferencesDialog.cpp:5233
z
z
rtabmap::CalibrationDialog::setStereoMode
void setStereoMode(bool stereo, const QString &leftSuffix="left", const QString &rightSuffix="right")
Definition: CalibrationDialog.cpp:353
x
x
error
void error(const char *str)
UThread::start
void start()
Definition: UThread.cpp:122
rtabmap::PreferencesDialog::kPanelSource
@ kPanelSource
Definition: PreferencesDialog.h:78
rtabmap::PreferencesDialog::kSrcRGBD
@ kSrcRGBD
Definition: PreferencesDialog.h:88
rtabmap::IMUThread::enableIMUFiltering
void enableIMUFiltering(int filteringStrategy=1, const ParametersMap &parameters=ParametersMap(), bool baseFrameConversion=false)
Definition: IMUThread.cpp:88
rtabmap::PreferencesDialog::kSrcRGB
@ kSrcRGB
Definition: PreferencesDialog.h:115
rtabmap::PreferencesDialog::_3dRenderingGravity
QVector< QCheckBox * > _3dRenderingGravity
Definition: PreferencesDialog.h:482
rtabmap::PreferencesDialog::kPanelCloudRendering
@ kPanelCloudRendering
Definition: PreferencesDialog.h:76
rtabmap::PreferencesDialog::isStatisticsPublished
bool isStatisticsPublished() const
Definition: PreferencesDialog.cpp:7047
rtabmap::PreferencesDialog::addParameters
void addParameters(const QObjectList &children)
Definition: PreferencesDialog.cpp:5014
rtabmap::PreferencesDialog::kSrcOpenNI_PCL
@ kSrcOpenNI_PCL
Definition: PreferencesDialog.h:89
rtabmap::PreferencesDialog::getIMUFilteringStrategy
int getIMUFilteringStrategy() const
Definition: PreferencesDialog.cpp:6319
rtabmap::CameraOpenNI2::kTypeColorDepth
@ kTypeColorDepth
Definition: CameraOpenNI2.h:49
rtabmap::PreferencesDialog::getGeneralLoggerLevel
int getGeneralLoggerLevel() const
Definition: PreferencesDialog.cpp:5727
rtabmap::PreferencesDialog::getGeneralLoggerThreads
std::vector< std::string > getGeneralLoggerThreads() const
Definition: PreferencesDialog.cpp:5751
rtabmap::PreferencesDialog::isPosteriorGraphView
bool isPosteriorGraphView() const
Definition: PreferencesDialog.cpp:5799
rtabmap::PreferencesDialog::getSourceDevice
QString getSourceDevice() const
Definition: PreferencesDialog.cpp:6235
rtabmap::CameraModel::opticalRotation
static Transform opticalRotation()
Definition: CameraModel.h:45
CameraRGB.h
rtabmap::CameraStereoZed::available
static bool available()
Definition: CameraStereoZed.cpp:235
rtabmap::Camera
Definition: Camera.h:43
rtabmap::PreferencesDialog::isOctomapShown
bool isOctomapShown() const
Definition: PreferencesDialog.cpp:5848
rtabmap::GraphViewer::saveSettings
void saveSettings(QSettings &settings, const QString &group="") const
Definition: GraphViewer.cpp:1258
rtabmap::PreferencesDialog::_progressDialog
QProgressDialog * _progressDialog
Definition: PreferencesDialog.h:457
rtabmap::SensorCaptureThread::setStereoToDepth
void setStereoToDepth(bool enabled)
Definition: SensorCaptureThread.h:128
rtabmap::PreferencesDialog::isCloudsKept
bool isCloudsKept() const
Definition: PreferencesDialog.cpp:7085
rtabmap::PreferencesDialog::testOdometry
void testOdometry()
Definition: PreferencesDialog.cpp:7183
rtabmap::VWDictionary::kNNFlannLSH
@ kNNFlannLSH
Definition: VWDictionary.h:52
rtabmap::PreferencesDialog::_monitoringState
bool _monitoringState
Definition: PreferencesDialog.h:455
glm::pitch
GLM_FUNC_DECL T pitch(detail::tquat< T, P > const &x)
rtabmap::CalibrationDialog::setBoardHeight
void setBoardHeight(int height)
Definition: CalibrationDialog.cpp:432
rtabmap::PreferencesDialog::readSettingsBegin
void readSettingsBegin()
Definition: PreferencesDialog.cpp:3821
rtabmap::SensorCapture
Definition: SensorCapture.h:49
rtabmap::PreferencesDialog::kSrcDatabase
@ kSrcDatabase
Definition: PreferencesDialog.h:120
rtabmap::Transform::inverse
Transform inverse() const
Definition: Transform.cpp:178
rtabmap::LidarVLP16
Definition: LidarVLP16.h:45
rtabmap::PreferencesDialog::kSrcStereoImages
@ kSrcStereoImages
Definition: PreferencesDialog.h:105
rtabmap::PreferencesDialog::getSourceDriverStr
QString getSourceDriverStr() const
Definition: PreferencesDialog.cpp:6213
rtabmap::PreferencesDialog::setupSignals
void setupSignals()
Definition: PreferencesDialog.cpp:1815
rtabmap::PreferencesDialog::getGeneralLoggerPauseLevel
int getGeneralLoggerPauseLevel() const
Definition: PreferencesDialog.cpp:5735
rtabmap::PreferencesDialog::closeEvent
virtual void closeEvent(QCloseEvent *event)
Definition: PreferencesDialog.cpp:1889
rtabmap::PreferencesDialog::getScanNormalKSearch
int getScanNormalKSearch() const
Definition: PreferencesDialog.cpp:5911
rtabmap::PreferencesDialog::selectSourceStereoImagesPathLeft
void selectSourceStereoImagesPathLeft()
Definition: PreferencesDialog.cpp:4553
rtabmap::PreferencesDialog::makeObsoleteSourcePanel
void makeObsoleteSourcePanel()
Definition: PreferencesDialog.cpp:5194
rtabmap::PreferencesDialog::isLandmarksShown
bool isLandmarksShown() const
Definition: PreferencesDialog.cpp:5932
rtabmap::PreferencesDialog::closeDialog
void closeDialog(QAbstractButton *button)
Definition: PreferencesDialog.cpp:1899
rtabmap::PreferencesDialog::imageHighestHypShown
bool imageHighestHypShown() const
Definition: PreferencesDialog.cpp:5771
rtabmap::PreferencesDialog::getGridMapOpacity
double getGridMapOpacity() const
Definition: PreferencesDialog.cpp:6156
path
path
rtabmap::OdometryViewer
Definition: OdometryViewer.h:48
key
const gtsam::Symbol key( 'X', 0)
UWARN
#define UWARN(...)
rtabmap::PreferencesDialog::projMinClusterSize
int projMinClusterSize() const
Definition: PreferencesDialog.cpp:6144
rtabmap::CameraOpenNICV
Definition: CameraOpenNICV.h:36
f
Point2(* f)(const Point3 &, OptionalJacobian< 2, 3 >)
rtabmap::PreferencesDialog::getCloudFilteringAngle
double getCloudFilteringAngle() const
Definition: PreferencesDialog.cpp:6100
rtabmap::CameraStereoDC1394
Definition: CameraStereoDC1394.h:39
rtabmap::CalibrationDialog::setSavingDirectory
void setSavingDirectory(const QString &savingDirectory)
Definition: CalibrationDialog.h:82
rtabmap::PreferencesDialog::isSLAMMode
bool isSLAMMode() const
Definition: PreferencesDialog.cpp:7097
rtabmap::PreferencesDialog::isOdomSensorAsGt
bool isOdomSensorAsGt() const
Definition: PreferencesDialog.cpp:5819
uFormat
std::string UTILITE_EXPORT uFormat(const char *fmt,...)
Definition: UConversion.cpp:365
rtabmap::PreferencesDialog::selectSourceVideoPath
void selectSourceVideoPath()
Definition: PreferencesDialog.cpp:4597
M_PI
#define M_PI
Definition: tango-gl/include/tango-gl/util.h:66
rtabmap::PreferencesDialog::readGuiSettings
virtual void readGuiSettings(const QString &filePath=QString())
Definition: PreferencesDialog.cpp:2460
rtabmap::PreferencesDialog::getGridUIResolution
double getGridUIResolution() const
Definition: PreferencesDialog.cpp:6116
rtabmap::PreferencesDialog::_3dRenderingMinRange
QVector< QDoubleSpinBox * > _3dRenderingMinRange
Definition: PreferencesDialog.h:474
rtabmap::PreferencesDialog::loadWindowGeometry
void loadWindowGeometry(QWidget *window)
Definition: PreferencesDialog.cpp:3868
rtabmap::PreferencesDialog::getTimeLimit
float getTimeLimit() const
Definition: PreferencesDialog.cpp:7089
rtabmap::PreferencesDialog::getCloudDecimation
int getCloudDecimation(int index) const
Definition: PreferencesDialog.cpp:5982
OdometryViewer.h
rtabmap::PreferencesDialog::isGroundTruthAligned
bool isGroundTruthAligned() const
Definition: PreferencesDialog.cpp:5831
rtabmap::PreferencesDialog::getCeilingFilteringHeight
double getCeilingFilteringHeight() const
Definition: PreferencesDialog.cpp:5887
PreferencesDialog.h
rtabmap::CalibrationDialog::saveSettings
void saveSettings(QSettings &settings, const QString &group="") const
Definition: CalibrationDialog.cpp:175
rtabmap::CameraOpenNI2::kTypeIRDepth
@ kTypeIRDepth
Definition: CameraOpenNI2.h:49
rtabmap::SensorData::imageRaw
const cv::Mat & imageRaw() const
Definition: SensorData.h:183
rtabmap::VWDictionary::kNNFlannKdTree
@ kNNFlannKdTree
Definition: VWDictionary.h:51
ULogger.h
ULogger class and convenient macros.
a
ArrayXXi a
rtabmap::PreferencesDialog::getParamMessage
virtual QString getParamMessage()
Definition: PreferencesDialog.cpp:3770
UPlot.h
rtabmap::CameraStereoZed
Definition: CameraStereoZed.h:43
rtabmap::PreferencesDialog::kSrcFreenect2
@ kSrcFreenect2
Definition: PreferencesDialog.h:94
rtabmap::Transform
Definition: Transform.h:41
rtabmap::PreferencesDialog::selectSourceImagesPathOdom
void selectSourceImagesPathOdom()
Definition: PreferencesDialog.cpp:4505
rtabmap::PreferencesDialog::getSourceImageDecimation
int getSourceImageDecimation() const
Definition: PreferencesDialog.cpp:6347
rtabmap::PreferencesDialog::_3dRenderingOpacityScan
QVector< QDoubleSpinBox * > _3dRenderingOpacityScan
Definition: PreferencesDialog.h:477
rtabmap::CameraOpenNICV::available
static bool available()
Definition: CameraOpenNICV.cpp:36
Memory.h
rtabmap::DepthCalibrationDialog::saveSettings
void saveSettings(QSettings &settings, const QString &group="") const
Definition: DepthCalibrationDialog.cpp:100
rtabmap::CameraMyntEye::available
static bool available()
Definition: CameraMyntEye.cpp:506
rtabmap::PreferencesDialog::calibrateOdomSensorExtrinsics
void calibrateOdomSensorExtrinsics()
Definition: PreferencesDialog.cpp:7605
rtabmap::PreferencesDialog::setupKpRoiPanel
void setupKpRoiPanel()
Definition: PreferencesDialog.cpp:5300
rtabmap::PostProcessingDialog::loadSettings
void loadSettings(QSettings &settings, const QString &group="")
Definition: PostProcessingDialog.cpp:166
rtabmap::PreferencesDialog::_3dRenderingPtSizeFeatures
QVector< QSpinBox * > _3dRenderingPtSizeFeatures
Definition: PreferencesDialog.h:481
rtabmap::Parameters::readINI
static void readINI(const std::string &configFile, ParametersMap &parameters, bool modifiedOnly=false)
Definition: Parameters.cpp:1273
rtabmap::PreferencesDialog::calibrateSimple
void calibrateSimple()
Definition: PreferencesDialog.cpp:7596
UPlotCurve
Definition: UPlot.h:93
rtabmap::PreferencesDialog::getElevationMapShown
int getElevationMapShown() const
Definition: PreferencesDialog.cpp:6124
rtabmap::PreferencesDialog::updateBasicParameter
void updateBasicParameter()
Definition: PreferencesDialog.cpp:5099
rtabmap::PreferencesDialog::selectSourceRGBDImagesPathRGB
void selectSourceRGBDImagesPathRGB()
Definition: PreferencesDialog.cpp:4447
rtabmap::PreferencesDialog::createOdomSensor
SensorCapture * createOdomSensor(Transform &extrinsics, double &timeOffset, float &scaleFactor, double &waitTime)
Definition: PreferencesDialog.cpp:6960
rtabmap::PreferencesDialog::getScanOpacity
double getScanOpacity(int index) const
Definition: PreferencesDialog.cpp:6061
rtabmap::PostProcessingDialog
Definition: PostProcessingDialog.h:43
rtabmap::PreferencesDialog::getSourceScanNormalsK
int getSourceScanNormalsK() const
Definition: PreferencesDialog.cpp:6391
rtabmap::PreferencesDialog::getScanColorScheme
int getScanColorScheme(int index) const
Definition: PreferencesDialog.cpp:6056
rtabmap::PreferencesDialog::_3dRenderingShowFeatures
QVector< QCheckBox * > _3dRenderingShowFeatures
Definition: PreferencesDialog.h:479
rtabmap::PreferencesDialog::getOdomF2MGravitySigma
double getOdomF2MGravitySigma() const
Definition: PreferencesDialog.cpp:5827
rtabmap::PreferencesDialog::getDownsamplingStepScan
int getDownsamplingStepScan(int index) const
Definition: PreferencesDialog.cpp:6036
values
leaf::MyValues values
rtabmap::PreferencesDialog::_3dRenderingPtSize
QVector< QSpinBox * > _3dRenderingPtSize
Definition: PreferencesDialog.h:470
rtabmap::PreferencesDialog::openDatabaseViewer
void openDatabaseViewer()
Definition: PreferencesDialog.cpp:4356
rtabmap::PreferencesDialog::_3dRenderingVoxelSizeScan
QVector< QDoubleSpinBox * > _3dRenderingVoxelSizeScan
Definition: PreferencesDialog.h:475
rtabmap::PreferencesDialog::kSrcFlyCapture2
@ kSrcFlyCapture2
Definition: PreferencesDialog.h:104
IMUFilter.h
rtabmap::CameraRGBDImages
Definition: CameraRGBDImages.h:35
rtabmap::CalibrationDialog::setCameraName
void setCameraName(const QString &name)
Definition: CalibrationDialog.cpp:323
rtabmap::PreferencesDialog::changeOdometryOpenVINSRightMask
void changeOdometryOpenVINSRightMask()
Definition: PreferencesDialog.cpp:5500
rtabmap::PreferencesDialog::saveWindowGeometry
void saveWindowGeometry(const QWidget *window)
Definition: PreferencesDialog.cpp:3848
iter
iterator iter(handle obj)
rtabmap::PreferencesDialog::kSrcRealSense
@ kSrcRealSense
Definition: PreferencesDialog.h:95
rtabmap::PreferencesDialog::_3dRenderingShowFrustums
QVector< QCheckBox * > _3dRenderingShowFrustums
Definition: PreferencesDialog.h:480
rtabmap::PreferencesDialog::changeSuperPointModelPath
void changeSuperPointModelPath()
Definition: PreferencesDialog.cpp:5534
rtabmap::CameraStereoFlyCapture2
Definition: CameraStereoFlyCapture2.h:41
ULOGGER_ERROR
#define ULOGGER_ERROR(...)
Definition: ULogger.h:56
rtabmap::PreferencesDialog::loadWidgetState
void loadWidgetState(QWidget *widget)
Definition: PreferencesDialog.cpp:4024
rtabmap::PreferencesDialog::getKpMaxFeatures
int getKpMaxFeatures() const
Definition: PreferencesDialog.cpp:7105
rtabmap::PreferencesDialog::isIMUGravityShown
bool isIMUGravityShown(int index) const
Definition: PreferencesDialog.cpp:5940
rtabmap::PreferencesDialog::saveCustomConfig
void saveCustomConfig(const QString &section, const QString &key, const QString &value)
Definition: PreferencesDialog.cpp:4099
rtabmap::PreferencesDialog::_3dRenderingRoiRatios
QVector< QLineEdit * > _3dRenderingRoiRatios
Definition: PreferencesDialog.h:467
rtabmap::CameraViewer::setDecimation
void setDecimation(int value)
Definition: CameraViewer.cpp:126
rtabmap::CameraRealSense2::available
static bool available()
Definition: CameraRealSense2.cpp:45
rtabmap::SensorCaptureThread::setImageDecimation
void setImageDecimation(int decimation)
Definition: SensorCaptureThread.h:126
rtabmap::Optimizer::kTypeTORO
@ kTypeTORO
Definition: Optimizer.h:66
rtabmap::CameraK4A::available
static bool available()
Definition: CameraK4A.cpp:42
camera
Camera camera(Pose3(Rot3().retract(Vector3(0.1, 0.2, 0.3)), Point3(0, 5, 0)), Cal3Bundler0(1, 0, 0))
c_str
const char * c_str(Args &&...args)
rtabmap::PreferencesDialog::isLocalizationsCountGraphView
bool isLocalizationsCountGraphView() const
Definition: PreferencesDialog.cpp:5807
rtabmap::StereoCameraModel::stereoTransform
Transform stereoTransform() const
Definition: StereoCameraModel.cpp:593
rtabmap::PostProcessingDialog::saveSettings
void saveSettings(QSettings &settings, const QString &group="") const
Definition: PostProcessingDialog.cpp:141
UStl.h
Wrappers of STL for convenient functions.
rtabmap::Feature2D::kFeatureKaze
@ kFeatureKaze
Definition: Features2d.h:118
rtabmap::PreferencesDialog::_createCalibrationDialog
CreateSimpleCalibrationDialog * _createCalibrationDialog
Definition: PreferencesDialog.h:461
rtabmap::PreferencesDialog::testLidar
void testLidar()
Definition: PreferencesDialog.cpp:7832
ExportCloudsDialog.h
rtabmap::PreferencesDialog::createCamera
Camera * createCamera(bool useRawImages=false, bool useColor=true)
Definition: PreferencesDialog.cpp:6404
rtabmap::PreferencesDialog::getSourceDistortionModel
QString getSourceDistortionModel() const
Definition: PreferencesDialog.cpp:6331
rtabmap::PreferencesDialog::getSourceScanRangeMax
double getSourceScanRangeMax() const
Definition: PreferencesDialog.cpp:6383
rtabmap::PreferencesDialog::setInputRate
void setInputRate(double value)
Definition: PreferencesDialog.cpp:7115
UDEBUG
#define UDEBUG(...)
rtabmap::PreferencesDialog::getCloudMeshingAngle
double getCloudMeshingAngle() const
Definition: PreferencesDialog.cpp:5966
rtabmap::CalibrationDialog::squareSize
double squareSize() const
Definition: CalibrationDialog.cpp:396
rtabmap::PreferencesDialog::writeGuiSettings
virtual void writeGuiSettings(const QString &filePath=QString()) const
Definition: PreferencesDialog.cpp:3061
rtabmap::CameraModel::imageSize
const cv::Size & imageSize() const
Definition: CameraModel.h:119
rtabmap::CalibrationDialog::resetSettings
void resetSettings()
Definition: CalibrationDialog.cpp:240
rtabmap::Parameters::getType
static std::string getType(const std::string &paramKey)
Definition: Parameters.cpp:470
rtabmap::CalibrationDialog
Definition: CalibrationDialog.h:52
rtabmap::PreferencesDialog::projFlatObstaclesDetected
bool projFlatObstaclesDetected() const
Definition: PreferencesDialog.cpp:6152
rtabmap::PreferencesDialog::showEvent
virtual void showEvent(QShowEvent *event)
Definition: PreferencesDialog.cpp:3775
rtabmap::CameraRealSense
Definition: CameraRealSense.h:49
rtabmap::PreferencesDialog::getNoiseMinNeighbors
int getNoiseMinNeighbors() const
Definition: PreferencesDialog.cpp:5883
rtabmap::PreferencesDialog::saveMainWindowState
void saveMainWindowState(const QMainWindow *mainWindow)
Definition: PreferencesDialog.cpp:3893
rtabmap::PreferencesDialog::saveWidgetState
void saveWidgetState(const QWidget *widget)
Definition: PreferencesDialog.cpp:3951
rtabmap::PreferencesDialog::getOctomapPointSize
int getOctomapPointSize() const
Definition: PreferencesDialog.cpp:5870
rtabmap::Odometry
Definition: Odometry.h:42
ExportBundlerDialog.h
rtabmap::PreferencesDialog::notifyWhenNewGlobalPathIsReceived
bool notifyWhenNewGlobalPathIsReceived() const
Definition: PreferencesDialog.cpp:5787
rtabmap::PreferencesDialog::selectSourceImagesPathScans
void selectSourceImagesPathScans()
Definition: PreferencesDialog.cpp:4462
rtabmap::sortCallback
bool sortCallback(const std::string &a, const std::string &b)
Definition: PreferencesDialog.cpp:4301
rtabmap::ImageView
Definition: ImageView.h:49
rtabmap::CameraOpenni::available
static bool available()
Definition: CameraOpenni.cpp:51
rtabmap::StereoCameraModel::name
const std::string & name() const
Definition: StereoCameraModel.h:92
rtabmap::PreferencesDialog::getLoopThr
double getLoopThr() const
Definition: PreferencesDialog.cpp:7051
rtabmap::PreferencesDialog::selectSourceStereoVideoPath2
void selectSourceStereoVideoPath2()
Definition: PreferencesDialog.cpp:4625
rtabmap::DBReader
Definition: DBReader.h:46
rtabmap::PreferencesDialog::_3dRenderingMinDepth
QVector< QDoubleSpinBox * > _3dRenderingMinDepth
Definition: PreferencesDialog.h:466
float
float
rtabmap::PreferencesDialog::getSourceScanVoxelSize
double getSourceScanVoxelSize() const
Definition: PreferencesDialog.cpp:6387
rtabmap::CameraOpenNI2::available
static bool available()
Definition: CameraOpenNI2.cpp:42
rtabmap::PreferencesDialog::getOdomSourceDriver
PreferencesDialog::Src getOdomSourceDriver() const
Definition: PreferencesDialog.cpp:6240
rtabmap::Optimizer::kTypeG2O
@ kTypeG2O
Definition: Optimizer.h:67
rtabmap::PreferencesDialog::_3dRenderingMaxDepth
QVector< QDoubleSpinBox * > _3dRenderingMaxDepth
Definition: PreferencesDialog.h:465
rtabmap::PreferencesDialog::kSrcStereoRealSense2
@ kSrcStereoRealSense2
Definition: PreferencesDialog.h:110
rtabmap::PreferencesDialog::kSrcStereoZed
@ kSrcStereoZed
Definition: PreferencesDialog.h:107
rtabmap::PreferencesDialog::getCloudPointSize
int getCloudPointSize(int index) const
Definition: PreferencesDialog.cpp:6025
rtabmap::StereoCameraModel::saveStereoTransform
bool saveStereoTransform(const std::string &directory) const
Definition: StereoCameraModel.cpp:347
rtabmap::DatabaseViewer::openDatabase
bool openDatabase(const QString &path, const ParametersMap &overridenParameters=ParametersMap())
Definition: DatabaseViewer.cpp:820
rtabmap::PreferencesDialog::_3dRenderingMaxRange
QVector< QDoubleSpinBox * > _3dRenderingMaxRange
Definition: PreferencesDialog.h:473
rtabmap::PreferencesDialog::loadConfigFrom
void loadConfigFrom()
Definition: PreferencesDialog.cpp:2413
rtabmap::PreferencesDialog::getFloorFilteringHeight
double getFloorFilteringHeight() const
Definition: PreferencesDialog.cpp:5891
rtabmap::Lidar
Definition: Lidar.h:40
rtabmap::PreferencesDialog::updateStereoDisparityVisibility
void updateStereoDisparityVisibility()
Definition: PreferencesDialog.cpp:5324
rtabmap::PreferencesDialog::getCloudMinDepth
double getCloudMinDepth(int index) const
Definition: PreferencesDialog.cpp:5992
rtabmap::PreferencesDialog::setTimeLimit
void setTimeLimit(float value)
Definition: PreferencesDialog.cpp:7149
false
#define false
Definition: ConvertUTF.c:56
rtabmap::CalibrationDialog::setBoardWidth
void setBoardWidth(int width)
Definition: CalibrationDialog.cpp:423
rtabmap::PreferencesDialog::changeOdometryOpenVINSLeftMask
void changeOdometryOpenVINSLeftMask()
Definition: PreferencesDialog.cpp:5483
rtabmap::PreferencesDialog::getNoiseRadius
double getNoiseRadius() const
Definition: PreferencesDialog.cpp:5879
rtabmap::PreferencesDialog::kSrcLidarVLP16
@ kSrcLidarVLP16
Definition: PreferencesDialog.h:123
rtabmap::PreferencesDialog::changePyDescriptorPath
void changePyDescriptorPath()
Definition: PreferencesDialog.cpp:5585
rtabmap::PreferencesDialog::selectSourceStereoVideoPath
void selectSourceStereoVideoPath()
Definition: PreferencesDialog.cpp:4611
rtabmap::PreferencesDialog::getSourceDriver
PreferencesDialog::Src getSourceDriver() const
Definition: PreferencesDialog.cpp:6192
rtabmap::CameraRealSense::RGBSource
RGBSource
Definition: CameraRealSense.h:54
rtabmap::PreferencesDialog::getIMUFilteringBaseFrameConversion
bool getIMUFilteringBaseFrameConversion() const
Definition: PreferencesDialog.cpp:6323
rtabmap::PreferencesDialog::getOctomapTreeDepth
int getOctomapTreeDepth() const
Definition: PreferencesDialog.cpp:5866
OptimizerG2O.h
uStr2Float
float UTILITE_EXPORT uStr2Float(const std::string &str)
Definition: UConversion.cpp:138
rtabmap::Optimizer::kTypeCeres
@ kTypeCeres
Definition: Optimizer.h:69
rtabmap::Parameters::createDefaultWorkingDirectory
static std::string createDefaultWorkingDirectory()
Definition: Parameters.cpp:66
t
Point2 t(10, 10)
rtabmap::ExportCloudsDialog::saveSettings
void saveSettings(QSettings &settings, const QString &group="") const
Definition: ExportCloudsDialog.cpp:353
rtabmap::CameraFreenect::kTypeColorDepth
@ kTypeColorDepth
Definition: CameraFreenect.h:49
rtabmap::PreferencesDialog::kPanelGeneral
@ kPanelGeneral
Definition: PreferencesDialog.h:75
rtabmap
Definition: CameraARCore.cpp:35
rtabmap::PreferencesDialog::getGeneralLoggerPrintThreadId
bool getGeneralLoggerPrintThreadId() const
Definition: PreferencesDialog.cpp:5747
rtabmap::PreferencesDialog::kSrcOpenNI_CV
@ kSrcOpenNI_CV
Definition: PreferencesDialog.h:91
UEventsManager.h
rtabmap::SensorCaptureThread::setHistogramMethod
void setHistogramMethod(int histogramMethod)
Definition: SensorCaptureThread.h:127
rtabmap::PreferencesDialog::kSrcUndef
@ kSrcUndef
Definition: PreferencesDialog.h:86
rtabmap::CameraModel::localTransform
const Transform & localTransform() const
Definition: CameraModel.h:116
rtabmap::PreferencesDialog::selectSourceImagesPath
void selectSourceImagesPath()
Definition: PreferencesDialog.cpp:4581
rtabmap::PreferencesDialog::kSrcFreenect
@ kSrcFreenect
Definition: PreferencesDialog.h:90
rtabmap::PreferencesDialog::setDetectionRate
void setDetectionRate(double value)
Definition: PreferencesDialog.cpp:7132
rtabmap::PreferencesDialog::visualizeDistortionModel
void visualizeDistortionModel()
Definition: PreferencesDialog.cpp:4372
UERROR
#define UERROR(...)
rtabmap::PreferencesDialog::changePyMatcherModel
void changePyMatcherModel()
Definition: PreferencesDialog.cpp:5568
rtabmap::PreferencesDialog::selectSourceRealsense2JsonPath
void selectSourceRealsense2JsonPath()
Definition: PreferencesDialog.cpp:4709
DatabaseViewer.h
rtabmap::PreferencesDialog::_obsoletePanels
PANEL_FLAGS _obsoletePanels
Definition: PreferencesDialog.h:447
rtabmap::OptimizerG2O::isCSparseAvailable
static bool isCSparseAvailable()
Definition: OptimizerG2O.cpp:126
trace.model
model
Definition: trace.py:4
rtabmap::PreferencesDialog::getGeneralLoggerEventLevel
int getGeneralLoggerEventLevel() const
Definition: PreferencesDialog.cpp:5731
rtabmap::PreferencesDialog::getSourceScanRangeMin
double getSourceScanRangeMin() const
Definition: PreferencesDialog.cpp:6379
rtabmap::PreferencesDialog::kSrcOpenNI_CV_ASUS
@ kSrcOpenNI_CV_ASUS
Definition: PreferencesDialog.h:92
value
value
rtabmap::PreferencesDialog::calibrate
void calibrate()
Definition: PreferencesDialog.cpp:7372
rtabmap::PreferencesDialog::changePyDetectorPath
void changePyDetectorPath()
Definition: PreferencesDialog.cpp:5601
i
int i
rtabmap::PreferencesDialog::isSourceMirroring
bool isSourceMirroring() const
Definition: PreferencesDialog.cpp:6167
ULOGGER_WARN
#define ULOGGER_WARN(...)
Definition: ULogger.h:55
rtabmap::CameraOpenni
Definition: CameraOpenni.h:55
rtabmap::ExportBundlerDialog::saveSettings
void saveSettings(QSettings &settings, const QString &group="") const
Definition: ExportBundlerDialog.cpp:87
rtabmap::Parameters::writeINI
static void writeINI(const std::string &configFile, const ParametersMap &parameters)
Definition: Parameters.cpp:1287
rtabmap::SensorCaptureThread::enableBilateralFiltering
void enableBilateralFiltering(float sigmaS, float sigmaR)
Definition: SensorCaptureThread.cpp:216
text
text
rtabmap::PreferencesDialog::isDepthFilteringAvailable
bool isDepthFilteringAvailable() const
Definition: PreferencesDialog.cpp:6327
rtabmap::PreferencesDialog::updateSourceGrpVisibility
void updateSourceGrpVisibility()
Definition: PreferencesDialog.cpp:5618
rtabmap::PreferencesDialog::readSettingsEnd
void readSettingsEnd()
Definition: PreferencesDialog.cpp:3830
rtabmap::PreferencesDialog::selectSourceDriver
void selectSourceDriver(Src src, int variant=0)
Definition: PreferencesDialog.cpp:4187
glm::roll
GLM_FUNC_DECL T roll(detail::tquat< T, P > const &x)
rtabmap::PreferencesDialog::isWordsCountGraphView
bool isWordsCountGraphView() const
Definition: PreferencesDialog.cpp:5803
rtabmap::PreferencesDialog::kSrcK4W2
@ kSrcK4W2
Definition: PreferencesDialog.h:97
rtabmap::PreferencesDialog::getScanMinRange
double getScanMinRange(int index) const
Definition: PreferencesDialog.cpp:6046
rtabmap::PreferencesDialog::selectSourceOniPath
void selectSourceOniPath()
Definition: PreferencesDialog.cpp:4653
rtabmap::CameraVideo
Definition: CameraVideo.h:36
rtabmap::PreferencesDialog::kSrcDC1394
@ kSrcDC1394
Definition: PreferencesDialog.h:103
rtabmap::PreferencesDialog::isSourceScanDeskewing
bool isSourceScanDeskewing() const
Definition: PreferencesDialog.cpp:6371
rtabmap::CreateSimpleCalibrationDialog::setCameraInfoDir
void setCameraInfoDir(const QString &folder)
Definition: CreateSimpleCalibrationDialog.h:52
rtabmap::PreferencesDialog::getGridMapShown
bool getGridMapShown() const
Definition: PreferencesDialog.cpp:6120
uBool2Str
std::string UTILITE_EXPORT uBool2Str(bool boolean)
Definition: UConversion.cpp:156
rtabmap::CameraK4W2
Definition: CameraK4W2.h:44
rtabmap::PreferencesDialog::selectSourceOni2Path
void selectSourceOni2Path()
Definition: PreferencesDialog.cpp:4667
rtabmap::PreferencesDialog::isCacheSavedInFigures
bool isCacheSavedInFigures() const
Definition: PreferencesDialog.cpp:5783
rtabmap::PreferencesDialog::writeSettings
void writeSettings(const QString &filePath=QString())
Definition: PreferencesDialog.cpp:3018
rtabmap::PreferencesDialog::parseModel
bool parseModel(QList< QGroupBox * > &boxes, QStandardItem *parentItem, int currentLevel, int &absoluteIndex)
Definition: PreferencesDialog.cpp:1764
rtabmap::Feature2D::kFeatureSurf
@ kFeatureSurf
Definition: Features2d.h:109
rtabmap::CameraSeerSense
Definition: CameraSeerSense.h:14
rtabmap::PreferencesDialog::isOdomOnlyInliersShown
bool isOdomOnlyInliersShown() const
Definition: PreferencesDialog.cpp:5795
rtabmap::PreferencesDialog::isSubtractFiltering
bool isSubtractFiltering() const
Definition: PreferencesDialog.cpp:6092
rtabmap::Feature2D::kFeatureOrbOctree
@ kFeatureOrbOctree
Definition: Features2d.h:119
rtabmap::PreferencesDialog::kSrcSeerSense
@ kSrcSeerSense
Definition: PreferencesDialog.h:100


rtabmap
Author(s): Mathieu Labbe
autogenerated on Thu Jul 25 2024 02:50:14