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


rtabmap
Author(s): Mathieu Labbe
autogenerated on Thu Feb 13 2025 03:44:58