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


rtabmap
Author(s): Mathieu Labbe
autogenerated on Mon Apr 28 2025 02:45:58