29 #include <pcl/pcl_config.h>
30 #if PCL_VERSION_COMPARE(>=, 1, 8, 0)
40 #include <QtCore/QSettings>
41 #include <QtCore/QDir>
42 #include <QtCore/QTimer>
45 #include <QButtonGroup>
46 #include <QFileDialog>
47 #include <QInputDialog>
48 #include <QMessageBox>
49 #include <QtGui/QStandardItemModel>
50 #include <QMainWindow>
51 #include <QProgressDialog>
54 #include <QFormLayout>
55 #include <QDesktopServices>
56 #include <QtGui/QCloseEvent>
58 #include "ui_preferencesDialog.h"
60 #include "rtabmap/core/Version.h"
94 #include "camera_tof_icp_ini.h"
95 #include "lidar3d_icp_ini.h"
97 #include <opencv2/opencv_modules.hpp>
99 #if CV_MAJOR_VERSION < 3
100 #ifdef HAVE_OPENCV_GPU
101 #include <opencv2/gpu/gpu.hpp>
104 #ifdef HAVE_OPENCV_CUDAFEATURES2D
105 #include <opencv2/core/cuda.hpp>
115 _obsoletePanels(kPanelDummy),
119 _progressDialog(new QProgressDialog(
this)),
131 _ui =
new Ui_preferencesDialog();
134 bool haveCuda =
false;
135 #if CV_MAJOR_VERSION < 3
136 #ifdef HAVE_OPENCV_GPU
137 haveCuda = cv::gpu::getCudaEnabledDeviceCount() != 0;
140 #ifdef HAVE_OPENCV_CUDAFEATURES2D
141 haveCuda = cv::cuda::getCudaEnabledDeviceCount() != 0;
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);
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);
158 _ui->checkBox_ORBGpu->setChecked(
false);
159 _ui->checkBox_ORBGpu->setEnabled(
false);
160 _ui->label_orbGpu->setEnabled(
false);
163 _ui->comboBox_dictionary_strategy->setItemData(4, 0, Qt::UserRole - 1);
164 _ui->reextract_nn->setItemData(4, 0, Qt::UserRole - 1);
167 #ifndef RTABMAP_OCTOMAP
168 _ui->groupBox_octomap->setChecked(
false);
169 _ui->groupBox_octomap->setEnabled(
false);
172 #ifndef RTABMAP_GRIDMAP
173 _ui->checkBox_elevation_shown->setChecked(
false);
174 _ui->checkBox_elevation_shown->setEnabled(
false);
175 _ui->label_show_elevation->setEnabled(
false);
178 #ifndef RTABMAP_REALSENSE_SLAM
179 _ui->checkbox_realsenseOdom->setChecked(
false);
180 _ui->checkbox_realsenseOdom->setEnabled(
false);
181 _ui->label_realsenseOdom->setEnabled(
false);
184 #ifndef RTABMAP_FOVIS
185 _ui->odom_strategy->setItemData(2, 0, Qt::UserRole - 1);
187 #ifndef RTABMAP_VISO2
188 _ui->odom_strategy->setItemData(3, 0, Qt::UserRole - 1);
191 _ui->odom_strategy->setItemData(4, 0, Qt::UserRole - 1);
193 #ifndef RTABMAP_ORB_SLAM
194 _ui->odom_strategy->setItemData(5, 0, Qt::UserRole - 1);
195 #elif RTABMAP_ORB_SLAM == 3
196 _ui->odom_strategy->setItemText(5,
"ORB SLAM 3");
197 _ui->groupBox_odomORBSLAM->setTitle(
"ORB SLAM 3");
199 _ui->odom_strategy->setItemText(5,
"ORB SLAM 2");
200 _ui->groupBox_odomORBSLAM->setTitle(
"ORB SLAM 2");
202 #ifndef RTABMAP_OKVIS
203 _ui->odom_strategy->setItemData(6, 0, Qt::UserRole - 1);
206 _ui->odom_strategy->setItemData(7, 0, Qt::UserRole - 1);
208 #ifndef RTABMAP_MSCKF_VIO
209 _ui->odom_strategy->setItemData(8, 0, Qt::UserRole - 1);
212 _ui->odom_strategy->setItemData(9, 0, Qt::UserRole - 1);
214 #ifndef RTABMAP_OPENVINS
215 _ui->odom_strategy->setItemData(10, 0, Qt::UserRole - 1);
217 #ifndef RTABMAP_FLOAM
218 _ui->odom_strategy->setItemData(11, 0, Qt::UserRole - 1);
220 #ifndef RTABMAP_OPEN3D
221 _ui->odom_strategy->setItemData(12, 0, Qt::UserRole - 1);
224 #if CV_MAJOR_VERSION < 3
225 _ui->stereosgbm_mode->setItemData(2, 0, Qt::UserRole - 1);
229 #ifndef RTABMAP_NONFREE
230 _ui->comboBox_detector_strategy->setItemData(0, 0, Qt::UserRole - 1);
231 _ui->comboBox_detector_strategy->setItemData(12, 0, Qt::UserRole - 1);
232 _ui->comboBox_detector_strategy->setItemData(14, 0, Qt::UserRole - 1);
233 _ui->vis_feature_detector->setItemData(0, 0, Qt::UserRole - 1);
234 _ui->vis_feature_detector->setItemData(12, 0, Qt::UserRole - 1);
235 _ui->vis_feature_detector->setItemData(14, 0, Qt::UserRole - 1);
239 #if CV_MAJOR_VERSION < 3 || (CV_MAJOR_VERSION == 4 && CV_MINOR_VERSION <= 3) || (CV_MAJOR_VERSION == 3 && (CV_MINOR_VERSION < 4 || (CV_MINOR_VERSION==4 && CV_SUBMINOR_VERSION<11)))
240 #ifndef RTABMAP_NONFREE
241 _ui->comboBox_detector_strategy->setItemData(1, 0, Qt::UserRole - 1);
242 _ui->vis_feature_detector->setItemData(1, 0, Qt::UserRole - 1);
246 #if CV_MAJOR_VERSION >= 3 && !defined(HAVE_OPENCV_XFEATURES2D)
247 _ui->comboBox_detector_strategy->setItemData(3, 0, Qt::UserRole - 1);
248 _ui->comboBox_detector_strategy->setItemData(4, 0, Qt::UserRole - 1);
249 _ui->comboBox_detector_strategy->setItemData(5, 0, Qt::UserRole - 1);
250 _ui->comboBox_detector_strategy->setItemData(6, 0, Qt::UserRole - 1);
251 _ui->comboBox_detector_strategy->setItemData(12, 0, Qt::UserRole - 1);
252 _ui->comboBox_detector_strategy->setItemData(13, 0, Qt::UserRole - 1);
253 _ui->comboBox_detector_strategy->setItemData(14, 0, Qt::UserRole - 1);
254 _ui->vis_feature_detector->setItemData(3, 0, Qt::UserRole - 1);
255 _ui->vis_feature_detector->setItemData(4, 0, Qt::UserRole - 1);
256 _ui->vis_feature_detector->setItemData(5, 0, Qt::UserRole - 1);
257 _ui->vis_feature_detector->setItemData(6, 0, Qt::UserRole - 1);
258 _ui->vis_feature_detector->setItemData(12, 0, Qt::UserRole - 1);
259 _ui->vis_feature_detector->setItemData(13, 0, Qt::UserRole - 1);
260 _ui->vis_feature_detector->setItemData(14, 0, Qt::UserRole - 1);
263 #ifndef RTABMAP_ORB_OCTREE
264 _ui->comboBox_detector_strategy->setItemData(10, 0, Qt::UserRole - 1);
265 _ui->vis_feature_detector->setItemData(10, 0, Qt::UserRole - 1);
268 #ifndef RTABMAP_TORCH
269 _ui->comboBox_detector_strategy->setItemData(11, 0, Qt::UserRole - 1);
270 _ui->vis_feature_detector->setItemData(11, 0, Qt::UserRole - 1);
273 #ifndef RTABMAP_PYTHON
274 _ui->comboBox_detector_strategy->setItemData(15, 0, Qt::UserRole - 1);
275 _ui->vis_feature_detector->setItemData(15, 0, Qt::UserRole - 1);
276 _ui->reextract_nn->setItemData(6, 0, Qt::UserRole - 1);
277 _ui->comboBox_globalDescriptorExtractor->setItemData(1, 0, Qt::UserRole - 1);
280 #if !defined(HAVE_OPENCV_XFEATURES2D) || (CV_MAJOR_VERSION == 3 && (CV_MINOR_VERSION<4 || CV_MINOR_VERSION==4 && CV_SUBMINOR_VERSION<1))
281 _ui->reextract_nn->setItemData(7, 0, Qt::UserRole - 1);
284 #if CV_MAJOR_VERSION >= 3
285 _ui->groupBox_fast_opencv2->setEnabled(
false);
287 _ui->comboBox_detector_strategy->setItemData(9, 0, Qt::UserRole - 1);
288 _ui->comboBox_detector_strategy->setItemData(13, 0, Qt::UserRole - 1);
289 _ui->comboBox_detector_strategy->setItemData(14, 0, Qt::UserRole - 1);
290 _ui->vis_feature_detector->setItemData(9, 0, Qt::UserRole - 1);
291 _ui->vis_feature_detector->setItemData(13, 0, Qt::UserRole - 1);
292 _ui->vis_feature_detector->setItemData(14, 0, Qt::UserRole - 1);
295 _ui->comboBox_cameraImages_odomFormat->setItemData(4, 0, Qt::UserRole - 1);
296 _ui->comboBox_cameraImages_gtFormat->setItemData(4, 0, Qt::UserRole - 1);
299 _ui->graphOptimization_type->setItemData(1, 0, Qt::UserRole - 1);
300 _ui->odom_f2m_bundleStrategy->setItemData(1, 0, Qt::UserRole - 1);
301 _ui->loopClosure_bundle->setItemData(1, 0, Qt::UserRole - 1);
302 _ui->groupBoxx_g2o->setEnabled(
false);
304 #ifdef RTABMAP_ORB_SLAM
308 _ui->graphOptimization_type->setItemData(1, 0, Qt::UserRole - 1);
313 _ui->comboBox_g2o_solver->setItemData(0, 0, Qt::UserRole - 1);
317 _ui->comboBox_g2o_solver->setItemData(2, 0, Qt::UserRole - 1);
321 _ui->graphOptimization_type->setItemData(0, 0, Qt::UserRole - 1);
325 _ui->graphOptimization_type->setItemData(2, 0, Qt::UserRole - 1);
329 _ui->odom_f2m_bundleStrategy->setItemData(2, 0, Qt::UserRole - 1);
330 _ui->loopClosure_bundle->setItemData(2, 0, Qt::UserRole - 1);
334 _ui->graphOptimization_type->setItemData(3, 0, Qt::UserRole - 1);
335 _ui->odom_f2m_bundleStrategy->setItemData(3, 0, Qt::UserRole - 1);
336 _ui->loopClosure_bundle->setItemData(3, 0, Qt::UserRole - 1);
338 #ifdef RTABMAP_VERTIGO
342 _ui->graphOptimization_robust->setEnabled(
false);
344 #ifndef RTABMAP_POINTMATCHER
345 _ui->comboBox_icpStrategy->setItemData(1, 0, Qt::UserRole - 1);
347 #ifndef RTABMAP_CCCORELIB
348 _ui->comboBox_icpStrategy->setItemData(2, 0, Qt::UserRole - 1);
387 _ui->comboBox_odom_sensor->setItemData(1, 0, Qt::UserRole - 1);
400 _ui->comboBox_odom_sensor->setItemData(2, 0, Qt::UserRole - 1);
404 _ui->comboBox_stereoZed_resolution->setItemData(2, 0, Qt::UserRole - 1);
405 _ui->comboBox_stereoZed_resolution->setItemData(4, 0, Qt::UserRole - 1);
406 _ui->comboBox_stereoZed_resolution->setItemData(6, 0, Qt::UserRole - 1);
407 _ui->comboBox_stereoZed_quality->setItemData(3, 0, Qt::UserRole - 1);
428 _ui->comboBox_odom_sensor->setItemData(3, 0, Qt::UserRole - 1);
433 #if PCL_VERSION_COMPARE(<, 1, 7, 2)
434 _ui->checkBox_showFrustums->setEnabled(
false);
435 _ui->checkBox_showFrustums->setChecked(
false);
436 _ui->checkBox_showOdomFrustums->setEnabled(
false);
437 _ui->checkBox_showOdomFrustums->setChecked(
false);
441 #if CV_MAJOR_VERSION < 3 || (CV_MAJOR_VERSION == 3 && (CV_MINOR_VERSION <4 || (CV_MINOR_VERSION ==4 && CV_SUBMINOR_VERSION<2)))
442 _ui->ArucoDictionary->setItemData(17, 0, Qt::UserRole - 1);
443 _ui->ArucoDictionary->setItemData(18, 0, Qt::UserRole - 1);
444 _ui->ArucoDictionary->setItemData(19, 0, Qt::UserRole - 1);
445 _ui->ArucoDictionary->setItemData(20, 0, Qt::UserRole - 1);
447 #ifndef HAVE_OPENCV_ARUCO
448 _ui->label_markerDetection->setText(
_ui->label_markerDetection->text()+
" This option works only if OpenCV has been built with \"aruco\" module.");
451 #ifndef RTABMAP_MADGWICK
452 _ui->comboBox_imuFilter_strategy->setItemData(1, 0, Qt::UserRole - 1);
456 UASSERT(
_ui->odom_registration->count() == 4);
469 _ui->predictionPlot->showLegend(
false);
471 QButtonGroup * buttonGroup =
new QButtonGroup(
this);
472 buttonGroup->addButton(
_ui->radioButton_basic);
473 buttonGroup->addButton(
_ui->radioButton_advanced);
476 connect(
_ui->buttonBox_global, SIGNAL(
clicked(QAbstractButton *)),
this, SLOT(
closeDialog(QAbstractButton *)));
477 connect(
_ui->buttonBox_local, SIGNAL(
clicked(QAbstractButton *)),
this, SLOT(
resetApply(QAbstractButton *)));
483 connect(
_ui->radioButton_basic, SIGNAL(toggled(
bool)),
this, SLOT(
setupTreeView()));
596 for(
int i=0;
i<2; ++
i)
676 _ui->comboBox_loggerFilter->SetDisplayText(
"Select:");
681 connect(
_ui->general_doubleSpinBox_imgRate, SIGNAL(valueChanged(
double)),
_ui->doubleSpinBox_OdomORBSLAMFps, SLOT(setValue(
double)));
685 _ui->stackedWidget_src->setCurrentIndex(
_ui->comboBox_sourceType->currentIndex());
686 connect(
_ui->comboBox_sourceType, SIGNAL(currentIndexChanged(
int)),
_ui->stackedWidget_src, SLOT(setCurrentIndex(
int)));
692 _ui->stackedWidget_image->setCurrentIndex(
_ui->source_comboBox_image_type->currentIndex());
693 connect(
_ui->source_comboBox_image_type, SIGNAL(currentIndexChanged(
int)),
_ui->stackedWidget_image, SLOT(setCurrentIndex(
int)));
723 connect(
_ui->source_checkBox_stereoToDepthDB, SIGNAL(toggled(
bool)),
_ui->checkbox_stereo_depthGenerated, SLOT(setChecked(
bool)));
724 connect(
_ui->checkbox_stereo_depthGenerated, SIGNAL(toggled(
bool)),
_ui->source_checkBox_stereoToDepthDB, SLOT(setChecked(
bool)));
727 _ui->stackedWidget_rgbd->setCurrentIndex(
_ui->comboBox_cameraRGBD->currentIndex());
728 connect(
_ui->comboBox_cameraRGBD, SIGNAL(currentIndexChanged(
int)),
_ui->stackedWidget_rgbd, SLOT(setCurrentIndex(
int)));
730 _ui->stackedWidget_stereo->setCurrentIndex(
_ui->comboBox_cameraStereo->currentIndex());
731 connect(
_ui->comboBox_cameraStereo, SIGNAL(currentIndexChanged(
int)),
_ui->stackedWidget_stereo, SLOT(setCurrentIndex(
int)));
776 connect(
_ui->lineEdit_cameraRGBDImages_path_rgb, SIGNAL(textChanged(
const QString &)),
this, SLOT(
makeObsoleteSourcePanel()));
777 connect(
_ui->lineEdit_cameraRGBDImages_path_depth, SIGNAL(textChanged(
const QString &)),
this, SLOT(
makeObsoleteSourcePanel()));
785 connect(
_ui->lineEdit_cameraImages_laser_transform, SIGNAL(textChanged(
const QString &)),
this, SLOT(
makeObsoleteSourcePanel()));
793 connect(
_ui->lineEdit_cameraImages_imu_transform, SIGNAL(textChanged(
const QString &)),
this, SLOT(
makeObsoleteSourcePanel()));
803 connect(
_ui->lineEdit_cameraStereoImages_path_left, SIGNAL(textChanged(
const QString &)),
this, SLOT(
makeObsoleteSourcePanel()));
804 connect(
_ui->lineEdit_cameraStereoImages_path_right, SIGNAL(textChanged(
const QString &)),
this, SLOT(
makeObsoleteSourcePanel()));
842 connect(
_ui->comboBox_depthai_subpixel_fractional_bits, SIGNAL(currentIndexChanged(
int)),
this, SLOT(
makeObsoleteSourcePanel()));
883 connect(
_ui->lineEdit_odom_sensor_path_calibration, SIGNAL(textChanged(
const QString &)),
this, SLOT(
makeObsoleteSourcePanel()));
891 connect(
_ui->comboBox_imuFilter_strategy, SIGNAL(currentIndexChanged(
int)),
_ui->stackedWidget_imuFilter, SLOT(setCurrentIndex(
int)));
892 _ui->stackedWidget_imuFilter->setCurrentIndex(
_ui->comboBox_imuFilter_strategy->currentIndex());
897 connect(
_ui->comboBox_lidar_src, SIGNAL(currentIndexChanged(
int)),
_ui->stackedWidget_lidar_src, SLOT(setCurrentIndex(
int)));
898 _ui->stackedWidget_lidar_src->setCurrentIndex(
_ui->comboBox_lidar_src->currentIndex());
907 connect(
_ui->doubleSpinBox_source_scanNormalsForceGroundUp, SIGNAL(valueChanged(
double)),
this, SLOT(
makeObsoleteSourcePanel()));
922 connect(
_ui->general_doubleSpinBox_timeThr, SIGNAL(valueChanged(
double)),
_ui->general_doubleSpinBox_timeThr_2, SLOT(setValue(
double)));
923 connect(
_ui->general_doubleSpinBox_hardThr, SIGNAL(valueChanged(
double)),
_ui->general_doubleSpinBox_hardThr_2, SLOT(setValue(
double)));
924 connect(
_ui->doubleSpinBox_similarityThreshold, SIGNAL(valueChanged(
double)),
_ui->doubleSpinBox_similarityThreshold_2, SLOT(setValue(
double)));
925 connect(
_ui->general_doubleSpinBox_detectionRate, SIGNAL(valueChanged(
double)),
_ui->general_doubleSpinBox_detectionRate_2, SLOT(setValue(
double)));
926 connect(
_ui->general_spinBox_imagesBufferSize, SIGNAL(valueChanged(
int)),
_ui->general_spinBox_imagesBufferSize_2, SLOT(setValue(
int)));
927 connect(
_ui->general_spinBox_maxStMemSize, SIGNAL(valueChanged(
int)),
_ui->general_spinBox_maxStMemSize_2, SLOT(setValue(
int)));
931 connect(
_ui->doubleSpinBox_similarityThreshold_2, SIGNAL(editingFinished()),
this, SLOT(
updateBasicParameter()));
932 connect(
_ui->general_doubleSpinBox_detectionRate_2, SIGNAL(editingFinished()),
this, SLOT(
updateBasicParameter()));
933 connect(
_ui->general_spinBox_imagesBufferSize_2, SIGNAL(editingFinished()),
this, SLOT(
updateBasicParameter()));
944 _ui->groupBox_publishing->setObjectName(Parameters::kRtabmapPublishStats().
c_str());
945 _ui->general_checkBox_publishRawData->setObjectName(Parameters::kRtabmapPublishLastSignature().
c_str());
946 _ui->general_checkBox_publishPdf->setObjectName(Parameters::kRtabmapPublishPdf().
c_str());
947 _ui->general_checkBox_publishLikelihood->setObjectName(Parameters::kRtabmapPublishLikelihood().
c_str());
948 _ui->general_checkBox_publishRMSE->setObjectName(Parameters::kRtabmapComputeRMSE().
c_str());
949 _ui->general_checkBox_saveWMState->setObjectName(Parameters::kRtabmapSaveWMState().
c_str());
950 _ui->general_checkBox_publishRAM->setObjectName(Parameters::kRtabmapPublishRAMUsage().
c_str());
951 _ui->general_checkBox_statisticLogsBufferedInRAM->setObjectName(Parameters::kRtabmapStatisticLogsBufferedInRAM().
c_str());
952 _ui->groupBox_statistics->setObjectName(Parameters::kRtabmapStatisticLogged().
c_str());
953 _ui->general_checkBox_statisticLoggedHeaders->setObjectName(Parameters::kRtabmapStatisticLoggedHeaders().
c_str());
954 _ui->general_doubleSpinBox_timeThr->setObjectName(Parameters::kRtabmapTimeThr().
c_str());
955 _ui->general_spinBox_memoryThr->setObjectName(Parameters::kRtabmapMemoryThr().
c_str());
956 _ui->general_doubleSpinBox_detectionRate->setObjectName(Parameters::kRtabmapDetectionRate().
c_str());
957 _ui->general_spinBox_imagesBufferSize->setObjectName(Parameters::kRtabmapImageBufferSize().
c_str());
958 _ui->general_checkBox_createIntermediateNodes->setObjectName(Parameters::kRtabmapCreateIntermediateNodes().
c_str());
959 _ui->general_spinBox_maxRetrieved->setObjectName(Parameters::kRtabmapMaxRetrieved().
c_str());
960 _ui->general_spinBox_max_republished->setObjectName(Parameters::kRtabmapMaxRepublished().
c_str());
961 _ui->general_checkBox_startNewMapOnLoopClosure->setObjectName(Parameters::kRtabmapStartNewMapOnLoopClosure().
c_str());
962 _ui->general_checkBox_startNewMapOnGoodSignature->setObjectName(Parameters::kRtabmapStartNewMapOnGoodSignature().
c_str());
963 _ui->general_checkBox_imagesAlreadyRectified->setObjectName(Parameters::kRtabmapImagesAlreadyRectified().
c_str());
964 _ui->general_checkBox_rectifyOnlyFeatures->setObjectName(Parameters::kRtabmapRectifyOnlyFeatures().
c_str());
965 _ui->checkBox_rtabmap_loopGPS->setObjectName(Parameters::kRtabmapLoopGPS().
c_str());
966 _ui->lineEdit_workingDirectory->setObjectName(Parameters::kRtabmapWorkingDirectory().
c_str());
970 _ui->general_checkBox_keepRawData->setObjectName(Parameters::kMemImageKept().
c_str());
971 _ui->general_checkBox_keepBinaryData->setObjectName(Parameters::kMemBinDataKept().
c_str());
972 _ui->general_checkBox_saveIntermediateNodeData->setObjectName(Parameters::kMemIntermediateNodeDataKept().
c_str());
973 _ui->lineEdit_rgbCompressionFormat->setObjectName(Parameters::kMemImageCompressionFormat().
c_str());
974 _ui->general_checkBox_keepDescriptors->setObjectName(Parameters::kMemRawDescriptorsKept().
c_str());
975 _ui->general_checkBox_saveDepth16bits->setObjectName(Parameters::kMemSaveDepth16Format().
c_str());
976 _ui->general_checkBox_compressionParallelized->setObjectName(Parameters::kMemCompressionParallelized().
c_str());
977 _ui->general_checkBox_reduceGraph->setObjectName(Parameters::kMemReduceGraph().
c_str());
978 _ui->general_checkBox_keepNotLinkedNodes->setObjectName(Parameters::kMemNotLinkedNodesKept().
c_str());
979 _ui->general_spinBox_maxStMemSize->setObjectName(Parameters::kMemSTMSize().
c_str());
980 _ui->doubleSpinBox_similarityThreshold->setObjectName(Parameters::kMemRehearsalSimilarity().
c_str());
981 _ui->general_checkBox_SLAM_mode->setObjectName(Parameters::kMemIncrementalMemory().
c_str());
982 _ui->general_checkBox_saveLocalizationData->setObjectName(Parameters::kMemLocalizationDataSaved().
c_str());
983 _ui->general_doubleSpinBox_recentWmRatio->setObjectName(Parameters::kMemRecentWmRatio().
c_str());
984 _ui->general_checkBox_transferSortingByWeightId->setObjectName(Parameters::kMemTransferSortingByWeightId().
c_str());
985 _ui->general_checkBox_RehearsalIdUpdatedToNewOne->setObjectName(Parameters::kMemRehearsalIdUpdatedToNewOne().
c_str());
986 _ui->general_checkBox_generateIds->setObjectName(Parameters::kMemGenerateIds().
c_str());
987 _ui->general_checkBox_badSignaturesIgnored->setObjectName(Parameters::kMemBadSignaturesIgnored().
c_str());
988 _ui->general_checkBox_createMapLabels->setObjectName(Parameters::kMemMapLabelsAdded().
c_str());
989 _ui->general_checkBox_initWMWithAllNodes->setObjectName(Parameters::kMemInitWMWithAllNodes().
c_str());
990 _ui->checkBox_localSpaceScanMatchingIDsSaved->setObjectName(Parameters::kRGBDScanMatchingIdsSavedInLinks().
c_str());
991 _ui->checkBox_localSpaceCreateGlobalScanMap->setObjectName(Parameters::kRGBDProximityGlobalScanMap().
c_str());
992 _ui->spinBox_imagePreDecimation->setObjectName(Parameters::kMemImagePreDecimation().
c_str());
993 _ui->spinBox_imagePostDecimation->setObjectName(Parameters::kMemImagePostDecimation().
c_str());
994 _ui->general_spinBox_laserScanDownsample->setObjectName(Parameters::kMemLaserScanDownsampleStepSize().
c_str());
995 _ui->general_doubleSpinBox_laserScanVoxelSize->setObjectName(Parameters::kMemLaserScanVoxelSize().
c_str());
996 _ui->general_spinBox_laserScanNormalK->setObjectName(Parameters::kMemLaserScanNormalK().
c_str());
997 _ui->general_doubleSpinBox_laserScanNormalRadius->setObjectName(Parameters::kMemLaserScanNormalRadius().
c_str());
998 _ui->checkBox_useOdomFeatures->setObjectName(Parameters::kMemUseOdomFeatures().
c_str());
999 _ui->memCovOffDiagIgnored->setObjectName(Parameters::kMemCovOffDiagIgnored().
c_str());
1000 _ui->general_checkBox_rotateImagesUpsideUp->setObjectName(Parameters::kMemRotateImagesUpsideUp().
c_str());
1003 _ui->checkBox_dbInMemory->setObjectName(Parameters::kDbSqlite3InMemory().
c_str());
1004 _ui->spinBox_dbCacheSize->setObjectName(Parameters::kDbSqlite3CacheSize().
c_str());
1005 _ui->comboBox_dbJournalMode->setObjectName(Parameters::kDbSqlite3JournalMode().
c_str());
1006 _ui->comboBox_dbSynchronous->setObjectName(Parameters::kDbSqlite3Synchronous().
c_str());
1007 _ui->comboBox_dbTempStore->setObjectName(Parameters::kDbSqlite3TempStore().
c_str());
1008 _ui->lineEdit_targetDatabaseVersion->setObjectName(Parameters::kDbTargetVersion().
c_str());
1012 _ui->general_doubleSpinBox_hardThr->setObjectName(Parameters::kRtabmapLoopThr().
c_str());
1013 _ui->general_doubleSpinBox_agressiveThr->setObjectName(Parameters::kRGBDAggressiveLoopThr().
c_str());
1014 _ui->general_doubleSpinBox_loopRatio->setObjectName(Parameters::kRtabmapLoopRatio().
c_str());
1015 _ui->comboBox_virtualPlaceLikelihoodRatio->setObjectName(Parameters::kRtabmapVirtualPlaceLikelihoodRatio().
c_str());
1016 _ui->comboBox_globalDescriptorExtractor->setObjectName(Parameters::kMemGlobalDescriptorStrategy().
c_str());
1020 _ui->general_doubleSpinBox_vp->setObjectName(Parameters::kBayesVirtualPlacePriorThr().
c_str());
1021 _ui->lineEdit_bayes_predictionLC->setObjectName(Parameters::kBayesPredictionLC().
c_str());
1022 _ui->checkBox_bayes_fullPredictionUpdate->setObjectName(Parameters::kBayesFullPredictionUpdate().
c_str());
1023 connect(
_ui->lineEdit_bayes_predictionLC, SIGNAL(textChanged(
const QString &)),
this, SLOT(
updatePredictionPlot()));
1026 _ui->comboBox_dictionary_strategy->setObjectName(Parameters::kKpNNStrategy().
c_str());
1027 _ui->checkBox_dictionary_incremental->setObjectName(Parameters::kKpIncrementalDictionary().
c_str());
1028 _ui->checkBox_kp_incrementalFlann->setObjectName(Parameters::kKpIncrementalFlann().
c_str());
1029 _ui->checkBox_kp_byteToFloat->setObjectName(Parameters::kKpByteToFloat().
c_str());
1030 _ui->surf_doubleSpinBox_rebalancingFactor->setObjectName(Parameters::kKpFlannRebalancingFactor().
c_str());
1031 _ui->comboBox_detector_strategy->setObjectName(Parameters::kKpDetectorStrategy().
c_str());
1032 _ui->surf_doubleSpinBox_nndrRatio->setObjectName(Parameters::kKpNndrRatio().
c_str());
1033 _ui->surf_doubleSpinBox_maxDepth->setObjectName(Parameters::kKpMaxDepth().
c_str());
1034 _ui->surf_doubleSpinBox_minDepth->setObjectName(Parameters::kKpMinDepth().
c_str());
1035 _ui->checkBox_memDepthAsMask->setObjectName(Parameters::kMemDepthAsMask().
c_str());
1036 _ui->checkBox_memStereoFromMotion->setObjectName(Parameters::kMemStereoFromMotion().
c_str());
1037 _ui->surf_spinBox_wordsPerImageTarget->setObjectName(Parameters::kKpMaxFeatures().
c_str());
1038 _ui->checkBox_kp_ssc->setObjectName(Parameters::kKpSSC().
c_str());
1039 _ui->spinBox_KPGridRows->setObjectName(Parameters::kKpGridRows().
c_str());
1040 _ui->spinBox_KPGridCols->setObjectName(Parameters::kKpGridCols().
c_str());
1041 _ui->surf_doubleSpinBox_ratioBadSign->setObjectName(Parameters::kKpBadSignRatio().
c_str());
1042 _ui->checkBox_kp_tfIdfLikelihoodUsed->setObjectName(Parameters::kKpTfIdfLikelihoodUsed().
c_str());
1043 _ui->checkBox_kp_parallelized->setObjectName(Parameters::kKpParallelized().
c_str());
1044 _ui->lineEdit_kp_roi->setObjectName(Parameters::kKpRoiRatios().
c_str());
1045 _ui->lineEdit_dictionaryPath->setObjectName(Parameters::kKpDictionaryPath().
c_str());
1047 _ui->checkBox_kp_newWordsComparedTogether->setObjectName(Parameters::kKpNewWordsComparedTogether().
c_str());
1048 _ui->subpix_winSize_kp->setObjectName(Parameters::kKpSubPixWinSize().
c_str());
1049 _ui->subpix_iterations_kp->setObjectName(Parameters::kKpSubPixIterations().
c_str());
1050 _ui->subpix_eps_kp->setObjectName(Parameters::kKpSubPixEps().
c_str());
1052 _ui->subpix_winSize->setObjectName(Parameters::kKpSubPixWinSize().
c_str());
1053 _ui->subpix_iterations->setObjectName(Parameters::kKpSubPixIterations().
c_str());
1054 _ui->subpix_eps->setObjectName(Parameters::kKpSubPixEps().
c_str());
1057 _ui->surf_doubleSpinBox_hessianThr->setObjectName(Parameters::kSURFHessianThreshold().
c_str());
1058 _ui->surf_spinBox_octaves->setObjectName(Parameters::kSURFOctaves().
c_str());
1059 _ui->surf_spinBox_octaveLayers->setObjectName(Parameters::kSURFOctaveLayers().
c_str());
1060 _ui->checkBox_surfExtended->setObjectName(Parameters::kSURFExtended().
c_str());
1061 _ui->surf_checkBox_upright->setObjectName(Parameters::kSURFUpright().
c_str());
1062 _ui->surf_checkBox_gpuVersion->setObjectName(Parameters::kSURFGpuVersion().
c_str());
1063 _ui->surf_doubleSpinBox_gpuKeypointsRatio->setObjectName(Parameters::kSURFGpuKeypointsRatio().
c_str());
1066 _ui->sift_spinBox_nFeatures->setObjectName(Parameters::kSIFTNFeatures().
c_str());
1067 _ui->sift_spinBox_nOctaveLayers->setObjectName(Parameters::kSIFTNOctaveLayers().
c_str());
1068 _ui->sift_doubleSpinBox_contrastThr->setObjectName(Parameters::kSIFTContrastThreshold().
c_str());
1069 _ui->sift_doubleSpinBox_edgeThr->setObjectName(Parameters::kSIFTEdgeThreshold().
c_str());
1070 _ui->sift_doubleSpinBox_sigma->setObjectName(Parameters::kSIFTSigma().
c_str());
1071 _ui->sift_checkBox_rootsift->setObjectName(Parameters::kSIFTRootSIFT().
c_str());
1074 _ui->briefBytes->setObjectName(Parameters::kBRIEFBytes().
c_str());
1077 _ui->fastSuppressNonMax->setObjectName(Parameters::kFASTNonmaxSuppression().
c_str());
1078 _ui->fastThreshold->setObjectName(Parameters::kFASTThreshold().
c_str());
1079 _ui->fastThresholdMin->setObjectName(Parameters::kFASTMinThreshold().
c_str());
1080 _ui->fastThresholdMax->setObjectName(Parameters::kFASTMaxThreshold().
c_str());
1081 _ui->fastGridRows->setObjectName(Parameters::kFASTGridRows().
c_str());
1082 _ui->fastGridCols->setObjectName(Parameters::kFASTGridCols().
c_str());
1083 _ui->fastGpu->setObjectName(Parameters::kFASTGpu().
c_str());
1084 _ui->fastKeypointRatio->setObjectName(Parameters::kFASTGpuKeypointsRatio().
c_str());
1085 _ui->fastCV->setObjectName(Parameters::kFASTCV().
c_str());
1088 _ui->doubleSpinBox_ORBScaleFactor->setObjectName(Parameters::kORBScaleFactor().
c_str());
1089 _ui->spinBox_ORBNLevels->setObjectName(Parameters::kORBNLevels().
c_str());
1090 _ui->spinBox_ORBEdgeThreshold->setObjectName(Parameters::kORBEdgeThreshold().
c_str());
1091 _ui->spinBox_ORBFirstLevel->setObjectName(Parameters::kORBFirstLevel().
c_str());
1092 _ui->spinBox_ORBWTA_K->setObjectName(Parameters::kORBWTA_K().
c_str());
1093 _ui->spinBox_ORBScoreType->setObjectName(Parameters::kORBScoreType().
c_str());
1094 _ui->spinBox_ORBPatchSize->setObjectName(Parameters::kORBPatchSize().
c_str());
1095 _ui->checkBox_ORBGpu->setObjectName(Parameters::kORBGpu().
c_str());
1098 _ui->checkBox_FREAKOrientationNormalized->setObjectName(Parameters::kFREAKOrientationNormalized().
c_str());
1099 _ui->checkBox_FREAKScaleNormalized->setObjectName(Parameters::kFREAKScaleNormalized().
c_str());
1100 _ui->doubleSpinBox_FREAKPatternScale->setObjectName(Parameters::kFREAKPatternScale().
c_str());
1101 _ui->spinBox_FREAKNOctaves->setObjectName(Parameters::kFREAKNOctaves().
c_str());
1104 _ui->doubleSpinBox_GFTT_qualityLevel->setObjectName(Parameters::kGFTTQualityLevel().
c_str());
1105 _ui->doubleSpinBox_GFTT_minDistance->setObjectName(Parameters::kGFTTMinDistance().
c_str());
1106 _ui->spinBox_GFTT_blockSize->setObjectName(Parameters::kGFTTBlockSize().
c_str());
1107 _ui->checkBox_GFTT_useHarrisDetector->setObjectName(Parameters::kGFTTUseHarrisDetector().
c_str());
1108 _ui->doubleSpinBox_GFTT_k->setObjectName(Parameters::kGFTTK().
c_str());
1111 _ui->spinBox_BRISK_thresh->setObjectName(Parameters::kBRISKThresh().
c_str());
1112 _ui->spinBox_BRISK_octaves->setObjectName(Parameters::kBRISKOctaves().
c_str());
1113 _ui->doubleSpinBox_BRISK_patterScale->setObjectName(Parameters::kBRISKPatternScale().
c_str());
1116 _ui->checkBox_kaze_extended->setObjectName(Parameters::kKAZEExtended().
c_str());
1117 _ui->checkBox_kaze_upright->setObjectName(Parameters::kKAZEUpright().
c_str());
1118 _ui->doubleSpinBox_kaze_threshold->setObjectName(Parameters::kKAZEThreshold().
c_str());
1119 _ui->spinBox_kaze_octaves->setObjectName(Parameters::kKAZENOctaves().
c_str());
1120 _ui->spinBox_kaze_octavelayers->setObjectName(Parameters::kKAZENOctaveLayers().
c_str());
1121 _ui->spinBox_kaze_diffusivity->setObjectName(Parameters::kKAZEDiffusivity().
c_str());
1124 _ui->lineEdit_sptorch_path->setObjectName(Parameters::kSuperPointModelPath().
c_str());
1126 _ui->doubleSpinBox_sptorch_threshold->setObjectName(Parameters::kSuperPointThreshold().
c_str());
1127 _ui->checkBox_sptorch_nms->setObjectName(Parameters::kSuperPointNMS().
c_str());
1128 _ui->spinBox_sptorch_minDistance->setObjectName(Parameters::kSuperPointNMSRadius().
c_str());
1129 _ui->checkBox_sptorch_cuda->setObjectName(Parameters::kSuperPointCuda().
c_str());
1132 _ui->lineEdit_pymatcher_path->setObjectName(Parameters::kPyMatcherPath().
c_str());
1134 _ui->pymatcher_matchThreshold->setObjectName(Parameters::kPyMatcherThreshold().
c_str());
1135 _ui->pymatcher_iterations->setObjectName(Parameters::kPyMatcherIterations().
c_str());
1136 _ui->checkBox_pymatcher_cuda->setObjectName(Parameters::kPyMatcherCuda().
c_str());
1137 _ui->lineEdit_pymatcher_model->setObjectName(Parameters::kPyMatcherModel().
c_str());
1141 _ui->lineEdit_pydetector_path->setObjectName(Parameters::kPyDetectorPath().
c_str());
1143 _ui->checkBox_pydetector_cuda->setObjectName(Parameters::kPyDetectorCuda().
c_str());
1146 _ui->checkBox_gms_withRotation->setObjectName(Parameters::kGMSWithRotation().
c_str());
1147 _ui->checkBox_gms_withScale->setObjectName(Parameters::kGMSWithScale().
c_str());
1148 _ui->gms_thresholdFactor->setObjectName(Parameters::kGMSThresholdFactor().
c_str());
1151 _ui->lineEdit_pydescriptor_path->setObjectName(Parameters::kPyDescriptorPath().
c_str());
1153 _ui->pydescriptor_dim->setObjectName(Parameters::kPyDescriptorDim().
c_str());
1156 _ui->groupBox_vh_epipolar2->setObjectName(Parameters::kVhEpEnabled().
c_str());
1157 _ui->surf_spinBox_matchCountMinAccepted->setObjectName(Parameters::kVhEpMatchCountMin().
c_str());
1158 _ui->surf_doubleSpinBox_ransacParam1->setObjectName(Parameters::kVhEpRansacParam1().
c_str());
1159 _ui->surf_doubleSpinBox_ransacParam2->setObjectName(Parameters::kVhEpRansacParam2().
c_str());
1162 _ui->general_checkBox_activateRGBD->setObjectName(Parameters::kRGBDEnabled().
c_str());
1163 _ui->rgdb_linearUpdate->setObjectName(Parameters::kRGBDLinearUpdate().
c_str());
1164 _ui->rgdb_angularUpdate->setObjectName(Parameters::kRGBDAngularUpdate().
c_str());
1165 _ui->rgdb_linearSpeedUpdate->setObjectName(Parameters::kRGBDLinearSpeedUpdate().
c_str());
1166 _ui->rgdb_angularSpeedUpdate->setObjectName(Parameters::kRGBDAngularSpeedUpdate().
c_str());
1167 _ui->rgbd_forceOdom3DoF->setObjectName(Parameters::kRGBDForceOdom3DoF().
c_str());
1168 _ui->rgbd_savedLocalizationIgnored->setObjectName(Parameters::kRGBDStartAtOrigin().
c_str());
1169 _ui->rgdb_rehearsalWeightIgnoredWhileMoving->setObjectName(Parameters::kMemRehearsalWeightIgnoredWhileMoving().
c_str());
1170 _ui->rgdb_newMapOdomChange->setObjectName(Parameters::kRGBDNewMapOdomChangeDistance().
c_str());
1171 _ui->odomScanHistory->setObjectName(Parameters::kRGBDNeighborLinkRefining().
c_str());
1172 _ui->odomGravity->setObjectName(Parameters::kMemUseOdomGravity().
c_str());
1173 _ui->spinBox_maxLocalLocationsRetrieved->setObjectName(Parameters::kRGBDMaxLocalRetrieved().
c_str());
1174 _ui->rgbd_loopCovLimited->setObjectName(Parameters::kRGBDLoopCovLimited().
c_str());
1176 _ui->graphOptimization_type->setObjectName(Parameters::kOptimizerStrategy().
c_str());
1177 _ui->graphOptimization_iterations->setObjectName(Parameters::kOptimizerIterations().
c_str());
1178 _ui->graphOptimization_covarianceIgnored->setObjectName(Parameters::kOptimizerVarianceIgnored().
c_str());
1179 _ui->graphOptimization_fromGraphEnd->setObjectName(Parameters::kRGBDOptimizeFromGraphEnd().
c_str());
1180 _ui->graphOptimization_maxError->setObjectName(Parameters::kRGBDOptimizeMaxError().
c_str());
1181 _ui->graphOptimization_gravitySigma->setObjectName(Parameters::kOptimizerGravitySigma().
c_str());
1182 _ui->graphOptimization_stopEpsilon->setObjectName(Parameters::kOptimizerEpsilon().
c_str());
1183 _ui->graphOptimization_robust->setObjectName(Parameters::kOptimizerRobust().
c_str());
1184 _ui->graphOptimization_priorsIgnored->setObjectName(Parameters::kOptimizerPriorsIgnored().
c_str());
1185 _ui->graphOptimization_landmarksIgnored->setObjectName(Parameters::kOptimizerLandmarksIgnored().
c_str());
1187 _ui->comboBox_g2o_solver->setObjectName(Parameters::kg2oSolver().
c_str());
1188 _ui->comboBox_g2o_optimizer->setObjectName(Parameters::kg2oOptimizer().
c_str());
1189 _ui->doubleSpinBox_g2o_pixelVariance->setObjectName(Parameters::kg2oPixelVariance().
c_str());
1190 _ui->doubleSpinBox_g2o_robustKernelDelta->setObjectName(Parameters::kg2oRobustKernelDelta().
c_str());
1191 _ui->doubleSpinBox_g2o_baseline->setObjectName(Parameters::kg2oBaseline().
c_str());
1193 _ui->comboBox_gtsam_optimizer->setObjectName(Parameters::kGTSAMOptimizer().
c_str());
1194 _ui->gtsam_incremental->setObjectName(Parameters::kGTSAMIncremental().
c_str());
1195 _ui->gtsam_incremental_threshold->setObjectName(Parameters::kGTSAMIncRelinearizeThreshold().
c_str());
1196 _ui->gtsam_incremental_skip->setObjectName(Parameters::kGTSAMIncRelinearizeSkip().
c_str());
1198 _ui->graphPlan_goalReachedRadius->setObjectName(Parameters::kRGBDGoalReachedRadius().
c_str());
1199 _ui->graphPlan_goalsSavedInUserData->setObjectName(Parameters::kRGBDGoalsSavedInUserData().
c_str());
1200 _ui->graphPlan_stuckIterations->setObjectName(Parameters::kRGBDPlanStuckIterations().
c_str());
1201 _ui->graphPlan_linearVelocity->setObjectName(Parameters::kRGBDPlanLinearVelocity().
c_str());
1202 _ui->graphPlan_angularVelocity->setObjectName(Parameters::kRGBDPlanAngularVelocity().
c_str());
1204 _ui->groupBox_localDetection_time->setObjectName(Parameters::kRGBDProximityByTime().
c_str());
1205 _ui->groupBox_localDetection_space->setObjectName(Parameters::kRGBDProximityBySpace().
c_str());
1206 _ui->localDetection_radius->setObjectName(Parameters::kRGBDLocalRadius().
c_str());
1207 _ui->maxLocalizationDistance->setObjectName(Parameters::kRGBDMaxLoopClosureDistance().
c_str());
1208 _ui->localDetection_maxDiffID->setObjectName(Parameters::kRGBDProximityMaxGraphDepth().
c_str());
1209 _ui->localDetection_maxNeighbors->setObjectName(Parameters::kRGBDProximityPathMaxNeighbors().
c_str());
1210 _ui->localDetection_maxPaths->setObjectName(Parameters::kRGBDProximityMaxPaths().
c_str());
1211 _ui->localDetection_pathFilteringRadius->setObjectName(Parameters::kRGBDProximityPathFilteringRadius().
c_str());
1212 _ui->localDetection_angle->setObjectName(Parameters::kRGBDProximityAngle().
c_str());
1213 _ui->localDetection_mergedScanCovFactor->setObjectName(Parameters::kRGBDProximityMergedScanCovFactor().
c_str());
1214 _ui->checkBox_localSpaceOdomGuess->setObjectName(Parameters::kRGBDProximityOdomGuess().
c_str());
1215 _ui->checkBox_localSpacePathOdomPosesUsed->setObjectName(Parameters::kRGBDProximityPathRawPosesUsed().
c_str());
1216 _ui->rgdb_localImmunizationRatio->setObjectName(Parameters::kRGBDLocalImmunizationRatio().
c_str());
1217 _ui->loopClosure_identityGuess->setObjectName(Parameters::kRGBDLoopClosureIdentityGuess().
c_str());
1218 _ui->loopClosure_reextract->setObjectName(Parameters::kRGBDLoopClosureReextractFeatures().
c_str());
1219 _ui->loopClosure_bunlde->setObjectName(Parameters::kRGBDLocalBundleOnLoopClosure().
c_str());
1220 _ui->loopClosure_invertedReg->setObjectName(Parameters::kRGBDInvertedReg().
c_str());
1221 _ui->checkbox_rgbd_createOccupancyGrid->setObjectName(Parameters::kRGBDCreateOccupancyGrid().
c_str());
1222 _ui->RGBDMarkerDetection->setObjectName(Parameters::kRGBDMarkerDetection().
c_str());
1223 _ui->spinBox_maxOdomCacheSize->setObjectName(Parameters::kRGBDMaxOdomCacheSize().
c_str());
1224 _ui->checkbox_localizationSmoothing->setObjectName(Parameters::kRGBDLocalizationSmoothing().
c_str());
1225 _ui->doubleSpinBox_localizationPriorError->setObjectName(Parameters::kRGBDLocalizationPriorError().
c_str());
1228 _ui->reg_repeatOnce->setObjectName(Parameters::kRegRepeatOnce().
c_str());
1229 _ui->comboBox_registrationStrategy->setObjectName(Parameters::kRegStrategy().
c_str());
1230 _ui->loopClosure_bowForce2D->setObjectName(Parameters::kRegForce3DoF().
c_str());
1233 _ui->loopClosure_bowMinInliers->setObjectName(Parameters::kVisMinInliers().
c_str());
1234 _ui->loopClosure_bowInlierDistance->setObjectName(Parameters::kVisInlierDistance().
c_str());
1235 _ui->loopClosure_bowIterations->setObjectName(Parameters::kVisIterations().
c_str());
1236 _ui->loopClosure_bowRefineIterations->setObjectName(Parameters::kVisRefineIterations().
c_str());
1237 _ui->visMeanDistance->setObjectName(Parameters::kVisMeanInliersDistance().
c_str());
1238 _ui->visMinDistribution->setObjectName(Parameters::kVisMinInliersDistribution().
c_str());
1239 _ui->loopClosure_estimationType->setObjectName(Parameters::kVisEstimationType().
c_str());
1240 connect(
_ui->loopClosure_estimationType, SIGNAL(currentIndexChanged(
int)),
_ui->stackedWidget_loopClosureEstimation, SLOT(setCurrentIndex(
int)));
1241 _ui->stackedWidget_loopClosureEstimation->setCurrentIndex(Parameters::defaultVisEstimationType());
1242 _ui->loopClosure_forwardEst->setObjectName(Parameters::kVisForwardEstOnly().
c_str());
1243 _ui->loopClosure_bowEpipolarGeometryVar->setObjectName(Parameters::kVisEpipolarGeometryVar().
c_str());
1244 _ui->loopClosure_pnpReprojError->setObjectName(Parameters::kVisPnPReprojError().
c_str());
1245 _ui->loopClosure_pnpFlags->setObjectName(Parameters::kVisPnPFlags().
c_str());
1246 _ui->loopClosure_pnpRefineIterations->setObjectName(Parameters::kVisPnPRefineIterations().
c_str());
1247 _ui->loopClosure_pnpVarMedianRatio->setObjectName(Parameters::kVisPnPVarianceMedianRatio().
c_str());
1248 _ui->loopClosure_pnpMaxVariance->setObjectName(Parameters::kVisPnPMaxVariance().
c_str());
1249 _ui->loopClosure_pnpSamplingPolicy->setObjectName(Parameters::kVisPnPSamplingPolicy().
c_str());
1250 _ui->loopClosure_pnpSplitLinearCovComponents->setObjectName(Parameters::kVisPnPSplitLinearCovComponents().
c_str());
1251 _ui->reextract_nn->setObjectName(Parameters::kVisCorNNType().
c_str());
1253 _ui->reextract_nndrRatio->setObjectName(Parameters::kVisCorNNDR().
c_str());
1254 _ui->spinBox_visCorGuessWinSize->setObjectName(Parameters::kVisCorGuessWinSize().
c_str());
1255 _ui->checkBox_visCorGuessMatchToProjection->setObjectName(Parameters::kVisCorGuessMatchToProjection().
c_str());
1256 _ui->vis_feature_detector->setObjectName(Parameters::kVisFeatureType().
c_str());
1257 _ui->reextract_maxFeatures->setObjectName(Parameters::kVisMaxFeatures().
c_str());
1258 _ui->checkBox_visSSC->setObjectName(Parameters::kVisSSC().
c_str());
1259 _ui->reextract_gridrows->setObjectName(Parameters::kVisGridRows().
c_str());
1260 _ui->reextract_gridcols->setObjectName(Parameters::kVisGridCols().
c_str());
1261 _ui->loopClosure_bowMaxDepth->setObjectName(Parameters::kVisMaxDepth().
c_str());
1262 _ui->loopClosure_bowMinDepth->setObjectName(Parameters::kVisMinDepth().
c_str());
1263 _ui->checkBox_visDepthAsMask->setObjectName(Parameters::kVisDepthAsMask().
c_str());
1264 _ui->loopClosure_roi->setObjectName(Parameters::kVisRoiRatios().
c_str());
1265 _ui->subpix_winSize->setObjectName(Parameters::kVisSubPixWinSize().
c_str());
1266 _ui->subpix_iterations->setObjectName(Parameters::kVisSubPixIterations().
c_str());
1267 _ui->subpix_eps->setObjectName(Parameters::kVisSubPixEps().
c_str());
1268 _ui->odom_flow_winSize_2->setObjectName(Parameters::kVisCorFlowWinSize().
c_str());
1269 _ui->odom_flow_maxLevel_2->setObjectName(Parameters::kVisCorFlowMaxLevel().
c_str());
1270 _ui->odom_flow_iterations_2->setObjectName(Parameters::kVisCorFlowIterations().
c_str());
1271 _ui->odom_flow_eps_2->setObjectName(Parameters::kVisCorFlowEps().
c_str());
1272 _ui->loopClosure_bundle->setObjectName(Parameters::kVisBundleAdjustment().
c_str());
1275 _ui->comboBox_icpStrategy->setObjectName(Parameters::kIcpStrategy().
c_str());
1276 connect(
_ui->comboBox_icpStrategy, SIGNAL(currentIndexChanged(
int)),
_ui->stackedWidget_icpStrategy, SLOT(setCurrentIndex(
int)));
1277 _ui->comboBox_icpStrategy->setCurrentIndex(Parameters::defaultIcpStrategy());
1278 _ui->globalDetection_icpMaxTranslation->setObjectName(Parameters::kIcpMaxTranslation().
c_str());
1279 _ui->globalDetection_icpMaxRotation->setObjectName(Parameters::kIcpMaxRotation().
c_str());
1280 _ui->loopClosure_icpVoxelSize->setObjectName(Parameters::kIcpVoxelSize().
c_str());
1281 _ui->loopClosure_icpDownsamplingStep->setObjectName(Parameters::kIcpDownsamplingStep().
c_str());
1282 _ui->loopClosure_icpRangeMin->setObjectName(Parameters::kIcpRangeMin().
c_str());
1283 _ui->loopClosure_icpRangeMax->setObjectName(Parameters::kIcpRangeMax().
c_str());
1284 _ui->loopClosure_icpFiltersEnabled->setObjectName(Parameters::kIcpFiltersEnabled().
c_str());
1285 _ui->loopClosure_icpMaxCorrespondenceDistance->setObjectName(Parameters::kIcpMaxCorrespondenceDistance().
c_str());
1286 _ui->loopClosure_icpReciprocalCorrespondences->setObjectName(Parameters::kIcpReciprocalCorrespondences().
c_str());
1287 _ui->loopClosure_icpIterations->setObjectName(Parameters::kIcpIterations().
c_str());
1288 _ui->loopClosure_icpEpsilon->setObjectName(Parameters::kIcpEpsilon().
c_str());
1289 _ui->loopClosure_icpRatio->setObjectName(Parameters::kIcpCorrespondenceRatio().
c_str());
1290 _ui->doubleSpinBox_icpOutlierRatio->setObjectName(Parameters::kIcpOutlierRatio().
c_str());
1291 _ui->loopClosure_icpPointToPlane->setObjectName(Parameters::kIcpPointToPlane().
c_str());
1292 _ui->loopClosure_icpPointToPlaneNormals->setObjectName(Parameters::kIcpPointToPlaneK().
c_str());
1293 _ui->loopClosure_icpPointToPlaneNormalsRadius->setObjectName(Parameters::kIcpPointToPlaneRadius().
c_str());
1294 _ui->loopClosure_icpPointToPlaneGroundNormalsUp->setObjectName(Parameters::kIcpPointToPlaneGroundNormalsUp().
c_str());
1295 _ui->loopClosure_icpPointToPlaneNormalsMinComplexity->setObjectName(Parameters::kIcpPointToPlaneMinComplexity().
c_str());
1296 _ui->loopClosure_icpPointToPlaneLowComplexityStrategy->setObjectName(Parameters::kIcpPointToPlaneLowComplexityStrategy().
c_str());
1297 _ui->loopClosure_icpDebugExportFormat->setObjectName(Parameters::kIcpDebugExportFormat().
c_str());
1299 _ui->lineEdit_IcpPMConfigPath->setObjectName(Parameters::kIcpPMConfig().
c_str());
1301 _ui->spinBox_icpPMMatcherKnn->setObjectName(Parameters::kIcpPMMatcherKnn().
c_str());
1302 _ui->doubleSpinBox_icpPMMatcherEpsilon->setObjectName(Parameters::kIcpPMMatcherEpsilon().
c_str());
1303 _ui->loopClosure_icpPMMatcherIntensity->setObjectName(Parameters::kIcpPMMatcherIntensity().
c_str());
1304 _ui->loopClosure_icpForce4DoF->setObjectName(Parameters::kIcpForce4DoF().
c_str());
1306 _ui->spinBox_icpCCSamplingLimit->setObjectName(Parameters::kIcpCCSamplingLimit().
c_str());
1307 _ui->checkBox_icpCCFilterOutFarthestPoints->setObjectName(Parameters::kIcpCCFilterOutFarthestPoints().
c_str());
1308 _ui->doubleSpinBox_icpCCMaxFinalRMS->setObjectName(Parameters::kIcpCCMaxFinalRMS().
c_str());
1312 _ui->groupBox_grid_3d->setObjectName(Parameters::kGrid3D().
c_str());
1313 _ui->checkBox_grid_groundObstacle->setObjectName(Parameters::kGridGroundIsObstacle().
c_str());
1314 _ui->doubleSpinBox_grid_resolution->setObjectName(Parameters::kGridCellSize().
c_str());
1315 _ui->checkBox_grid_preVoxelFiltering->setObjectName(Parameters::kGridPreVoxelFiltering().
c_str());
1316 _ui->spinBox_grid_decimation->setObjectName(Parameters::kGridDepthDecimation().
c_str());
1317 _ui->doubleSpinBox_grid_maxDepth->setObjectName(Parameters::kGridRangeMax().
c_str());
1318 _ui->doubleSpinBox_grid_minDepth->setObjectName(Parameters::kGridRangeMin().
c_str());
1319 _ui->lineEdit_grid_roi->setObjectName(Parameters::kGridDepthRoiRatios().
c_str());
1320 _ui->checkBox_grid_projRayTracing->setObjectName(Parameters::kGridRayTracing().
c_str());
1321 _ui->doubleSpinBox_grid_footprintLength->setObjectName(Parameters::kGridFootprintLength().
c_str());
1322 _ui->doubleSpinBox_grid_footprintWidth->setObjectName(Parameters::kGridFootprintWidth().
c_str());
1323 _ui->doubleSpinBox_grid_footprintHeight->setObjectName(Parameters::kGridFootprintHeight().
c_str());
1324 _ui->checkBox_grid_flatObstaclesDetected->setObjectName(Parameters::kGridFlatObstacleDetected().
c_str());
1325 _ui->comboBox_grid_sensor->setObjectName(Parameters::kGridSensor().
c_str());
1326 _ui->checkBox_grid_projMapFrame->setObjectName(Parameters::kGridMapFrameProjection().
c_str());
1327 _ui->doubleSpinBox_grid_maxGroundAngle->setObjectName(Parameters::kGridMaxGroundAngle().
c_str());
1328 _ui->spinBox_grid_normalK->setObjectName(Parameters::kGridNormalK().
c_str());
1329 _ui->doubleSpinBox_grid_maxGroundHeight->setObjectName(Parameters::kGridMaxGroundHeight().
c_str());
1330 _ui->doubleSpinBox_grid_maxObstacleHeight->setObjectName(Parameters::kGridMaxObstacleHeight().
c_str());
1331 _ui->doubleSpinBox_grid_clusterRadius->setObjectName(Parameters::kGridClusterRadius().
c_str());
1332 _ui->spinBox_grid_minClusterSize->setObjectName(Parameters::kGridMinClusterSize().
c_str());
1333 _ui->doubleSpinBox_grid_minGroundHeight->setObjectName(Parameters::kGridMinGroundHeight().
c_str());
1334 _ui->spinBox_grid_noiseMinNeighbors->setObjectName(Parameters::kGridNoiseFilteringMinNeighbors().
c_str());
1335 _ui->doubleSpinBox_grid_noiseRadius->setObjectName(Parameters::kGridNoiseFilteringRadius().
c_str());
1336 _ui->groupBox_grid_normalsSegmentation->setObjectName(Parameters::kGridNormalsSegmentation().
c_str());
1337 _ui->checkBox_grid_unknownSpaceFilled->setObjectName(Parameters::kGridScan2dUnknownSpaceFilled().
c_str());
1338 _ui->spinBox_grid_scanDecimation->setObjectName(Parameters::kGridScanDecimation().
c_str());
1340 _ui->doubleSpinBox_grid_updateError->setObjectName(Parameters::kGridGlobalUpdateError().
c_str());
1341 _ui->doubleSpinBox_grid_minMapSize->setObjectName(Parameters::kGridGlobalMinSize().
c_str());
1342 _ui->spinBox_grid_maxNodes->setObjectName(Parameters::kGridGlobalMaxNodes().
c_str());
1343 _ui->doubleSpinBox_grid_altitudeDelta->setObjectName(Parameters::kGridGlobalAltitudeDelta().
c_str());
1344 _ui->doubleSpinBox_grid_footprintRadius->setObjectName(Parameters::kGridGlobalFootprintRadius().
c_str());
1345 _ui->doubleSpinBox_grid_occThr->setObjectName(Parameters::kGridGlobalOccupancyThr().
c_str());
1346 _ui->doubleSpinBox_grid_probHit->setObjectName(Parameters::kGridGlobalProbHit().
c_str());
1347 _ui->doubleSpinBox_grid_probMiss->setObjectName(Parameters::kGridGlobalProbMiss().
c_str());
1348 _ui->doubleSpinBox_grid_clampingMin->setObjectName(Parameters::kGridGlobalProbClampingMin().
c_str());
1349 _ui->doubleSpinBox_grid_clampingMax->setObjectName(Parameters::kGridGlobalProbClampingMax().
c_str());
1350 _ui->checkBox_grid_erode->setObjectName(Parameters::kGridGlobalEroded().
c_str());
1351 _ui->spinBox_grid_floodfilldepth->setObjectName(Parameters::kGridGlobalFloodFillDepth().
c_str());
1354 _ui->odom_strategy->setObjectName(Parameters::kOdomStrategy().
c_str());
1356 _ui->odom_strategy->setCurrentIndex(Parameters::defaultOdomStrategy());
1358 _ui->odom_countdown->setObjectName(Parameters::kOdomResetCountdown().
c_str());
1359 _ui->odom_holonomic->setObjectName(Parameters::kOdomHolonomic().
c_str());
1360 _ui->odom_fillInfoData->setObjectName(Parameters::kOdomFillInfoData().
c_str());
1361 _ui->odom_dataBufferSize->setObjectName(Parameters::kOdomImageBufferSize().
c_str());
1362 _ui->odom_flow_keyframeThr->setObjectName(Parameters::kOdomKeyFrameThr().
c_str());
1363 _ui->odom_VisKeyFrameThr->setObjectName(Parameters::kOdomVisKeyFrameThr().
c_str());
1364 _ui->odom_flow_scanKeyframeThr->setObjectName(Parameters::kOdomScanKeyFrameThr().
c_str());
1365 _ui->odom_flow_guessMotion->setObjectName(Parameters::kOdomGuessMotion().
c_str());
1366 _ui->odom_guess_smoothing_delay->setObjectName(Parameters::kOdomGuessSmoothingDelay().
c_str());
1367 _ui->odom_imageDecimation->setObjectName(Parameters::kOdomImageDecimation().
c_str());
1368 _ui->odom_alignWithGround->setObjectName(Parameters::kOdomAlignWithGround().
c_str());
1369 _ui->odom_lidar_deskewing->setObjectName(Parameters::kOdomDeskewing().
c_str());
1372 _ui->odom_localHistory->setObjectName(Parameters::kOdomF2MMaxSize().
c_str());
1373 _ui->spinBox_odom_f2m_maxNewFeatures->setObjectName(Parameters::kOdomF2MMaxNewFeatures().
c_str());
1374 _ui->spinBox_odom_f2m_scanMaxSize->setObjectName(Parameters::kOdomF2MScanMaxSize().
c_str());
1375 _ui->doubleSpinBox_odom_f2m_scanRadius->setObjectName(Parameters::kOdomF2MScanSubtractRadius().
c_str());
1376 _ui->doubleSpinBox_odom_f2m_scanAngle->setObjectName(Parameters::kOdomF2MScanSubtractAngle().
c_str());
1377 _ui->doubleSpinBox_odom_f2m_scanRange->setObjectName(Parameters::kOdomF2MScanRange().
c_str());
1378 _ui->odom_f2m_validDepthRatio->setObjectName(Parameters::kOdomF2MValidDepthRatio().
c_str());
1379 _ui->odom_f2m_bundleStrategy->setObjectName(Parameters::kOdomF2MBundleAdjustment().
c_str());
1380 _ui->odom_f2m_bundleMaxFrames->setObjectName(Parameters::kOdomF2MBundleAdjustmentMaxFrames().
c_str());
1383 _ui->comboBox_odomf2f_corType->setObjectName(Parameters::kVisCorType().
c_str());
1386 _ui->doubleSpinBox_minFlow->setObjectName(Parameters::kOdomMonoInitMinFlow().
c_str());
1387 _ui->doubleSpinBox_minInitTranslation->setObjectName(Parameters::kOdomMonoInitMinTranslation().
c_str());
1388 _ui->doubleSpinBox_minTranslation->setObjectName(Parameters::kOdomMonoMinTranslation().
c_str());
1389 _ui->doubleSpinBox_maxVariance->setObjectName(Parameters::kOdomMonoMaxVariance().
c_str());
1392 _ui->odom_filteringStrategy->setObjectName(Parameters::kOdomFilteringStrategy().
c_str());
1393 _ui->stackedWidget_odometryFiltering->setCurrentIndex(
_ui->odom_filteringStrategy->currentIndex());
1394 connect(
_ui->odom_filteringStrategy, SIGNAL(currentIndexChanged(
int)),
_ui->stackedWidget_odometryFiltering, SLOT(setCurrentIndex(
int)));
1395 _ui->spinBox_particleSize->setObjectName(Parameters::kOdomParticleSize().
c_str());
1396 _ui->doubleSpinBox_particleNoiseT->setObjectName(Parameters::kOdomParticleNoiseT().
c_str());
1397 _ui->doubleSpinBox_particleLambdaT->setObjectName(Parameters::kOdomParticleLambdaT().
c_str());
1398 _ui->doubleSpinBox_particleNoiseR->setObjectName(Parameters::kOdomParticleNoiseR().
c_str());
1399 _ui->doubleSpinBox_particleLambdaR->setObjectName(Parameters::kOdomParticleLambdaR().
c_str());
1402 _ui->doubleSpinBox_kalmanProcessNoise->setObjectName(Parameters::kOdomKalmanProcessNoise().
c_str());
1403 _ui->doubleSpinBox_kalmanMeasurementNoise->setObjectName(Parameters::kOdomKalmanMeasurementNoise().
c_str());
1406 _ui->spinBox_OdomFovisFeatureWindowSize->setObjectName(Parameters::kOdomFovisFeatureWindowSize().
c_str());
1407 _ui->spinBox_OdomFovisMaxPyramidLevel->setObjectName(Parameters::kOdomFovisMaxPyramidLevel().
c_str());
1408 _ui->spinBox_OdomFovisMinPyramidLevel->setObjectName(Parameters::kOdomFovisMinPyramidLevel().
c_str());
1409 _ui->spinBox_OdomFovisTargetPixelsPerFeature->setObjectName(Parameters::kOdomFovisTargetPixelsPerFeature().
c_str());
1410 _ui->spinBox_OdomFovisFastThreshold->setObjectName(Parameters::kOdomFovisFastThreshold().
c_str());
1411 _ui->checkBox_OdomFovisUseAdaptiveThreshold->setObjectName(Parameters::kOdomFovisUseAdaptiveThreshold().
c_str());
1412 _ui->doubleSpinBox_OdomFovisFastThresholdAdaptiveGain->setObjectName(Parameters::kOdomFovisFastThresholdAdaptiveGain().
c_str());
1413 _ui->checkBox_OdomFovisUseHomographyInitialization->setObjectName(Parameters::kOdomFovisUseHomographyInitialization().
c_str());
1415 _ui->checkBox_OdomFovisUseBucketing->setObjectName(Parameters::kOdomFovisUseBucketing().
c_str());
1416 _ui->spinBox_OdomFovisBucketWidth->setObjectName(Parameters::kOdomFovisBucketWidth().
c_str());
1417 _ui->spinBox_OdomFovisBucketHeight->setObjectName(Parameters::kOdomFovisBucketHeight().
c_str());
1418 _ui->spinBox_OdomFovisMaxKeypointsPerBucket->setObjectName(Parameters::kOdomFovisMaxKeypointsPerBucket().
c_str());
1419 _ui->checkBox_OdomFovisUseImageNormalization->setObjectName(Parameters::kOdomFovisUseImageNormalization().
c_str());
1421 _ui->doubleSpinBox_OdomFovisInlierMaxReprojectionError->setObjectName(Parameters::kOdomFovisInlierMaxReprojectionError().
c_str());
1422 _ui->doubleSpinBox_OdomFovisCliqueInlierThreshold->setObjectName(Parameters::kOdomFovisCliqueInlierThreshold().
c_str());
1423 _ui->spinBox_OdomFovisMinFeaturesForEstimate->setObjectName(Parameters::kOdomFovisMinFeaturesForEstimate().
c_str());
1424 _ui->doubleSpinBox_OdomFovisMaxMeanReprojectionError->setObjectName(Parameters::kOdomFovisMaxMeanReprojectionError().
c_str());
1425 _ui->checkBox_OdomFovisUseSubpixelRefinement->setObjectName(Parameters::kOdomFovisUseSubpixelRefinement().
c_str());
1426 _ui->spinBox_OdomFovisFeatureSearchWindow->setObjectName(Parameters::kOdomFovisFeatureSearchWindow().
c_str());
1427 _ui->checkBox_OdomFovisUpdateTargetFeaturesWithRefined->setObjectName(Parameters::kOdomFovisUpdateTargetFeaturesWithRefined().
c_str());
1429 _ui->checkBox_OdomFovisStereoRequireMutualMatch->setObjectName(Parameters::kOdomFovisStereoRequireMutualMatch().
c_str());
1430 _ui->doubleSpinBox_OdomFovisStereoMaxDistEpipolarLine->setObjectName(Parameters::kOdomFovisStereoMaxDistEpipolarLine().
c_str());
1431 _ui->doubleSpinBox_OdomFovisStereoMaxRefinementDisplacement->setObjectName(Parameters::kOdomFovisStereoMaxRefinementDisplacement().
c_str());
1432 _ui->spinBox_OdomFovisStereoMaxDisparity->setObjectName(Parameters::kOdomFovisStereoMaxDisparity().
c_str());
1435 _ui->spinBox_OdomViso2RansacIters->setObjectName(Parameters::kOdomViso2RansacIters().
c_str());
1436 _ui->doubleSpinBox_OdomViso2InlierThreshold->setObjectName(Parameters::kOdomViso2InlierThreshold().
c_str());
1437 _ui->checkBox_OdomViso2Reweighting->setObjectName(Parameters::kOdomViso2Reweighting().
c_str());
1439 _ui->spinBox_OdomViso2MatchNmsN->setObjectName(Parameters::kOdomViso2MatchNmsN().
c_str());
1440 _ui->spinBox_OdomViso2MatchNmsTau->setObjectName(Parameters::kOdomViso2MatchNmsTau().
c_str());
1441 _ui->spinBox_OdomViso2MatchBinsize->setObjectName(Parameters::kOdomViso2MatchBinsize().
c_str());
1442 _ui->spinBox_OdomViso2MatchRadius->setObjectName(Parameters::kOdomViso2MatchRadius().
c_str());
1443 _ui->spinBox_OdomViso2MatchDispTolerance->setObjectName(Parameters::kOdomViso2MatchDispTolerance().
c_str());
1444 _ui->spinBox_OdomViso2MatchOutlierDispTolerance->setObjectName(Parameters::kOdomViso2MatchOutlierDispTolerance().
c_str());
1445 _ui->spinBox_OdomViso2MatchOutlierFlowTolerance->setObjectName(Parameters::kOdomViso2MatchOutlierFlowTolerance().
c_str());
1446 _ui->checkBox_OdomViso2MatchMultiStage->setObjectName(Parameters::kOdomViso2MatchMultiStage().
c_str());
1447 _ui->checkBox_OdomViso2MatchHalfResolution->setObjectName(Parameters::kOdomViso2MatchHalfResolution().
c_str());
1448 _ui->spinBox_OdomViso2MatchRefinement->setObjectName(Parameters::kOdomViso2MatchRefinement().
c_str());
1450 _ui->spinBox_OdomViso2BucketMaxFeatures->setObjectName(Parameters::kOdomViso2BucketMaxFeatures().
c_str());
1451 _ui->doubleSpinBox_OdomViso2BucketWidth->setObjectName(Parameters::kOdomViso2BucketWidth().
c_str());
1452 _ui->doubleSpinBox_OdomViso2BucketHeight->setObjectName(Parameters::kOdomViso2BucketHeight().
c_str());
1455 _ui->lineEdit_OdomORBSLAMVocPath->setObjectName(Parameters::kOdomORBSLAMVocPath().
c_str());
1457 _ui->doubleSpinBox_OdomORBSLAMBf->setObjectName(Parameters::kOdomORBSLAMBf().
c_str());
1458 _ui->doubleSpinBox_OdomORBSLAMThDepth->setObjectName(Parameters::kOdomORBSLAMThDepth().
c_str());
1459 _ui->doubleSpinBox_OdomORBSLAMFps->setObjectName(Parameters::kOdomORBSLAMFps().
c_str());
1460 _ui->spinBox_OdomORBSLAMMaxFeatures->setObjectName(Parameters::kOdomORBSLAMMaxFeatures().
c_str());
1461 _ui->spinBox_OdomORBSLAMMapSize->setObjectName(Parameters::kOdomORBSLAMMapSize().
c_str());
1462 _ui->groupBox_OdomORBSLAMInertial->setObjectName(Parameters::kOdomORBSLAMInertial().
c_str());
1463 _ui->doubleSpinBox_ORBSLAMGyroNoise->setObjectName(Parameters::kOdomORBSLAMGyroNoise().
c_str());
1464 _ui->doubleSpinBox_ORBSLAMAccNoise->setObjectName(Parameters::kOdomORBSLAMAccNoise().
c_str());
1465 _ui->doubleSpinBox_ORBSLAMGyroWalk->setObjectName(Parameters::kOdomORBSLAMGyroWalk().
c_str());
1466 _ui->doubleSpinBox_ORBSLAMAccWalk->setObjectName(Parameters::kOdomORBSLAMAccWalk().
c_str());
1467 _ui->doubleSpinBox_ORBSLAMSamplingRate->setObjectName(Parameters::kOdomORBSLAMSamplingRate().
c_str());
1470 _ui->lineEdit_OdomOkvisPath->setObjectName(Parameters::kOdomOKVISConfigPath().
c_str());
1474 _ui->odom_loam_sensor->setObjectName(Parameters::kOdomLOAMSensor().
c_str());
1475 _ui->odom_loam_scan_period->setObjectName(Parameters::kOdomLOAMScanPeriod().
c_str());
1476 _ui->odom_loam_resolution->setObjectName(Parameters::kOdomLOAMResolution().
c_str());
1477 _ui->odom_loam_linvar->setObjectName(Parameters::kOdomLOAMLinVar().
c_str());
1478 _ui->odom_loam_angvar->setObjectName(Parameters::kOdomLOAMAngVar().
c_str());
1479 _ui->odom_loam_localMapping->setObjectName(Parameters::kOdomLOAMLocalMapping().
c_str());
1482 _ui->OdomMSCKFGridRow->setObjectName(Parameters::kOdomMSCKFGridRow().
c_str());
1483 _ui->OdomMSCKFGridCol->setObjectName(Parameters::kOdomMSCKFGridCol().
c_str());
1484 _ui->OdomMSCKFGridMinFeatureNum->setObjectName(Parameters::kOdomMSCKFGridMinFeatureNum().
c_str());
1485 _ui->OdomMSCKFGridMaxFeatureNum->setObjectName(Parameters::kOdomMSCKFGridMaxFeatureNum().
c_str());
1486 _ui->OdomMSCKFPyramidLevels->setObjectName(Parameters::kOdomMSCKFPyramidLevels().
c_str());
1487 _ui->OdomMSCKFPatchSize->setObjectName(Parameters::kOdomMSCKFPatchSize().
c_str());
1488 _ui->OdomMSCKFFastThreshold->setObjectName(Parameters::kOdomMSCKFFastThreshold().
c_str());
1489 _ui->OdomMSCKFMaxIteration->setObjectName(Parameters::kOdomMSCKFMaxIteration().
c_str());
1490 _ui->OdomMSCKFMaxCamStateSize->setObjectName(Parameters::kOdomMSCKFMaxCamStateSize().
c_str());
1491 _ui->OdomMSCKFTrackPrecision->setObjectName(Parameters::kOdomMSCKFTrackPrecision().
c_str());
1492 _ui->OdomMSCKFRansacThreshold->setObjectName(Parameters::kOdomMSCKFRansacThreshold().
c_str());
1493 _ui->OdomMSCKFStereoThreshold->setObjectName(Parameters::kOdomMSCKFStereoThreshold().
c_str());
1494 _ui->OdomMSCKFPositionStdThreshold->setObjectName(Parameters::kOdomMSCKFPositionStdThreshold().
c_str());
1495 _ui->OdomMSCKFRotationThreshold->setObjectName(Parameters::kOdomMSCKFRotationThreshold().
c_str());
1496 _ui->OdomMSCKFTranslationThreshold->setObjectName(Parameters::kOdomMSCKFTranslationThreshold().
c_str());
1497 _ui->OdomMSCKFTrackingRateThreshold->setObjectName(Parameters::kOdomMSCKFTrackingRateThreshold().
c_str());
1498 _ui->OdomMSCKFOptTranslationThreshold->setObjectName(Parameters::kOdomMSCKFOptTranslationThreshold().
c_str());
1499 _ui->OdomMSCKFNoiseGyro->setObjectName(Parameters::kOdomMSCKFNoiseGyro().
c_str());
1500 _ui->OdomMSCKFNoiseAcc->setObjectName(Parameters::kOdomMSCKFNoiseAcc().
c_str());
1501 _ui->OdomMSCKFNoiseGyroBias->setObjectName(Parameters::kOdomMSCKFNoiseGyroBias().
c_str());
1502 _ui->OdomMSCKFNoiseAccBias->setObjectName(Parameters::kOdomMSCKFNoiseAccBias().
c_str());
1503 _ui->OdomMSCKFNoiseFeature->setObjectName(Parameters::kOdomMSCKFNoiseFeature().
c_str());
1504 _ui->OdomMSCKFInitCovVel->setObjectName(Parameters::kOdomMSCKFInitCovVel().
c_str());
1505 _ui->OdomMSCKFInitCovGyroBias->setObjectName(Parameters::kOdomMSCKFInitCovGyroBias().
c_str());
1506 _ui->OdomMSCKFInitCovAccBias->setObjectName(Parameters::kOdomMSCKFInitCovAccBias().
c_str());
1507 _ui->OdomMSCKFInitCovExRot->setObjectName(Parameters::kOdomMSCKFInitCovExRot().
c_str());
1508 _ui->OdomMSCKFInitCovExTrans->setObjectName(Parameters::kOdomMSCKFInitCovExTrans().
c_str());
1511 _ui->lineEdit_OdomVinsPath->setObjectName(Parameters::kOdomVINSConfigPath().
c_str());
1515 _ui->checkBox_OdomOpenVINSUseStereo->setObjectName(Parameters::kOdomOpenVINSUseStereo().
c_str());
1516 _ui->checkBox_OdomOpenVINSUseKLT->setObjectName(Parameters::kOdomOpenVINSUseKLT().
c_str());
1517 _ui->spinBox_OdomOpenVINSNumPts->setObjectName(Parameters::kOdomOpenVINSNumPts().
c_str());
1518 _ui->spinBox_OdomOpenVINSMinPxDist->setObjectName(Parameters::kOdomOpenVINSMinPxDist().
c_str());
1519 _ui->checkBox_OdomOpenVINSFiTriangulate1d->setObjectName(Parameters::kOdomOpenVINSFiTriangulate1d().
c_str());
1520 _ui->checkBox_OdomOpenVINSFiRefineFeatures->setObjectName(Parameters::kOdomOpenVINSFiRefineFeatures().
c_str());
1521 _ui->spinBox_OdomOpenVINSFiMaxRuns->setObjectName(Parameters::kOdomOpenVINSFiMaxRuns().
c_str());
1522 _ui->doubleSpinBox_OdomOpenVINSFiMaxBaseline->setObjectName(Parameters::kOdomOpenVINSFiMaxBaseline().
c_str());
1523 _ui->doubleSpinBox_OdomOpenVINSFiMaxCondNumber->setObjectName(Parameters::kOdomOpenVINSFiMaxCondNumber().
c_str());
1525 _ui->checkBox_OdomOpenVINSUseFEJ->setObjectName(Parameters::kOdomOpenVINSUseFEJ().
c_str());
1526 _ui->comboBox_OdomOpenVINSIntegration->setObjectName(Parameters::kOdomOpenVINSIntegration().
c_str());
1527 _ui->checkBox_OdomOpenVINSCalibCamExtrinsics->setObjectName(Parameters::kOdomOpenVINSCalibCamExtrinsics().
c_str());
1528 _ui->checkBox_OdomOpenVINSCalibCamIntrinsics->setObjectName(Parameters::kOdomOpenVINSCalibCamIntrinsics().
c_str());
1529 _ui->checkBox_OdomOpenVINSCalibCamTimeoffset->setObjectName(Parameters::kOdomOpenVINSCalibCamTimeoffset().
c_str());
1530 _ui->checkBox_OdomOpenVINSCalibIMUIntrinsics->setObjectName(Parameters::kOdomOpenVINSCalibIMUIntrinsics().
c_str());
1531 _ui->checkBox_OdomOpenVINSCalibIMUGSensitivity->setObjectName(Parameters::kOdomOpenVINSCalibIMUGSensitivity().
c_str());
1532 _ui->spinBox_OdomOpenVINSMaxClones->setObjectName(Parameters::kOdomOpenVINSMaxClones().
c_str());
1533 _ui->spinBox_OdomOpenVINSMaxSLAM->setObjectName(Parameters::kOdomOpenVINSMaxSLAM().
c_str());
1534 _ui->spinBox_OdomOpenVINSMaxSLAMInUpdate->setObjectName(Parameters::kOdomOpenVINSMaxSLAMInUpdate().
c_str());
1535 _ui->spinBox_OdomOpenVINSMaxMSCKFInUpdate->setObjectName(Parameters::kOdomOpenVINSMaxMSCKFInUpdate().
c_str());
1536 _ui->comboBox_OdomOpenVINSFeatRepMSCKF->setObjectName(Parameters::kOdomOpenVINSFeatRepMSCKF().
c_str());
1537 _ui->comboBox_OdomOpenVINSFeatRepSLAM->setObjectName(Parameters::kOdomOpenVINSFeatRepSLAM().
c_str());
1538 _ui->doubleSpinBox_OdomOpenVINSDtSLAMDelay->setObjectName(Parameters::kOdomOpenVINSDtSLAMDelay().
c_str());
1539 _ui->doubleSpinBox_OdomOpenVINSGravityMag->setObjectName(Parameters::kOdomOpenVINSGravityMag().
c_str());
1540 _ui->lineEdit_OdomOpenVINSLeftMaskPath->setObjectName(Parameters::kOdomOpenVINSLeftMaskPath().
c_str());
1542 _ui->lineEdit_OdomOpenVINSRightMaskPath->setObjectName(Parameters::kOdomOpenVINSRightMaskPath().
c_str());
1545 _ui->doubleSpinBox_OdomOpenVINSInitWindowTime->setObjectName(Parameters::kOdomOpenVINSInitWindowTime().
c_str());
1546 _ui->doubleSpinBox_OdomOpenVINSInitIMUThresh->setObjectName(Parameters::kOdomOpenVINSInitIMUThresh().
c_str());
1547 _ui->doubleSpinBox_OdomOpenVINSInitMaxDisparity->setObjectName(Parameters::kOdomOpenVINSInitMaxDisparity().
c_str());
1548 _ui->spinBox_OdomOpenVINSInitMaxFeatures->setObjectName(Parameters::kOdomOpenVINSInitMaxFeatures().
c_str());
1549 _ui->checkBox_OdomOpenVINSInitDynUse->setObjectName(Parameters::kOdomOpenVINSInitDynUse().
c_str());
1550 _ui->checkBox_OdomOpenVINSInitDynMLEOptCalib->setObjectName(Parameters::kOdomOpenVINSInitDynMLEOptCalib().
c_str());
1551 _ui->spinBox_OdomOpenVINSInitDynMLEMaxIter->setObjectName(Parameters::kOdomOpenVINSInitDynMLEMaxIter().
c_str());
1552 _ui->doubleSpinBox_OdomOpenVINSInitDynMLEMaxTime->setObjectName(Parameters::kOdomOpenVINSInitDynMLEMaxTime().
c_str());
1553 _ui->spinBox_OdomOpenVINSInitDynMLEMaxThreads->setObjectName(Parameters::kOdomOpenVINSInitDynMLEMaxThreads().
c_str());
1554 _ui->spinBox_OdomOpenVINSInitDynNumPose->setObjectName(Parameters::kOdomOpenVINSInitDynNumPose().
c_str());
1555 _ui->doubleSpinBox_OdomOpenVINSInitDynMinDeg->setObjectName(Parameters::kOdomOpenVINSInitDynMinDeg().
c_str());
1556 _ui->doubleSpinBox_OdomOpenVINSInitDynInflationOri->setObjectName(Parameters::kOdomOpenVINSInitDynInflationOri().
c_str());
1557 _ui->doubleSpinBox_OdomOpenVINSInitDynInflationVel->setObjectName(Parameters::kOdomOpenVINSInitDynInflationVel().
c_str());
1558 _ui->doubleSpinBox_OdomOpenVINSInitDynInflationBg->setObjectName(Parameters::kOdomOpenVINSInitDynInflationBg().
c_str());
1559 _ui->doubleSpinBox_OdomOpenVINSInitDynInflationBa->setObjectName(Parameters::kOdomOpenVINSInitDynInflationBa().
c_str());
1560 _ui->doubleSpinBox_OdomOpenVINSInitDynMinRecCond->setObjectName(Parameters::kOdomOpenVINSInitDynMinRecCond().
c_str());
1562 _ui->checkBox_OdomOpenVINSTryZUPT->setObjectName(Parameters::kOdomOpenVINSTryZUPT().
c_str());
1563 _ui->doubleSpinBox_OdomOpenVINSZUPTChi2Multiplier->setObjectName(Parameters::kOdomOpenVINSZUPTChi2Multiplier().
c_str());
1564 _ui->doubleSpinBox_OdomOpenVINSZUPTMaxVelodicy->setObjectName(Parameters::kOdomOpenVINSZUPTMaxVelodicy().
c_str());
1565 _ui->doubleSpinBox_OdomOpenVINSZUPTNoiseMultiplier->setObjectName(Parameters::kOdomOpenVINSZUPTNoiseMultiplier().
c_str());
1566 _ui->doubleSpinBox_OdomOpenVINSZUPTMaxDisparity->setObjectName(Parameters::kOdomOpenVINSZUPTMaxDisparity().
c_str());
1567 _ui->checkBox_OdomOpenVINSZUPTOnlyAtBeginning->setObjectName(Parameters::kOdomOpenVINSZUPTOnlyAtBeginning().
c_str());
1569 _ui->doubleSpinBox_OdomOpenVINSAccelerometerNoiseDensity->setObjectName(Parameters::kOdomOpenVINSAccelerometerNoiseDensity().
c_str());
1570 _ui->doubleSpinBox_OdomOpenVINSAccelerometerRandomWalk->setObjectName(Parameters::kOdomOpenVINSAccelerometerRandomWalk().
c_str());
1571 _ui->doubleSpinBox_OdomOpenVINSGyroscopeNoiseDensity->setObjectName(Parameters::kOdomOpenVINSGyroscopeNoiseDensity().
c_str());
1572 _ui->doubleSpinBox_OdomOpenVINSGyroscopeRandomWalk->setObjectName(Parameters::kOdomOpenVINSGyroscopeRandomWalk().
c_str());
1573 _ui->doubleSpinBox_OdomOpenVINSUpMSCKFSigmaPx->setObjectName(Parameters::kOdomOpenVINSUpMSCKFSigmaPx().
c_str());
1574 _ui->doubleSpinBox_OdomOpenVINSUpMSCKFChi2Multiplier->setObjectName(Parameters::kOdomOpenVINSUpMSCKFChi2Multiplier().
c_str());
1575 _ui->doubleSpinBox_OdomOpenVINSUpSLAMSigmaPx->setObjectName(Parameters::kOdomOpenVINSUpSLAMSigmaPx().
c_str());
1576 _ui->doubleSpinBox_OdomOpenVINSUpSLAMChi2Multiplier->setObjectName(Parameters::kOdomOpenVINSUpSLAMChi2Multiplier().
c_str());
1579 _ui->stereo_winWidth->setObjectName(Parameters::kStereoWinWidth().
c_str());
1580 _ui->stereo_winHeight->setObjectName(Parameters::kStereoWinHeight().
c_str());
1581 _ui->stereo_maxLevel->setObjectName(Parameters::kStereoMaxLevel().
c_str());
1582 _ui->stereo_iterations->setObjectName(Parameters::kStereoIterations().
c_str());
1583 _ui->stereo_minDisparity->setObjectName(Parameters::kStereoMinDisparity().
c_str());
1584 _ui->stereo_maxDisparity->setObjectName(Parameters::kStereoMaxDisparity().
c_str());
1585 _ui->stereo_ssd->setObjectName(Parameters::kStereoSSD().
c_str());
1586 _ui->stereo_flow_eps->setObjectName(Parameters::kStereoEps().
c_str());
1587 _ui->stereo_opticalFlow->setObjectName(Parameters::kStereoOpticalFlow().
c_str());
1590 _ui->odom_open3d_method->setObjectName(Parameters::kOdomOpen3DMethod().
c_str());
1591 _ui->odom_open3d_max_depth->setObjectName(Parameters::kOdomOpen3DMaxDepth().
c_str());
1594 _ui->comboBox_stereoDense_strategy->setObjectName(Parameters::kStereoDenseStrategy().
c_str());
1595 connect(
_ui->comboBox_stereoDense_strategy, SIGNAL(currentIndexChanged(
int)),
_ui->stackedWidget_stereoDense, SLOT(setCurrentIndex(
int)));
1596 _ui->comboBox_stereoDense_strategy->setCurrentIndex(Parameters::defaultStereoDenseStrategy());
1597 _ui->stackedWidget_stereoDense->setCurrentIndex(Parameters::defaultStereoDenseStrategy());
1600 _ui->stereobm_blockSize->setObjectName(Parameters::kStereoBMBlockSize().
c_str());
1601 _ui->stereobm_minDisparity->setObjectName(Parameters::kStereoBMMinDisparity().
c_str());
1602 _ui->stereobm_numDisparities->setObjectName(Parameters::kStereoBMNumDisparities().
c_str());
1603 _ui->stereobm_preFilterCap->setObjectName(Parameters::kStereoBMPreFilterCap().
c_str());
1604 _ui->stereobm_preFilterSize->setObjectName(Parameters::kStereoBMPreFilterSize().
c_str());
1605 _ui->stereobm_speckleRange->setObjectName(Parameters::kStereoBMSpeckleRange().
c_str());
1606 _ui->stereobm_speckleWinSize->setObjectName(Parameters::kStereoBMSpeckleWindowSize().
c_str());
1607 _ui->stereobm_tetureThreshold->setObjectName(Parameters::kStereoBMTextureThreshold().
c_str());
1608 _ui->stereobm_uniquessRatio->setObjectName(Parameters::kStereoBMUniquenessRatio().
c_str());
1609 _ui->stereobm_disp12MaxDiff->setObjectName(Parameters::kStereoBMDisp12MaxDiff().
c_str());
1612 _ui->stereosgbm_blockSize->setObjectName(Parameters::kStereoSGBMBlockSize().
c_str());
1613 _ui->stereosgbm_minDisparity->setObjectName(Parameters::kStereoSGBMMinDisparity().
c_str());
1614 _ui->stereosgbm_numDisparities->setObjectName(Parameters::kStereoSGBMNumDisparities().
c_str());
1615 _ui->stereosgbm_preFilterCap->setObjectName(Parameters::kStereoSGBMPreFilterCap().
c_str());
1616 _ui->stereosgbm_speckleRange->setObjectName(Parameters::kStereoSGBMSpeckleRange().
c_str());
1617 _ui->stereosgbm_speckleWinSize->setObjectName(Parameters::kStereoSGBMSpeckleWindowSize().
c_str());
1618 _ui->stereosgbm_uniquessRatio->setObjectName(Parameters::kStereoSGBMUniquenessRatio().
c_str());
1619 _ui->stereosgbm_disp12MaxDiff->setObjectName(Parameters::kStereoSGBMDisp12MaxDiff().
c_str());
1620 _ui->stereosgbm_p1->setObjectName(Parameters::kStereoSGBMP1().
c_str());
1621 _ui->stereosgbm_p2->setObjectName(Parameters::kStereoSGBMP2().
c_str());
1622 _ui->stereosgbm_mode->setObjectName(Parameters::kStereoSGBMMode().
c_str());
1625 _ui->ArucoDictionary->setObjectName(Parameters::kMarkerDictionary().
c_str());
1626 _ui->ArucoMarkerLength->setObjectName(Parameters::kMarkerLength().
c_str());
1627 _ui->ArucoMaxDepthError->setObjectName(Parameters::kMarkerMaxDepthError().
c_str());
1628 _ui->ArucoVarianceLinear->setObjectName(Parameters::kMarkerVarianceLinear().
c_str());
1629 _ui->ArucoVarianceAngular->setObjectName(Parameters::kMarkerVarianceAngular().
c_str());
1630 _ui->ArucoMarkerRangeMin->setObjectName(Parameters::kMarkerMinRange().
c_str());
1631 _ui->ArucoMarkerRangeMax->setObjectName(Parameters::kMarkerMaxRange().
c_str());
1632 _ui->ArucoMarkerPriors->setObjectName(Parameters::kMarkerPriors().
c_str());
1633 _ui->ArucoPriorsVarianceLinear->setObjectName(Parameters::kMarkerPriorsVarianceLinear().
c_str());
1634 _ui->ArucoPriorsVarianceAngular->setObjectName(Parameters::kMarkerPriorsVarianceAngular().
c_str());
1635 _ui->ArucoCornerRefinementMethod->setObjectName(Parameters::kMarkerCornerRefinementMethod().
c_str());
1638 _ui->doubleSpinBox_imuFilterMadgwickGain->setObjectName(Parameters::kImuFilterMadgwickGain().
c_str());
1639 _ui->doubleSpinBox_imuFilterMadgwickZeta->setObjectName(Parameters::kImuFilterMadgwickZeta().
c_str());
1640 _ui->doubleSpinBox_imuFilterComplementaryGainAcc->setObjectName(Parameters::kImuFilterComplementaryGainAcc().
c_str());
1641 _ui->doubleSpinBox_imuFilterComplementaryBiasAlpha->setObjectName(Parameters::kImuFilterComplementaryBiasAlpha().
c_str());
1642 _ui->checkBox_imuFilterComplementaryDoAdaptiveGain->setObjectName(Parameters::kImuFilterComplementaryDoAdpativeGain().
c_str());
1643 _ui->checkBox_imuFilterComplementaryDoBiasEstimation->setObjectName(Parameters::kImuFilterComplementaryDoBiasEstimation().
c_str());
1655 connect(
_ui->doubleSpinBox_kp_roi0, SIGNAL(valueChanged(
double)),
this, SLOT(
updateKpROI()));
1656 connect(
_ui->doubleSpinBox_kp_roi1, SIGNAL(valueChanged(
double)),
this, SLOT(
updateKpROI()));
1657 connect(
_ui->doubleSpinBox_kp_roi2, SIGNAL(valueChanged(
double)),
this, SLOT(
updateKpROI()));
1658 connect(
_ui->doubleSpinBox_kp_roi3, SIGNAL(valueChanged(
double)),
this, SLOT(
updateKpROI()));
1659 connect(
_ui->checkBox_useOdomFeatures, SIGNAL(toggled(
bool)),
this, SLOT(
useOdomFeatures()));
1663 _ui->stackedWidget->setCurrentIndex(0);
1683 for(ParametersMap::const_iterator
iter=defaults.begin();
iter!=defaults.end(); ++
iter)
1698 for(
int i =0;
i<boxes.size();++
i)
1700 if(boxes[
i] ==
_ui->groupBox_source0)
1702 _ui->stackedWidget->setCurrentIndex(
i);
1718 _ui->treeView->setModel(0);
1724 if(
_ui->radioButton_basic->isChecked())
1726 boxes = boxes.mid(0,7);
1733 QStandardItem * parentItem =
_indexModel->invisibleRootItem();
1735 this->
parseModel(boxes, parentItem, 0, index);
1736 if(
_ui->radioButton_advanced->isChecked() && index !=
_ui->stackedWidget->count()-1)
1738 ULOGGER_ERROR(
"The tree model is not the same size of the stacked widgets...%d vs %d advanced stacks", index,
_ui->stackedWidget->count()-1);
1740 int currentIndex =
_ui->stackedWidget->currentIndex();
1741 if(
_ui->radioButton_basic->isChecked())
1743 if(currentIndex >= 6)
1745 _ui->stackedWidget->setCurrentIndex(6);
1751 if(currentIndex == 6)
1753 _ui->stackedWidget->setCurrentIndex(7);
1757 _ui->treeView->expandToDepth(1);
1760 connect(
_ui->treeView->selectionModel(), SIGNAL(currentChanged(
const QModelIndex &,
const QModelIndex &)),
this, SLOT(
clicked(
const QModelIndex &,
const QModelIndex &)));
1772 QStandardItem * currentItem = 0;
1773 while(absoluteIndex < boxes.size())
1775 QString objectName = boxes.at(absoluteIndex)->objectName();
1776 QString title = boxes.at(absoluteIndex)->title();
1778 int lvl = QString(objectName.at(objectName.size()-1)).toInt(&ok);
1781 ULOGGER_ERROR(
"Error while parsing the first number of the QGroupBox title (%s), the first character must be the number in the hierarchy", title.toStdString().c_str());
1786 if(lvl == currentLevel)
1788 QStandardItem * item =
new QStandardItem(title);
1789 item->setData(absoluteIndex);
1792 parentItem->appendRow(item);
1795 else if(lvl > currentLevel)
1797 if(lvl>currentLevel+1)
1799 ULOGGER_ERROR(
"Intermediary lvl doesn't exist, lvl %d to %d, indexes %d and %d", currentLevel, lvl, absoluteIndex-1, absoluteIndex);
1804 parseModel(boxes, currentItem, currentLevel+1, absoluteIndex);
1818 for(rtabmap::ParametersMap::const_iterator
iter=parameters.begin();
iter!=parameters.end(); ++
iter)
1820 QWidget * obj =
_ui->stackedWidget->findChild<QWidget*>((*iter).first.c_str());
1824 obj->setToolTip(tr(
"%1 (Default=\"%2\")").arg(
iter->first.c_str()).arg(
iter->second.c_str()));
1826 QSpinBox * spin = qobject_cast<QSpinBox *>(obj);
1827 QDoubleSpinBox * doubleSpin = qobject_cast<QDoubleSpinBox *>(obj);
1828 QComboBox * combo = qobject_cast<QComboBox *>(obj);
1829 QCheckBox *
check = qobject_cast<QCheckBox *>(obj);
1830 QRadioButton * radio = qobject_cast<QRadioButton *>(obj);
1831 QLineEdit * lineEdit = qobject_cast<QLineEdit *>(obj);
1832 QGroupBox * groupBox = qobject_cast<QGroupBox *>(obj);
1835 connect(spin, SIGNAL(valueChanged(
int)),
this, SLOT(
addParameter(
int)));
1839 connect(doubleSpin, SIGNAL(valueChanged(
double)),
this, SLOT(
addParameter(
double)));
1843 connect(combo, SIGNAL(currentIndexChanged(
int)),
this, SLOT(
addParameter(
int)));
1851 connect(radio, SIGNAL(toggled(
bool)),
this, SLOT(
addParameter(
bool)));
1855 connect(lineEdit, SIGNAL(textChanged(
const QString &)),
this, SLOT(
addParameter(
const QString &)));
1859 connect(groupBox, SIGNAL(toggled(
bool)),
this, SLOT(
addParameter(
bool)));
1863 ULOGGER_WARN(
"QWidget called %s can't be cast to a supported widget", (*iter).first.c_str());
1868 ULOGGER_WARN(
"Can't find the related QWidget for parameter %s", (*iter).first.c_str());
1875 QStandardItem * item =
_indexModel->itemFromIndex(current);
1876 if(item && item->isEnabled())
1878 int index = item->data().toInt();
1879 if(
_ui->radioButton_advanced->isChecked() && index >= 6)
1883 _ui->stackedWidget->setCurrentIndex(index);
1884 _ui->scrollArea->horizontalScrollBar()->setValue(0);
1885 _ui->scrollArea->verticalScrollBar()->setValue(0);
1903 QDialogButtonBox::ButtonRole role =
_ui->buttonBox_global->buttonRole(button);
1906 case QDialogButtonBox::RejectRole:
1914 case QDialogButtonBox::AcceptRole:
1937 QDialogButtonBox::ButtonRole role =
_ui->buttonBox_local->buttonRole(button);
1940 case QDialogButtonBox::ApplyRole:
1948 case QDialogButtonBox::ResetRole:
1959 if(groupBox->objectName() ==
_ui->groupBox_generalSettingsGui0->objectName())
1961 _ui->general_checkBox_imagesKept->setChecked(
true);
1962 _ui->general_checkBox_missing_cache_republished->setChecked(
true);
1963 _ui->general_checkBox_cloudsKept->setChecked(
true);
1964 _ui->checkBox_beep->setChecked(
false);
1965 _ui->checkBox_stamps->setChecked(
true);
1966 _ui->checkBox_cacheStatistics->setChecked(
true);
1967 _ui->checkBox_notifyWhenNewGlobalPathIsReceived->setChecked(
false);
1968 _ui->checkBox_verticalLayoutUsed->setChecked(
true);
1969 _ui->checkBox_imageRejectedShown->setChecked(
true);
1970 _ui->checkBox_imageHighestHypShown->setChecked(
false);
1971 _ui->spinBox_odomQualityWarnThr->setValue(50);
1972 _ui->checkBox_odom_onlyInliersShown->setChecked(
false);
1973 _ui->radioButton_posteriorGraphView->setChecked(
true);
1974 _ui->radioButton_wordsGraphView->setChecked(
false);
1975 _ui->radioButton_localizationsGraphView->setChecked(
false);
1976 _ui->radioButton_localizationsGraphViewOdomCache->setChecked(
false);
1977 _ui->radioButton_nochangeGraphView->setChecked(
false);
1978 _ui->checkbox_odomDisabled->setChecked(
false);
1979 _ui->checkbox_groundTruthAlign->setChecked(
true);
1981 else if(groupBox->objectName() ==
_ui->groupBox_cloudRendering1->objectName())
1983 for(
int i=0;
i<2; ++
i)
2008 _ui->doubleSpinBox_voxel->setValue(0);
2009 _ui->doubleSpinBox_noiseRadius->setValue(0);
2010 _ui->spinBox_noiseMinNeighbors->setValue(5);
2012 _ui->doubleSpinBox_ceilingFilterHeight->setValue(0);
2013 _ui->doubleSpinBox_floorFilterHeight->setValue(0);
2014 _ui->spinBox_normalKSearch->setValue(10);
2015 _ui->doubleSpinBox_normalRadiusSearch->setValue(0.0);
2017 _ui->doubleSpinBox_ceilingFilterHeight_scan->setValue(0);
2018 _ui->doubleSpinBox_floorFilterHeight_scan->setValue(0);
2019 _ui->spinBox_normalKSearch_scan->setValue(0);
2020 _ui->doubleSpinBox_normalRadiusSearch_scan->setValue(0.0);
2022 _ui->checkBox_showGraphs->setChecked(
true);
2023 _ui->checkBox_showLabels->setChecked(
false);
2024 _ui->checkBox_showFrames->setChecked(
false);
2025 _ui->checkBox_showLandmarks->setChecked(
true);
2026 _ui->doubleSpinBox_landmarkSize->setValue(0);
2027 _ui->checkBox_showIMUGravity->setChecked(
false);
2028 _ui->checkBox_showIMUAcc->setChecked(
false);
2030 _ui->doubleSpinBox_mesh_angleTolerance->setValue(15.0);
2031 _ui->groupBox_organized->setChecked(
false);
2032 #if PCL_VERSION_COMPARE(>=, 1, 7, 2)
2033 _ui->checkBox_mesh_quad->setChecked(
true);
2035 _ui->checkBox_mesh_quad->setChecked(
false);
2037 _ui->checkBox_mesh_texture->setChecked(
false);
2038 _ui->spinBox_mesh_triangleSize->setValue(2);
2040 else if(groupBox->objectName() ==
_ui->groupBox_filtering2->objectName())
2042 _ui->radioButton_noFiltering->setChecked(
true);
2043 _ui->radioButton_nodeFiltering->setChecked(
false);
2044 _ui->radioButton_subtractFiltering->setChecked(
false);
2045 _ui->doubleSpinBox_cloudFilterRadius->setValue(0.1);
2046 _ui->doubleSpinBox_cloudFilterAngle->setValue(30);
2047 _ui->spinBox_subtractFilteringMinPts->setValue(5);
2048 _ui->doubleSpinBox_subtractFilteringRadius->setValue(0.02);
2049 _ui->doubleSpinBox_subtractFilteringAngle->setValue(0);
2051 else if(groupBox->objectName() ==
_ui->groupBox_gridMap2->objectName())
2053 _ui->doubleSpinBox_map_resolution->setValue(0);
2054 _ui->checkBox_map_shown->setChecked(
false);
2055 _ui->doubleSpinBox_map_opacity->setValue(0.75);
2056 _ui->checkBox_elevation_shown->setCheckState(Qt::Unchecked);
2058 _ui->groupBox_octomap->setChecked(
false);
2059 _ui->spinBox_octomap_treeDepth->setValue(16);
2060 _ui->checkBox_octomap_2dgrid->setChecked(
true);
2061 _ui->checkBox_octomap_show3dMap->setChecked(
true);
2062 _ui->comboBox_octomap_renderingType->setCurrentIndex(0);
2063 _ui->spinBox_octomap_pointSize->setValue(5);
2065 else if(groupBox->objectName() ==
_ui->groupBox_logging1->objectName())
2067 _ui->comboBox_loggerLevel->setCurrentIndex(2);
2068 _ui->comboBox_loggerEventLevel->setCurrentIndex(3);
2069 _ui->comboBox_loggerPauseLevel->setCurrentIndex(3);
2070 _ui->checkBox_logger_printTime->setChecked(
true);
2071 _ui->checkBox_logger_printThreadId->setChecked(
false);
2072 _ui->comboBox_loggerType->setCurrentIndex(1);
2073 for(
int i=0;
i<
_ui->comboBox_loggerFilter->count(); ++
i)
2075 _ui->comboBox_loggerFilter->setItemChecked(
i,
false);
2078 else if(groupBox->objectName() ==
_ui->groupBox_source0->objectName())
2080 _ui->general_doubleSpinBox_imgRate->setValue(0.0);
2081 _ui->source_mirroring->setChecked(
false);
2082 _ui->lineEdit_calibrationFile->clear();
2083 _ui->comboBox_sourceType->setCurrentIndex(
kSrcRGBD);
2084 _ui->lineEdit_sourceDevice->setText(
"");
2085 _ui->lineEdit_sourceLocalTransform->setText(
"0 0 0 0 0 0");
2088 _ui->source_images_spinBox_startPos->setValue(0);
2089 _ui->source_images_spinBox_maxFrames->setValue(0);
2090 _ui->spinBox_usbcam_streamWidth->setValue(0);
2091 _ui->spinBox_usbcam_streamHeight->setValue(0);
2092 _ui->checkBox_rgb_rectify->setChecked(
false);
2093 _ui->comboBox_cameraImages_bayerMode->setCurrentIndex(0);
2095 _ui->source_checkBox_ignoreOdometry->setChecked(
false);
2096 _ui->source_checkBox_ignoreGoalDelay->setChecked(
true);
2097 _ui->source_checkBox_ignoreGoals->setChecked(
true);
2098 _ui->source_checkBox_ignoreLandmarks->setChecked(
true);
2099 _ui->source_checkBox_ignoreFeatures->setChecked(
true);
2100 _ui->source_checkBox_ignorePriors->setChecked(
false);
2101 _ui->source_spinBox_databaseStartId->setValue(0);
2102 _ui->source_spinBox_databaseStopId->setValue(0);
2103 _ui->source_spinBox_database_cameraIndex->setValue(-1);
2104 _ui->source_checkBox_useDbStamps->setChecked(
true);
2135 _ui->checkbox_rgbd_colorOnly->setChecked(
false);
2136 _ui->spinBox_source_imageDecimation->setValue(1);
2137 _ui->comboBox_source_histogramMethod->setCurrentIndex(0);
2138 _ui->checkbox_source_feature_detection->setChecked(
false);
2139 _ui->checkbox_stereo_depthGenerated->setChecked(
false);
2140 _ui->checkBox_stereo_exposureCompensation->setChecked(
false);
2141 _ui->openni2_autoWhiteBalance->setChecked(
true);
2142 _ui->openni2_autoExposure->setChecked(
true);
2143 _ui->openni2_exposure->setValue(0);
2144 _ui->openni2_gain->setValue(100);
2145 _ui->openni2_mirroring->setChecked(
false);
2146 _ui->openni2_stampsIdsUsed->setChecked(
false);
2147 _ui->openni2_hshift->setValue(0);
2148 _ui->openni2_vshift->setValue(0);
2149 _ui->openni2_depth_decimation->setValue(1);
2150 _ui->comboBox_freenect2Format->setCurrentIndex(1);
2151 _ui->doubleSpinBox_freenect2MinDepth->setValue(0.3);
2152 _ui->doubleSpinBox_freenect2MaxDepth->setValue(12.0);
2153 _ui->checkBox_freenect2BilateralFiltering->setChecked(
true);
2154 _ui->checkBox_freenect2EdgeAwareFiltering->setChecked(
true);
2155 _ui->checkBox_freenect2NoiseFiltering->setChecked(
true);
2156 _ui->lineEdit_freenect2Pipeline->setText(
"");
2157 _ui->comboBox_k4w2Format->setCurrentIndex(1);
2158 _ui->comboBox_realsensePresetRGB->setCurrentIndex(0);
2159 _ui->comboBox_realsensePresetDepth->setCurrentIndex(2);
2160 _ui->checkbox_realsenseOdom->setChecked(
false);
2161 _ui->checkbox_realsenseDepthScaledToRGBSize->setChecked(
false);
2162 _ui->comboBox_realsenseRGBSource->setCurrentIndex(0);
2163 _ui->checkbox_rs2_emitter->setChecked(
true);
2164 _ui->checkbox_rs2_irMode->setChecked(
false);
2165 _ui->checkbox_rs2_irDepth->setChecked(
true);
2166 _ui->spinBox_rs2_width->setValue(848);
2167 _ui->spinBox_rs2_height->setValue(480);
2168 _ui->spinBox_rs2_rate->setValue(60);
2169 _ui->spinBox_rs2_width_depth->setValue(640);
2170 _ui->spinBox_rs2_height_depth->setValue(480);
2171 _ui->spinBox_rs2_rate_depth->setValue(30);
2172 _ui->checkbox_rs2_globalTimeStync->setChecked(
true);
2173 _ui->lineEdit_rs2_jsonFile->clear();
2174 _ui->lineEdit_openniOniPath->clear();
2175 _ui->lineEdit_openni2OniPath->clear();
2176 _ui->comboBox_k4a_rgb_resolution->setCurrentIndex(0);
2177 _ui->comboBox_k4a_framerate->setCurrentIndex(2);
2178 _ui->comboBox_k4a_depth_resolution->setCurrentIndex(2);
2179 _ui->checkbox_k4a_irDepth->setChecked(
false);
2180 _ui->lineEdit_k4a_mkv->clear();
2181 _ui->source_checkBox_useMKVStamps->setChecked(
true);
2182 _ui->lineEdit_cameraRGBDImages_path_rgb->setText(
"");
2183 _ui->lineEdit_cameraRGBDImages_path_depth->setText(
"");
2184 _ui->doubleSpinBox_cameraRGBDImages_scale->setValue(1.0);
2185 _ui->spinBox_cameraRGBDImages_startIndex->setValue(0);
2186 _ui->spinBox_cameraRGBDImages_maxFrames->setValue(0);
2187 _ui->lineEdit_source_distortionModel->setText(
"");
2188 _ui->groupBox_bilateral->setChecked(
false);
2189 _ui->doubleSpinBox_bilateral_sigmaS->setValue(10.0);
2190 _ui->doubleSpinBox_bilateral_sigmaR->setValue(0.1);
2193 _ui->lineEdit_cameraStereoImages_path_left->setText(
"");
2194 _ui->lineEdit_cameraStereoImages_path_right->setText(
"");
2195 _ui->checkBox_stereo_rectify->setChecked(
false);
2196 _ui->spinBox_cameraStereoImages_startIndex->setValue(0);
2197 _ui->spinBox_cameraStereoImages_maxFrames->setValue(0);
2198 _ui->lineEdit_cameraStereoVideo_path->setText(
"");
2199 _ui->lineEdit_cameraStereoVideo_path_2->setText(
"");
2200 _ui->spinBox_stereo_right_device->setValue(-1);
2201 _ui->spinBox_stereousbcam_streamWidth->setValue(0);
2202 _ui->spinBox_stereousbcam_streamHeight->setValue(0);
2204 _ui->comboBox_stereoZed_quality->setCurrentIndex(1);
2205 _ui->checkbox_stereoZed_selfCalibration->setChecked(
true);
2206 _ui->comboBox_stereoZed_sensingMode->setCurrentIndex(0);
2207 _ui->spinBox_stereoZed_confidenceThr->setValue(100);
2208 _ui->spinBox_stereoZed_texturenessConfidenceThr->setValue(90);
2209 _ui->lineEdit_zedSvoPath->clear();
2210 _ui->comboBox_stereoZedOC_resolution->setCurrentIndex(3);
2211 _ui->checkbox_stereoMyntEye_rectify->setChecked(
false);
2212 _ui->checkbox_stereoMyntEye_depth->setChecked(
false);
2213 _ui->checkbox_stereoMyntEye_autoExposure->setChecked(
true);
2214 _ui->spinBox_stereoMyntEye_gain->setValue(24);
2215 _ui->spinBox_stereoMyntEye_brightness->setValue(120);
2216 _ui->spinBox_stereoMyntEye_contrast->setValue(116);
2217 _ui->spinBox_stereoMyntEye_irControl->setValue(0);
2218 _ui->comboBox_depthai_resolution->setCurrentIndex(1);
2219 _ui->comboBox_depthai_output_mode->setCurrentIndex(0);
2220 _ui->spinBox_depthai_conf_threshold->setValue(200);
2221 _ui->checkBox_depthai_extended_disparity->setChecked(
false);
2222 _ui->comboBox_depthai_subpixel_fractional_bits->setCurrentIndex(2);
2223 _ui->comboBox_depthai_disparity_companding->setCurrentIndex(1);
2224 _ui->spinBox_depthai_lrc_threshold->setValue(5);
2225 _ui->checkBox_depthai_use_spec_translation->setChecked(
false);
2226 _ui->doubleSpinBox_depthai_alpha_scaling->setValue(-1);
2227 _ui->checkBox_depthai_imu_published->setChecked(
true);
2228 _ui->doubleSpinBox_depthai_dot_intensity->setValue(0.0);
2229 _ui->doubleSpinBox_depthai_flood_intensity->setValue(0.0);
2230 _ui->comboBox_depthai_detect_features->setCurrentIndex(0);
2231 _ui->lineEdit_depthai_blob_path->clear();
2233 _ui->checkBox_cameraImages_configForEachFrame->setChecked(
false);
2234 _ui->checkBox_cameraImages_timestamps->setChecked(
false);
2235 _ui->checkBox_cameraImages_syncTimeStamps->setChecked(
true);
2236 _ui->lineEdit_cameraImages_timestamps->setText(
"");
2237 _ui->lineEdit_cameraImages_path_scans->setText(
"");
2238 _ui->lineEdit_cameraImages_laser_transform->setText(
"0 0 0 0 0 0");
2239 _ui->spinBox_cameraImages_max_scan_pts->setValue(0);
2240 _ui->lineEdit_cameraImages_odom->setText(
"");
2241 _ui->comboBox_cameraImages_odomFormat->setCurrentIndex(0);
2242 _ui->lineEdit_cameraImages_gt->setText(
"");
2243 _ui->comboBox_cameraImages_gtFormat->setCurrentIndex(0);
2244 _ui->doubleSpinBox_maxPoseTimeDiff->setValue(0.02);
2245 _ui->lineEdit_cameraImages_path_imu->setText(
"");
2246 _ui->lineEdit_cameraImages_imu_transform->setText(
"0 0 1 0 -1 0 1 0 0");
2247 _ui->spinBox_cameraImages_max_imu_rate->setValue(0);
2249 _ui->comboBox_odom_sensor->setCurrentIndex(0);
2250 _ui->lineEdit_odom_sensor_extrinsics->setText(
"-0.000622602 0.0303752 0.031389 -0.00272485 0.00749254 0.0");
2251 _ui->lineEdit_odom_sensor_path_calibration->setText(
"");
2252 _ui->lineEdit_odomSourceDevice->setText(
"");
2253 _ui->doubleSpinBox_odom_sensor_time_offset->setValue(0.0);
2254 _ui->doubleSpinBox_odom_sensor_scale_factor->setValue(1);
2255 _ui->doubleSpinBox_odom_sensor_wait_time->setValue(100);
2256 _ui->checkBox_odom_sensor_use_as_gt->setChecked(
false);
2258 _ui->comboBox_imuFilter_strategy->setCurrentIndex(2);
2259 _ui->doubleSpinBox_imuFilterMadgwickGain->setValue(Parameters::defaultImuFilterMadgwickGain());
2260 _ui->doubleSpinBox_imuFilterMadgwickZeta->setValue(Parameters::defaultImuFilterMadgwickZeta());
2261 _ui->doubleSpinBox_imuFilterComplementaryGainAcc->setValue(Parameters::defaultImuFilterComplementaryGainAcc());
2262 _ui->doubleSpinBox_imuFilterComplementaryBiasAlpha->setValue(Parameters::defaultImuFilterComplementaryBiasAlpha());
2263 _ui->checkBox_imuFilterComplementaryDoAdaptiveGain->setChecked(Parameters::defaultImuFilterComplementaryDoAdpativeGain());
2264 _ui->checkBox_imuFilterComplementaryDoBiasEstimation->setChecked(Parameters::defaultImuFilterComplementaryDoBiasEstimation());
2265 _ui->checkBox_imuFilter_baseFrameConversion->setChecked(
true);
2266 _ui->checkbox_publishInterIMU->setChecked(
false);
2268 _ui->comboBox_lidar_src->setCurrentIndex(0);
2269 _ui->checkBox_source_scanDeskewing->setChecked(
false);
2270 _ui->checkBox_source_scanFromDepth->setChecked(
false);
2271 _ui->spinBox_source_scanDownsampleStep->setValue(1);
2272 _ui->doubleSpinBox_source_scanRangeMin->setValue(0);
2273 _ui->doubleSpinBox_source_scanRangeMax->setValue(0);
2274 _ui->doubleSpinBox_source_scanVoxelSize->setValue(0.0
f);
2275 _ui->spinBox_source_scanNormalsK->setValue(0);
2276 _ui->doubleSpinBox_source_scanNormalsRadius->setValue(0.0);
2277 _ui->doubleSpinBox_source_scanNormalsForceGroundUp->setValue(0);
2279 _ui->lineEdit_lidar_local_transform->setText(
"0 0 0 0 0 0");
2280 _ui->lineEdit_vlp16_pcap_path->clear();
2281 _ui->spinBox_vlp16_ip1->setValue(192);
2282 _ui->spinBox_vlp16_ip2->setValue(168);
2283 _ui->spinBox_vlp16_ip3->setValue(1);
2284 _ui->spinBox_vlp16_ip4->setValue(201);
2285 _ui->spinBox_vlp16_port->setValue(2368);
2286 _ui->checkBox_vlp16_organized->setChecked(
false);
2287 _ui->checkBox_vlp16_hostTime->setChecked(
true);
2288 _ui->checkBox_vlp16_stamp_last->setChecked(
true);
2290 _ui->groupBox_depthFromScan->setChecked(
false);
2291 _ui->groupBox_depthFromScan_fillHoles->setChecked(
true);
2292 _ui->radioButton_depthFromScan_vertical->setChecked(
true);
2293 _ui->radioButton_depthFromScan_horizontal->setChecked(
false);
2294 _ui->checkBox_depthFromScan_fillBorders->setChecked(
false);
2296 else if(groupBox->objectName() ==
_ui->groupBox_rtabmap_basic0->objectName())
2298 _ui->general_doubleSpinBox_timeThr_2->setValue(Parameters::defaultRtabmapTimeThr());
2299 _ui->general_doubleSpinBox_hardThr_2->setValue(Parameters::defaultRtabmapLoopThr());
2300 _ui->doubleSpinBox_similarityThreshold_2->setValue(Parameters::defaultMemRehearsalSimilarity());
2301 _ui->general_spinBox_imagesBufferSize_2->setValue(Parameters::defaultRtabmapImageBufferSize());
2302 _ui->general_spinBox_maxStMemSize_2->setValue(Parameters::defaultMemSTMSize());
2303 _ui->general_checkBox_publishStats_2->setChecked(Parameters::defaultRtabmapPublishStats());
2304 _ui->general_checkBox_activateRGBD_2->setChecked(Parameters::defaultRGBDEnabled());
2305 _ui->general_checkBox_SLAM_mode_2->setChecked(Parameters::defaultMemIncrementalMemory());
2306 _ui->general_doubleSpinBox_detectionRate_2->setValue(Parameters::defaultRtabmapDetectionRate());
2308 _ui->general_doubleSpinBox_timeThr->setValue(Parameters::defaultRtabmapTimeThr());
2309 _ui->general_doubleSpinBox_hardThr->setValue(Parameters::defaultRtabmapLoopThr());
2310 _ui->doubleSpinBox_similarityThreshold->setValue(Parameters::defaultMemRehearsalSimilarity());
2311 _ui->general_spinBox_imagesBufferSize->setValue(Parameters::defaultRtabmapImageBufferSize());
2312 _ui->general_spinBox_maxStMemSize->setValue(Parameters::defaultMemSTMSize());
2313 _ui->general_doubleSpinBox_detectionRate->setValue(Parameters::defaultRtabmapDetectionRate());
2317 QObjectList children = groupBox->children();
2320 for(
int i=0;
i<children.size(); ++
i)
2322 key = children.at(
i)->objectName().toStdString();
2325 if(
key.compare(Parameters::kRtabmapWorkingDirectory().c_str()) == 0)
2333 if(qobject_cast<const QGroupBox*>(children.at(
i)))
2338 else if(qobject_cast<const QGroupBox*>(children.at(
i)))
2342 else if(qobject_cast<const QStackedWidget*>(children.at(
i)))
2344 QStackedWidget * stackedWidget = (QStackedWidget*)children.at(
i);
2345 for(
int j=0;
j<stackedWidget->count(); ++
j)
2347 const QObjectList & children2 = stackedWidget->widget(
j)->children();
2348 for(
int k=0; k<children2.size(); ++k)
2350 if(qobject_cast<QGroupBox *>(children2.at(k)))
2359 if(groupBox->findChild<QLineEdit*>(
_ui->lineEdit_kp_roi->objectName()))
2364 if(groupBox->objectName() ==
_ui->groupBox_odometry1->objectName())
2366 _ui->odom_registration->setCurrentIndex(3);
2367 _ui->odom_f2m_gravitySigma->setValue(-1);
2375 if(panelNumber >= 0 && panelNumber < boxes.size())
2379 else if(panelNumber == -1)
2381 for(QList<QGroupBox*>::iterator
iter = boxes.begin();
iter!=boxes.end(); ++
iter)
2388 ULOGGER_WARN(
"panel number and the number of stacked widget doesn't match");
2395 return _ui->lineEdit_workingDirectory->text();
2400 QString privatePath = QDir::homePath() +
"/.rtabmap";
2401 if(!QDir(privatePath).exists())
2403 QDir::home().mkdir(
".rtabmap");
2405 return privatePath +
"/rtabmap.ini";
2415 QString
path = QFileDialog::getOpenFileName(
this, tr(
"Load settings..."), this->
getWorkingDirectory(),
"*.ini");
2433 QStandardItem * parentItem =
_indexModel->invisibleRootItem();
2436 for(
int i=1;
i<parentItem->rowCount(); ++
i)
2438 parentItem->child(
i)->setEnabled(
false);
2441 _ui->radioButton_basic->setEnabled(
false);
2442 _ui->radioButton_advanced->setEnabled(
false);
2447 QStandardItem * parentItem =
_indexModel->invisibleRootItem();
2450 for(
int i=0;
i<parentItem->rowCount(); ++
i)
2452 parentItem->child(
i)->setEnabled(
true);
2455 _ui->radioButton_basic->setEnabled(
true);
2456 _ui->radioButton_advanced->setEnabled(
true);
2463 if(!filePath.isEmpty())
2467 QSettings settings(
path, QSettings::IniFormat);
2468 settings.beginGroup(
"Gui");
2469 settings.beginGroup(
"General");
2470 _ui->general_checkBox_imagesKept->setChecked(settings.value(
"imagesKept",
_ui->general_checkBox_imagesKept->isChecked()).toBool());
2471 _ui->general_checkBox_missing_cache_republished->setChecked(settings.value(
"missingRepublished",
_ui->general_checkBox_missing_cache_republished->isChecked()).toBool());
2472 _ui->general_checkBox_cloudsKept->setChecked(settings.value(
"cloudsKept",
_ui->general_checkBox_cloudsKept->isChecked()).toBool());
2473 _ui->comboBox_loggerLevel->setCurrentIndex(settings.value(
"loggerLevel",
_ui->comboBox_loggerLevel->currentIndex()).toInt());
2474 _ui->comboBox_loggerEventLevel->setCurrentIndex(settings.value(
"loggerEventLevel",
_ui->comboBox_loggerEventLevel->currentIndex()).toInt());
2475 _ui->comboBox_loggerPauseLevel->setCurrentIndex(settings.value(
"loggerPauseLevel",
_ui->comboBox_loggerPauseLevel->currentIndex()).toInt());
2476 _ui->comboBox_loggerType->setCurrentIndex(settings.value(
"loggerType",
_ui->comboBox_loggerType->currentIndex()).toInt());
2477 _ui->checkBox_logger_printTime->setChecked(settings.value(
"loggerPrintTime",
_ui->checkBox_logger_printTime->isChecked()).toBool());
2478 _ui->checkBox_logger_printThreadId->setChecked(settings.value(
"loggerPrintThreadId",
_ui->checkBox_logger_printThreadId->isChecked()).toBool());
2479 _ui->checkBox_verticalLayoutUsed->setChecked(settings.value(
"verticalLayoutUsed",
_ui->checkBox_verticalLayoutUsed->isChecked()).toBool());
2480 _ui->checkBox_imageRejectedShown->setChecked(settings.value(
"imageRejectedShown",
_ui->checkBox_imageRejectedShown->isChecked()).toBool());
2481 _ui->checkBox_imageHighestHypShown->setChecked(settings.value(
"imageHighestHypShown",
_ui->checkBox_imageHighestHypShown->isChecked()).toBool());
2482 _ui->checkBox_beep->setChecked(settings.value(
"beep",
_ui->checkBox_beep->isChecked()).toBool());
2483 _ui->checkBox_stamps->setChecked(settings.value(
"figure_time",
_ui->checkBox_stamps->isChecked()).toBool());
2484 _ui->checkBox_cacheStatistics->setChecked(settings.value(
"figure_cache",
_ui->checkBox_cacheStatistics->isChecked()).toBool());
2485 _ui->checkBox_notifyWhenNewGlobalPathIsReceived->setChecked(settings.value(
"notifyNewGlobalPath",
_ui->checkBox_notifyWhenNewGlobalPathIsReceived->isChecked()).toBool());
2486 _ui->spinBox_odomQualityWarnThr->setValue(settings.value(
"odomQualityThr",
_ui->spinBox_odomQualityWarnThr->value()).toInt());
2487 _ui->checkBox_odom_onlyInliersShown->setChecked(settings.value(
"odomOnlyInliersShown",
_ui->checkBox_odom_onlyInliersShown->isChecked()).toBool());
2488 _ui->radioButton_posteriorGraphView->setChecked(settings.value(
"posteriorGraphView",
_ui->radioButton_posteriorGraphView->isChecked()).toBool());
2489 _ui->radioButton_wordsGraphView->setChecked(settings.value(
"wordsGraphView",
_ui->radioButton_wordsGraphView->isChecked()).toBool());
2490 _ui->radioButton_localizationsGraphView->setChecked(settings.value(
"localizationsGraphView",
_ui->radioButton_localizationsGraphView->isChecked()).toBool());
2491 _ui->radioButton_localizationsGraphViewOdomCache->setChecked(settings.value(
"localizationsGraphViewOdomCache",
_ui->radioButton_localizationsGraphViewOdomCache->isChecked()).toBool());
2492 _ui->radioButton_nochangeGraphView->setChecked(settings.value(
"nochangeGraphView",
_ui->radioButton_nochangeGraphView->isChecked()).toBool());
2493 _ui->checkbox_odomDisabled->setChecked(settings.value(
"odomDisabled",
_ui->checkbox_odomDisabled->isChecked()).toBool());
2494 _ui->odom_registration->setCurrentIndex(settings.value(
"odomRegistration",
_ui->odom_registration->currentIndex()).toInt());
2495 _ui->odom_f2m_gravitySigma->setValue(settings.value(
"odomF2MGravitySigma",
_ui->odom_f2m_gravitySigma->value()).toDouble());
2496 _ui->checkbox_groundTruthAlign->setChecked(settings.value(
"gtAlign",
_ui->checkbox_groundTruthAlign->isChecked()).toBool());
2498 for(
int i=0;
i<2; ++
i)
2524 _ui->doubleSpinBox_voxel->setValue(settings.value(
"cloudVoxel",
_ui->doubleSpinBox_voxel->value()).toDouble());
2525 _ui->doubleSpinBox_noiseRadius->setValue(settings.value(
"cloudNoiseRadius",
_ui->doubleSpinBox_noiseRadius->value()).toDouble());
2526 _ui->spinBox_noiseMinNeighbors->setValue(settings.value(
"cloudNoiseMinNeighbors",
_ui->spinBox_noiseMinNeighbors->value()).toInt());
2527 _ui->doubleSpinBox_ceilingFilterHeight->setValue(settings.value(
"cloudCeilingHeight",
_ui->doubleSpinBox_ceilingFilterHeight->value()).toDouble());
2528 _ui->doubleSpinBox_floorFilterHeight->setValue(settings.value(
"cloudFloorHeight",
_ui->doubleSpinBox_floorFilterHeight->value()).toDouble());
2529 _ui->spinBox_normalKSearch->setValue(settings.value(
"normalKSearch",
_ui->spinBox_normalKSearch->value()).toInt());
2530 _ui->doubleSpinBox_normalRadiusSearch->setValue(settings.value(
"normalRadiusSearch",
_ui->doubleSpinBox_normalRadiusSearch->value()).toDouble());
2531 _ui->doubleSpinBox_ceilingFilterHeight_scan->setValue(settings.value(
"scanCeilingHeight",
_ui->doubleSpinBox_ceilingFilterHeight_scan->value()).toDouble());
2532 _ui->doubleSpinBox_floorFilterHeight_scan->setValue(settings.value(
"scanFloorHeight",
_ui->doubleSpinBox_floorFilterHeight_scan->value()).toDouble());
2533 _ui->spinBox_normalKSearch_scan->setValue(settings.value(
"scanNormalKSearch",
_ui->spinBox_normalKSearch_scan->value()).toInt());
2534 _ui->doubleSpinBox_normalRadiusSearch_scan->setValue(settings.value(
"scanNormalRadiusSearch",
_ui->doubleSpinBox_normalRadiusSearch_scan->value()).toDouble());
2536 _ui->checkBox_showGraphs->setChecked(settings.value(
"showGraphs",
_ui->checkBox_showGraphs->isChecked()).toBool());
2537 _ui->checkBox_showLabels->setChecked(settings.value(
"showLabels",
_ui->checkBox_showLabels->isChecked()).toBool());
2538 _ui->checkBox_showFrames->setChecked(settings.value(
"showFrames",
_ui->checkBox_showFrames->isChecked()).toBool());
2539 _ui->checkBox_showLandmarks->setChecked(settings.value(
"showLandmarks",
_ui->checkBox_showLandmarks->isChecked()).toBool());
2540 _ui->doubleSpinBox_landmarkSize->setValue(settings.value(
"landmarkSize",
_ui->doubleSpinBox_landmarkSize->value()).toDouble());
2541 _ui->checkBox_showIMUGravity->setChecked(settings.value(
"showIMUGravity",
_ui->checkBox_showIMUGravity->isChecked()).toBool());
2542 _ui->checkBox_showIMUAcc->setChecked(settings.value(
"showIMUAcc",
_ui->checkBox_showIMUAcc->isChecked()).toBool());
2544 _ui->radioButton_noFiltering->setChecked(settings.value(
"noFiltering",
_ui->radioButton_noFiltering->isChecked()).toBool());
2545 _ui->radioButton_nodeFiltering->setChecked(settings.value(
"cloudFiltering",
_ui->radioButton_nodeFiltering->isChecked()).toBool());
2546 _ui->doubleSpinBox_cloudFilterRadius->setValue(settings.value(
"cloudFilteringRadius",
_ui->doubleSpinBox_cloudFilterRadius->value()).toDouble());
2547 _ui->doubleSpinBox_cloudFilterAngle->setValue(settings.value(
"cloudFilteringAngle",
_ui->doubleSpinBox_cloudFilterAngle->value()).toDouble());
2548 _ui->radioButton_subtractFiltering->setChecked(settings.value(
"subtractFiltering",
_ui->radioButton_subtractFiltering->isChecked()).toBool());
2549 _ui->spinBox_subtractFilteringMinPts->setValue(settings.value(
"subtractFilteringMinPts",
_ui->spinBox_subtractFilteringMinPts->value()).toInt());
2550 _ui->doubleSpinBox_subtractFilteringRadius->setValue(settings.value(
"subtractFilteringRadius",
_ui->doubleSpinBox_subtractFilteringRadius->value()).toDouble());
2551 _ui->doubleSpinBox_subtractFilteringAngle->setValue(settings.value(
"subtractFilteringAngle",
_ui->doubleSpinBox_subtractFilteringAngle->value()).toDouble());
2553 _ui->doubleSpinBox_map_resolution->setValue(settings.value(
"gridUIResolution",
_ui->doubleSpinBox_map_resolution->value()).toDouble());
2554 _ui->checkBox_map_shown->setChecked(settings.value(
"gridMapShown",
_ui->checkBox_map_shown->isChecked()).toBool());
2555 _ui->doubleSpinBox_map_opacity->setValue(settings.value(
"gridMapOpacity",
_ui->doubleSpinBox_map_opacity->value()).toDouble());
2556 _ui->checkBox_elevation_shown->setCheckState((Qt::CheckState)settings.value(
"elevationMapShown",
_ui->checkBox_elevation_shown->checkState()).toInt());
2558 _ui->groupBox_octomap->setChecked(settings.value(
"octomap",
_ui->groupBox_octomap->isChecked()).toBool());
2559 _ui->spinBox_octomap_treeDepth->setValue(settings.value(
"octomap_depth",
_ui->spinBox_octomap_treeDepth->value()).toInt());
2560 _ui->checkBox_octomap_2dgrid->setChecked(settings.value(
"octomap_2dgrid",
_ui->checkBox_octomap_2dgrid->isChecked()).toBool());
2561 _ui->checkBox_octomap_show3dMap->setChecked(settings.value(
"octomap_3dmap",
_ui->checkBox_octomap_show3dMap->isChecked()).toBool());
2562 _ui->comboBox_octomap_renderingType->setCurrentIndex(settings.value(
"octomap_rendering_type",
_ui->comboBox_octomap_renderingType->currentIndex()).toInt());
2563 _ui->spinBox_octomap_pointSize->setValue(settings.value(
"octomap_point_size",
_ui->spinBox_octomap_pointSize->value()).toInt());
2565 _ui->groupBox_organized->setChecked(settings.value(
"meshing",
_ui->groupBox_organized->isChecked()).toBool());
2566 _ui->doubleSpinBox_mesh_angleTolerance->setValue(settings.value(
"meshing_angle",
_ui->doubleSpinBox_mesh_angleTolerance->value()).toDouble());
2567 _ui->checkBox_mesh_quad->setChecked(settings.value(
"meshing_quad",
_ui->checkBox_mesh_quad->isChecked()).toBool());
2568 _ui->checkBox_mesh_texture->setChecked(settings.value(
"meshing_texture",
_ui->checkBox_mesh_texture->isChecked()).toBool());
2569 _ui->spinBox_mesh_triangleSize->setValue(settings.value(
"meshing_triangle_size",
_ui->spinBox_mesh_triangleSize->value()).toInt());
2571 settings.endGroup();
2573 settings.endGroup();
2579 if(!filePath.isEmpty())
2583 QSettings settings(
path, QSettings::IniFormat);
2585 settings.beginGroup(
"Camera");
2586 _ui->general_doubleSpinBox_imgRate->setValue(settings.value(
"imgRate",
_ui->general_doubleSpinBox_imgRate->value()).toDouble());
2587 _ui->source_mirroring->setChecked(settings.value(
"mirroring",
_ui->source_mirroring->isChecked()).toBool());
2588 _ui->lineEdit_calibrationFile->setText(settings.value(
"calibrationName",
_ui->lineEdit_calibrationFile->text()).toString());
2589 _ui->comboBox_sourceType->setCurrentIndex(settings.value(
"type",
_ui->comboBox_sourceType->currentIndex()).toInt());
2590 _ui->lineEdit_sourceDevice->setText(settings.value(
"device",
_ui->lineEdit_sourceDevice->text()).toString());
2591 _ui->lineEdit_sourceLocalTransform->setText(settings.value(
"localTransform",
_ui->lineEdit_sourceLocalTransform->text()).toString());
2592 _ui->spinBox_source_imageDecimation->setValue(settings.value(
"imageDecimation",
_ui->spinBox_source_imageDecimation->value()).toInt());
2593 _ui->comboBox_source_histogramMethod->setCurrentIndex(settings.value(
"histogramMethod",
_ui->comboBox_source_histogramMethod->currentIndex()).toInt());
2594 _ui->checkbox_source_feature_detection->setChecked(settings.value(
"featureDetection",
_ui->checkbox_source_feature_detection->isChecked()).toBool());
2596 if(
_ui->lineEdit_sourceLocalTransform->text().compare(
"0 0 1 -1 0 0 0 -1 0") == 0)
2598 UWARN(
"From 0.20.11, the local transform of the camera should not contain optical rotation (read=\"%s\"). Resetting to default Identity for convenience.",
_ui->lineEdit_sourceLocalTransform->text().toStdString().c_str());
2599 _ui->lineEdit_sourceLocalTransform->setText(
"0 0 0 0 0 0");
2602 settings.beginGroup(
"rgbd");
2603 _ui->comboBox_cameraRGBD->setCurrentIndex(settings.value(
"driver",
_ui->comboBox_cameraRGBD->currentIndex()).toInt());
2604 _ui->checkbox_rgbd_colorOnly->setChecked(settings.value(
"rgbdColorOnly",
_ui->checkbox_rgbd_colorOnly->isChecked()).toBool());
2605 _ui->lineEdit_source_distortionModel->setText(settings.value(
"distortion_model",
_ui->lineEdit_source_distortionModel->text()).toString());
2606 _ui->groupBox_bilateral->setChecked(settings.value(
"bilateral",
_ui->groupBox_bilateral->isChecked()).toBool());
2607 _ui->doubleSpinBox_bilateral_sigmaS->setValue(settings.value(
"bilateral_sigma_s",
_ui->doubleSpinBox_bilateral_sigmaS->value()).toDouble());
2608 _ui->doubleSpinBox_bilateral_sigmaR->setValue(settings.value(
"bilateral_sigma_r",
_ui->doubleSpinBox_bilateral_sigmaR->value()).toDouble());
2609 settings.endGroup();
2611 settings.beginGroup(
"stereo");
2612 _ui->comboBox_cameraStereo->setCurrentIndex(settings.value(
"driver",
_ui->comboBox_cameraStereo->currentIndex()).toInt());
2613 _ui->checkbox_stereo_depthGenerated->setChecked(settings.value(
"depthGenerated",
_ui->checkbox_stereo_depthGenerated->isChecked()).toBool());
2614 _ui->checkBox_stereo_exposureCompensation->setChecked(settings.value(
"exposureCompensation",
_ui->checkBox_stereo_exposureCompensation->isChecked()).toBool());
2615 settings.endGroup();
2617 settings.beginGroup(
"rgb");
2618 _ui->source_comboBox_image_type->setCurrentIndex(settings.value(
"driver",
_ui->source_comboBox_image_type->currentIndex()).toInt());
2619 _ui->checkBox_rgb_rectify->setChecked(settings.value(
"rectify",
_ui->checkBox_rgb_rectify->isChecked()).toBool());
2620 settings.endGroup();
2622 settings.beginGroup(
"Openni");
2623 _ui->lineEdit_openniOniPath->setText(settings.value(
"oniPath",
_ui->lineEdit_openniOniPath->text()).toString());
2624 settings.endGroup();
2626 settings.beginGroup(
"Openni2");
2627 _ui->openni2_autoWhiteBalance->setChecked(settings.value(
"autoWhiteBalance",
_ui->openni2_autoWhiteBalance->isChecked()).toBool());
2628 _ui->openni2_autoExposure->setChecked(settings.value(
"autoExposure",
_ui->openni2_autoExposure->isChecked()).toBool());
2629 _ui->openni2_exposure->setValue(settings.value(
"exposure",
_ui->openni2_exposure->value()).toInt());
2630 _ui->openni2_gain->setValue(settings.value(
"gain",
_ui->openni2_gain->value()).toInt());
2631 _ui->openni2_mirroring->setChecked(settings.value(
"mirroring",
_ui->openni2_mirroring->isChecked()).toBool());
2632 _ui->openni2_stampsIdsUsed->setChecked(settings.value(
"stampsIdsUsed",
_ui->openni2_stampsIdsUsed->isChecked()).toBool());
2633 _ui->lineEdit_openni2OniPath->setText(settings.value(
"oniPath",
_ui->lineEdit_openni2OniPath->text()).toString());
2634 _ui->openni2_hshift->setValue(settings.value(
"hshift",
_ui->openni2_hshift->value()).toInt());
2635 _ui->openni2_vshift->setValue(settings.value(
"vshift",
_ui->openni2_vshift->value()).toInt());
2636 _ui->openni2_depth_decimation->setValue(settings.value(
"depthDecimation",
_ui->openni2_depth_decimation->value()).toInt());
2637 settings.endGroup();
2639 settings.beginGroup(
"Freenect2");
2640 _ui->comboBox_freenect2Format->setCurrentIndex(settings.value(
"format",
_ui->comboBox_freenect2Format->currentIndex()).toInt());
2641 _ui->doubleSpinBox_freenect2MinDepth->setValue(settings.value(
"minDepth",
_ui->doubleSpinBox_freenect2MinDepth->value()).toDouble());
2642 _ui->doubleSpinBox_freenect2MaxDepth->setValue(settings.value(
"maxDepth",
_ui->doubleSpinBox_freenect2MaxDepth->value()).toDouble());
2643 _ui->checkBox_freenect2BilateralFiltering->setChecked(settings.value(
"bilateralFiltering",
_ui->checkBox_freenect2BilateralFiltering->isChecked()).toBool());
2644 _ui->checkBox_freenect2EdgeAwareFiltering->setChecked(settings.value(
"edgeAwareFiltering",
_ui->checkBox_freenect2EdgeAwareFiltering->isChecked()).toBool());
2645 _ui->checkBox_freenect2NoiseFiltering->setChecked(settings.value(
"noiseFiltering",
_ui->checkBox_freenect2NoiseFiltering->isChecked()).toBool());
2646 _ui->lineEdit_freenect2Pipeline->setText(settings.value(
"pipeline",
_ui->lineEdit_freenect2Pipeline->text()).toString());
2647 settings.endGroup();
2649 settings.beginGroup(
"K4W2");
2650 _ui->comboBox_k4w2Format->setCurrentIndex(settings.value(
"format",
_ui->comboBox_k4w2Format->currentIndex()).toInt());
2651 settings.endGroup();
2653 settings.beginGroup(
"K4A");
2654 _ui->comboBox_k4a_rgb_resolution->setCurrentIndex(settings.value(
"rgb_resolution",
_ui->comboBox_k4a_rgb_resolution->currentIndex()).toInt());
2655 _ui->comboBox_k4a_framerate->setCurrentIndex(settings.value(
"framerate",
_ui->comboBox_k4a_framerate->currentIndex()).toInt());
2656 _ui->comboBox_k4a_depth_resolution->setCurrentIndex(settings.value(
"depth_resolution",
_ui->comboBox_k4a_depth_resolution->currentIndex()).toInt());
2657 _ui->checkbox_k4a_irDepth->setChecked(settings.value(
"ir",
_ui->checkbox_k4a_irDepth->isChecked()).toBool());
2658 _ui->lineEdit_k4a_mkv->setText(settings.value(
"mkvPath",
_ui->lineEdit_k4a_mkv->text()).toString());
2659 _ui->source_checkBox_useMKVStamps->setChecked(settings.value(
"useMkvStamps",
_ui->source_checkBox_useMKVStamps->isChecked()).toBool());
2660 settings.endGroup();
2662 settings.beginGroup(
"RealSense");
2663 _ui->comboBox_realsensePresetRGB->setCurrentIndex(settings.value(
"presetRGB",
_ui->comboBox_realsensePresetRGB->currentIndex()).toInt());
2664 _ui->comboBox_realsensePresetDepth->setCurrentIndex(settings.value(
"presetDepth",
_ui->comboBox_realsensePresetDepth->currentIndex()).toInt());
2665 _ui->checkbox_realsenseOdom->setChecked(settings.value(
"odom",
_ui->checkbox_realsenseOdom->isChecked()).toBool());
2666 _ui->checkbox_realsenseDepthScaledToRGBSize->setChecked(settings.value(
"depthScaled",
_ui->checkbox_realsenseDepthScaledToRGBSize->isChecked()).toBool());
2667 _ui->comboBox_realsenseRGBSource->setCurrentIndex(settings.value(
"rgbSource",
_ui->comboBox_realsenseRGBSource->currentIndex()).toInt());
2668 settings.endGroup();
2670 settings.beginGroup(
"RealSense2");
2671 _ui->checkbox_rs2_emitter->setChecked(settings.value(
"emitter",
_ui->checkbox_rs2_emitter->isChecked()).toBool());
2672 _ui->checkbox_rs2_irMode->setChecked(settings.value(
"ir",
_ui->checkbox_rs2_irMode->isChecked()).toBool());
2673 _ui->checkbox_rs2_irDepth->setChecked(settings.value(
"irdepth",
_ui->checkbox_rs2_irDepth->isChecked()).toBool());
2674 _ui->spinBox_rs2_width->setValue(settings.value(
"width",
_ui->spinBox_rs2_width->value()).toInt());
2675 _ui->spinBox_rs2_height->setValue(settings.value(
"height",
_ui->spinBox_rs2_height->value()).toInt());
2676 _ui->spinBox_rs2_rate->setValue(settings.value(
"rate",
_ui->spinBox_rs2_rate->value()).toInt());
2677 _ui->spinBox_rs2_width_depth->setValue(settings.value(
"width_depth",
_ui->spinBox_rs2_width_depth->value()).toInt());
2678 _ui->spinBox_rs2_height_depth->setValue(settings.value(
"height_depth",
_ui->spinBox_rs2_height_depth->value()).toInt());
2679 _ui->spinBox_rs2_rate_depth->setValue(settings.value(
"rate_depth",
_ui->spinBox_rs2_rate_depth->value()).toInt());
2680 _ui->checkbox_rs2_globalTimeStync->setChecked(settings.value(
"global_time_sync",
_ui->checkbox_rs2_globalTimeStync->isChecked()).toBool());
2681 _ui->lineEdit_rs2_jsonFile->setText(settings.value(
"json_preset",
_ui->lineEdit_rs2_jsonFile->text()).toString());
2682 settings.endGroup();
2684 settings.beginGroup(
"RGBDImages");
2685 _ui->lineEdit_cameraRGBDImages_path_rgb->setText(settings.value(
"path_rgb",
_ui->lineEdit_cameraRGBDImages_path_rgb->text()).toString());
2686 _ui->lineEdit_cameraRGBDImages_path_depth->setText(settings.value(
"path_depth",
_ui->lineEdit_cameraRGBDImages_path_depth->text()).toString());
2687 _ui->doubleSpinBox_cameraRGBDImages_scale->setValue(settings.value(
"scale",
_ui->doubleSpinBox_cameraRGBDImages_scale->value()).toDouble());
2688 _ui->spinBox_cameraRGBDImages_startIndex->setValue(settings.value(
"start_index",
_ui->spinBox_cameraRGBDImages_startIndex->value()).toInt());
2689 _ui->spinBox_cameraRGBDImages_maxFrames->setValue(settings.value(
"max_frames",
_ui->spinBox_cameraRGBDImages_maxFrames->value()).toInt());
2690 settings.endGroup();
2692 settings.beginGroup(
"StereoImages");
2693 _ui->lineEdit_cameraStereoImages_path_left->setText(settings.value(
"path_left",
_ui->lineEdit_cameraStereoImages_path_left->text()).toString());
2694 _ui->lineEdit_cameraStereoImages_path_right->setText(settings.value(
"path_right",
_ui->lineEdit_cameraStereoImages_path_right->text()).toString());
2695 _ui->checkBox_stereo_rectify->setChecked(settings.value(
"rectify",
_ui->checkBox_stereo_rectify->isChecked()).toBool());
2696 _ui->spinBox_cameraStereoImages_startIndex->setValue(settings.value(
"start_index",
_ui->spinBox_cameraStereoImages_startIndex->value()).toInt());
2697 _ui->spinBox_cameraStereoImages_maxFrames->setValue(settings.value(
"max_frames",
_ui->spinBox_cameraStereoImages_maxFrames->value()).toInt());
2698 settings.endGroup();
2700 settings.beginGroup(
"StereoVideo");
2701 _ui->lineEdit_cameraStereoVideo_path->setText(settings.value(
"path",
_ui->lineEdit_cameraStereoVideo_path->text()).toString());
2702 _ui->lineEdit_cameraStereoVideo_path_2->setText(settings.value(
"path2",
_ui->lineEdit_cameraStereoVideo_path_2->text()).toString());
2703 _ui->spinBox_stereo_right_device->setValue(settings.value(
"device2",
_ui->spinBox_stereo_right_device->value()).toInt());
2704 _ui->spinBox_stereousbcam_streamWidth->setValue(settings.value(
"width",
_ui->spinBox_stereousbcam_streamWidth->value()).toInt());
2705 _ui->spinBox_stereousbcam_streamHeight->setValue(settings.value(
"height",
_ui->spinBox_stereousbcam_streamHeight->value()).toInt());
2706 settings.endGroup();
2708 settings.beginGroup(
"StereoZed");
2709 _ui->comboBox_stereoZed_resolution->setCurrentIndex(settings.value(
"resolution",
_ui->comboBox_stereoZed_resolution->currentIndex()).toInt());
2710 _ui->comboBox_stereoZed_quality->setCurrentIndex(settings.value(
"quality",
_ui->comboBox_stereoZed_quality->currentIndex()).toInt());
2711 _ui->checkbox_stereoZed_selfCalibration->setChecked(settings.value(
"self_calibration",
_ui->checkbox_stereoZed_selfCalibration->isChecked()).toBool());
2712 _ui->comboBox_stereoZed_sensingMode->setCurrentIndex(settings.value(
"sensing_mode",
_ui->comboBox_stereoZed_sensingMode->currentIndex()).toInt());
2713 _ui->spinBox_stereoZed_confidenceThr->setValue(settings.value(
"confidence_thr",
_ui->spinBox_stereoZed_confidenceThr->value()).toInt());
2714 _ui->spinBox_stereoZed_texturenessConfidenceThr->setValue(settings.value(
"textureness_confidence_thr",
_ui->spinBox_stereoZed_texturenessConfidenceThr->value()).toInt());
2715 _ui->lineEdit_zedSvoPath->setText(settings.value(
"svo_path",
_ui->lineEdit_zedSvoPath->text()).toString());
2716 settings.endGroup();
2718 settings.beginGroup(
"MyntEye");
2719 _ui->checkbox_stereoMyntEye_rectify->setChecked(settings.value(
"rectify",
_ui->checkbox_stereoMyntEye_rectify->isChecked()).toBool());
2720 _ui->checkbox_stereoMyntEye_depth->setChecked(settings.value(
"depth",
_ui->checkbox_stereoMyntEye_depth->isChecked()).toBool());
2721 _ui->checkbox_stereoMyntEye_autoExposure->setChecked(settings.value(
"auto_exposure",
_ui->checkbox_stereoMyntEye_autoExposure->isChecked()).toBool());
2722 _ui->spinBox_stereoMyntEye_gain->setValue(settings.value(
"gain",
_ui->spinBox_stereoMyntEye_gain->value()).toInt());
2723 _ui->spinBox_stereoMyntEye_brightness->setValue(settings.value(
"brightness",
_ui->spinBox_stereoMyntEye_brightness->value()).toInt());
2724 _ui->spinBox_stereoMyntEye_contrast->setValue(settings.value(
"contrast",
_ui->spinBox_stereoMyntEye_contrast->value()).toInt());
2725 _ui->spinBox_stereoMyntEye_irControl->setValue(settings.value(
"ir_control",
_ui->spinBox_stereoMyntEye_irControl->value()).toInt());
2726 settings.endGroup();
2728 settings.beginGroup(
"DepthAI");
2729 _ui->comboBox_depthai_resolution->setCurrentIndex(settings.value(
"resolution",
_ui->comboBox_depthai_resolution->currentIndex()).toInt());
2730 _ui->comboBox_depthai_output_mode->setCurrentIndex(settings.value(
"output_mode",
_ui->comboBox_depthai_output_mode->currentIndex()).toInt());
2731 _ui->spinBox_depthai_conf_threshold->setValue(settings.value(
"conf_threshold",
_ui->spinBox_depthai_conf_threshold->value()).toInt());
2732 _ui->spinBox_depthai_lrc_threshold->setValue(settings.value(
"lrc_threshold",
_ui->spinBox_depthai_lrc_threshold->value()).toInt());
2733 _ui->checkBox_depthai_extended_disparity->setChecked(settings.value(
"extended_disparity",
_ui->checkBox_depthai_extended_disparity->isChecked()).toBool());
2734 _ui->comboBox_depthai_subpixel_fractional_bits->setCurrentIndex(settings.value(
"subpixel_fractional_bits",
_ui->comboBox_depthai_subpixel_fractional_bits->currentIndex()).toInt());
2735 _ui->comboBox_depthai_disparity_companding->setCurrentIndex(settings.value(
"companding",
_ui->comboBox_depthai_disparity_companding->currentIndex()).toInt());
2736 _ui->checkBox_depthai_use_spec_translation->setChecked(settings.value(
"use_spec_translation",
_ui->checkBox_depthai_use_spec_translation->isChecked()).toBool());
2737 _ui->doubleSpinBox_depthai_alpha_scaling->setValue(settings.value(
"alpha_scaling",
_ui->doubleSpinBox_depthai_alpha_scaling->value()).toDouble());
2738 _ui->checkBox_depthai_imu_published->setChecked(settings.value(
"imu_published",
_ui->checkBox_depthai_imu_published->isChecked()).toBool());
2739 _ui->doubleSpinBox_depthai_dot_intensity->setValue(settings.value(
"dot_intensity",
_ui->doubleSpinBox_depthai_dot_intensity->value()).toDouble());
2740 _ui->doubleSpinBox_depthai_flood_intensity->setValue(settings.value(
"flood_intensity",
_ui->doubleSpinBox_depthai_flood_intensity->value()).toDouble());
2741 _ui->comboBox_depthai_detect_features->setCurrentIndex(settings.value(
"detect_features",
_ui->comboBox_depthai_detect_features->currentIndex()).toInt());
2742 _ui->lineEdit_depthai_blob_path->setText(settings.value(
"blob_path",
_ui->lineEdit_depthai_blob_path->text()).toString());
2743 settings.endGroup();
2745 settings.beginGroup(
"Images");
2746 _ui->source_images_lineEdit_path->setText(settings.value(
"path",
_ui->source_images_lineEdit_path->text()).toString());
2747 _ui->source_images_spinBox_startPos->setValue(settings.value(
"startPos",
_ui->source_images_spinBox_startPos->value()).toInt());
2748 _ui->source_images_spinBox_maxFrames->setValue(settings.value(
"maxFrames",
_ui->source_images_spinBox_maxFrames->value()).toInt());
2749 _ui->comboBox_cameraImages_bayerMode->setCurrentIndex(settings.value(
"bayerMode",
_ui->comboBox_cameraImages_bayerMode->currentIndex()).toInt());
2751 _ui->checkBox_cameraImages_configForEachFrame->setChecked(settings.value(
"config_each_frame",
_ui->checkBox_cameraImages_configForEachFrame->isChecked()).toBool());
2752 _ui->checkBox_cameraImages_timestamps->setChecked(settings.value(
"filenames_as_stamps",
_ui->checkBox_cameraImages_timestamps->isChecked()).toBool());
2753 _ui->checkBox_cameraImages_syncTimeStamps->setChecked(settings.value(
"sync_stamps",
_ui->checkBox_cameraImages_syncTimeStamps->isChecked()).toBool());
2754 _ui->lineEdit_cameraImages_timestamps->setText(settings.value(
"stamps",
_ui->lineEdit_cameraImages_timestamps->text()).toString());
2755 _ui->lineEdit_cameraImages_path_scans->setText(settings.value(
"path_scans",
_ui->lineEdit_cameraImages_path_scans->text()).toString());
2756 _ui->lineEdit_cameraImages_laser_transform->setText(settings.value(
"scan_transform",
_ui->lineEdit_cameraImages_laser_transform->text()).toString());
2757 _ui->spinBox_cameraImages_max_scan_pts->setValue(settings.value(
"scan_max_pts",
_ui->spinBox_cameraImages_max_scan_pts->value()).toInt());
2758 _ui->lineEdit_cameraImages_odom->setText(settings.value(
"odom_path",
_ui->lineEdit_cameraImages_odom->text()).toString());
2759 _ui->comboBox_cameraImages_odomFormat->setCurrentIndex(settings.value(
"odom_format",
_ui->comboBox_cameraImages_odomFormat->currentIndex()).toInt());
2760 _ui->lineEdit_cameraImages_gt->setText(settings.value(
"gt_path",
_ui->lineEdit_cameraImages_gt->text()).toString());
2761 _ui->comboBox_cameraImages_gtFormat->setCurrentIndex(settings.value(
"gt_format",
_ui->comboBox_cameraImages_gtFormat->currentIndex()).toInt());
2762 _ui->doubleSpinBox_maxPoseTimeDiff->setValue(settings.value(
"max_pose_time_diff",
_ui->doubleSpinBox_maxPoseTimeDiff->value()).toDouble());
2764 _ui->lineEdit_cameraImages_path_imu->setText(settings.value(
"imu_path",
_ui->lineEdit_cameraImages_path_imu->text()).toString());
2765 _ui->lineEdit_cameraImages_imu_transform->setText(settings.value(
"imu_local_transform",
_ui->lineEdit_cameraImages_imu_transform->text()).toString());
2766 _ui->spinBox_cameraImages_max_imu_rate->setValue(settings.value(
"imu_rate",
_ui->spinBox_cameraImages_max_imu_rate->value()).toInt());
2767 settings.endGroup();
2769 settings.beginGroup(
"OdomSensor");
2770 _ui->comboBox_odom_sensor->setCurrentIndex(settings.value(
"odom_sensor",
_ui->comboBox_odom_sensor->currentIndex()).toInt());
2771 _ui->lineEdit_odom_sensor_extrinsics->setText(settings.value(
"odom_sensor_extrinsics",
_ui->lineEdit_odom_sensor_extrinsics->text()).toString());
2772 _ui->lineEdit_odom_sensor_path_calibration->setText(settings.value(
"odom_sensor_calibration_path",
_ui->lineEdit_odom_sensor_path_calibration->text()).toString());
2773 _ui->lineEdit_odomSourceDevice->setText(settings.value(
"odom_sensor_device",
_ui->lineEdit_odomSourceDevice->text()).toString());
2774 _ui->doubleSpinBox_odom_sensor_time_offset->setValue(settings.value(
"odom_sensor_offset_time",
_ui->doubleSpinBox_odom_sensor_time_offset->value()).toDouble());
2775 _ui->doubleSpinBox_odom_sensor_scale_factor->setValue(settings.value(
"odom_sensor_scale_factor",
_ui->doubleSpinBox_odom_sensor_scale_factor->value()).toDouble());
2776 _ui->doubleSpinBox_odom_sensor_wait_time->setValue(settings.value(
"odom_sensor_wait_time",
_ui->doubleSpinBox_odom_sensor_wait_time->value()).toDouble());
2777 _ui->checkBox_odom_sensor_use_as_gt->setChecked(settings.value(
"odom_sensor_odom_as_gt",
_ui->checkBox_odom_sensor_use_as_gt->isChecked()).toBool());
2778 settings.endGroup();
2780 settings.beginGroup(
"UsbCam");
2781 _ui->spinBox_usbcam_streamWidth->setValue(settings.value(
"width",
_ui->spinBox_usbcam_streamWidth->value()).toInt());
2782 _ui->spinBox_usbcam_streamHeight->setValue(settings.value(
"height",
_ui->spinBox_usbcam_streamHeight->value()).toInt());
2783 settings.endGroup();
2785 settings.beginGroup(
"Video");
2786 _ui->source_video_lineEdit_path->setText(settings.value(
"path",
_ui->source_video_lineEdit_path->text()).toString());
2787 settings.endGroup();
2789 settings.beginGroup(
"IMU");
2790 _ui->comboBox_imuFilter_strategy->setCurrentIndex(settings.value(
"strategy",
_ui->comboBox_imuFilter_strategy->currentIndex()).toInt());
2791 _ui->doubleSpinBox_imuFilterMadgwickGain->setValue(settings.value(
"madgwick_gain",
_ui->doubleSpinBox_imuFilterMadgwickGain->value()).toDouble());
2792 _ui->doubleSpinBox_imuFilterMadgwickZeta->setValue(settings.value(
"madgwick_zeta",
_ui->doubleSpinBox_imuFilterMadgwickZeta->value()).toDouble());
2793 _ui->doubleSpinBox_imuFilterComplementaryGainAcc->setValue(settings.value(
"complementary_gain_acc",
_ui->doubleSpinBox_imuFilterComplementaryGainAcc->value()).toDouble());
2794 _ui->doubleSpinBox_imuFilterComplementaryBiasAlpha->setValue(settings.value(
"complementary_bias_alpha",
_ui->doubleSpinBox_imuFilterComplementaryBiasAlpha->value()).toDouble());
2795 _ui->checkBox_imuFilterComplementaryDoAdaptiveGain->setChecked(settings.value(
"complementary_adaptive_gain",
_ui->checkBox_imuFilterComplementaryDoAdaptiveGain->isChecked()).toBool());
2796 _ui->checkBox_imuFilterComplementaryDoBiasEstimation->setChecked(settings.value(
"complementary_biais_estimation",
_ui->checkBox_imuFilterComplementaryDoBiasEstimation->isChecked()).toBool());
2797 _ui->checkBox_imuFilter_baseFrameConversion->setChecked(settings.value(
"base_frame_conversion",
_ui->checkBox_imuFilter_baseFrameConversion->isChecked()).toBool());
2798 _ui->checkbox_publishInterIMU->setChecked(settings.value(
"publish_inter_imu",
_ui->checkbox_publishInterIMU->isChecked()).toBool());
2799 settings.endGroup();
2801 settings.beginGroup(
"Scan");
2802 _ui->comboBox_lidar_src->setCurrentIndex(settings.value(
"source",
_ui->comboBox_lidar_src->currentIndex()).toInt());
2803 _ui->checkBox_source_scanDeskewing->setChecked(settings.value(
"deskewing",
_ui->checkBox_source_scanDeskewing->isChecked()).toBool());
2804 _ui->checkBox_source_scanFromDepth->setChecked(settings.value(
"fromDepth",
_ui->checkBox_source_scanFromDepth->isChecked()).toBool());
2805 _ui->spinBox_source_scanDownsampleStep->setValue(settings.value(
"downsampleStep",
_ui->spinBox_source_scanDownsampleStep->value()).toInt());
2806 _ui->doubleSpinBox_source_scanRangeMin->setValue(settings.value(
"rangeMin",
_ui->doubleSpinBox_source_scanRangeMin->value()).toDouble());
2807 _ui->doubleSpinBox_source_scanRangeMax->setValue(settings.value(
"rangeMax",
_ui->doubleSpinBox_source_scanRangeMax->value()).toDouble());
2808 _ui->doubleSpinBox_source_scanVoxelSize->setValue(settings.value(
"voxelSize",
_ui->doubleSpinBox_source_scanVoxelSize->value()).toDouble());
2809 _ui->spinBox_source_scanNormalsK->setValue(settings.value(
"normalsK",
_ui->spinBox_source_scanNormalsK->value()).toInt());
2810 _ui->doubleSpinBox_source_scanNormalsRadius->setValue(settings.value(
"normalsRadius",
_ui->doubleSpinBox_source_scanNormalsRadius->value()).toDouble());
2811 _ui->doubleSpinBox_source_scanNormalsForceGroundUp->setValue(settings.value(
"normalsUpF",
_ui->doubleSpinBox_source_scanNormalsForceGroundUp->value()).toDouble());
2812 settings.endGroup();
2814 settings.beginGroup(
"DepthFromScan");
2815 _ui->groupBox_depthFromScan->setChecked(settings.value(
"depthFromScan",
_ui->groupBox_depthFromScan->isChecked()).toBool());
2816 _ui->groupBox_depthFromScan_fillHoles->setChecked(settings.value(
"depthFromScanFillHoles",
_ui->groupBox_depthFromScan_fillHoles->isChecked()).toBool());
2817 _ui->radioButton_depthFromScan_vertical->setChecked(settings.value(
"depthFromScanVertical",
_ui->radioButton_depthFromScan_vertical->isChecked()).toBool());
2818 _ui->radioButton_depthFromScan_horizontal->setChecked(settings.value(
"depthFromScanHorizontal",
_ui->radioButton_depthFromScan_horizontal->isChecked()).toBool());
2819 _ui->checkBox_depthFromScan_fillBorders->setChecked(settings.value(
"depthFromScanFillBorders",
_ui->checkBox_depthFromScan_fillBorders->isChecked()).toBool());
2820 settings.endGroup();
2822 settings.beginGroup(
"Database");
2823 _ui->source_database_lineEdit_path->setText(settings.value(
"path",
_ui->source_database_lineEdit_path->text()).toString());
2824 _ui->source_checkBox_ignoreOdometry->setChecked(settings.value(
"ignoreOdometry",
_ui->source_checkBox_ignoreOdometry->isChecked()).toBool());
2825 _ui->source_checkBox_ignoreGoalDelay->setChecked(settings.value(
"ignoreGoalDelay",
_ui->source_checkBox_ignoreGoalDelay->isChecked()).toBool());
2826 _ui->source_checkBox_ignoreGoals->setChecked(settings.value(
"ignoreGoals",
_ui->source_checkBox_ignoreGoals->isChecked()).toBool());
2827 _ui->source_checkBox_ignoreLandmarks->setChecked(settings.value(
"ignoreLandmarks",
_ui->source_checkBox_ignoreLandmarks->isChecked()).toBool());
2828 _ui->source_checkBox_ignoreFeatures->setChecked(settings.value(
"ignoreFeatures",
_ui->source_checkBox_ignoreFeatures->isChecked()).toBool());
2829 _ui->source_checkBox_ignorePriors->setChecked(settings.value(
"ignorePriors",
_ui->source_checkBox_ignorePriors->isChecked()).toBool());
2830 _ui->source_spinBox_databaseStartId->setValue(settings.value(
"startId",
_ui->source_spinBox_databaseStartId->value()).toInt());
2831 _ui->source_spinBox_databaseStopId->setValue(settings.value(
"stopId",
_ui->source_spinBox_databaseStopId->value()).toInt());
2832 _ui->source_spinBox_database_cameraIndex->setValue(settings.value(
"cameraIndex",
_ui->source_spinBox_database_cameraIndex->value()).toInt());
2833 _ui->source_checkBox_useDbStamps->setChecked(settings.value(
"useDatabaseStamps",
_ui->source_checkBox_useDbStamps->isChecked()).toBool());
2834 settings.endGroup();
2836 settings.endGroup();
2838 settings.beginGroup(
"Lidar");
2840 settings.beginGroup(
"VLP16");
2841 _ui->lineEdit_lidar_local_transform->setText(settings.value(
"localTransform",
_ui->lineEdit_lidar_local_transform->text()).toString());
2842 _ui->lineEdit_vlp16_pcap_path->setText(settings.value(
"pcapPath",
_ui->lineEdit_vlp16_pcap_path->text()).toString());
2843 _ui->spinBox_vlp16_ip1->setValue(settings.value(
"ip1",
_ui->spinBox_vlp16_ip1->value()).toInt());
2844 _ui->spinBox_vlp16_ip2->setValue(settings.value(
"ip2",
_ui->spinBox_vlp16_ip2->value()).toInt());
2845 _ui->spinBox_vlp16_ip3->setValue(settings.value(
"ip3",
_ui->spinBox_vlp16_ip3->value()).toInt());
2846 _ui->spinBox_vlp16_ip4->setValue(settings.value(
"ip4",
_ui->spinBox_vlp16_ip4->value()).toInt());
2847 _ui->spinBox_vlp16_port->setValue(settings.value(
"port",
_ui->spinBox_vlp16_port->value()).toInt());
2848 _ui->checkBox_vlp16_organized->setChecked(settings.value(
"organized",
_ui->checkBox_vlp16_organized->isChecked()).toBool());
2849 _ui->checkBox_vlp16_hostTime->setChecked(settings.value(
"hostTime",
_ui->checkBox_vlp16_hostTime->isChecked()).toBool());
2850 _ui->checkBox_vlp16_stamp_last->setChecked(settings.value(
"stampLast",
_ui->checkBox_vlp16_stamp_last->isChecked()).toBool());
2851 settings.endGroup();
2853 settings.endGroup();
2867 if(!filePath.isEmpty())
2874 if(!QFile::exists(
path))
2876 QMessageBox::information(
this, tr(
"INI file doesn't exist..."), tr(
"The configuration file \"%1\" does not exist, it will be created with default parameters.").
arg(
path));
2882 for(rtabmap::ParametersMap::const_iterator
iter = parameters.begin();
iter!=parameters.end(); ++
iter)
2885 if(
iter->first.compare(Parameters::kRtabmapWorkingDirectory()) == 0)
2889 UWARN(
"Reading config: Working directory is empty. Keeping old one (\"%s\").",
2899 UWARN(
"Reading config: Not existing working directory \"%s\". Keeping old one (\"%s\").",
2901 this->getWorkingDirectory().toStdString().c_str());
2907 UWARN(
"Reading config: Not existing working directory \"%s\". Using default one (\"%s\").",
2909 defaultWorkingDir.c_str());
2910 value = defaultWorkingDir;
2916 if(
iter->first.compare(Parameters::kIcpStrategy()) == 0)
2918 if(
value.compare(
"true") == 0)
2922 else if(
value.compare(
"false") == 0)
2932 if(parameters.find(Parameters::kRtabmapWorkingDirectory()) == parameters.end())
2936 QMessageBox::information(
this,
2937 tr(
"Working directory"),
2938 tr(
"RTAB-Map needs a working directory to put the database.\n\n"
2939 "By default, the directory \"%1\" is used.\n\n"
2940 "The working directory can be changed any time in the "
2952 QString
path = QFileDialog::getSaveFileName(
this, tr(
"Save settings..."), this->
getWorkingDirectory()+QDir::separator()+
"config.ini",
"*.ini");
2965 int button = QMessageBox::warning(
this,
2966 tr(
"Reset settings..."),
2967 tr(
"This will reset all settings. Restore all settings to default without saving them first?"),
2968 QMessageBox::Cancel | QMessageBox::Yes | QMessageBox::Save,
2969 QMessageBox::Cancel);
2970 if(button == QMessageBox::Yes ||
2982 if(!presetHexHeader.empty())
2990 parameters.erase(Parameters::kRtabmapWorkingDirectory());
2991 for(ParametersMap::iterator
iter=parameters.begin();
iter!=parameters.end(); ++
iter)
2999 if(sender() ==
_ui->pushButton_presets_camera_tof_icp)
3003 else if(sender() ==
_ui->pushButton_presets_lidar_3d_icp)
3009 UERROR(
"Unknown sender!");
3012 QMessageBox::information(
this,
3014 tr(
"Loaded \"%1\" preset!").
arg(((QPushButton*)sender())->
text()),
3040 bool different =
true;
3064 if(!filePath.isEmpty())
3068 QSettings settings(
path, QSettings::IniFormat);
3069 settings.beginGroup(
"Gui");
3071 settings.beginGroup(
"General");
3072 settings.remove(
"");
3073 settings.setValue(
"imagesKept",
_ui->general_checkBox_imagesKept->isChecked());
3074 settings.setValue(
"missingRepublished",
_ui->general_checkBox_missing_cache_republished->isChecked());
3075 settings.setValue(
"cloudsKept",
_ui->general_checkBox_cloudsKept->isChecked());
3076 settings.setValue(
"loggerLevel",
_ui->comboBox_loggerLevel->currentIndex());
3077 settings.setValue(
"loggerEventLevel",
_ui->comboBox_loggerEventLevel->currentIndex());
3078 settings.setValue(
"loggerPauseLevel",
_ui->comboBox_loggerPauseLevel->currentIndex());
3079 settings.setValue(
"loggerType",
_ui->comboBox_loggerType->currentIndex());
3080 settings.setValue(
"loggerPrintTime",
_ui->checkBox_logger_printTime->isChecked());
3081 settings.setValue(
"loggerPrintThreadId",
_ui->checkBox_logger_printThreadId->isChecked());
3082 settings.setValue(
"verticalLayoutUsed",
_ui->checkBox_verticalLayoutUsed->isChecked());
3083 settings.setValue(
"imageRejectedShown",
_ui->checkBox_imageRejectedShown->isChecked());
3084 settings.setValue(
"imageHighestHypShown",
_ui->checkBox_imageHighestHypShown->isChecked());
3085 settings.setValue(
"beep",
_ui->checkBox_beep->isChecked());
3086 settings.setValue(
"figure_time",
_ui->checkBox_stamps->isChecked());
3087 settings.setValue(
"figure_cache",
_ui->checkBox_cacheStatistics->isChecked());
3088 settings.setValue(
"notifyNewGlobalPath",
_ui->checkBox_notifyWhenNewGlobalPathIsReceived->isChecked());
3089 settings.setValue(
"odomQualityThr",
_ui->spinBox_odomQualityWarnThr->value());
3090 settings.setValue(
"odomOnlyInliersShown",
_ui->checkBox_odom_onlyInliersShown->isChecked());
3091 settings.setValue(
"posteriorGraphView",
_ui->radioButton_posteriorGraphView->isChecked());
3092 settings.setValue(
"wordsGraphView",
_ui->radioButton_wordsGraphView->isChecked());
3093 settings.setValue(
"localizationsGraphView",
_ui->radioButton_localizationsGraphView->isChecked());
3094 settings.setValue(
"localizationsGraphViewOdomCache",
_ui->radioButton_localizationsGraphViewOdomCache->isChecked());
3095 settings.setValue(
"nochangeGraphView",
_ui->radioButton_nochangeGraphView->isChecked());
3096 settings.setValue(
"odomDisabled",
_ui->checkbox_odomDisabled->isChecked());
3097 settings.setValue(
"odomRegistration",
_ui->odom_registration->currentIndex());
3098 settings.setValue(
"odomF2MGravitySigma",
_ui->odom_f2m_gravitySigma->value());
3099 settings.setValue(
"gtAlign",
_ui->checkbox_groundTruthAlign->isChecked());
3101 for(
int i=0;
i<2; ++
i)
3126 settings.setValue(
"cloudVoxel",
_ui->doubleSpinBox_voxel->value());
3127 settings.setValue(
"cloudNoiseRadius",
_ui->doubleSpinBox_noiseRadius->value());
3128 settings.setValue(
"cloudNoiseMinNeighbors",
_ui->spinBox_noiseMinNeighbors->value());
3129 settings.setValue(
"cloudCeilingHeight",
_ui->doubleSpinBox_ceilingFilterHeight->value());
3130 settings.setValue(
"cloudFloorHeight",
_ui->doubleSpinBox_floorFilterHeight->value());
3131 settings.setValue(
"normalKSearch",
_ui->spinBox_normalKSearch->value());
3132 settings.setValue(
"normalRadiusSearch",
_ui->doubleSpinBox_normalRadiusSearch->value());
3133 settings.setValue(
"scanCeilingHeight",
_ui->doubleSpinBox_ceilingFilterHeight_scan->value());
3134 settings.setValue(
"scanFloorHeight",
_ui->doubleSpinBox_floorFilterHeight_scan->value());
3135 settings.setValue(
"scanNormalKSearch",
_ui->spinBox_normalKSearch_scan->value());
3136 settings.setValue(
"scanNormalRadiusSearch",
_ui->doubleSpinBox_normalRadiusSearch_scan->value());
3138 settings.setValue(
"showGraphs",
_ui->checkBox_showGraphs->isChecked());
3139 settings.setValue(
"showLabels",
_ui->checkBox_showLabels->isChecked());
3140 settings.setValue(
"showFrames",
_ui->checkBox_showFrames->isChecked());
3141 settings.setValue(
"showLandmarks",
_ui->checkBox_showLandmarks->isChecked());
3142 settings.setValue(
"landmarkSize",
_ui->doubleSpinBox_landmarkSize->value());
3143 settings.setValue(
"showIMUGravity",
_ui->checkBox_showIMUGravity->isChecked());
3144 settings.setValue(
"showIMUAcc",
_ui->checkBox_showIMUAcc->isChecked());
3147 settings.setValue(
"noFiltering",
_ui->radioButton_noFiltering->isChecked());
3148 settings.setValue(
"cloudFiltering",
_ui->radioButton_nodeFiltering->isChecked());
3149 settings.setValue(
"cloudFilteringRadius",
_ui->doubleSpinBox_cloudFilterRadius->value());
3150 settings.setValue(
"cloudFilteringAngle",
_ui->doubleSpinBox_cloudFilterAngle->value());
3151 settings.setValue(
"subtractFiltering",
_ui->radioButton_subtractFiltering->isChecked());
3152 settings.setValue(
"subtractFilteringMinPts",
_ui->spinBox_subtractFilteringMinPts->value());
3153 settings.setValue(
"subtractFilteringRadius",
_ui->doubleSpinBox_subtractFilteringRadius->value());
3154 settings.setValue(
"subtractFilteringAngle",
_ui->doubleSpinBox_subtractFilteringAngle->value());
3156 settings.setValue(
"gridUIResolution",
_ui->doubleSpinBox_map_resolution->value());
3157 settings.setValue(
"gridMapShown",
_ui->checkBox_map_shown->isChecked());
3158 settings.setValue(
"gridMapOpacity",
_ui->doubleSpinBox_map_opacity->value());
3159 settings.setValue(
"elevationMapShown",
_ui->checkBox_elevation_shown->checkState());
3162 settings.setValue(
"octomap",
_ui->groupBox_octomap->isChecked());
3163 settings.setValue(
"octomap_depth",
_ui->spinBox_octomap_treeDepth->value());
3164 settings.setValue(
"octomap_2dgrid",
_ui->checkBox_octomap_2dgrid->isChecked());
3165 settings.setValue(
"octomap_3dmap",
_ui->checkBox_octomap_show3dMap->isChecked());
3166 settings.setValue(
"octomap_rendering_type",
_ui->comboBox_octomap_renderingType->currentIndex());
3167 settings.setValue(
"octomap_point_size",
_ui->spinBox_octomap_pointSize->value());
3170 settings.setValue(
"meshing",
_ui->groupBox_organized->isChecked());
3171 settings.setValue(
"meshing_angle",
_ui->doubleSpinBox_mesh_angleTolerance->value());
3172 settings.setValue(
"meshing_quad",
_ui->checkBox_mesh_quad->isChecked());
3173 settings.setValue(
"meshing_texture",
_ui->checkBox_mesh_texture->isChecked());
3174 settings.setValue(
"meshing_triangle_size",
_ui->spinBox_mesh_triangleSize->value());
3176 settings.endGroup();
3178 settings.endGroup();
3184 if(!filePath.isEmpty())
3188 QSettings settings(
path, QSettings::IniFormat);
3190 settings.beginGroup(
"Camera");
3191 settings.remove(
"");
3192 settings.setValue(
"imgRate",
_ui->general_doubleSpinBox_imgRate->value());
3193 settings.setValue(
"mirroring",
_ui->source_mirroring->isChecked());
3194 settings.setValue(
"calibrationName",
_ui->lineEdit_calibrationFile->text());
3195 settings.setValue(
"type",
_ui->comboBox_sourceType->currentIndex());
3196 settings.setValue(
"device",
_ui->lineEdit_sourceDevice->text());
3197 settings.setValue(
"localTransform",
_ui->lineEdit_sourceLocalTransform->text());
3198 settings.setValue(
"imageDecimation",
_ui->spinBox_source_imageDecimation->value());
3199 settings.setValue(
"histogramMethod",
_ui->comboBox_source_histogramMethod->currentIndex());
3200 settings.setValue(
"featureDetection",
_ui->checkbox_source_feature_detection->isChecked());
3202 settings.beginGroup(
"rgbd");
3203 settings.setValue(
"driver",
_ui->comboBox_cameraRGBD->currentIndex());
3204 settings.setValue(
"rgbdColorOnly",
_ui->checkbox_rgbd_colorOnly->isChecked());
3205 settings.setValue(
"distortion_model",
_ui->lineEdit_source_distortionModel->text());
3206 settings.setValue(
"bilateral",
_ui->groupBox_bilateral->isChecked());
3207 settings.setValue(
"bilateral_sigma_s",
_ui->doubleSpinBox_bilateral_sigmaS->value());
3208 settings.setValue(
"bilateral_sigma_r",
_ui->doubleSpinBox_bilateral_sigmaR->value());
3209 settings.endGroup();
3211 settings.beginGroup(
"stereo");
3212 settings.setValue(
"driver",
_ui->comboBox_cameraStereo->currentIndex());
3213 settings.setValue(
"depthGenerated",
_ui->checkbox_stereo_depthGenerated->isChecked());
3214 settings.setValue(
"exposureCompensation",
_ui->checkBox_stereo_exposureCompensation->isChecked());
3215 settings.endGroup();
3217 settings.beginGroup(
"rgb");
3218 settings.setValue(
"driver",
_ui->source_comboBox_image_type->currentIndex());
3219 settings.setValue(
"rectify",
_ui->checkBox_rgb_rectify->isChecked());
3220 settings.endGroup();
3222 settings.beginGroup(
"Openni");
3223 settings.setValue(
"oniPath",
_ui->lineEdit_openniOniPath->text());
3224 settings.endGroup();
3226 settings.beginGroup(
"Openni2");
3227 settings.setValue(
"autoWhiteBalance",
_ui->openni2_autoWhiteBalance->isChecked());
3228 settings.setValue(
"autoExposure",
_ui->openni2_autoExposure->isChecked());
3229 settings.setValue(
"exposure",
_ui->openni2_exposure->value());
3230 settings.setValue(
"gain",
_ui->openni2_gain->value());
3231 settings.setValue(
"mirroring",
_ui->openni2_mirroring->isChecked());
3232 settings.setValue(
"stampsIdsUsed",
_ui->openni2_stampsIdsUsed->isChecked());
3233 settings.setValue(
"oniPath",
_ui->lineEdit_openni2OniPath->text());
3234 settings.setValue(
"hshift",
_ui->openni2_hshift->value());
3235 settings.setValue(
"vshift",
_ui->openni2_vshift->value());
3236 settings.setValue(
"depthDecimation",
_ui->openni2_depth_decimation->value());
3237 settings.endGroup();
3239 settings.beginGroup(
"Freenect2");
3240 settings.setValue(
"format",
_ui->comboBox_freenect2Format->currentIndex());
3241 settings.setValue(
"minDepth",
_ui->doubleSpinBox_freenect2MinDepth->value());
3242 settings.setValue(
"maxDepth",
_ui->doubleSpinBox_freenect2MaxDepth->value());
3243 settings.setValue(
"bilateralFiltering",
_ui->checkBox_freenect2BilateralFiltering->isChecked());
3244 settings.setValue(
"edgeAwareFiltering",
_ui->checkBox_freenect2EdgeAwareFiltering->isChecked());
3245 settings.setValue(
"noiseFiltering",
_ui->checkBox_freenect2NoiseFiltering->isChecked());
3246 settings.setValue(
"pipeline",
_ui->lineEdit_freenect2Pipeline->text());
3247 settings.endGroup();
3249 settings.beginGroup(
"K4W2");
3250 settings.setValue(
"format",
_ui->comboBox_k4w2Format->currentIndex());
3251 settings.endGroup();
3253 settings.beginGroup(
"K4A");
3254 settings.setValue(
"rgb_resolution",
_ui->comboBox_k4a_rgb_resolution->currentIndex());
3255 settings.setValue(
"framerate",
_ui->comboBox_k4a_framerate->currentIndex());
3256 settings.setValue(
"depth_resolution",
_ui->comboBox_k4a_depth_resolution->currentIndex());
3257 settings.setValue(
"ir",
_ui->checkbox_k4a_irDepth->isChecked());
3258 settings.setValue(
"mkvPath",
_ui->lineEdit_k4a_mkv->text());
3259 settings.setValue(
"useMkvStamps",
_ui->source_checkBox_useMKVStamps->isChecked());
3260 settings.endGroup();
3262 settings.beginGroup(
"RealSense");
3263 settings.setValue(
"presetRGB",
_ui->comboBox_realsensePresetRGB->currentIndex());
3264 settings.setValue(
"presetDepth",
_ui->comboBox_realsensePresetDepth->currentIndex());
3265 settings.setValue(
"odom",
_ui->checkbox_realsenseOdom->isChecked());
3266 settings.setValue(
"depthScaled",
_ui->checkbox_realsenseDepthScaledToRGBSize->isChecked());
3267 settings.setValue(
"rgbSource",
_ui->comboBox_realsenseRGBSource->currentIndex());
3268 settings.endGroup();
3270 settings.beginGroup(
"RealSense2");
3271 settings.setValue(
"emitter",
_ui->checkbox_rs2_emitter->isChecked());
3272 settings.setValue(
"ir",
_ui->checkbox_rs2_irMode->isChecked());
3273 settings.setValue(
"irdepth",
_ui->checkbox_rs2_irDepth->isChecked());
3274 settings.setValue(
"width",
_ui->spinBox_rs2_width->value());
3275 settings.setValue(
"height",
_ui->spinBox_rs2_height->value());
3276 settings.setValue(
"rate",
_ui->spinBox_rs2_rate->value());
3277 settings.setValue(
"width_depth",
_ui->spinBox_rs2_width_depth->value());
3278 settings.setValue(
"height_depth",
_ui->spinBox_rs2_height_depth->value());
3279 settings.setValue(
"rate_depth",
_ui->spinBox_rs2_rate_depth->value());
3280 settings.setValue(
"global_time_sync",
_ui->checkbox_rs2_globalTimeStync->isChecked());
3281 settings.setValue(
"json_preset",
_ui->lineEdit_rs2_jsonFile->text());
3282 settings.endGroup();
3284 settings.beginGroup(
"RGBDImages");
3285 settings.setValue(
"path_rgb",
_ui->lineEdit_cameraRGBDImages_path_rgb->text());
3286 settings.setValue(
"path_depth",
_ui->lineEdit_cameraRGBDImages_path_depth->text());
3287 settings.setValue(
"scale",
_ui->doubleSpinBox_cameraRGBDImages_scale->value());
3288 settings.setValue(
"start_index",
_ui->spinBox_cameraRGBDImages_startIndex->value());
3289 settings.setValue(
"max_frames",
_ui->spinBox_cameraRGBDImages_maxFrames->value());
3290 settings.endGroup();
3292 settings.beginGroup(
"StereoImages");
3293 settings.setValue(
"path_left",
_ui->lineEdit_cameraStereoImages_path_left->text());
3294 settings.setValue(
"path_right",
_ui->lineEdit_cameraStereoImages_path_right->text());
3295 settings.setValue(
"rectify",
_ui->checkBox_stereo_rectify->isChecked());
3296 settings.setValue(
"start_index",
_ui->spinBox_cameraStereoImages_startIndex->value());
3297 settings.setValue(
"max_frames",
_ui->spinBox_cameraStereoImages_maxFrames->value());
3298 settings.endGroup();
3300 settings.beginGroup(
"StereoVideo");
3301 settings.setValue(
"path",
_ui->lineEdit_cameraStereoVideo_path->text());
3302 settings.setValue(
"path2",
_ui->lineEdit_cameraStereoVideo_path_2->text());
3303 settings.setValue(
"device2",
_ui->spinBox_stereo_right_device->value());
3304 settings.setValue(
"width",
_ui->spinBox_stereousbcam_streamWidth->value());
3305 settings.setValue(
"height",
_ui->spinBox_stereousbcam_streamHeight->value());
3306 settings.endGroup();
3308 settings.beginGroup(
"StereoZed");
3309 settings.setValue(
"resolution",
_ui->comboBox_stereoZed_resolution->currentIndex());
3310 settings.setValue(
"quality",
_ui->comboBox_stereoZed_quality->currentIndex());
3311 settings.setValue(
"self_calibration",
_ui->checkbox_stereoZed_selfCalibration->isChecked());
3312 settings.setValue(
"sensing_mode",
_ui->comboBox_stereoZed_sensingMode->currentIndex());
3313 settings.setValue(
"confidence_thr",
_ui->spinBox_stereoZed_confidenceThr->value());
3314 settings.setValue(
"textureness_confidence_thr",
_ui->spinBox_stereoZed_texturenessConfidenceThr->value());
3315 settings.setValue(
"svo_path",
_ui->lineEdit_zedSvoPath->text());
3316 settings.endGroup();
3318 settings.beginGroup(
"MyntEye");
3319 settings.setValue(
"rectify",
_ui->checkbox_stereoMyntEye_rectify->isChecked());
3320 settings.setValue(
"depth",
_ui->checkbox_stereoMyntEye_depth->isChecked());
3321 settings.setValue(
"auto_exposure",
_ui->checkbox_stereoMyntEye_autoExposure->isChecked());
3322 settings.setValue(
"gain",
_ui->spinBox_stereoMyntEye_gain->value());
3323 settings.setValue(
"brightness",
_ui->spinBox_stereoMyntEye_brightness->value());
3324 settings.setValue(
"contrast",
_ui->spinBox_stereoMyntEye_contrast->value());
3325 settings.setValue(
"ir_control",
_ui->spinBox_stereoMyntEye_irControl->value());
3326 settings.endGroup();
3328 settings.beginGroup(
"DepthAI");
3329 settings.setValue(
"resolution",
_ui->comboBox_depthai_resolution->currentIndex());
3330 settings.setValue(
"output_mode",
_ui->comboBox_depthai_output_mode->currentIndex());
3331 settings.setValue(
"conf_threshold",
_ui->spinBox_depthai_conf_threshold->value());
3332 settings.setValue(
"lrc_threshold",
_ui->spinBox_depthai_lrc_threshold->value());
3333 settings.setValue(
"extended_disparity",
_ui->checkBox_depthai_extended_disparity->isChecked());
3334 settings.setValue(
"subpixel_fractional_bits",
_ui->comboBox_depthai_subpixel_fractional_bits->currentIndex());
3335 settings.setValue(
"companding",
_ui->comboBox_depthai_disparity_companding->currentIndex());
3336 settings.setValue(
"use_spec_translation",
_ui->checkBox_depthai_use_spec_translation->isChecked());
3337 settings.setValue(
"alpha_scaling",
_ui->doubleSpinBox_depthai_alpha_scaling->value());
3338 settings.setValue(
"imu_published",
_ui->checkBox_depthai_imu_published->isChecked());
3339 settings.setValue(
"dot_intensity",
_ui->doubleSpinBox_depthai_dot_intensity->value());
3340 settings.setValue(
"flood_intensity",
_ui->doubleSpinBox_depthai_flood_intensity->value());
3341 settings.setValue(
"detect_features",
_ui->comboBox_depthai_detect_features->currentIndex());
3342 settings.setValue(
"blob_path",
_ui->lineEdit_depthai_blob_path->text());
3343 settings.endGroup();
3345 settings.beginGroup(
"Images");
3346 settings.setValue(
"path",
_ui->source_images_lineEdit_path->text());
3347 settings.setValue(
"startPos",
_ui->source_images_spinBox_startPos->value());
3348 settings.setValue(
"maxFrames",
_ui->source_images_spinBox_maxFrames->value());
3349 settings.setValue(
"bayerMode",
_ui->comboBox_cameraImages_bayerMode->currentIndex());
3350 settings.setValue(
"config_each_frame",
_ui->checkBox_cameraImages_configForEachFrame->isChecked());
3351 settings.setValue(
"filenames_as_stamps",
_ui->checkBox_cameraImages_timestamps->isChecked());
3352 settings.setValue(
"sync_stamps",
_ui->checkBox_cameraImages_syncTimeStamps->isChecked());
3353 settings.setValue(
"stamps",
_ui->lineEdit_cameraImages_timestamps->text());
3354 settings.setValue(
"path_scans",
_ui->lineEdit_cameraImages_path_scans->text());
3355 settings.setValue(
"scan_transform",
_ui->lineEdit_cameraImages_laser_transform->text());
3356 settings.setValue(
"scan_max_pts",
_ui->spinBox_cameraImages_max_scan_pts->value());
3357 settings.setValue(
"odom_path",
_ui->lineEdit_cameraImages_odom->text());
3358 settings.setValue(
"odom_format",
_ui->comboBox_cameraImages_odomFormat->currentIndex());
3359 settings.setValue(
"gt_path",
_ui->lineEdit_cameraImages_gt->text());
3360 settings.setValue(
"gt_format",
_ui->comboBox_cameraImages_gtFormat->currentIndex());
3361 settings.setValue(
"max_pose_time_diff",
_ui->doubleSpinBox_maxPoseTimeDiff->value());
3362 settings.setValue(
"imu_path",
_ui->lineEdit_cameraImages_path_imu->text());
3363 settings.setValue(
"imu_local_transform",
_ui->lineEdit_cameraImages_imu_transform->text());
3364 settings.setValue(
"imu_rate",
_ui->spinBox_cameraImages_max_imu_rate->value());
3365 settings.endGroup();
3367 settings.beginGroup(
"OdomSensor");
3368 settings.setValue(
"odom_sensor",
_ui->comboBox_odom_sensor->currentIndex());
3369 settings.setValue(
"odom_sensor_extrinsics",
_ui->lineEdit_odom_sensor_extrinsics->text());
3370 settings.setValue(
"odom_sensor_calibration_path",
_ui->lineEdit_odom_sensor_path_calibration->text());
3371 settings.setValue(
"odom_sensor_device",
_ui->lineEdit_odomSourceDevice->text());
3372 settings.setValue(
"odom_sensor_offset_time",
_ui->doubleSpinBox_odom_sensor_time_offset->value());
3373 settings.setValue(
"odom_sensor_scale_factor",
_ui->doubleSpinBox_odom_sensor_scale_factor->value());
3374 settings.setValue(
"odom_sensor_wait_time",
_ui->doubleSpinBox_odom_sensor_wait_time->value());
3375 settings.setValue(
"odom_sensor_odom_as_gt",
_ui->checkBox_odom_sensor_use_as_gt->isChecked());
3376 settings.endGroup();
3378 settings.beginGroup(
"UsbCam");
3379 settings.setValue(
"width",
_ui->spinBox_usbcam_streamWidth->value());
3380 settings.setValue(
"height",
_ui->spinBox_usbcam_streamHeight->value());
3381 settings.endGroup();
3383 settings.beginGroup(
"Video");
3384 settings.setValue(
"path",
_ui->source_video_lineEdit_path->text());
3385 settings.endGroup();
3387 settings.beginGroup(
"IMU");
3388 settings.setValue(
"strategy",
_ui->comboBox_imuFilter_strategy->currentIndex());
3389 settings.setValue(
"madgwick_gain",
_ui->doubleSpinBox_imuFilterMadgwickGain->value());
3390 settings.setValue(
"madgwick_zeta",
_ui->doubleSpinBox_imuFilterMadgwickZeta->value());
3391 settings.setValue(
"complementary_gain_acc",
_ui->doubleSpinBox_imuFilterComplementaryGainAcc->value());
3392 settings.setValue(
"complementary_bias_alpha",
_ui->doubleSpinBox_imuFilterComplementaryBiasAlpha->value());
3393 settings.setValue(
"complementary_adaptive_gain",
_ui->checkBox_imuFilterComplementaryDoAdaptiveGain->isChecked());
3394 settings.setValue(
"complementary_biais_estimation",
_ui->checkBox_imuFilterComplementaryDoBiasEstimation->isChecked());
3395 settings.setValue(
"base_frame_conversion",
_ui->checkBox_imuFilter_baseFrameConversion->isChecked());
3396 settings.setValue(
"publish_inter_imu",
_ui->checkbox_publishInterIMU->isChecked());
3397 settings.endGroup();
3399 settings.beginGroup(
"Scan");
3400 settings.setValue(
"source",
_ui->comboBox_lidar_src->currentIndex());
3401 settings.setValue(
"deskewing",
_ui->checkBox_source_scanDeskewing->isChecked());
3402 settings.setValue(
"fromDepth",
_ui->checkBox_source_scanFromDepth->isChecked());
3403 settings.setValue(
"downsampleStep",
_ui->spinBox_source_scanDownsampleStep->value());
3404 settings.setValue(
"rangeMin",
_ui->doubleSpinBox_source_scanRangeMin->value());
3405 settings.setValue(
"rangeMax",
_ui->doubleSpinBox_source_scanRangeMax->value());
3406 settings.setValue(
"voxelSize",
_ui->doubleSpinBox_source_scanVoxelSize->value());
3407 settings.setValue(
"normalsK",
_ui->spinBox_source_scanNormalsK->value());
3408 settings.setValue(
"normalsRadius",
_ui->doubleSpinBox_source_scanNormalsRadius->value());
3409 settings.setValue(
"normalsUpF",
_ui->doubleSpinBox_source_scanNormalsForceGroundUp->value());
3410 settings.endGroup();
3412 settings.beginGroup(
"DepthFromScan");
3413 settings.setValue(
"depthFromScan",
_ui->groupBox_depthFromScan->isChecked());
3414 settings.setValue(
"depthFromScanFillHoles",
_ui->groupBox_depthFromScan_fillHoles->isChecked());
3415 settings.setValue(
"depthFromScanVertical",
_ui->radioButton_depthFromScan_vertical->isChecked());
3416 settings.setValue(
"depthFromScanHorizontal",
_ui->radioButton_depthFromScan_horizontal->isChecked());
3417 settings.setValue(
"depthFromScanFillBorders",
_ui->checkBox_depthFromScan_fillBorders->isChecked());
3418 settings.endGroup();
3420 settings.beginGroup(
"Database");
3421 settings.setValue(
"path",
_ui->source_database_lineEdit_path->text());
3422 settings.setValue(
"ignoreOdometry",
_ui->source_checkBox_ignoreOdometry->isChecked());
3423 settings.setValue(
"ignoreGoalDelay",
_ui->source_checkBox_ignoreGoalDelay->isChecked());
3424 settings.setValue(
"ignoreGoals",
_ui->source_checkBox_ignoreGoals->isChecked());
3425 settings.setValue(
"ignoreLandmarks",
_ui->source_checkBox_ignoreLandmarks->isChecked());
3426 settings.setValue(
"ignoreFeatures",
_ui->source_checkBox_ignoreFeatures->isChecked());
3427 settings.setValue(
"ignorePriors",
_ui->source_checkBox_ignorePriors->isChecked());
3428 settings.setValue(
"startId",
_ui->source_spinBox_databaseStartId->value());
3429 settings.setValue(
"stopId",
_ui->source_spinBox_databaseStopId->value());
3430 settings.setValue(
"cameraIndex",
_ui->source_spinBox_database_cameraIndex->value());
3431 settings.setValue(
"useDatabaseStamps",
_ui->source_checkBox_useDbStamps->isChecked());
3432 settings.endGroup();
3434 settings.endGroup();
3436 settings.beginGroup(
"Lidar");
3438 settings.beginGroup(
"VLP16");
3439 settings.setValue(
"localTransform",
_ui->lineEdit_lidar_local_transform->text());
3440 settings.setValue(
"pcapPath",
_ui->lineEdit_vlp16_pcap_path->text());
3441 settings.setValue(
"ip1",
_ui->spinBox_vlp16_ip1->value());
3442 settings.setValue(
"ip2",
_ui->spinBox_vlp16_ip2->value());
3443 settings.setValue(
"ip3",
_ui->spinBox_vlp16_ip3->value());
3444 settings.setValue(
"ip4",
_ui->spinBox_vlp16_ip4->value());
3445 settings.setValue(
"port",
_ui->spinBox_vlp16_port->value());
3446 settings.setValue(
"organized",
_ui->checkBox_vlp16_organized->isChecked());
3447 settings.setValue(
"hostTime",
_ui->checkBox_vlp16_hostTime->isChecked());
3448 settings.setValue(
"stampLast",
_ui->checkBox_vlp16_stamp_last->isChecked());
3449 settings.endGroup();
3451 settings.endGroup();
3459 if(!filePath.isEmpty())
3469 #if CV_MAJOR_VERSION < 3 || (CV_MAJOR_VERSION == 4 && CV_MINOR_VERSION <= 3) || (CV_MAJOR_VERSION == 3 && (CV_MINOR_VERSION < 4 || (CV_MINOR_VERSION==4 && CV_SUBMINOR_VERSION<11)))
3470 #ifndef RTABMAP_NONFREE
3473 if(
_ui->comboBox_detector_strategy->currentIndex() <= 1 ||
_ui->comboBox_detector_strategy->currentIndex() == 12)
3475 QMessageBox::warning(
this, tr(
"Parameter warning"),
3476 tr(
"Selected feature type (SURF/SIFT) is not available. RTAB-Map is not built "
3477 "with the nonfree module from OpenCV. ORB is set instead for the bag-of-words dictionary."));
3481 if(
_ui->vis_feature_detector->currentIndex() <= 1 ||
_ui->vis_feature_detector->currentIndex() == 12)
3483 QMessageBox::warning(
this, tr(
"Parameter warning"),
3484 tr(
"Selected feature type (SURF/SIFT) is not available. RTAB-Map is not built "
3485 "with the nonfree module from OpenCV. Fast/Brief is set instead for the re-extraction "
3486 "of features on loop closure."));
3490 #else //>= 4.4.0 >= 3.4.11
3491 #ifndef RTABMAP_NONFREE
3494 if(
_ui->comboBox_detector_strategy->currentIndex() < 1 ||
_ui->comboBox_detector_strategy->currentIndex() == 12)
3496 QMessageBox::warning(
this, tr(
"Parameter warning"),
3497 tr(
"Selected feature type (SURF) is not available. RTAB-Map is not built "
3498 "with the nonfree module from OpenCV. SIFT is set instead for the bag-of-words dictionary."));
3502 if(
_ui->vis_feature_detector->currentIndex() < 1 ||
_ui->vis_feature_detector->currentIndex() == 12)
3504 QMessageBox::warning(
this, tr(
"Parameter warning"),
3505 tr(
"Selected feature type (SURF) is not available. RTAB-Map is not built "
3506 "with the nonfree module from OpenCV. Fast/Brief is set instead for the re-extraction "
3507 "of features on loop closure."));
3513 #if CV_MAJOR_VERSION < 3
3516 #ifdef RTABMAP_NONFREE
3517 QMessageBox::warning(
this, tr(
"Parameter warning"),
3518 tr(
"Selected feature type (KAZE) is not available on OpenCV2. SURF is set instead "
3519 "for the bag-of-words dictionary."));
3522 QMessageBox::warning(
this, tr(
"Parameter warning"),
3523 tr(
"Selected feature type (KAZE) is not available on OpenCV2. ORB is set instead "
3524 "for the bag-of-words dictionary."));
3530 #ifdef RTABMAP_NONFREE
3531 QMessageBox::warning(
this, tr(
"Parameter warning"),
3532 tr(
"Selected feature type (KAZE) is not available on OpenCV2. SURF is set instead "
3533 "for the re-extraction of features on loop closure."));
3536 QMessageBox::warning(
this, tr(
"Parameter warning"),
3537 tr(
"Selected feature type (KAZE) is not available on OpenCV2. ORB is set instead "
3538 "for the re-extraction of features on loop closure."));
3544 #ifndef RTABMAP_ORB_OCTREE
3547 QMessageBox::warning(
this, tr(
"Parameter warning"),
3548 tr(
"Selected feature type (ORB Octree) is not available. ORB is set instead "
3549 "for the bag-of-words dictionary."));
3554 QMessageBox::warning(
this, tr(
"Parameter warning"),
3555 tr(
"Selected feature type (ORB Octree) is not available on OpenCV2. ORB is set instead "
3556 "for the re-extraction of features on loop closure."));
3566 QMessageBox::warning(
this, tr(
"Parameter warning"),
3567 tr(
"Selected graph optimization strategy (TORO) is not available. RTAB-Map is not built "
3568 "with TORO. GTSAM is set instead for graph optimization strategy."));
3571 #ifndef RTABMAP_ORB_SLAM
3574 QMessageBox::warning(
this, tr(
"Parameter warning"),
3575 tr(
"Selected graph optimization strategy (TORO) is not available. RTAB-Map is not built "
3576 "with TORO. g2o is set instead for graph optimization strategy."));
3581 #ifdef RTABMAP_ORB_SLAM
3582 if(
_ui->graphOptimization_type->currentIndex() == 1)
3589 QMessageBox::warning(
this, tr(
"Parameter warning"),
3590 tr(
"Selected graph optimization strategy (g2o) is not available. RTAB-Map is not built "
3591 "with g2o. GTSAM is set instead for graph optimization strategy."));
3596 QMessageBox::warning(
this, tr(
"Parameter warning"),
3597 tr(
"Selected graph optimization strategy (g2o) is not available. RTAB-Map is not built "
3598 "with g2o. TORO is set instead for graph optimization strategy."));
3604 #ifndef RTABMAP_ORB_SLAM
3607 QMessageBox::warning(
this, tr(
"Parameter warning"),
3608 tr(
"Selected graph optimization strategy (GTSAM) is not available. RTAB-Map is not built "
3609 "with GTSAM. g2o is set instead for graph optimization strategy."));
3616 QMessageBox::warning(
this, tr(
"Parameter warning"),
3617 tr(
"Selected graph optimization strategy (GTSAM) is not available. RTAB-Map is not built "
3618 "with GTSAM. TORO is set instead for graph optimization strategy."));
3626 QMessageBox::warning(
this, tr(
"Parameter warning"),
3627 tr(
"Selected visual registration bundle adjustment optimization strategy (g2o) is not available. RTAB-Map is not built "
3628 "with g2o. Bundle adjustment is disabled."));
3629 _ui->loopClosure_bundle->setCurrentIndex(0);
3633 QMessageBox::warning(
this, tr(
"Parameter warning"),
3634 tr(
"Selected visual registration bundle adjustment optimization strategy (cvsba) is not available. RTAB-Map is not built "
3635 "with cvsba. Bundle adjustment is disabled."));
3636 _ui->loopClosure_bundle->setCurrentIndex(0);
3640 QMessageBox::warning(
this, tr(
"Parameter warning"),
3641 tr(
"Selected visual registration bundle adjustment optimization strategy (Ceres) is not available. RTAB-Map is not built "
3642 "with cERES. Bundle adjustment is disabled."));
3643 _ui->loopClosure_bundle->setCurrentIndex(0);
3649 QMessageBox::warning(
this, tr(
"Parameter warning"),
3650 tr(
"Selected odometry local bundle adjustment optimization strategy (g2o) is not available. RTAB-Map is not built "
3651 "with g2o. Bundle adjustment is disabled."));
3652 _ui->odom_f2m_bundleStrategy->setCurrentIndex(0);
3656 QMessageBox::warning(
this, tr(
"Parameter warning"),
3657 tr(
"Selected odometry local bundle adjustment optimization strategy (cvsba) is not available. RTAB-Map is not built "
3658 "with cvsba. Bundle adjustment is disabled."));
3659 _ui->odom_f2m_bundleStrategy->setCurrentIndex(0);
3663 QMessageBox::warning(
this, tr(
"Parameter warning"),
3664 tr(
"Selected odometry local bundle adjustment optimization strategy (Ceres) is not available. RTAB-Map is not built "
3665 "with Ceres. Bundle adjustment is disabled."));
3666 _ui->odom_f2m_bundleStrategy->setCurrentIndex(0);
3670 if(
_ui->graphOptimization_robust->isChecked() &&
_ui->graphOptimization_maxError->value()>0.0)
3672 QMessageBox::warning(
this, tr(
"Parameter warning"),
3673 tr(
"Robust graph optimization and maximum optimization error threshold cannot be "
3674 "both used at the same time. Disabling robust optimization."));
3675 _ui->graphOptimization_robust->setChecked(
false);
3682 QMessageBox::warning(
this, tr(
"Parameter warning"),
3683 tr(
"With the selected feature type (SURF or SIFT), parameter \"Visual word->Nearest Neighbor\" "
3684 "cannot be LSH (used for binary descriptor). KD-tree is set instead for the bag-of-words dictionary."));
3691 QMessageBox::warning(
this, tr(
"Parameter warning"),
3692 tr(
"With the selected feature type (SURF or SIFT), parameter \"Visual word->Nearest Neighbor\" "
3693 "cannot be LSH (used for binary descriptor). KD-tree is set instead for the re-extraction "
3694 "of features on loop closure."));
3698 if(
_ui->doubleSpinBox_freenect2MinDepth->value() >=
_ui->doubleSpinBox_freenect2MaxDepth->value())
3700 QMessageBox::warning(
this, tr(
"Parameter warning"),
3701 tr(
"Freenect2 minimum depth (%1 m) should be lower than maximum depth (%2 m). Setting maximum depth to %3 m.")
3702 .
arg(
_ui->doubleSpinBox_freenect2MinDepth->value())
3703 .
arg(
_ui->doubleSpinBox_freenect2MaxDepth->value())
3704 .arg(
_ui->doubleSpinBox_freenect2MaxDepth->value()+1));
3705 _ui->doubleSpinBox_freenect2MaxDepth->setValue(
_ui->doubleSpinBox_freenect2MaxDepth->value()+1);
3708 if(
_ui->surf_doubleSpinBox_maxDepth->value() > 0.0 &&
3709 _ui->surf_doubleSpinBox_minDepth->value() >=
_ui->surf_doubleSpinBox_maxDepth->value())
3711 QMessageBox::warning(
this, tr(
"Parameter warning"),
3712 tr(
"Visual word minimum depth (%1 m) should be lower than maximum depth (%2 m). Setting maximum depth to %3 m.")
3713 .
arg(
_ui->surf_doubleSpinBox_minDepth->value())
3714 .
arg(
_ui->surf_doubleSpinBox_maxDepth->value())
3715 .arg(
_ui->surf_doubleSpinBox_maxDepth->value()+1));
3716 _ui->doubleSpinBox_freenect2MinDepth->setValue(0);
3719 if(
_ui->loopClosure_bowMaxDepth->value() > 0.0 &&
3720 _ui->loopClosure_bowMinDepth->value() >=
_ui->loopClosure_bowMaxDepth->value())
3722 QMessageBox::warning(
this, tr(
"Parameter warning"),
3723 tr(
"Visual registration word minimum depth (%1 m) should be lower than maximum depth (%2 m). Setting maximum depth to %3 m.")
3724 .
arg(
_ui->loopClosure_bowMinDepth->value())
3725 .
arg(
_ui->loopClosure_bowMaxDepth->value())
3726 .arg(
_ui->loopClosure_bowMaxDepth->value()+1));
3727 _ui->loopClosure_bowMinDepth->setValue(0);
3730 if(
_ui->fastThresholdMax->value() <
_ui->fastThresholdMin->value())
3732 QMessageBox::warning(
this, tr(
"Parameter warning"),
3733 tr(
"FAST minimum threshold cannot be lower than maximum threshold. Setting minimum to 1."));
3734 _ui->fastThresholdMin->setValue(1);
3736 if(
_ui->fastThreshold->value() >
_ui->fastThresholdMax->value())
3738 QMessageBox::warning(
this, tr(
"Parameter warning"),
3739 tr(
"FAST threshold cannot be higher than maximum threshold. Maximum value set to current threshold."));
3740 _ui->fastThresholdMax->setValue(
_ui->fastThreshold->value());
3742 if(
_ui->fastThreshold->value() <
_ui->fastThresholdMin->value())
3744 QMessageBox::warning(
this, tr(
"Parameter warning"),
3745 tr(
"FAST threshold cannot be lower than minimum threshold. Minimum value set to current threshold."));
3746 _ui->fastThresholdMin->setValue(
_ui->fastThreshold->value());
3749 if(
_ui->checkbox_odomDisabled->isChecked() &&
3750 _ui->general_checkBox_SLAM_mode->isChecked() &&
3751 _ui->general_checkBox_activateRGBD->isChecked())
3753 QMessageBox::warning(
this, tr(
"Parameter warning"),
3754 tr(
"Odometry is disabled but incremental RGB-D SLAM is activated! Re-enabling odometry."));
3755 _ui->checkbox_odomDisabled->setChecked(
false);
3758 #if CV_MAJOR_VERSION < 3 || (CV_MAJOR_VERSION == 3 && (CV_MINOR_VERSION <4 || (CV_MINOR_VERSION ==4 && CV_SUBMINOR_VERSION<2)))
3759 if(
_ui->ArucoDictionary->currentIndex()>=17)
3761 QMessageBox::warning(
this, tr(
"Parameter warning"),
3762 tr(
"ArUco dictionary: cannot select AprilTag dictionary, OpenCV version should be at least 3.4.2. Setting back to 0."));
3763 _ui->ArucoDictionary->setCurrentIndex(0);
3772 return tr(
"Reading parameters from the configuration file...");
3780 _ui->lineEdit_dictionaryPath->setEnabled(
false);
3781 _ui->toolButton_dictionaryPath->setEnabled(
false);
3782 _ui->label_dictionaryPath->setEnabled(
false);
3784 _ui->groupBox_source0->setEnabled(
false);
3785 _ui->groupBox_odometry1->setEnabled(
false);
3787 this->setWindowTitle(tr(
"Preferences [Monitoring mode]"));
3791 _ui->lineEdit_dictionaryPath->setEnabled(
true);
3792 _ui->toolButton_dictionaryPath->setEnabled(
true);
3793 _ui->label_dictionaryPath->setEnabled(
true);
3795 _ui->groupBox_source0->setEnabled(
true);
3796 _ui->groupBox_odometry1->setEnabled(
true);
3798 this->setWindowTitle(tr(
"Preferences"));
3804 std::set<std::string> threadsCheckedSet(threadsChecked.begin(), threadsChecked.end());
3805 _ui->comboBox_loggerFilter->clear();
3806 for(std::map<std::string, unsigned long>::iterator
iter=threads.begin();
iter!=threads.end(); ++
iter)
3808 if(threadsCheckedSet.find(
iter->first.c_str()) != threadsCheckedSet.end())
3810 _ui->comboBox_loggerFilter->addItem(QString(
iter->first.c_str()), QVariant(
true));
3814 _ui->comboBox_loggerFilter->addItem(QString(
iter->first.c_str()), QVariant(
false));
3832 QApplication::processEvents();
3837 if(this->isVisible())
3850 if(!window->objectName().isEmpty() && !window->isMaximized())
3853 settings.beginGroup(
"Gui");
3854 settings.beginGroup(window->objectName());
3855 settings.setValue(
"geometry", window->saveGeometry());
3856 settings.endGroup();
3857 settings.endGroup();
3860 settingsTmp.beginGroup(
"Gui");
3861 settingsTmp.beginGroup(window->objectName());
3862 settingsTmp.setValue(
"geometry", window->saveGeometry());
3863 settingsTmp.endGroup();
3864 settingsTmp.endGroup();
3870 if(!window->objectName().isEmpty())
3874 settings.beginGroup(
"Gui");
3875 settings.beginGroup(window->objectName());
3876 bytes = settings.value(
"geometry", QByteArray()).toByteArray();
3877 if(!
bytes.isEmpty())
3879 window->restoreGeometry(
bytes);
3881 settings.endGroup();
3882 settings.endGroup();
3885 settingsTmp.beginGroup(
"Gui");
3886 settingsTmp.beginGroup(window->objectName());
3887 settingsTmp.setValue(
"geometry", window->saveGeometry());
3888 settingsTmp.endGroup();
3889 settingsTmp.endGroup();
3895 if(!mainWindow->objectName().isEmpty())
3900 settings.beginGroup(
"Gui");
3901 settings.beginGroup(mainWindow->objectName());
3902 settings.setValue(
"state", mainWindow->saveState());
3903 settings.setValue(
"maximized", mainWindow->isMaximized());
3904 settings.setValue(
"status_bar", mainWindow->statusBar()->isVisible());
3905 settings.endGroup();
3906 settings.endGroup();
3909 settingsTmp.beginGroup(
"Gui");
3910 settingsTmp.beginGroup(mainWindow->objectName());
3911 settingsTmp.setValue(
"state", mainWindow->saveState());
3912 settingsTmp.setValue(
"maximized", mainWindow->isMaximized());
3913 settingsTmp.setValue(
"status_bar", mainWindow->statusBar()->isVisible());
3914 settingsTmp.endGroup();
3915 settingsTmp.endGroup();
3921 if(!mainWindow->objectName().isEmpty())
3927 settings.beginGroup(
"Gui");
3928 settings.beginGroup(mainWindow->objectName());
3929 bytes = settings.value(
"state", QByteArray()).toByteArray();
3930 if(!
bytes.isEmpty())
3932 mainWindow->restoreState(
bytes);
3934 maximized = settings.value(
"maximized",
false).toBool();
3935 statusBarShown = settings.value(
"status_bar",
false).toBool();
3936 mainWindow->statusBar()->setVisible(statusBarShown);
3937 settings.endGroup();
3938 settings.endGroup();
3941 settingsTmp.beginGroup(
"Gui");
3942 settingsTmp.beginGroup(mainWindow->objectName());
3943 settingsTmp.setValue(
"state", mainWindow->saveState());
3944 settingsTmp.setValue(
"maximized", maximized);
3945 settingsTmp.setValue(
"status_bar", statusBarShown);
3946 settingsTmp.endGroup();
3947 settingsTmp.endGroup();
3953 if(!widget->objectName().isEmpty())
3956 settings.beginGroup(
"Gui");
3957 settings.beginGroup(widget->objectName());
3960 settingsTmp.beginGroup(
"Gui");
3961 settingsTmp.beginGroup(widget->objectName());
3963 const CloudViewer * cloudViewer = qobject_cast<const CloudViewer*>(widget);
3964 const ImageView * imageView = qobject_cast<const ImageView*>(widget);
3965 const ExportCloudsDialog * exportCloudsDialog = qobject_cast<const ExportCloudsDialog*>(widget);
3966 const ExportBundlerDialog * exportBundlerDialog = qobject_cast<const ExportBundlerDialog*>(widget);
3967 const PostProcessingDialog * postProcessingDialog = qobject_cast<const PostProcessingDialog *>(widget);
3968 const GraphViewer * graphViewer = qobject_cast<const GraphViewer *>(widget);
3969 const CalibrationDialog * calibrationDialog = qobject_cast<const CalibrationDialog *>(widget);
3970 const DepthCalibrationDialog * depthCalibrationDialog = qobject_cast<const DepthCalibrationDialog *>(widget);
3982 else if(exportCloudsDialog)
3987 else if(exportBundlerDialog)
3992 else if(postProcessingDialog)
3997 else if(graphViewer)
4002 else if(calibrationDialog)
4007 else if(depthCalibrationDialog)
4014 UERROR(
"Widget \"%s\" cannot be exported in config file.", widget->objectName().toStdString().c_str());
4017 settings.endGroup();
4018 settings.endGroup();
4019 settingsTmp.endGroup();
4020 settingsTmp.endGroup();
4026 if(!widget->objectName().isEmpty())
4030 settings.beginGroup(
"Gui");
4031 settings.beginGroup(widget->objectName());
4034 settingsTmp.beginGroup(
"Gui");
4035 settingsTmp.beginGroup(widget->objectName());
4037 CloudViewer * cloudViewer = qobject_cast<CloudViewer*>(widget);
4038 ImageView * imageView = qobject_cast<ImageView*>(widget);
4042 GraphViewer * graphViewer = qobject_cast<GraphViewer *>(widget);
4043 CalibrationDialog * calibrationDialog = qobject_cast<CalibrationDialog *>(widget);
4056 else if(exportCloudsDialog)
4061 else if(exportBundlerDialog)
4066 else if(postProcessingDialog)
4071 else if(graphViewer)
4076 else if(calibrationDialog)
4081 else if(depthCalibrationDialog)
4088 UERROR(
"Widget \"%s\" cannot be loaded from config file.", widget->objectName().toStdString().c_str());
4091 settings.endGroup();
4092 settings.endGroup();
4093 settingsTmp.endGroup();
4094 settingsTmp.endGroup();
4102 settings.beginGroup(
"Gui");
4103 settings.beginGroup(section);
4105 settings.endGroup();
4106 settings.endGroup();
4109 settingsTmp.beginGroup(
"Gui");
4110 settingsTmp.beginGroup(section);
4112 settingsTmp.endGroup();
4113 settingsTmp.endGroup();
4120 settings.beginGroup(
"Gui");
4121 settings.beginGroup(section);
4122 value = settings.value(
key, QString()).toString();
4123 settings.endGroup();
4124 settings.endGroup();
4127 settingsTmp.beginGroup(
"Gui");
4128 settingsTmp.beginGroup(section);
4130 settingsTmp.endGroup();
4131 settingsTmp.endGroup();
4161 if(parameters.size())
4163 for(rtabmap::ParametersMap::const_iterator
iter = parameters.begin();
iter!=parameters.end(); ++
iter)
4167 if(setOtherParametersToDefault)
4173 if(parameters.find(
iter->first) == parameters.end() &&
4174 iter->first.compare(Parameters::kRtabmapWorkingDirectory())!=0)
4180 if(!this->isVisible())
4192 if(
_ui->comboBox_imuFilter_strategy->currentIndex()==0)
4194 _ui->comboBox_imuFilter_strategy->setCurrentIndex(2);
4201 _ui->comboBox_sourceType->setCurrentIndex(0);
4202 _ui->comboBox_cameraRGBD->setCurrentIndex(src -
kSrcRGBD);
4205 _ui->lineEdit_openniOniPath->clear();
4209 _ui->lineEdit_openni2OniPath->clear();
4213 _ui->lineEdit_k4a_mkv->clear();
4221 _ui->spinBox_rs2_width->setValue(1280);
4222 _ui->spinBox_rs2_height->setValue(720);
4223 _ui->spinBox_rs2_rate->setValue(30);
4224 _ui->checkbox_rs2_irMode->setChecked(
false);
4225 _ui->checkbox_rs2_emitter->setChecked(
true);
4229 _ui->spinBox_rs2_width->setValue(848);
4230 _ui->spinBox_rs2_height->setValue(480);
4231 _ui->spinBox_rs2_rate->setValue(60);
4232 _ui->checkbox_rs2_irMode->setChecked(
true);
4233 _ui->checkbox_rs2_emitter->setChecked(
false);
4239 _ui->comboBox_sourceType->setCurrentIndex(1);
4240 _ui->comboBox_cameraStereo->setCurrentIndex(src -
kSrcStereo);
4245 _ui->comboBox_imuFilter_strategy->setCurrentIndex(0);
4249 _ui->checkBox_depthai_imu_published->setChecked(variant >= 1);
4250 _ui->comboBox_depthai_resolution->setCurrentIndex(variant >= 1?1:3);
4251 _ui->comboBox_depthai_output_mode->setCurrentIndex(variant==2?2:0);
4252 _ui->doubleSpinBox_depthai_dot_intensity->setValue(variant==2?1:0);
4257 _ui->comboBox_sourceType->setCurrentIndex(2);
4258 _ui->source_comboBox_image_type->setCurrentIndex(src -
kSrcRGB);
4262 _ui->comboBox_sourceType->setCurrentIndex(3);
4270 QMessageBox::question(
this, tr(
"Camera Source..."),
4271 tr(
"Do you want to use default camera settings?"),
4272 QMessageBox::Yes | QMessageBox::No, QMessageBox::Yes) == QMessageBox::Yes)
4275 _ui->comboBox_lidar_src->setCurrentIndex(0);
4276 _ui->comboBox_odom_sensor->setCurrentIndex(0);
4279 QMessageBox::question(
this, tr(
"LiDAR Source..."),
4280 tr(
"Do you want to use \"LiDAR 3D ICP\" preset?"),
4281 QMessageBox::Yes | QMessageBox::No, QMessageBox::Yes) == QMessageBox::Yes)
4284 _ui->comboBox_sourceType->setCurrentIndex(4);
4285 _ui->comboBox_odom_sensor->setCurrentIndex(0);
4308 QString dir =
_ui->source_database_lineEdit_path->text();
4313 QStringList paths = QFileDialog::getOpenFileNames(
this, tr(
"Select file"), dir, tr(
"RTAB-Map database files (*.db)"));
4316 int r = QMessageBox::question(
this, tr(
"Odometry in database..."), tr(
"Use odometry saved in database (if some saved)?"), QMessageBox::Yes | QMessageBox::No, QMessageBox::Yes);
4317 _ui->source_checkBox_ignoreOdometry->setChecked(r != QMessageBox::Yes);
4319 if (
_ui->general_doubleSpinBox_detectionRate->value() != 0 &&
_ui->general_spinBox_imagesBufferSize->value() != 0)
4321 r = QMessageBox::question(
this, tr(
"Detection rate..."),
4322 tr(
"Do you want to process all frames? \n\nClicking \"Yes\" will set "
4323 "RTAB-Map's detection rate (%1 Hz) and buffer size (%2) to 0 to make "
4324 "sure that all frames are processed.")
4325 .
arg(
_ui->general_doubleSpinBox_detectionRate->value())
4326 .
arg(
_ui->general_spinBox_imagesBufferSize->value()),
4327 QMessageBox::Yes | QMessageBox::No, QMessageBox::Yes);
4328 if (r == QMessageBox::Yes)
4330 _ui->general_doubleSpinBox_detectionRate->setValue(0.0);
4331 _ui->general_spinBox_imagesBufferSize->setValue(0);
4335 if(paths.size() > 1)
4337 std::vector<std::string> vFileNames(paths.size());
4338 for(
int i=0;
i<paths.size(); ++
i)
4340 vFileNames[
i] = paths[
i].toStdString();
4342 std::sort(vFileNames.begin(), vFileNames.end(),
sortCallback);
4343 for(
int i=0;
i<paths.size(); ++
i)
4345 paths[
i] = vFileNames[
i].c_str();
4349 _ui->source_database_lineEdit_path->setText(paths.size()==1?paths.front():paths.join(
";"));
4350 _ui->source_spinBox_databaseStartId->setValue(0);
4351 _ui->source_spinBox_databaseStopId->setValue(0);
4352 _ui->source_spinBox_database_cameraIndex->setValue(-1);
4359 viewer->setWindowModality(Qt::WindowModal);
4360 viewer->setAttribute(Qt::WA_DeleteOnClose,
true);
4374 if(!
_ui->lineEdit_source_distortionModel->text().isEmpty() &&
4375 QFileInfo(
_ui->lineEdit_source_distortionModel->text()).exists())
4378 model.load(
_ui->lineEdit_source_distortionModel->text().toStdString());
4382 QString
name = QFileInfo(
_ui->lineEdit_source_distortionModel->text()).baseName()+
".png";
4383 cv::imwrite(
name.toStdString(),
img);
4384 QDesktopServices::openUrl(QUrl::fromLocalFile(
name));
4388 QMessageBox::warning(
this, tr(
"Distortion Model"), tr(
"Model loaded from \"%1\" is not valid!").
arg(
_ui->lineEdit_source_distortionModel->text()));
4393 QMessageBox::warning(
this, tr(
"Distortion Model"), tr(
"File \"%1\" doesn't exist!").
arg(
_ui->lineEdit_source_distortionModel->text()));
4399 QString dir =
_ui->lineEdit_calibrationFile->text();
4404 else if(!dir.contains(
'.'))
4408 QString
path = QFileDialog::getOpenFileName(
this, tr(
"Select file"), dir, tr(
"Calibration file (*.yaml)"));
4411 _ui->lineEdit_calibrationFile->setText(
path);
4417 QString dir =
_ui->lineEdit_odom_sensor_path_calibration->text();
4422 else if(!dir.contains(
'.'))
4426 QString
path = QFileDialog::getOpenFileName(
this, tr(
"Select file"), dir, tr(
"Calibration file (*.yaml)"));
4429 _ui->lineEdit_odom_sensor_path_calibration->setText(
path);
4435 QString dir =
_ui->lineEdit_cameraImages_timestamps->text();
4440 QString
path = QFileDialog::getOpenFileName(
this, tr(
"Select file"), dir, tr(
"Timestamps file (*.txt)"));
4443 _ui->lineEdit_cameraImages_timestamps->setText(
path);
4449 QString dir =
_ui->lineEdit_cameraRGBDImages_path_rgb->text();
4454 QString
path = QFileDialog::getExistingDirectory(
this, tr(
"Select RGB images directory"), dir);
4457 _ui->lineEdit_cameraRGBDImages_path_rgb->setText(
path);
4464 QString dir =
_ui->lineEdit_cameraImages_path_scans->text();
4469 QString
path = QFileDialog::getExistingDirectory(
this, tr(
"Select scans directory"), dir);
4472 _ui->lineEdit_cameraImages_path_scans->setText(
path);
4478 QString dir =
_ui->lineEdit_cameraImages_path_imu->text();
4483 QString
path = QFileDialog::getOpenFileName(
this, tr(
"Select file "), dir, tr(
"EuRoC IMU file (*.csv)"));
4486 _ui->lineEdit_cameraImages_path_imu->setText(
path);
4493 QString dir =
_ui->lineEdit_cameraRGBDImages_path_depth->text();
4498 QString
path = QFileDialog::getExistingDirectory(
this, tr(
"Select depth images directory"), dir);
4501 _ui->lineEdit_cameraRGBDImages_path_depth->setText(
path);
4507 QString dir =
_ui->lineEdit_cameraImages_odom->text();
4512 QString
path = QFileDialog::getOpenFileName(
this, tr(
"Select file"), dir, tr(
"Odometry (*.txt *.log *.toro *.g2o *.csv)"));
4516 for(
int i=0;
i<
_ui->comboBox_cameraImages_odomFormat->count(); ++
i)
4518 list.push_back(
_ui->comboBox_cameraImages_odomFormat->itemText(
i));
4520 QString item = QInputDialog::getItem(
this, tr(
"Odometry Format"), tr(
"Format:"),
list,
_ui->comboBox_cameraImages_odomFormat->currentIndex(),
false);
4523 _ui->lineEdit_cameraImages_odom->setText(
path);
4524 _ui->comboBox_cameraImages_odomFormat->setCurrentIndex(
_ui->comboBox_cameraImages_odomFormat->findText(item));
4531 QString dir =
_ui->lineEdit_cameraImages_gt->text();
4536 QString
path = QFileDialog::getOpenFileName(
this, tr(
"Select file"), dir, tr(
"Ground Truth (*.txt *.log *.toro *.g2o *.csv)"));
4540 for(
int i=0;
i<
_ui->comboBox_cameraImages_gtFormat->count(); ++
i)
4542 list.push_back(
_ui->comboBox_cameraImages_gtFormat->itemText(
i));
4544 QString item = QInputDialog::getItem(
this, tr(
"Ground Truth Format"), tr(
"Format:"),
list,
_ui->comboBox_cameraImages_gtFormat->currentIndex(),
false);
4547 _ui->lineEdit_cameraImages_gt->setText(
path);
4548 _ui->comboBox_cameraImages_gtFormat->setCurrentIndex(
_ui->comboBox_cameraImages_gtFormat->findText(item));
4555 QString dir =
_ui->lineEdit_cameraStereoImages_path_left->text();
4560 QString
path = QFileDialog::getExistingDirectory(
this, tr(
"Select left images directory"), dir);
4563 _ui->lineEdit_cameraStereoImages_path_left->setText(
path);
4569 QString dir =
_ui->lineEdit_cameraStereoImages_path_right->text();
4574 QString
path = QFileDialog::getExistingDirectory(
this, tr(
"Select right images directory"), dir);
4577 _ui->lineEdit_cameraStereoImages_path_right->setText(
path);
4583 QString dir =
_ui->source_images_lineEdit_path->text();
4588 QString
path = QFileDialog::getExistingDirectory(
this, tr(
"Select images directory"),
_ui->source_images_lineEdit_path->text());
4591 _ui->source_images_lineEdit_path->setText(
path);
4592 _ui->source_images_spinBox_startPos->setValue(0);
4593 _ui->source_images_spinBox_maxFrames->setValue(0);
4599 QString dir =
_ui->source_video_lineEdit_path->text();
4604 QString
path = QFileDialog::getOpenFileName(
this, tr(
"Select file"), dir, tr(
"Videos (*.avi *.mpg *.mp4 *.mov *.mkv)"));
4607 _ui->source_video_lineEdit_path->setText(
path);
4613 QString dir =
_ui->lineEdit_cameraStereoVideo_path->text();
4618 QString
path = QFileDialog::getOpenFileName(
this, tr(
"Select file"), dir, tr(
"Videos (*.avi *.mpg *.mp4 *.mov *.mkv)"));
4621 _ui->lineEdit_cameraStereoVideo_path->setText(
path);
4627 QString dir =
_ui->lineEdit_cameraStereoVideo_path_2->text();
4632 QString
path = QFileDialog::getOpenFileName(
this, tr(
"Select file"), dir, tr(
"Videos (*.avi *.mpg *.mp4 *.mov *.mkv)"));
4635 _ui->lineEdit_cameraStereoVideo_path_2->setText(
path);
4641 QString dir =
_ui->lineEdit_source_distortionModel->text();
4646 QString
path = QFileDialog::getOpenFileName(
this, tr(
"Select file"), dir, tr(
"Distortion model (*.bin *.txt)"));
4649 _ui->lineEdit_source_distortionModel->setText(
path);
4655 QString dir =
_ui->lineEdit_openniOniPath->text();
4660 QString
path = QFileDialog::getOpenFileName(
this, tr(
"Select file"), dir, tr(
"OpenNI (*.oni)"));
4663 _ui->lineEdit_openniOniPath->setText(
path);
4669 QString dir =
_ui->lineEdit_openni2OniPath->text();
4674 QString
path = QFileDialog::getOpenFileName(
this, tr(
"Select file"), dir, tr(
"OpenNI (*.oni)"));
4677 _ui->lineEdit_openni2OniPath->setText(
path);
4683 QString dir =
_ui->lineEdit_k4a_mkv->text();
4688 QString
path = QFileDialog::getOpenFileName(
this, tr(
"Select file"), dir, tr(
"K4A recording (*.mkv)"));
4689 if (!
path.isEmpty())
4691 _ui->lineEdit_k4a_mkv->setText(
path);
4697 QString dir =
_ui->lineEdit_zedSvoPath->text();
4702 QString
path = QFileDialog::getOpenFileName(
this, tr(
"Select file"), dir, tr(
"ZED (*.svo)"));
4705 _ui->lineEdit_zedSvoPath->setText(
path);
4711 QString dir =
_ui->lineEdit_rs2_jsonFile->text();
4716 QString
path = QFileDialog::getOpenFileName(
this, tr(
"Select RealSense2 preset"), dir, tr(
"JSON (*.json)"));
4719 _ui->lineEdit_rs2_jsonFile->setText(
path);
4725 QString dir =
_ui->lineEdit_depthai_blob_path->text();
4730 QString
path = QFileDialog::getOpenFileName(
this, tr(
"Select file"), dir, tr(
"MyriadX blob (*.blob)"));
4733 _ui->lineEdit_depthai_blob_path->setText(
path);
4739 QString dir =
_ui->lineEdit_vlp16_pcap_path->text();
4744 QString
path = QFileDialog::getOpenFileName(
this, tr(
"Select file"), dir, tr(
"Velodyne recording (*.pcap)"));
4745 if (!
path.isEmpty())
4747 _ui->lineEdit_vlp16_pcap_path->setText(
path);
4754 QWidget * obj =
_ui->stackedWidget->findChild<QWidget*>(
key.c_str());
4759 QSpinBox * spin = qobject_cast<QSpinBox *>(obj);
4760 QDoubleSpinBox * doubleSpin = qobject_cast<QDoubleSpinBox *>(obj);
4761 QComboBox * combo = qobject_cast<QComboBox *>(obj);
4762 QCheckBox *
check = qobject_cast<QCheckBox *>(obj);
4763 QRadioButton * radio = qobject_cast<QRadioButton *>(obj);
4764 QLineEdit * lineEdit = qobject_cast<QLineEdit *>(obj);
4765 QGroupBox * groupBox = qobject_cast<QGroupBox *>(obj);
4769 spin->setValue(QString(
value.c_str()).toInt(&ok));
4772 UERROR(
"Conversion failed from \"%s\" for parameter %s",
value.c_str(),
key.c_str());
4777 doubleSpin->setValue(QString(
value.c_str()).toDouble(&ok));
4780 UERROR(
"Conversion failed from \"%s\" for parameter %s",
value.c_str(),
key.c_str());
4786 std::string valueCpy =
value;
4787 if(
key.compare(Parameters::kIcpStrategy()) == 0 ||
4788 key.compare(Parameters::kGridSensor()) == 0)
4790 if(
value.compare(
"true") == 0)
4794 else if(
value.compare(
"false") == 0)
4800 int valueInt = QString(valueCpy.c_str()).toInt(&ok);
4803 UERROR(
"Conversion failed from \"%s\" for parameter %s", valueCpy.c_str(),
key.c_str());
4807 #ifndef RTABMAP_NONFREE
4809 (combo->objectName().toStdString().compare(Parameters::kKpDetectorStrategy()) == 0 ||
4810 combo->objectName().toStdString().compare(Parameters::kVisFeatureType()) == 0))
4812 UWARN(
"Trying to set \"%s\" to SURF but RTAB-Map isn't built "
4813 "with the nonfree module from OpenCV. Keeping default combo value: %s.",
4814 combo->objectName().toStdString().c_str(),
4815 combo->currentText().toStdString().c_str());
4818 #if CV_MAJOR_VERSION < 3 || (CV_MAJOR_VERSION == 4 && CV_MINOR_VERSION <= 3) || (CV_MAJOR_VERSION == 3 && (CV_MINOR_VERSION < 4 || (CV_MINOR_VERSION==4 && CV_SUBMINOR_VERSION<11)))
4820 (combo->objectName().toStdString().compare(Parameters::kKpDetectorStrategy()) == 0 ||
4821 combo->objectName().toStdString().compare(Parameters::kVisFeatureType()) == 0))
4823 UWARN(
"Trying to set \"%s\" to SIFT but RTAB-Map isn't built "
4824 "with the nonfree module from OpenCV. Keeping default combo value: %s.",
4825 combo->objectName().toStdString().c_str(),
4826 combo->currentText().toStdString().c_str());
4831 #ifndef RTABMAP_ORB_SLAM
4835 if(valueInt==1 && combo->objectName().toStdString().compare(Parameters::kOptimizerStrategy()) == 0)
4837 UWARN(
"Trying to set \"%s\" to g2o but RTAB-Map isn't built "
4838 "with g2o. Keeping default combo value: %s.",
4839 combo->objectName().toStdString().c_str(),
4840 combo->currentText().toStdString().c_str());
4846 if(valueInt==2 && combo->objectName().toStdString().compare(Parameters::kOptimizerStrategy()) == 0)
4848 UWARN(
"Trying to set \"%s\" to GTSAM but RTAB-Map isn't built "
4849 "with GTSAM. Keeping default combo value: %s.",
4850 combo->objectName().toStdString().c_str(),
4851 combo->currentText().toStdString().c_str());
4857 combo->setCurrentIndex(valueInt);
4864 _ui->checkBox_useOdomFeatures->blockSignals(
true);
4866 _ui->checkBox_useOdomFeatures->blockSignals(
false);
4874 lineEdit->setText(
value.c_str());
4882 ULOGGER_WARN(
"QObject called %s can't be cast to a supported widget",
key.c_str());
4887 ULOGGER_WARN(
"Can't find the related QObject for parameter %s",
key.c_str());
4899 ULOGGER_ERROR(
"This slot must be triggered by a signal, not a direct call...");
4911 ULOGGER_ERROR(
"This slot must be triggered by a signal, not a direct call...");
4923 ULOGGER_ERROR(
"This slot must be triggered by a signal, not a direct call...");
4935 ULOGGER_ERROR(
"This slot must be triggered by a signal, not a direct call...");
4943 const QComboBox * comboBox = qobject_cast<const QComboBox*>(
object);
4944 const QSpinBox * spinbox = qobject_cast<const QSpinBox*>(
object);
4945 if(comboBox || spinbox)
4953 UWARN(
"Undefined object \"%s\"",
object->objectName().toStdString().c_str());
4967 const QCheckBox * checkbox = qobject_cast<const QCheckBox*>(
object);
4968 const QRadioButton * radio = qobject_cast<const QRadioButton*>(
object);
4969 const QGroupBox * groupBox = qobject_cast<const QGroupBox*>(
object);
4970 if(checkbox || radio || groupBox)
4978 UWARN(
"Undefined object \"%s\"",
object->objectName().toStdString().c_str());
4992 UDEBUG(
"modify param %s=%f",
object->objectName().toStdString().c_str(),
value);
5005 UDEBUG(
"modify param %s=%s",
object->objectName().toStdString().c_str(),
value.toStdString().c_str());
5017 for(
int i=0;
i<children.size(); ++
i)
5019 const QSpinBox * spin = qobject_cast<const QSpinBox *>(children[
i]);
5020 const QDoubleSpinBox * doubleSpin = qobject_cast<const QDoubleSpinBox *>(children[
i]);
5021 const QComboBox * combo = qobject_cast<const QComboBox *>(children[
i]);
5022 const QCheckBox *
check = qobject_cast<const QCheckBox *>(children[
i]);
5023 const QRadioButton * radio = qobject_cast<const QRadioButton *>(children[
i]);
5024 const QLineEdit * lineEdit = qobject_cast<const QLineEdit *>(children[
i]);
5025 const QGroupBox * groupBox = qobject_cast<const QGroupBox *>(children[
i]);
5026 const QStackedWidget * stackedWidget = qobject_cast<const QStackedWidget *>(children[
i]);
5053 if(groupBox->isCheckable())
5062 else if(stackedWidget)
5075 for(
int i=0;
i<stackedWidget->count(); ++
i)
5077 const QObjectList & children = stackedWidget->widget(
i)->children();
5084 const QObjectList & children = stackedWidget->widget(panel)->children();
5094 const QObjectList & children =
box->children();
5106 if(sender() ==
_ui->general_doubleSpinBox_timeThr_2)
5108 _ui->general_doubleSpinBox_timeThr->setValue(
_ui->general_doubleSpinBox_timeThr_2->value());
5110 else if(sender() ==
_ui->general_doubleSpinBox_hardThr_2)
5112 _ui->general_doubleSpinBox_hardThr->setValue(
_ui->general_doubleSpinBox_hardThr_2->value());
5114 else if(sender() ==
_ui->general_doubleSpinBox_detectionRate_2)
5116 _ui->general_doubleSpinBox_detectionRate->setValue(
_ui->general_doubleSpinBox_detectionRate_2->value());
5118 else if(sender() ==
_ui->general_spinBox_imagesBufferSize_2)
5120 _ui->general_spinBox_imagesBufferSize->setValue(
_ui->general_spinBox_imagesBufferSize_2->value());
5122 else if(sender() ==
_ui->general_spinBox_maxStMemSize_2)
5124 _ui->general_spinBox_maxStMemSize->setValue(
_ui->general_spinBox_maxStMemSize_2->value());
5126 else if(sender() ==
_ui->groupBox_publishing)
5128 _ui->general_checkBox_publishStats_2->setChecked(
_ui->groupBox_publishing->isChecked());
5130 else if(sender() ==
_ui->general_checkBox_publishStats_2)
5132 _ui->groupBox_publishing->setChecked(
_ui->general_checkBox_publishStats_2->isChecked());
5134 else if(sender() ==
_ui->doubleSpinBox_similarityThreshold_2)
5136 _ui->doubleSpinBox_similarityThreshold->setValue(
_ui->doubleSpinBox_similarityThreshold_2->value());
5138 else if(sender() ==
_ui->general_checkBox_activateRGBD)
5140 _ui->general_checkBox_activateRGBD_2->blockSignals(
true);
5141 _ui->general_checkBox_activateRGBD_2->setChecked(
_ui->general_checkBox_activateRGBD->isChecked());
5142 _ui->general_checkBox_activateRGBD_2->blockSignals(
false);
5144 else if(sender() ==
_ui->general_checkBox_activateRGBD_2)
5146 _ui->general_checkBox_activateRGBD->blockSignals(
true);
5147 _ui->general_checkBox_activateRGBD->setChecked(
_ui->general_checkBox_activateRGBD_2->isChecked());
5148 addParameter(
_ui->general_checkBox_activateRGBD,
_ui->general_checkBox_activateRGBD->isChecked());
5149 _ui->general_checkBox_activateRGBD->blockSignals(
false);
5151 else if(sender() ==
_ui->general_checkBox_SLAM_mode)
5153 _ui->general_checkBox_SLAM_mode_2->blockSignals(
true);
5154 _ui->general_checkBox_SLAM_mode_2->setChecked(
_ui->general_checkBox_SLAM_mode->isChecked());
5155 _ui->general_checkBox_SLAM_mode_2->blockSignals(
false);
5157 else if(sender() ==
_ui->general_checkBox_SLAM_mode_2)
5159 _ui->general_checkBox_SLAM_mode->blockSignals(
true);
5160 _ui->general_checkBox_SLAM_mode->setChecked(
_ui->general_checkBox_SLAM_mode_2->isChecked());
5161 addParameter(
_ui->general_checkBox_SLAM_mode,
_ui->general_checkBox_SLAM_mode->isChecked());
5162 _ui->general_checkBox_SLAM_mode->blockSignals(
false);
5167 _ui->general_doubleSpinBox_timeThr->setValue(
_ui->general_doubleSpinBox_timeThr_2->value());
5168 _ui->general_doubleSpinBox_hardThr->setValue(
_ui->general_doubleSpinBox_hardThr_2->value());
5169 _ui->general_doubleSpinBox_detectionRate->setValue(
_ui->general_doubleSpinBox_detectionRate_2->value());
5170 _ui->general_spinBox_imagesBufferSize->setValue(
_ui->general_spinBox_imagesBufferSize_2->value());
5171 _ui->general_spinBox_maxStMemSize->setValue(
_ui->general_spinBox_maxStMemSize_2->value());
5172 _ui->doubleSpinBox_similarityThreshold->setValue(
_ui->doubleSpinBox_similarityThreshold_2->value());
5208 QList<QGroupBox*> boxes;
5209 for(
int i=0;
i<
_ui->stackedWidget->count(); ++
i)
5212 const QObjectList & children =
_ui->stackedWidget->widget(
i)->children();
5213 for(
int j=0;
j<children.size(); ++
j)
5215 if((gb = qobject_cast<QGroupBox *>(children.at(
j))))
5227 ULOGGER_ERROR(
"A QGroupBox must be included in the first level of children in stacked widget, index=%d",
i);
5235 QStringList
values =
_ui->lineEdit_bayes_predictionLC->text().simplified().split(
' ');
5238 UERROR(
"Error parsing prediction (must have at least 2 items) : %s",
5239 _ui->lineEdit_bayes_predictionLC->text().toStdString().c_str());
5242 QVector<qreal> dataX((
values.
size()-2)*2 + 1);
5243 QVector<qreal> dataY((
values.
size()-2)*2 + 1);
5249 int loopClosureIndex = (dataX.size()-1)/2;
5255 UERROR(
"Error parsing prediction : \"%s\"",
values.
at(
i).toStdString().c_str());
5265 dataY[loopClosureIndex] =
value;
5266 dataX[loopClosureIndex] = 0;
5270 dataY[loopClosureIndex-lvl] =
value;
5271 dataX[loopClosureIndex-lvl] = -lvl;
5272 dataY[loopClosureIndex+lvl] =
value;
5273 dataX[loopClosureIndex+lvl] = lvl;
5278 _ui->label_prediction_sum->setNum(sum);
5281 _ui->label_prediction_sum->setText(QString(
"<font color=#FF0000>") +
_ui->label_prediction_sum->text() +
"</font>");
5285 _ui->label_prediction_sum->setText(QString(
"<font color=#00FF00>") +
_ui->label_prediction_sum->text() +
"</font>");
5289 _ui->label_prediction_sum->setText(QString(
"<font color=#FFa500>") +
_ui->label_prediction_sum->text() +
"</font>");
5293 _ui->label_prediction_sum->setText(QString(
"<font color=#000000>") +
_ui->label_prediction_sum->text() +
"</font>");
5296 _ui->predictionPlot->removeCurves();
5297 _ui->predictionPlot->addCurve(
new UPlotCurve(
"Prediction", dataX, dataY,
_ui->predictionPlot));
5302 QStringList strings =
_ui->lineEdit_kp_roi->text().split(
' ');
5303 if(strings.size()!=4)
5305 UERROR(
"ROI must have 4 values (%s)",
_ui->lineEdit_kp_roi->text().toStdString().c_str());
5308 _ui->doubleSpinBox_kp_roi0->setValue(strings[0].toDouble()*100.0);
5309 _ui->doubleSpinBox_kp_roi1->setValue(strings[1].toDouble()*100.0);
5310 _ui->doubleSpinBox_kp_roi2->setValue(strings[2].toDouble()*100.0);
5311 _ui->doubleSpinBox_kp_roi3->setValue(strings[3].toDouble()*100.0);
5316 QStringList strings;
5317 strings.append(QString::number(
_ui->doubleSpinBox_kp_roi0->value()/100.0));
5318 strings.append(QString::number(
_ui->doubleSpinBox_kp_roi1->value()/100.0));
5319 strings.append(QString::number(
_ui->doubleSpinBox_kp_roi2->value()/100.0));
5320 strings.append(QString::number(
_ui->doubleSpinBox_kp_roi3->value()/100.0));
5321 _ui->lineEdit_kp_roi->setText(strings.join(
" "));
5327 _ui->checkbox_stereo_depthGenerated->setVisible(
5329 _ui->comboBox_stereoZed_quality->currentIndex() == 0);
5330 _ui->label_stereo_depthGenerated->setVisible(
5332 _ui->comboBox_stereoZed_quality->currentIndex() == 0);
5334 _ui->checkBox_stereo_rectify->setEnabled(
5341 _ui->checkBox_stereo_rectify->setVisible(
_ui->checkBox_stereo_rectify->isEnabled());
5342 _ui->label_stereo_rectify->setVisible(
_ui->checkBox_stereo_rectify->isEnabled());
5347 _ui->groupBox_pymatcher->setVisible(
_ui->reextract_nn->currentIndex() == 6);
5348 _ui->groupBox_gms->setVisible(
_ui->reextract_nn->currentIndex() == 7);
5353 _ui->groupBox_pydescriptor->setVisible(
_ui->comboBox_globalDescriptorExtractor->currentIndex() == 1);
5360 _ui->stackedWidget_odometryType->setCurrentIndex(7);
5364 _ui->stackedWidget_odometryType->setCurrentIndex(index);
5366 _ui->groupBox_odomF2M->setVisible(index==0);
5367 _ui->groupBox_odomF2F->setVisible(index==1);
5368 _ui->groupBox_odomFovis->setVisible(index==2);
5369 _ui->groupBox_odomViso2->setVisible(index==3);
5370 _ui->groupBox_odomDVO->setVisible(index==4);
5371 _ui->groupBox_odomORBSLAM->setVisible(index==5);
5372 _ui->groupBox_odomOKVIS->setVisible(index==6);
5373 _ui->groupBox_odomLOAM->setVisible(index==7);
5374 _ui->groupBox_odomMSCKF->setVisible(index==8);
5375 _ui->groupBox_odomVINS->setVisible(index==9);
5376 _ui->groupBox_odomOpenVINS->setVisible(index==10);
5377 _ui->groupBox_odomOpen3D->setVisible(index==12);
5382 if(this->isVisible() &&
_ui->checkBox_useOdomFeatures->isChecked())
5384 int r = QMessageBox::question(
this, tr(
"Using odometry features for vocabulary..."),
5385 tr(
"Do you want to match vocabulary feature parameters "
5386 "with corresponding ones used for odometry?"), QMessageBox::Yes | QMessageBox::No, QMessageBox::Yes);
5388 if(r == QMessageBox::Yes)
5390 _ui->comboBox_detector_strategy->setCurrentIndex(
_ui->vis_feature_detector->currentIndex());
5391 _ui->surf_doubleSpinBox_maxDepth->setValue(
_ui->loopClosure_bowMaxDepth->value());
5392 _ui->surf_doubleSpinBox_minDepth->setValue(
_ui->loopClosure_bowMinDepth->value());
5393 _ui->surf_spinBox_wordsPerImageTarget->setValue(
_ui->reextract_maxFeatures->value());
5394 _ui->checkBox_kp_ssc->setChecked(
_ui->checkBox_visSSC->isChecked());
5395 _ui->spinBox_KPGridRows->setValue(
_ui->reextract_gridrows->value());
5396 _ui->spinBox_KPGridCols->setValue(
_ui->reextract_gridcols->value());
5397 _ui->lineEdit_kp_roi->setText(
_ui->loopClosure_roi->text());
5398 _ui->subpix_winSize_kp->setValue(
_ui->subpix_winSize->value());
5399 _ui->subpix_iterations_kp->setValue(
_ui->subpix_iterations->value());
5400 _ui->subpix_eps_kp->setValue(
_ui->subpix_eps->value());
5407 QString directory = QFileDialog::getExistingDirectory(
this, tr(
"Working directory"),
_ui->lineEdit_workingDirectory->text());
5408 if(!directory.isEmpty())
5410 ULOGGER_DEBUG(
"New working directory = %s", directory.toStdString().c_str());
5411 _ui->lineEdit_workingDirectory->setText(directory);
5418 if(
_ui->lineEdit_dictionaryPath->text().isEmpty())
5420 path = QFileDialog::getOpenFileName(
this, tr(
"Dictionary"), this->
getWorkingDirectory(), tr(
"Dictionary (*.txt *.db)"));
5424 path = QFileDialog::getOpenFileName(
this, tr(
"Dictionary"),
_ui->lineEdit_dictionaryPath->text(), tr(
"Dictionary (*.txt *.db)"));
5428 _ui->lineEdit_dictionaryPath->setText(
path);
5435 if(
_ui->lineEdit_OdomORBSLAMVocPath->text().isEmpty())
5437 path = QFileDialog::getOpenFileName(
this, tr(
"ORBSLAM Vocabulary"), this->
getWorkingDirectory(), tr(
"Vocabulary (*.txt)"));
5441 path = QFileDialog::getOpenFileName(
this, tr(
"ORBSLAM Vocabulary"),
_ui->lineEdit_OdomORBSLAMVocPath->text(), tr(
"Vocabulary (*.txt)"));
5445 _ui->lineEdit_OdomORBSLAMVocPath->setText(
path);
5452 if(
_ui->lineEdit_OdomOkvisPath->text().isEmpty())
5454 path = QFileDialog::getOpenFileName(
this, tr(
"OKVIS Config"), this->
getWorkingDirectory(), tr(
"OKVIS config (*.yaml)"));
5458 path = QFileDialog::getOpenFileName(
this, tr(
"OKVIS Config"),
_ui->lineEdit_OdomOkvisPath->text(), tr(
"OKVIS config (*.yaml)"));
5462 _ui->lineEdit_OdomOkvisPath->setText(
path);
5469 if(
_ui->lineEdit_OdomVinsPath->text().isEmpty())
5471 path = QFileDialog::getOpenFileName(
this, tr(
"VINS-Fusion Config"), this->
getWorkingDirectory(), tr(
"VINS-Fusion config (*.yaml)"));
5475 path = QFileDialog::getOpenFileName(
this, tr(
"VINS-Fusion Config"),
_ui->lineEdit_OdomVinsPath->text(), tr(
"VINS-Fusion config (*.yaml)"));
5479 _ui->lineEdit_OdomVinsPath->setText(
path);
5486 if(
_ui->lineEdit_OdomOpenVINSLeftMaskPath->text().isEmpty())
5488 path = QFileDialog::getOpenFileName(
this, tr(
"Select Left Mask"), this->
getWorkingDirectory(), tr(
"Image mask (*.jpg *.png)"));
5492 path = QFileDialog::getOpenFileName(
this, tr(
"Select Left Mask"),
_ui->lineEdit_OdomOpenVINSLeftMaskPath->text(), tr(
"Image mask (*.jpg *.png)"));
5496 _ui->lineEdit_OdomOpenVINSLeftMaskPath->setText(
path);
5503 if(
_ui->lineEdit_OdomOpenVINSRightMaskPath->text().isEmpty())
5505 path = QFileDialog::getOpenFileName(
this, tr(
"Select Right Mask"), this->
getWorkingDirectory(), tr(
"Image mask (*.jpg *.png)"));
5509 path = QFileDialog::getOpenFileName(
this, tr(
"Select Right Mask"),
_ui->lineEdit_OdomOpenVINSRightMaskPath->text(), tr(
"Image mask (*.jpg *.png)"));
5513 _ui->lineEdit_OdomOpenVINSRightMaskPath->setText(
path);
5520 if(
_ui->lineEdit_IcpPMConfigPath->text().isEmpty())
5522 path = QFileDialog::getOpenFileName(
this, tr(
"Select file"), this->
getWorkingDirectory(), tr(
"libpointmatcher (*.yaml)"));
5526 path = QFileDialog::getOpenFileName(
this, tr(
"Select file"),
_ui->lineEdit_IcpPMConfigPath->text(), tr(
"libpointmatcher (*.yaml)"));
5530 _ui->lineEdit_IcpPMConfigPath->setText(
path);
5537 if(
_ui->lineEdit_sptorch_path->text().isEmpty())
5539 path = QFileDialog::getOpenFileName(
this, tr(
"Select file"), this->
getWorkingDirectory(), tr(
"SuperPoint weights (*.pt)"));
5543 path = QFileDialog::getOpenFileName(
this, tr(
"Select file"),
_ui->lineEdit_sptorch_path->text(), tr(
"SuperPoint weights (*.pt)"));
5547 _ui->lineEdit_sptorch_path->setText(
path);
5554 if(
_ui->lineEdit_pymatcher_path->text().isEmpty())
5556 path = QFileDialog::getOpenFileName(
this, tr(
"Select file"), this->
getWorkingDirectory(), tr(
"Python wrapper (*.py)"));
5560 path = QFileDialog::getOpenFileName(
this, tr(
"Select file"),
_ui->lineEdit_pymatcher_path->text(), tr(
"Python wrapper (*.py)"));
5564 _ui->lineEdit_pymatcher_path->setText(
path);
5571 if(
_ui->lineEdit_pymatcher_model->text().isEmpty())
5573 path = QFileDialog::getOpenFileName(
this, tr(
"Select file"), this->
getWorkingDirectory(), tr(
"PyTorch model (*.pth *.pt)"));
5577 path = QFileDialog::getOpenFileName(
this, tr(
"Select file"),
_ui->lineEdit_pymatcher_model->text(), tr(
"PyTorch model (*.pth *.pt)"));
5581 _ui->lineEdit_pymatcher_model->setText(
path);
5588 if(
_ui->lineEdit_pydescriptor_path->text().isEmpty())
5590 path = QFileDialog::getOpenFileName(
this, tr(
"Select file"), this->
getWorkingDirectory(), tr(
"Python wrapper (*.py)"));
5594 path = QFileDialog::getOpenFileName(
this, tr(
"Select file"),
_ui->lineEdit_pydescriptor_path->text(), tr(
"Python wrapper (*.py)"));
5598 _ui->lineEdit_pydescriptor_path->setText(
path);
5604 if(
_ui->lineEdit_pydetector_path->text().isEmpty())
5606 path = QFileDialog::getOpenFileName(
this, tr(
"Select file"), this->
getWorkingDirectory(), tr(
"Python wrapper (*.py)"));
5610 path = QFileDialog::getOpenFileName(
this, tr(
"Select file"),
_ui->lineEdit_pydetector_path->text(), tr(
"Python wrapper (*.py)"));
5614 _ui->lineEdit_pydetector_path->setText(
path);
5620 _ui->stackedWidget_src->setVisible(
_ui->comboBox_sourceType->currentIndex() != 4);
5621 _ui->frame_camera_sensor->setVisible(
_ui->comboBox_sourceType->currentIndex() != 4);
5623 _ui->groupBox_sourceRGBD->setVisible(
_ui->comboBox_sourceType->currentIndex() == 0);
5624 _ui->groupBox_sourceStereo->setVisible(
_ui->comboBox_sourceType->currentIndex() == 1);
5625 _ui->groupBox_sourceRGB->setVisible(
_ui->comboBox_sourceType->currentIndex() == 2);
5626 _ui->groupBox_sourceDatabase->setVisible(
_ui->comboBox_sourceType->currentIndex() == 3);
5628 _ui->stackedWidget_rgbd->setVisible(
_ui->comboBox_sourceType->currentIndex() == 0 &&
5638 _ui->groupBox_openni2->setVisible(
_ui->comboBox_sourceType->currentIndex() == 0 &&
_ui->comboBox_cameraRGBD->currentIndex() ==
kSrcOpenNI2-
kSrcRGBD);
5639 _ui->groupBox_freenect2->setVisible(
_ui->comboBox_sourceType->currentIndex() == 0 &&
_ui->comboBox_cameraRGBD->currentIndex() ==
kSrcFreenect2-
kSrcRGBD);
5640 _ui->groupBox_k4w2->setVisible(
_ui->comboBox_sourceType->currentIndex() == 0 &&
_ui->comboBox_cameraRGBD->currentIndex() ==
kSrcK4W2 -
kSrcRGBD);
5641 _ui->groupBox_k4a->setVisible(
_ui->comboBox_sourceType->currentIndex() == 0 &&
_ui->comboBox_cameraRGBD->currentIndex() ==
kSrcK4A -
kSrcRGBD);
5642 _ui->groupBox_realsense->setVisible(
_ui->comboBox_sourceType->currentIndex() == 0 &&
_ui->comboBox_cameraRGBD->currentIndex() ==
kSrcRealSense -
kSrcRGBD);
5643 _ui->groupBox_realsense2->setVisible(
_ui->comboBox_sourceType->currentIndex() == 0 &&
_ui->comboBox_cameraRGBD->currentIndex() ==
kSrcRealSense2 -
kSrcRGBD);
5644 _ui->groupBox_cameraRGBDImages->setVisible(
_ui->comboBox_sourceType->currentIndex() == 0 &&
_ui->comboBox_cameraRGBD->currentIndex() ==
kSrcRGBDImages-
kSrcRGBD);
5645 _ui->groupBox_openni->setVisible(
_ui->comboBox_sourceType->currentIndex() == 0 &&
_ui->comboBox_cameraRGBD->currentIndex() ==
kSrcOpenNI_PCL -
kSrcRGBD);
5647 _ui->stackedWidget_stereo->setVisible(
_ui->comboBox_sourceType->currentIndex() == 1 &&
5656 _ui->groupBox_cameraStereoVideo->setVisible(
_ui->comboBox_sourceType->currentIndex() == 1 &&
_ui->comboBox_cameraStereo->currentIndex() ==
kSrcStereoVideo -
kSrcStereo);
5657 _ui->groupBox_cameraStereoUsb->setVisible(
_ui->comboBox_sourceType->currentIndex() == 1 &&
_ui->comboBox_cameraStereo->currentIndex() ==
kSrcStereoUsb -
kSrcStereo);
5658 _ui->groupBox_cameraStereoZed->setVisible(
_ui->comboBox_sourceType->currentIndex() == 1 &&
_ui->comboBox_cameraStereo->currentIndex() ==
kSrcStereoZed -
kSrcStereo);
5660 _ui->groupBox_cameraStereoZedOC->setVisible(
_ui->comboBox_sourceType->currentIndex() == 1 &&
_ui->comboBox_cameraStereo->currentIndex() ==
kSrcStereoZedOC -
kSrcStereo);
5663 _ui->stackedWidget_image->setVisible(
_ui->comboBox_sourceType->currentIndex() == 2 &&
5667 _ui->source_groupBox_images->setVisible(
_ui->comboBox_sourceType->currentIndex() == 2 &&
_ui->source_comboBox_image_type->currentIndex() ==
kSrcImages-
kSrcRGB);
5668 _ui->source_groupBox_video->setVisible(
_ui->comboBox_sourceType->currentIndex() == 2 &&
_ui->source_comboBox_image_type->currentIndex() ==
kSrcVideo-
kSrcRGB);
5669 _ui->source_groupBox_usbcam->setVisible(
_ui->comboBox_sourceType->currentIndex() == 2 &&
_ui->source_comboBox_image_type->currentIndex() ==
kSrcUsbDevice-
kSrcRGB);
5671 _ui->groupBox_sourceImages_optional->setVisible(
5674 (
_ui->comboBox_sourceType->currentIndex() == 2 &&
_ui->source_comboBox_image_type->currentIndex() ==
kSrcImages-
kSrcRGB));
5676 _ui->groupBox_depthImageFiltering->setEnabled(
5677 _ui->comboBox_sourceType->currentIndex() == 0 ||
5678 _ui->comboBox_sourceType->currentIndex() == 3);
5679 _ui->groupBox_depthImageFiltering->setVisible(
_ui->groupBox_depthImageFiltering->isEnabled());
5681 _ui->groupBox_depthFromScan->setVisible(
_ui->comboBox_sourceType->currentIndex() == 2 &&
_ui->source_comboBox_image_type->currentIndex() ==
kSrcImages-
kSrcRGB);
5685 _ui->groupBox_odom_sensor->setVisible(
_ui->comboBox_sourceType->currentIndex() != 3);
5688 _ui->comboBox_lidar_src->setEnabled(
_ui->comboBox_sourceType->currentIndex() != 3);
5689 if(!
_ui->comboBox_lidar_src->isEnabled() &&
_ui->comboBox_lidar_src->currentIndex() != 0)
5691 _ui->comboBox_lidar_src->setCurrentIndex(0);
5693 _ui->checkBox_source_scanFromDepth->setEnabled(
_ui->comboBox_sourceType->currentIndex() <= 1 ||
_ui->comboBox_sourceType->currentIndex() == 3);
5694 _ui->label_source_scanFromDepth->setEnabled(
_ui->checkBox_source_scanFromDepth->isEnabled());
5695 if(!
_ui->checkBox_source_scanFromDepth->isEnabled())
5697 _ui->checkBox_source_scanFromDepth->setChecked(
false);
5699 _ui->stackedWidget_lidar_src->setVisible(
_ui->comboBox_lidar_src->currentIndex() > 0);
5701 _ui->frame_lidar_sensor->setVisible(
_ui->comboBox_lidar_src->currentIndex() > 0 ||
_ui->checkBox_source_scanFromDepth->isChecked());
5702 _ui->pushButton_test_lidar->setEnabled(
_ui->comboBox_lidar_src->currentIndex() > 0);
5705 _ui->groupBox_imuFiltering->setEnabled(
5708 (
_ui->comboBox_sourceType->currentIndex() == 2 &&
_ui->source_comboBox_image_type->currentIndex() ==
kSrcImages-
kSrcRGB) ||
5710 (
_ui->comboBox_sourceType->currentIndex() == 0 &&
_ui->comboBox_cameraRGBD->currentIndex() ==
kSrcK4A -
kSrcRGBD) ||
5719 _ui->stackedWidget_imuFilter->setVisible(
_ui->comboBox_imuFilter_strategy->currentIndex() > 0);
5720 _ui->groupBox_madgwickfilter->setVisible(
_ui->comboBox_imuFilter_strategy->currentIndex() == 1);
5721 _ui->groupBox_complementaryfilter->setVisible(
_ui->comboBox_imuFilter_strategy->currentIndex() == 2);
5722 _ui->groupBox_imuFiltering->setVisible(
_ui->groupBox_imuFiltering->isEnabled());
5729 return _ui->comboBox_loggerLevel->currentIndex();
5733 return _ui->comboBox_loggerEventLevel->currentIndex();
5737 return _ui->comboBox_loggerPauseLevel->currentIndex();
5741 return _ui->comboBox_loggerType->currentIndex();
5745 return _ui->checkBox_logger_printTime->isChecked();
5749 return _ui->checkBox_logger_printThreadId->isChecked();
5753 std::vector<std::string> threads;
5754 for(
int i=0;
i<
_ui->comboBox_loggerFilter->count(); ++
i)
5756 if(
_ui->comboBox_loggerFilter->itemData(
i).toBool())
5758 threads.push_back(
_ui->comboBox_loggerFilter->itemText(
i).toStdString());
5765 return _ui->checkBox_verticalLayoutUsed->isChecked();
5769 return _ui->checkBox_imageRejectedShown->isChecked();
5773 return _ui->checkBox_imageHighestHypShown->isChecked();
5777 return _ui->checkBox_beep->isChecked();
5781 return _ui->checkBox_stamps->isChecked();
5785 return _ui->checkBox_cacheStatistics->isChecked();
5789 return _ui->checkBox_notifyWhenNewGlobalPathIsReceived->isChecked();
5793 return _ui->spinBox_odomQualityWarnThr->value();
5797 return _ui->checkBox_odom_onlyInliersShown->isChecked();
5801 return _ui->radioButton_posteriorGraphView->isChecked();
5805 return _ui->radioButton_wordsGraphView->isChecked();
5809 return _ui->radioButton_localizationsGraphView->isChecked();
5813 return _ui->radioButton_localizationsGraphViewOdomCache->isChecked();
5817 return _ui->checkbox_odomDisabled->isChecked();
5821 return _ui->checkBox_odom_sensor_use_as_gt->isChecked();
5825 return _ui->odom_registration->currentIndex();
5829 return _ui->odom_f2m_gravitySigma->value();
5833 return _ui->checkbox_groundTruthAlign->isChecked();
5838 UASSERT(index >= 0 && index <= 1);
5843 #ifdef RTABMAP_OCTOMAP
5844 return _ui->groupBox_octomap->isChecked();
5850 #ifdef RTABMAP_OCTOMAP
5851 return _ui->groupBox_octomap->isChecked() &&
_ui->checkBox_octomap_show3dMap->isChecked();
5857 return _ui->comboBox_octomap_renderingType->currentIndex();
5861 #ifdef RTABMAP_OCTOMAP
5862 return _ui->groupBox_octomap->isChecked() &&
_ui->checkBox_octomap_2dgrid->isChecked();
5868 return _ui->spinBox_octomap_treeDepth->value();
5872 return _ui->spinBox_octomap_pointSize->value();
5877 return _ui->doubleSpinBox_voxel->value();
5881 return _ui->doubleSpinBox_noiseRadius->value();
5885 return _ui->spinBox_noiseMinNeighbors->value();
5889 return _ui->doubleSpinBox_ceilingFilterHeight->value();
5893 return _ui->doubleSpinBox_floorFilterHeight->value();
5897 return _ui->spinBox_normalKSearch->value();
5901 return _ui->doubleSpinBox_normalRadiusSearch->value();
5905 return _ui->doubleSpinBox_ceilingFilterHeight_scan->value();
5909 return _ui->doubleSpinBox_floorFilterHeight_scan->value();
5913 return _ui->spinBox_normalKSearch_scan->value();
5917 return _ui->doubleSpinBox_normalRadiusSearch_scan->value();
5922 return _ui->checkBox_showGraphs->isChecked();
5926 return _ui->checkBox_showLabels->isChecked();
5930 return _ui->checkBox_showFrames->isChecked();
5934 return _ui->checkBox_showLandmarks->isChecked();
5938 return _ui->doubleSpinBox_landmarkSize->value();
5942 UASSERT(index >= 0 && index <= 1);
5947 UASSERT(index >= 0 && index <= 1);
5952 return _ui->checkBox_showIMUAcc->isChecked();
5956 return _ui->RGBDMarkerDetection->isChecked();
5960 return _ui->ArucoMarkerLength->value();
5964 return _ui->groupBox_organized->isChecked();
5968 return _ui->doubleSpinBox_mesh_angleTolerance->value()*
M_PI/180.0;
5972 return _ui->checkBox_mesh_quad->isChecked();
5976 return _ui->checkBox_mesh_texture->isChecked();
5980 return _ui->spinBox_mesh_triangleSize->value();
5984 UASSERT(index >= 0 && index <= 1);
5989 UASSERT(index >= 0 && index <= 1);
5994 UASSERT(index >= 0 && index <= 1);
5999 UASSERT(index >= 0 && index <= 1);
6000 std::vector<float> roiRatios;
6006 roiRatios.resize(4);
6017 UASSERT(index >= 0 && index <= 1);
6022 UASSERT(index >= 0 && index <= 1);
6027 UASSERT(index >= 0 && index <= 1);
6033 UASSERT(index >= 0 && index <= 1);
6038 UASSERT(index >= 0 && index <= 1);
6043 UASSERT(index >= 0 && index <= 1);
6048 UASSERT(index >= 0 && index <= 1);
6053 UASSERT(index >= 0 && index <= 1);
6058 UASSERT(index >= 0 && index <= 1);
6063 UASSERT(index >= 0 && index <= 1);
6068 UASSERT(index >= 0 && index <= 1);
6074 UASSERT(index >= 0 && index <= 1);
6079 UASSERT(index >= 0 && index <= 1);
6084 UASSERT(index >= 0 && index <= 1);
6090 return _ui->radioButton_nodeFiltering->isChecked();
6094 return _ui->radioButton_subtractFiltering->isChecked();
6098 return _ui->doubleSpinBox_cloudFilterRadius->value();
6102 return _ui->doubleSpinBox_cloudFilterAngle->value();
6106 return _ui->spinBox_subtractFilteringMinPts->value();
6110 return _ui->doubleSpinBox_subtractFilteringRadius->value();
6114 return _ui->doubleSpinBox_subtractFilteringAngle->value()*
M_PI/180.0;
6118 return _ui->doubleSpinBox_map_resolution->value();
6122 return _ui->checkBox_map_shown->isChecked();
6126 return _ui->checkBox_elevation_shown->checkState();
6130 return _ui->comboBox_grid_sensor->currentIndex();
6134 return _ui->checkBox_grid_projMapFrame->isChecked();
6138 return _ui->doubleSpinBox_grid_maxGroundAngle->value()*
M_PI/180.0;
6142 return _ui->doubleSpinBox_grid_maxGroundHeight->value();
6146 return _ui->spinBox_grid_minClusterSize->value();
6150 return _ui->doubleSpinBox_grid_maxObstacleHeight->value();
6154 return _ui->checkBox_grid_flatObstaclesDetected->isChecked();
6158 return _ui->doubleSpinBox_map_opacity->value();
6165 return _ui->general_doubleSpinBox_imgRate->value();
6169 return _ui->source_mirroring->isChecked();
6173 int index =
_ui->comboBox_sourceType->currentIndex();
6218 return _ui->comboBox_cameraRGBD->currentText();
6222 return _ui->comboBox_cameraStereo->currentText();
6226 return _ui->source_comboBox_image_type->currentText();
6237 return _ui->lineEdit_sourceDevice->text();
6242 if(
_ui->comboBox_odom_sensor->currentIndex() == 1)
6247 else if(
_ui->comboBox_odom_sensor->currentIndex() == 2)
6252 else if(
_ui->comboBox_odom_sensor->currentIndex() == 3)
6257 else if(
_ui->comboBox_odom_sensor->currentIndex() != 0)
6259 UERROR(
"Not implemented!");
6266 if(
_ui->comboBox_lidar_src->currentIndex() == 0)
6295 return _ui->lineEdit_cameraImages_path_imu->text();
6308 return _ui->spinBox_cameraImages_max_imu_rate->value();
6313 return _ui->source_checkBox_useDbStamps->isChecked();
6317 return _ui->checkbox_rgbd_colorOnly->isChecked();
6321 return _ui->comboBox_imuFilter_strategy->currentIndex();
6325 return _ui->checkBox_imuFilter_baseFrameConversion->isChecked();
6329 return _ui->groupBox_depthImageFiltering->isEnabled();
6333 return _ui->lineEdit_source_distortionModel->text();
6337 return _ui->groupBox_bilateral->isChecked();
6341 return _ui->doubleSpinBox_bilateral_sigmaS->value();
6345 return _ui->doubleSpinBox_bilateral_sigmaR->value();
6349 return _ui->spinBox_source_imageDecimation->value();
6353 return _ui->comboBox_source_histogramMethod->currentIndex();
6357 return _ui->checkbox_source_feature_detection->isChecked();
6361 return _ui->checkbox_stereo_depthGenerated->isChecked();
6365 return _ui->checkBox_stereo_exposureCompensation->isChecked();
6369 return _ui->checkBox_source_scanFromDepth->isChecked();
6373 return _ui->checkBox_source_scanDeskewing->isChecked();
6377 return _ui->spinBox_source_scanDownsampleStep->value();
6381 return _ui->doubleSpinBox_source_scanRangeMin->value();
6385 return _ui->doubleSpinBox_source_scanRangeMax->value();
6389 return _ui->doubleSpinBox_source_scanVoxelSize->value();
6393 return _ui->spinBox_source_scanNormalsK->value();
6397 return _ui->doubleSpinBox_source_scanNormalsRadius->value();
6401 return _ui->doubleSpinBox_source_scanNormalsForceGroundUp->value();
6408 _ui->lineEdit_sourceDevice->text(),
6409 _ui->lineEdit_calibrationFile->text(),
6419 const QString & calibrationPath,
6423 bool odomSensorExtrinsicsCalib)
6427 QMessageBox::warning(
this, tr(
"Odometry Sensor"),
6428 tr(
"Driver %1 cannot support odometry only mode.").
arg(driver), QMessageBox::Ok);
6438 QMessageBox::warning(
this, tr(
"Calibration"),
6439 tr(
"Using raw images for \"OpenNI\" driver is not yet supported. "
6440 "Factory calibration loaded from OpenNI is used."), QMessageBox::Ok);
6446 _ui->lineEdit_openniOniPath->text().isEmpty()?
device.toStdString():
_ui->lineEdit_openniOniPath->text().toStdString(),
6447 this->getGeneralInputRate(),
6448 this->getSourceLocalTransform());
6454 _ui->lineEdit_openni2OniPath->text().isEmpty()?
device.toStdString():
_ui->lineEdit_openni2OniPath->text().toStdString(),
6456 this->getGeneralInputRate(),
6457 this->getSourceLocalTransform());
6464 this->getGeneralInputRate(),
6465 this->getSourceLocalTransform());
6472 QMessageBox::warning(
this, tr(
"Calibration"),
6473 tr(
"Using raw images for \"OpenNI\" driver is not yet supported. "
6474 "Factory calibration loaded from OpenNI is used."), QMessageBox::Ok);
6490 this->getGeneralInputRate(),
6491 this->getSourceLocalTransform(),
6492 _ui->doubleSpinBox_freenect2MinDepth->value(),
6493 _ui->doubleSpinBox_freenect2MaxDepth->value(),
6494 _ui->checkBox_freenect2BilateralFiltering->isChecked(),
6495 _ui->checkBox_freenect2EdgeAwareFiltering->isChecked(),
6496 _ui->checkBox_freenect2NoiseFiltering->isChecked(),
6497 _ui->lineEdit_freenect2Pipeline->text().toStdString());
6502 device.isEmpty() ? 0 : atoi(
device.toStdString().c_str()),
6504 this->getGeneralInputRate(),
6505 this->getSourceLocalTransform());
6509 if (!
_ui->lineEdit_k4a_mkv->text().isEmpty())
6513 _ui->lineEdit_k4a_mkv->text().toStdString().c_str(),
6514 _ui->source_checkBox_useMKVStamps->isChecked() ? -1 :
this->getGeneralInputRate(),
6515 this->getSourceLocalTransform());
6520 device.isEmpty() ? 0 : atoi(
device.toStdString().c_str()),
6521 this->getGeneralInputRate(),
6522 this->getSourceLocalTransform());
6526 ((
CameraK4A*)
camera)->setPreferences(
_ui->comboBox_k4a_rgb_resolution->currentIndex(),
6527 _ui->comboBox_k4a_framerate->currentIndex(),
6528 _ui->comboBox_k4a_depth_resolution->currentIndex());
6532 if(useRawImages &&
_ui->comboBox_realsenseRGBSource->currentIndex()!=2)
6534 QMessageBox::warning(
this, tr(
"Calibration"),
6535 tr(
"Using raw images for \"RealSense\" driver is not yet supported for color and infrared streams. "
6536 "Factory calibration loaded from RealSense is used."), QMessageBox::Ok);
6542 device.isEmpty() ? 0 : atoi(
device.toStdString().c_str()),
6543 _ui->comboBox_realsensePresetRGB->currentIndex(),
6544 _ui->comboBox_realsensePresetDepth->currentIndex(),
6545 _ui->checkbox_realsenseOdom->isChecked(),
6546 this->getGeneralInputRate(),
6547 this->getSourceLocalTransform());
6556 QMessageBox::warning(
this, tr(
"Calibration"),
6557 tr(
"Using raw images for \"RealSense\" driver is not yet supported. "
6558 "Factory calibration loaded from RealSense2 is used."), QMessageBox::Ok);
6565 this->getGeneralInputRate(),
6566 this->getSourceLocalTransform());
6568 _ui->checkbox_publishInterIMU->isChecked(),
6573 ((
CameraRealSense2*)
camera)->setImagesRectified((
_ui->checkBox_stereo_rectify->isEnabled() &&
_ui->checkBox_stereo_rectify->isChecked()) && !useRawImages);
6581 ((
CameraRealSense2*)
camera)->setDepthResolution(
_ui->spinBox_rs2_width_depth->value(),
_ui->spinBox_rs2_height_depth->value(),
_ui->spinBox_rs2_rate_depth->value());
6592 QMessageBox::warning(
this, tr(
"Calibration"),
6593 tr(
"Using raw images for \"MyntEye\" driver is not yet supported. "
6594 "Factory calibration loaded from MyntEye is used."), QMessageBox::Ok);
6601 _ui->checkbox_stereoMyntEye_rectify->isChecked(),
6602 _ui->checkbox_stereoMyntEye_depth->isChecked(),
6603 this->getGeneralInputRate(),
6604 this->getSourceLocalTransform());
6606 if(
_ui->checkbox_stereoMyntEye_autoExposure->isChecked())
6613 _ui->spinBox_stereoMyntEye_gain->value(),
6614 _ui->spinBox_stereoMyntEye_brightness->value(),
6615 _ui->spinBox_stereoMyntEye_contrast->value());
6618 _ui->spinBox_stereoMyntEye_irControl->value());
6624 _ui->lineEdit_cameraRGBDImages_path_rgb->text().append(QDir::separator()).toStdString(),
6625 _ui->lineEdit_cameraRGBDImages_path_depth->text().append(QDir::separator()).toStdString(),
6626 _ui->doubleSpinBox_cameraRGBDImages_scale->value(),
6627 this->getGeneralInputRate(),
6628 this->getSourceLocalTransform());
6632 ((
CameraRGBDImages*)
camera)->setOdometryPath(
_ui->lineEdit_cameraImages_odom->text().toStdString(),
_ui->comboBox_cameraImages_odomFormat->currentIndex());
6633 ((
CameraRGBDImages*)
camera)->setGroundTruthPath(
_ui->lineEdit_cameraImages_gt->text().toStdString(),
_ui->comboBox_cameraImages_gtFormat->currentIndex());
6636 _ui->lineEdit_cameraImages_path_scans->text().isEmpty()?
"":
_ui->lineEdit_cameraImages_path_scans->text().append(QDir::separator()).toStdString(),
6637 _ui->spinBox_cameraImages_max_scan_pts->value(),
6640 _ui->checkBox_cameraImages_timestamps->isChecked(),
6641 _ui->lineEdit_cameraImages_timestamps->text().toStdString(),
6642 _ui->checkBox_cameraImages_syncTimeStamps->isChecked());
6655 QMessageBox::warning(
this, tr(
"Calibration"),
6656 tr(
"Using raw images for \"FlyCapture2\" driver is not yet supported. "
6657 "Factory calibration loaded from FlyCapture2 is used."), QMessageBox::Ok);
6670 _ui->lineEdit_cameraStereoImages_path_left->text().append(QDir::separator()).toStdString(),
6671 _ui->lineEdit_cameraStereoImages_path_right->text().append(QDir::separator()).toStdString(),
6672 (
_ui->checkBox_stereo_rectify->isEnabled() &&
_ui->checkBox_stereo_rectify->isChecked()) && !useRawImages,
6673 this->getGeneralInputRate(),
6674 this->getSourceLocalTransform());
6678 ((
CameraStereoImages*)
camera)->setOdometryPath(
_ui->lineEdit_cameraImages_odom->text().toStdString(),
_ui->comboBox_cameraImages_odomFormat->currentIndex());
6679 ((
CameraStereoImages*)
camera)->setGroundTruthPath(
_ui->lineEdit_cameraImages_gt->text().toStdString(),
_ui->comboBox_cameraImages_gtFormat->currentIndex());
6682 _ui->lineEdit_cameraImages_path_scans->text().isEmpty()?
"":
_ui->lineEdit_cameraImages_path_scans->text().append(QDir::separator()).toStdString(),
6683 _ui->spinBox_cameraImages_max_scan_pts->value(),
6686 _ui->checkBox_cameraImages_timestamps->isChecked(),
6687 _ui->lineEdit_cameraImages_timestamps->text().toStdString(),
6688 _ui->checkBox_cameraImages_syncTimeStamps->isChecked());
6694 if(
_ui->spinBox_stereo_right_device->value()>=0)
6697 device.isEmpty() ? 0 : atoi(
device.toStdString().c_str()),
6698 _ui->spinBox_stereo_right_device->value(),
6699 (
_ui->checkBox_stereo_rectify->isEnabled() &&
_ui->checkBox_stereo_rectify->isChecked()) && !useRawImages,
6700 this->getGeneralInputRate(),
6701 this->getSourceLocalTransform());
6706 device.isEmpty() ? 0 : atoi(
device.toStdString().c_str()),
6707 (
_ui->checkBox_stereo_rectify->isEnabled() &&
_ui->checkBox_stereo_rectify->isChecked()) && !useRawImages,
6708 this->getGeneralInputRate(),
6709 this->getSourceLocalTransform());
6711 ((
CameraStereoVideo*)
camera)->setResolution(
_ui->spinBox_stereousbcam_streamWidth->value(),
_ui->spinBox_stereousbcam_streamHeight->value());
6715 if(!
_ui->lineEdit_cameraStereoVideo_path_2->text().isEmpty())
6719 _ui->lineEdit_cameraStereoVideo_path->text().toStdString(),
6720 _ui->lineEdit_cameraStereoVideo_path_2->text().toStdString(),
6721 (
_ui->checkBox_stereo_rectify->isEnabled() &&
_ui->checkBox_stereo_rectify->isChecked()) && !useRawImages,
6722 this->getGeneralInputRate(),
6723 this->getSourceLocalTransform());
6729 _ui->lineEdit_cameraStereoVideo_path->text().toStdString(),
6730 (
_ui->checkBox_stereo_rectify->isEnabled() &&
_ui->checkBox_stereo_rectify->isChecked()) && !useRawImages,
6731 this->getGeneralInputRate(),
6732 this->getSourceLocalTransform());
6741 (
_ui->checkBox_stereo_rectify->isEnabled() &&
_ui->checkBox_stereo_rectify->isChecked()) && !useRawImages,
6742 this->getGeneralInputRate(),
6743 this->getSourceLocalTransform());
6749 if(!
_ui->lineEdit_zedSvoPath->text().isEmpty())
6752 _ui->lineEdit_zedSvoPath->text().toStdString(),
6753 _ui->comboBox_stereoZed_quality->currentIndex(),
6754 _ui->comboBox_stereoZed_sensingMode->currentIndex(),
6755 _ui->spinBox_stereoZed_confidenceThr->value(),
6759 _ui->checkbox_stereoZed_selfCalibration->isChecked(),
6760 _ui->loopClosure_bowForce2D->isChecked(),
6761 _ui->spinBox_stereoZed_texturenessConfidenceThr->value());
6767 _ui->comboBox_stereoZed_resolution->currentIndex(),
6769 _ui->comboBox_stereoZed_quality->currentIndex()==0&&odomOnly?1:
_ui->comboBox_stereoZed_quality->currentIndex(),
6770 _ui->comboBox_stereoZed_sensingMode->currentIndex(),
6771 _ui->spinBox_stereoZed_confidenceThr->value(),
6775 _ui->checkbox_stereoZed_selfCalibration->isChecked(),
6776 _ui->loopClosure_bowForce2D->isChecked(),
6777 _ui->spinBox_stereoZed_texturenessConfidenceThr->value());
6780 _ui->checkbox_publishInterIMU->isChecked(),
6788 device.isEmpty()?-1:atoi(
device.toStdString().c_str()),
6789 _ui->comboBox_stereoZedOC_resolution->currentIndex(),
6790 this->getGeneralInputRate(),
6791 this->getSourceLocalTransform());
6797 device.toStdString().c_str(),
6798 _ui->comboBox_depthai_resolution->currentIndex(),
6799 this->getGeneralInputRate(),
6800 this->getSourceLocalTransform());
6802 ((
CameraDepthAI*)
camera)->setDepthProfile(
_ui->spinBox_depthai_conf_threshold->value(),
_ui->spinBox_depthai_lrc_threshold->value());
6804 ((
CameraDepthAI*)
camera)->setSubpixelMode(
_ui->comboBox_depthai_subpixel_fractional_bits->currentIndex()!=0,
_ui->comboBox_depthai_subpixel_fractional_bits->currentIndex()==2?4:
_ui->comboBox_depthai_subpixel_fractional_bits->currentIndex()==3?5:3);
6805 ((
CameraDepthAI*)
camera)->setCompanding(
_ui->comboBox_depthai_disparity_companding->currentIndex()!=0,
_ui->comboBox_depthai_disparity_companding->currentIndex()==1?64:96);
6806 ((
CameraDepthAI*)
camera)->setRectification(
_ui->checkBox_depthai_use_spec_translation->isChecked(),
_ui->doubleSpinBox_depthai_alpha_scaling->value(), !useRawImages);
6807 ((
CameraDepthAI*)
camera)->setIMU(
_ui->checkBox_depthai_imu_published->isChecked(),
_ui->checkbox_publishInterIMU->isChecked());
6808 ((
CameraDepthAI*)
camera)->setIrIntensity(
_ui->doubleSpinBox_depthai_dot_intensity->value(),
_ui->doubleSpinBox_depthai_flood_intensity->value());
6811 if(
_ui->comboBox_depthai_detect_features->currentIndex() == 1)
6813 ((
CameraDepthAI*)
camera)->setGFTTDetector(
_ui->checkBox_GFTT_useHarrisDetector->isChecked(),
_ui->doubleSpinBox_GFTT_minDistance->value(),
_ui->reextract_maxFeatures->value());
6815 else if(
_ui->comboBox_depthai_detect_features->currentIndex() >= 2)
6817 ((
CameraDepthAI*)
camera)->setSuperPointDetector(
_ui->doubleSpinBox_sptorch_threshold->value(),
_ui->checkBox_sptorch_nms->isChecked(),
_ui->spinBox_sptorch_minDistance->value());
6828 _ui->checkbox_publishInterIMU->isChecked(),
6836 (
_ui->checkBox_rgb_rectify->isEnabled() &&
_ui->checkBox_rgb_rectify->isChecked()) && !useRawImages,
6837 this->getGeneralInputRate(),
6838 this->getSourceLocalTransform());
6839 ((
CameraVideo*)
camera)->setResolution(
_ui->spinBox_usbcam_streamWidth->value(),
_ui->spinBox_usbcam_streamHeight->value());
6844 _ui->source_video_lineEdit_path->text().toStdString(),
6845 (
_ui->checkBox_rgb_rectify->isEnabled() &&
_ui->checkBox_rgb_rectify->isChecked()) && !useRawImages,
6846 this->getGeneralInputRate(),
6847 this->getSourceLocalTransform());
6852 _ui->source_images_lineEdit_path->text().toStdString(),
6853 this->getGeneralInputRate(),
6854 this->getSourceLocalTransform());
6858 ((
CameraImages*)
camera)->setImagesRectified((
_ui->checkBox_rgb_rectify->isEnabled() &&
_ui->checkBox_rgb_rectify->isChecked()) && !useRawImages);
6862 _ui->lineEdit_cameraImages_odom->text().toStdString(),
6863 _ui->comboBox_cameraImages_odomFormat->currentIndex());
6865 _ui->lineEdit_cameraImages_gt->text().toStdString(),
6866 _ui->comboBox_cameraImages_gtFormat->currentIndex());
6869 _ui->lineEdit_cameraImages_path_scans->text().isEmpty()?
"":
_ui->lineEdit_cameraImages_path_scans->text().append(QDir::separator()).toStdString(),
6870 _ui->spinBox_cameraImages_max_scan_pts->value(),
6873 _ui->groupBox_depthFromScan->isChecked(),
6874 !
_ui->groupBox_depthFromScan_fillHoles->isChecked()?0:
_ui->radioButton_depthFromScan_vertical->isChecked()?1:-1,
6875 _ui->checkBox_depthFromScan_fillBorders->isChecked());
6877 _ui->checkBox_cameraImages_timestamps->isChecked(),
6878 _ui->lineEdit_cameraImages_timestamps->text().toStdString(),
6879 _ui->checkBox_cameraImages_syncTimeStamps->isChecked());
6885 _ui->source_checkBox_useDbStamps->isChecked()?-1:
this->getGeneralInputRate(),
6886 _ui->source_checkBox_ignoreOdometry->isChecked(),
6887 _ui->source_checkBox_ignoreGoalDelay->isChecked(),
6888 _ui->source_checkBox_ignoreGoals->isChecked(),
6889 _ui->source_spinBox_databaseStartId->value(),
6890 _ui->source_spinBox_database_cameraIndex->value(),
6891 _ui->source_spinBox_databaseStopId->value(),
6892 !
_ui->general_checkBox_createIntermediateNodes->isChecked(),
6893 _ui->source_checkBox_ignoreLandmarks->isChecked(),
6894 _ui->source_checkBox_ignoreFeatures->isChecked(),
6897 _ui->source_checkBox_ignorePriors->isChecked());
6901 UFATAL(
"Source driver undefined (%d)!", driver);
6908 QString calibrationFile = calibrationPath;
6911 calibrationFile.remove(
"_left.yaml").remove(
"_right.yaml").remove(
"_pose.yaml").remove(
"_rgb.yaml").remove(
"_depth.yaml");
6913 QString
name = QFileInfo(calibrationFile.remove(
".yaml")).fileName();
6914 if(!calibrationPath.isEmpty())
6916 QDir
d = QFileInfo(calibrationPath).dir();
6917 QString tmp = calibrationPath;
6918 if(!tmp.remove(QFileInfo(calibrationPath).baseName()).isEmpty())
6920 dir =
d.absolutePath();
6924 UDEBUG(
"useRawImages=%d dir=%s", useRawImages?1:0, dir.toStdString().c_str());
6926 if(!
camera->
init(useRawImages?
"":dir.toStdString(),
name.toStdString()))
6928 UWARN(
"init camera failed... ");
6929 QMessageBox::warning(
this,
6931 tr(
"Camera initialization failed..."));
6966 _ui->lineEdit_odomSourceDevice->text().compare(
_ui->lineEdit_sourceDevice->text()) == 0)
6968 QMessageBox::warning(
this, tr(
"Odometry Sensor"),
6969 tr(
"Cannot create an odometry sensor with same driver than camera AND with same "
6970 "device. Change device ID of the odometry or camera sensor. To use odometry option "
6971 "from a single camera, look at the parameters of that driver to enable it, "
6972 "then disable odometry sensor. "), QMessageBox::Ok);
6976 extrinsics =
Transform::fromString(
_ui->lineEdit_odom_sensor_extrinsics->text().replace(
"PI_2", QString::number(3.141592/2.0)).toStdString());
6977 timeOffset =
_ui->doubleSpinBox_odom_sensor_time_offset->value()/1000.0;
6978 scaleFactor = (
float)
_ui->doubleSpinBox_odom_sensor_scale_factor->value();
6979 waitTime =
_ui->doubleSpinBox_odom_sensor_wait_time->value()/1000.0;
6981 return createCamera(driver,
_ui->lineEdit_odomSourceDevice->text(),
_ui->lineEdit_odom_sensor_path_calibration->text(),
false,
true,
true,
false);
6992 #if PCL_VERSION_COMPARE(>=, 1, 8, 0)
6994 if(localTransform.
isNull())
6996 UWARN(
"Failed to parse lidar local transfor string \"%s\"!",
6997 _ui->lineEdit_lidar_local_transform->text().toStdString().c_str());
7000 if(!
_ui->lineEdit_vlp16_pcap_path->text().isEmpty())
7004 _ui->lineEdit_vlp16_pcap_path->text().toStdString(),
7005 _ui->checkBox_vlp16_organized->isChecked(),
7006 _ui->checkBox_vlp16_stamp_last->isChecked(),
7007 this->getGeneralInputRate(),
7015 boost::asio::ip::address_v4::from_string(
uFormat(
"%ld.%ld.%ld.%ld",
7016 (
size_t)
_ui->spinBox_vlp16_ip1->value(),
7017 (
size_t)
_ui->spinBox_vlp16_ip2->value(),
7018 (
size_t)
_ui->spinBox_vlp16_ip3->value(),
7019 (
size_t)
_ui->spinBox_vlp16_ip4->value())),
7020 _ui->spinBox_vlp16_port->value(),
7021 _ui->checkBox_vlp16_organized->isChecked(),
7022 _ui->checkBox_vlp16_hostTime->isChecked(),
7023 _ui->checkBox_vlp16_stamp_last->isChecked(),
7024 this->getGeneralInputRate(),
7030 UWARN(
"init lidar failed... ");
7031 QMessageBox::warning(
this,
7033 tr(
"Lidar initialization failed..."));
7038 UWARN(
"Lidar cannot be used with rtabmap built with PCL < 1.8... ");
7039 QMessageBox::warning(
this,
7041 tr(
"Lidar initialization failed..."));
7049 return _ui->groupBox_publishing->isChecked();
7053 return _ui->general_doubleSpinBox_hardThr->value();
7057 return _ui->general_doubleSpinBox_vp->value();
7061 return _ui->doubleSpinBox_similarityThreshold->value();
7065 return _ui->odom_strategy->currentIndex();
7069 return _ui->odom_dataBufferSize->value();
7079 return _ui->general_checkBox_imagesKept->isChecked();
7083 return _ui->general_checkBox_missing_cache_republished->isChecked();
7087 return _ui->general_checkBox_cloudsKept->isChecked();
7091 return _ui->general_doubleSpinBox_timeThr->value();
7095 return _ui->general_doubleSpinBox_detectionRate->value();
7099 return _ui->general_checkBox_SLAM_mode->isChecked();
7103 return _ui->general_checkBox_activateRGBD->isChecked();
7107 return _ui->surf_spinBox_wordsPerImageTarget->value();
7111 return _ui->graphOptimization_priorsIgnored->isChecked();
7118 if(
_ui->general_doubleSpinBox_imgRate->value() !=
value)
7120 _ui->general_doubleSpinBox_imgRate->setValue(
value);
7135 if(
_ui->general_doubleSpinBox_detectionRate->value() !=
value)
7137 _ui->general_doubleSpinBox_detectionRate->setValue(
value);
7152 if(
_ui->general_doubleSpinBox_timeThr->value() !=
value)
7154 _ui->general_doubleSpinBox_timeThr->setValue(
value);
7169 if(
_ui->general_checkBox_SLAM_mode->isChecked() != enabled)
7171 _ui->general_checkBox_SLAM_mode->setChecked(enabled);
7196 !
_ui->lineEdit_cameraImages_path_imu->text().isEmpty())
7198 imuThread =
new IMUThread(
_ui->spinBox_cameraImages_max_imu_rate->value(),
this->getIMULocalTransform());
7203 if(!imuThread->
init(
_ui->lineEdit_cameraImages_path_imu->text().toStdString()))
7205 QMessageBox::warning(
this, tr(
"Source IMU Path"),
7206 tr(
"Initialization of IMU data has failed! Path=%1.").
arg(
_ui->lineEdit_cameraImages_path_imu->text()), QMessageBox::Ok);
7218 int odomStrategy = Parameters::defaultOdomStrategy();
7220 if(odomStrategy != 1)
7223 parameters.erase(Parameters::kVisCorType());
7230 _ui->odom_dataBufferSize->value());
7234 _ui->spinBox_decimation_odom->value(),
7236 _ui->doubleSpinBox_maxDepth_odom->value(),
7237 this->getOdomQualityWarnThr(),
7239 this->getAllParameters());
7240 odomViewer->setWindowTitle(tr(
"Odometry viewer"));
7241 odomViewer->resize(1280, 480+QPushButton().minimumHeight());
7249 if(
_ui->checkbox_source_feature_detection->isChecked())
7256 _ui->checkBox_source_scanFromDepth->isChecked(),
7257 _ui->spinBox_source_scanDownsampleStep->value(),
7258 _ui->doubleSpinBox_source_scanRangeMin->value(),
7259 _ui->doubleSpinBox_source_scanRangeMax->value(),
7260 _ui->doubleSpinBox_source_scanVoxelSize->value(),
7261 _ui->spinBox_source_scanNormalsK->value(),
7262 _ui->doubleSpinBox_source_scanNormalsRadius->value(),
7263 (
float)
_ui->doubleSpinBox_source_scanNormalsForceGroundUp->value(),
7264 _ui->checkBox_source_scanDeskewing->isChecked());
7265 if(
_ui->comboBox_imuFilter_strategy->currentIndex()>0 &&
dynamic_cast<DBReader*
>(
camera) == 0)
7267 cameraThread.
enableIMUFiltering(
_ui->comboBox_imuFilter_strategy->currentIndex()-1,
this->getAllParameters(),
_ui->checkBox_imuFilter_baseFrameConversion->isChecked());
7271 if(
_ui->groupBox_bilateral->isChecked())
7274 _ui->doubleSpinBox_bilateral_sigmaS->value(),
7275 _ui->doubleSpinBox_bilateral_sigmaR->value());
7277 if(!
_ui->lineEdit_source_distortionModel->text().isEmpty())
7292 cameraThread.
start();
7304 imuThread->
join(
true);
7307 cameraThread.
join(
true);
7308 odomThread.
join(
true);
7314 window->setWindowTitle(tr(
"Camera viewer"));
7315 window->resize(1280, 480+QPushButton().minimumHeight());
7326 if(
_ui->checkbox_source_feature_detection->isChecked())
7333 _ui->checkBox_source_scanFromDepth->isChecked(),
7334 _ui->spinBox_source_scanDownsampleStep->value(),
7335 _ui->doubleSpinBox_source_scanRangeMin->value(),
7336 _ui->doubleSpinBox_source_scanRangeMax->value(),
7337 _ui->doubleSpinBox_source_scanVoxelSize->value(),
7338 _ui->spinBox_source_scanNormalsK->value(),
7339 _ui->doubleSpinBox_source_scanNormalsRadius->value(),
7340 (
float)
_ui->doubleSpinBox_source_scanNormalsForceGroundUp->value(),
7341 _ui->checkBox_source_scanDeskewing->isChecked());
7342 if(
_ui->comboBox_imuFilter_strategy->currentIndex()>0 &&
dynamic_cast<DBReader*
>(
camera) == 0)
7344 cameraThread.
enableIMUFiltering(
_ui->comboBox_imuFilter_strategy->currentIndex()-1,
this->getAllParameters(),
_ui->checkBox_imuFilter_baseFrameConversion->isChecked());
7348 if(
_ui->groupBox_bilateral->isChecked())
7351 _ui->doubleSpinBox_bilateral_sigmaS->value(),
7352 _ui->doubleSpinBox_bilateral_sigmaR->value());
7354 if(!
_ui->lineEdit_source_distortionModel->text().isEmpty())
7361 cameraThread.
start();
7364 cameraThread.
join(
true);
7376 QMessageBox::warning(
this,
7378 tr(
"Cannot calibrate database source!"));
7388 if(!dir.mkpath(
this->getCameraInfoDir()))
7399 QMessageBox::StandardButton button = QMessageBox::question(
this, tr(
"Calibration"),
7400 tr(
"With \"%1\" driver, Color and IR cameras cannot be streamed at the "
7401 "same time. A 3-steps calibration is required (Color -> IR -> extrinsics). We will "
7402 "start with the Color camera calibration. Do you want to continue?").
arg(this->
getSourceDriverStr()),
7403 QMessageBox::Yes | QMessageBox::No | QMessageBox::Ignore, QMessageBox::Yes);
7405 if(button == QMessageBox::Yes || button == QMessageBox::Ignore)
7412 if(button != QMessageBox::Ignore)
7425 cameraThread.
start();
7428 cameraThread.
join(
true);
7432 button = QMessageBox::question(
this, tr(
"Calibration"),
7433 tr(
"We will now calibrate the IR camera. Hide the IR projector with a Post-It and "
7434 "make sure you have enough ambient IR light (e.g., external IR source or sunlight!) to see the "
7435 "checkerboard with the IR camera. Do you want to continue?"),
7436 QMessageBox::Yes | QMessageBox::No | QMessageBox::Ignore, QMessageBox::Yes);
7437 if(button == QMessageBox::Yes || button == QMessageBox::Ignore)
7440 if(button != QMessageBox::Ignore)
7453 cameraThread.
start();
7456 cameraThread.
join(
true);
7460 button = QMessageBox::question(
this, tr(
"Calibration"),
7461 tr(
"We will now calibrate the extrinsics. Important: Make sure "
7462 "the cameras and the checkerboard don't move and that both "
7463 "cameras can see the checkerboard. We will repeat this "
7464 "multiple times. Each time, you will have to move the camera (or "
7465 "checkerboard) for a different point of view. Do you want to "
7467 QMessageBox::Yes | QMessageBox::No, QMessageBox::Yes);
7470 int totalSamples = 0;
7471 if(button == QMessageBox::Yes)
7473 totalSamples = QInputDialog::getInt(
this, tr(
"Calibration"), tr(
"Samples: "), 1, 1, 99, 1, &ok);
7487 for(;
count < totalSamples && button == QMessageBox::Yes; )
7518 if(
count < totalSamples)
7520 button = QMessageBox::question(
this, tr(
"Calibration"),
7521 tr(
"A stereo pair has been taken (total=%1/%2). Move the checkerboard or "
7522 "camera to another position. Press \"Yes\" when you are ready "
7523 "for the next capture.").
arg(
count).
arg(totalSamples),
7524 QMessageBox::Yes | QMessageBox::Abort, QMessageBox::Yes);
7529 button = QMessageBox::question(
this, tr(
"Calibration"),
7530 tr(
"Could not detect the checkerboard on both images or "
7531 "the point of view didn't change enough. Try again?"),
7532 QMessageBox::Yes | QMessageBox::No, QMessageBox::Yes);
7537 button = QMessageBox::question(
this, tr(
"Calibration"),
7538 tr(
"Failed to start the camera. Try again?"), QMessageBox::Yes | QMessageBox::No, QMessageBox::Yes);
7541 if(
count == totalSamples && button == QMessageBox::Yes)
7544 stereoModel.
setName(stereoModel.
name(),
"depth",
"rgb");
7547 QMessageBox::warning(
this, tr(
"Calibration"),
7548 tr(
"Extrinsic calibration has failed! Look on the terminal "
7549 "for possible error messages. Make sure corresponding calibration files exist "
7550 "in \"%1\" folder for camera \"%2\" or calibration name set. If not, re-do "
7551 "step 1 and 2 and make sure to export the calibration files.").
arg(this->
getCameraInfoDir()).
arg(serial.c_str()), QMessageBox::Ok);
7555 QMessageBox::information(
this, tr(
"Calibration"),
7556 tr(
"Calibration is completed! Extrinsics have been saved to \"%1/%2_pose.yaml\"").
arg(this->
getCameraInfoDir()).
arg(stereoModel.
name().c_str()), QMessageBox::Ok);
7572 bool rgbDepth = freenect2 || (driver==
kSrcStereoDepthAI &&
_ui->comboBox_depthai_output_mode->currentIndex() == 2);
7586 cameraThread.
start();
7591 cameraThread.
join(
true);
7609 QMessageBox::warning(
this,
7611 tr(
"Cannot calibrate database source!"));
7621 if(!dir.mkpath(
this->getCameraInfoDir()))
7631 QMessageBox::warning(
this,
7633 tr(
"No odometry sensor selected!"));
7639 QMessageBox::StandardButton button = QMessageBox::question(
this, tr(
"Calibration"),
7640 tr(
"We will calibrate the extrinsics. Important: Make sure "
7641 "the cameras and the checkerboard don't move and that both "
7642 "cameras can see the checkerboard. We will repeat this "
7643 "multiple times. Each time, you will have to move the camera (or "
7644 "checkerboard) for a different point of view. Do you want to "
7646 QMessageBox::Yes | QMessageBox::No, QMessageBox::Yes);
7648 if(button == QMessageBox::Yes)
7653 int totalSamples = 0;
7654 if(button == QMessageBox::Yes)
7656 QDialog dialog(
this);
7657 QFormLayout form(&dialog);
7660 QSpinBox *
samples =
new QSpinBox(&dialog);
7664 QSpinBox * boardWidth =
new QSpinBox(&dialog);
7665 boardWidth->setMinimum(2);
7666 boardWidth->setMaximum(99);
7668 QSpinBox * boardHeight =
new QSpinBox(&dialog);
7669 boardHeight->setMinimum(2);
7670 boardHeight->setMaximum(99);
7672 QDoubleSpinBox * squareSize =
new QDoubleSpinBox(&dialog);
7673 squareSize->setDecimals(4);
7674 squareSize->setMinimum(0.0001);
7675 squareSize->setMaximum(9);
7677 squareSize->setSuffix(
" m");
7678 form.addRow(
"Samples: ",
samples);
7679 form.addRow(
"Checkerboard Width: ", boardWidth);
7680 form.addRow(
"Checkerboard Height: ", boardHeight);
7681 form.addRow(
"Checkerboard Square Size: ", squareSize);
7684 QDialogButtonBox buttonBox(QDialogButtonBox::Ok | QDialogButtonBox::Cancel,
7686 form.addRow(&buttonBox);
7687 QObject::connect(&buttonBox, SIGNAL(accepted()), &dialog, SLOT(accept()));
7688 QObject::connect(&buttonBox, SIGNAL(rejected()), &dialog, SLOT(reject()));
7691 if (dialog.exec() == QDialog::Accepted) {
7695 totalSamples =
samples->value();
7712 for(;
count < totalSamples && button == QMessageBox::Yes; )
7717 _ui->lineEdit_odomSourceDevice->text(),
7718 _ui->lineEdit_odom_sensor_path_calibration->text(),
7719 false,
true,
false,
true);
7727 tr(
"Odom sensor is not calibrated. Camera and odometry sensor should be individually calibrated (intrinsics) before calibrating the extrinsics between them. Aborting..."), QMessageBox::Ok);
7740 int currentIndex =
_ui->comboBox_odom_sensor->currentIndex();
7741 _ui->comboBox_odom_sensor->setCurrentIndex(0);
7743 _ui->comboBox_odom_sensor->setCurrentIndex(currentIndex);
7751 tr(
"Odom sensor is not calibrated. Camera and odometry sensor should be individually calibrated (intrinsics) before calibrating the extrinsics between them. Aborting..."), QMessageBox::Ok);
7772 if(
count < totalSamples)
7775 tr(
"A stereo pair has been taken (total=%1/%2). Move the checkerboard or "
7776 "camera to another position. Press \"Yes\" when you are ready "
7777 "for the next capture.").
arg(
count).
arg(totalSamples),
7778 QMessageBox::Yes | QMessageBox::Abort, QMessageBox::Yes);
7784 tr(
"Could not detect the checkerboard on both images or "
7785 "the point of view didn't change enough. Try again?"),
7786 QMessageBox::Yes | QMessageBox::No, QMessageBox::Yes);
7792 tr(
"Failed to start the camera. Try again?"), QMessageBox::Yes | QMessageBox::No, QMessageBox::Yes);
7795 if(
count == totalSamples && button == QMessageBox::Yes)
7799 odomSensorModel =
CameraModel(
"odom_sensor", odomSensorModel.
imageSize(), odomSensorModel.
K(), cv::Mat::zeros(1,5,CV_64FC1), cv::Mat(), cv::Mat(), odomSensorModel.
localTransform());
7802 stereoModel.
setName(stereoModel.
name(),
"camera",
"odom_sensor");
7806 tr(
"Extrinsic calibration has failed! Look on the terminal "
7807 "for possible error messages."), QMessageBox::Ok);
7808 std::cout <<
"stereoModel: " << stereoModel << std::endl;
7816 UINFO(
"Odom sensor frame to camera frame: %s",
t.prettyPrint().c_str());
7820 _ui->lineEdit_odom_sensor_extrinsics->setText(QString(
"%1 %2 %3 %4 %5 %6")
7824 tr(
"Calibration is completed! Extrinsics have been computed: %1. "
7825 "You can close the calibration dialog.").
arg(
t.prettyPrint().c_str()), QMessageBox::Ok);
7835 window->setWindowTitle(tr(
"Lidar viewer"));
7836 window->setWindowFlags(Qt::Window);
7837 window->resize(1280, 480+QPushButton().minimumHeight());
7846 _ui->checkBox_source_scanFromDepth->isChecked(),
7847 _ui->spinBox_source_scanDownsampleStep->value(),
7848 _ui->doubleSpinBox_source_scanRangeMin->value(),
7849 _ui->doubleSpinBox_source_scanRangeMax->value(),
7850 _ui->doubleSpinBox_source_scanVoxelSize->value(),
7851 _ui->spinBox_source_scanNormalsK->value(),
7852 _ui->doubleSpinBox_source_scanNormalsRadius->value(),
7853 (
float)
_ui->doubleSpinBox_source_scanNormalsForceGroundUp->value(),
7854 _ui->checkBox_source_scanDeskewing->isChecked());
7858 lidarThread.
start();
7861 lidarThread.
join(
true);