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


rtabmap
Author(s): Mathieu Labbe
autogenerated on Sun Dec 1 2024 03:42:51