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);
162 _ui->checkBox_GFTT_gpu->setEnabled(
false);
163 _ui->label_GFTT_gpu->setEnabled(
false);
166 _ui->comboBox_dictionary_strategy->setItemData(4, 0, Qt::UserRole - 1);
167 _ui->reextract_nn->setItemData(4, 0, Qt::UserRole - 1);
169 #ifndef RTABMAP_CUDASIFT
170 _ui->sift_checkBox_gpu->setEnabled(
false);
171 _ui->sift_label_gpu->setEnabled(
false);
172 _ui->sift_doubleSpinBox_gaussianDiffThreshold->setEnabled(
false);
173 _ui->sift_label_gaussianThreshold->setEnabled(
false);
174 _ui->sift_checkBox_upscale->setEnabled(
false);
175 _ui->sift_label_upscale->setEnabled(
false);
178 #ifndef HAVE_OPENCV_CUDAOPTFLOW
179 _ui->odom_flow_gpu->setEnabled(
false);
180 _ui->label_odom_flow_gpu->setEnabled(
false);
181 _ui->stereo_flow_gpu->setEnabled(
false);
182 _ui->label_stereo_flow_gpu->setEnabled(
false);
185 #ifndef RTABMAP_OCTOMAP
186 _ui->groupBox_octomap->setChecked(
false);
187 _ui->groupBox_octomap->setEnabled(
false);
190 #ifndef RTABMAP_GRIDMAP
191 _ui->checkBox_elevation_shown->setChecked(
false);
192 _ui->checkBox_elevation_shown->setEnabled(
false);
193 _ui->label_show_elevation->setEnabled(
false);
196 #ifndef RTABMAP_REALSENSE_SLAM
197 _ui->checkbox_realsenseOdom->setChecked(
false);
198 _ui->checkbox_realsenseOdom->setEnabled(
false);
199 _ui->label_realsenseOdom->setEnabled(
false);
202 #ifndef RTABMAP_FOVIS
203 _ui->odom_strategy->setItemData(2, 0, Qt::UserRole - 1);
205 #ifndef RTABMAP_VISO2
206 _ui->odom_strategy->setItemData(3, 0, Qt::UserRole - 1);
209 _ui->odom_strategy->setItemData(4, 0, Qt::UserRole - 1);
211 #ifndef RTABMAP_ORB_SLAM
212 _ui->odom_strategy->setItemData(5, 0, Qt::UserRole - 1);
213 #elif RTABMAP_ORB_SLAM == 3
214 _ui->odom_strategy->setItemText(5,
"ORB SLAM 3");
215 _ui->groupBox_odomORBSLAM->setTitle(
"ORB SLAM 3");
217 _ui->odom_strategy->setItemText(5,
"ORB SLAM 2");
218 _ui->groupBox_odomORBSLAM->setTitle(
"ORB SLAM 2");
220 #ifndef RTABMAP_OKVIS
221 _ui->odom_strategy->setItemData(6, 0, Qt::UserRole - 1);
224 _ui->odom_strategy->setItemData(7, 0, Qt::UserRole - 1);
226 #ifndef RTABMAP_MSCKF_VIO
227 _ui->odom_strategy->setItemData(8, 0, Qt::UserRole - 1);
230 _ui->odom_strategy->setItemData(9, 0, Qt::UserRole - 1);
232 #ifndef RTABMAP_OPENVINS
233 _ui->odom_strategy->setItemData(10, 0, Qt::UserRole - 1);
235 #ifndef RTABMAP_FLOAM
236 _ui->odom_strategy->setItemData(11, 0, Qt::UserRole - 1);
238 #ifndef RTABMAP_OPEN3D
239 _ui->odom_strategy->setItemData(12, 0, Qt::UserRole - 1);
242 #if CV_MAJOR_VERSION < 3
243 _ui->stereosgbm_mode->setItemData(2, 0, Qt::UserRole - 1);
247 #ifndef RTABMAP_NONFREE
248 _ui->comboBox_detector_strategy->setItemData(0, 0, Qt::UserRole - 1);
249 _ui->comboBox_detector_strategy->setItemData(12, 0, Qt::UserRole - 1);
250 _ui->comboBox_detector_strategy->setItemData(14, 0, Qt::UserRole - 1);
251 _ui->vis_feature_detector->setItemData(0, 0, Qt::UserRole - 1);
252 _ui->vis_feature_detector->setItemData(12, 0, Qt::UserRole - 1);
253 _ui->vis_feature_detector->setItemData(14, 0, Qt::UserRole - 1);
257 #if CV_MAJOR_VERSION < 3 || (CV_MAJOR_VERSION == 4 && CV_MINOR_VERSION <= 3) || (CV_MAJOR_VERSION == 3 && (CV_MINOR_VERSION < 4 || (CV_MINOR_VERSION==4 && CV_SUBMINOR_VERSION<11)))
258 #ifndef RTABMAP_NONFREE
259 _ui->comboBox_detector_strategy->setItemData(1, 0, Qt::UserRole - 1);
260 _ui->vis_feature_detector->setItemData(1, 0, Qt::UserRole - 1);
263 #if CV_MAJOR_VERSION < 4 || (CV_MAJOR_VERSION == 4 && CV_MINOR_VERSION < 8)
264 _ui->sift_checkBox_preciseUpscale->setEnabled(
false);
265 _ui->sift_label_preciseUpscale->setEnabled(
false);
268 #if CV_MAJOR_VERSION >= 3 && !defined(HAVE_OPENCV_XFEATURES2D)
269 _ui->comboBox_detector_strategy->setItemData(3, 0, Qt::UserRole - 1);
270 _ui->comboBox_detector_strategy->setItemData(4, 0, Qt::UserRole - 1);
271 _ui->comboBox_detector_strategy->setItemData(5, 0, Qt::UserRole - 1);
272 _ui->comboBox_detector_strategy->setItemData(6, 0, Qt::UserRole - 1);
273 _ui->comboBox_detector_strategy->setItemData(12, 0, Qt::UserRole - 1);
274 _ui->comboBox_detector_strategy->setItemData(13, 0, Qt::UserRole - 1);
275 _ui->comboBox_detector_strategy->setItemData(14, 0, Qt::UserRole - 1);
276 _ui->vis_feature_detector->setItemData(3, 0, Qt::UserRole - 1);
277 _ui->vis_feature_detector->setItemData(4, 0, Qt::UserRole - 1);
278 _ui->vis_feature_detector->setItemData(5, 0, Qt::UserRole - 1);
279 _ui->vis_feature_detector->setItemData(6, 0, Qt::UserRole - 1);
280 _ui->vis_feature_detector->setItemData(12, 0, Qt::UserRole - 1);
281 _ui->vis_feature_detector->setItemData(13, 0, Qt::UserRole - 1);
282 _ui->vis_feature_detector->setItemData(14, 0, Qt::UserRole - 1);
285 #ifndef RTABMAP_ORB_OCTREE
286 _ui->comboBox_detector_strategy->setItemData(10, 0, Qt::UserRole - 1);
287 _ui->vis_feature_detector->setItemData(10, 0, Qt::UserRole - 1);
290 #ifndef RTABMAP_TORCH
291 _ui->comboBox_detector_strategy->setItemData(11, 0, Qt::UserRole - 1);
292 _ui->vis_feature_detector->setItemData(11, 0, Qt::UserRole - 1);
295 #ifndef RTABMAP_PYTHON
296 _ui->comboBox_detector_strategy->setItemData(15, 0, Qt::UserRole - 1);
297 _ui->vis_feature_detector->setItemData(15, 0, Qt::UserRole - 1);
298 _ui->reextract_nn->setItemData(6, 0, Qt::UserRole - 1);
299 _ui->comboBox_globalDescriptorExtractor->setItemData(1, 0, Qt::UserRole - 1);
302 #if !defined(HAVE_OPENCV_XFEATURES2D) || (CV_MAJOR_VERSION == 3 && (CV_MINOR_VERSION<4 || CV_MINOR_VERSION==4 && CV_SUBMINOR_VERSION<1))
303 _ui->reextract_nn->setItemData(7, 0, Qt::UserRole - 1);
306 #if CV_MAJOR_VERSION >= 3
307 _ui->groupBox_fast_opencv2->setEnabled(
false);
309 _ui->comboBox_detector_strategy->setItemData(9, 0, Qt::UserRole - 1);
310 _ui->comboBox_detector_strategy->setItemData(13, 0, Qt::UserRole - 1);
311 _ui->comboBox_detector_strategy->setItemData(14, 0, Qt::UserRole - 1);
312 _ui->vis_feature_detector->setItemData(9, 0, Qt::UserRole - 1);
313 _ui->vis_feature_detector->setItemData(13, 0, Qt::UserRole - 1);
314 _ui->vis_feature_detector->setItemData(14, 0, Qt::UserRole - 1);
317 _ui->comboBox_cameraImages_odomFormat->setItemData(4, 0, Qt::UserRole - 1);
318 _ui->comboBox_cameraImages_gtFormat->setItemData(4, 0, Qt::UserRole - 1);
321 _ui->graphOptimization_type->setItemData(1, 0, Qt::UserRole - 1);
322 _ui->odom_f2m_bundleStrategy->setItemData(1, 0, Qt::UserRole - 1);
323 _ui->loopClosure_bundle->setItemData(1, 0, Qt::UserRole - 1);
324 _ui->groupBoxx_g2o->setEnabled(
false);
326 #ifdef RTABMAP_ORB_SLAM
330 _ui->graphOptimization_type->setItemData(1, 0, Qt::UserRole - 1);
335 _ui->comboBox_g2o_solver->setItemData(0, 0, Qt::UserRole - 1);
339 _ui->comboBox_g2o_solver->setItemData(2, 0, Qt::UserRole - 1);
343 _ui->graphOptimization_type->setItemData(0, 0, Qt::UserRole - 1);
347 _ui->graphOptimization_type->setItemData(2, 0, Qt::UserRole - 1);
351 _ui->odom_f2m_bundleStrategy->setItemData(2, 0, Qt::UserRole - 1);
352 _ui->loopClosure_bundle->setItemData(2, 0, Qt::UserRole - 1);
356 _ui->graphOptimization_type->setItemData(3, 0, Qt::UserRole - 1);
357 _ui->odom_f2m_bundleStrategy->setItemData(3, 0, Qt::UserRole - 1);
358 _ui->loopClosure_bundle->setItemData(3, 0, Qt::UserRole - 1);
360 #ifdef RTABMAP_VERTIGO
364 _ui->graphOptimization_robust->setEnabled(
false);
366 #ifndef RTABMAP_POINTMATCHER
367 _ui->comboBox_icpStrategy->setItemData(1, 0, Qt::UserRole - 1);
369 #ifndef RTABMAP_CCCORELIB
370 _ui->comboBox_icpStrategy->setItemData(2, 0, Qt::UserRole - 1);
409 _ui->comboBox_odom_sensor->setItemData(1, 0, Qt::UserRole - 1);
422 _ui->comboBox_odom_sensor->setItemData(2, 0, Qt::UserRole - 1);
426 _ui->comboBox_stereoZed_resolution->setItemData(1, 0, Qt::UserRole - 1);
427 _ui->comboBox_stereoZed_resolution->setItemData(4, 0, Qt::UserRole - 1);
428 _ui->comboBox_stereoZed_resolution->setItemData(6, 0, Qt::UserRole - 1);
429 _ui->comboBox_stereoZed_quality->setItemData(3, 0, Qt::UserRole - 1);
450 _ui->comboBox_odom_sensor->setItemData(3, 0, Qt::UserRole - 1);
455 #if PCL_VERSION_COMPARE(<, 1, 7, 2)
456 _ui->checkBox_showFrustums->setEnabled(
false);
457 _ui->checkBox_showFrustums->setChecked(
false);
458 _ui->checkBox_showOdomFrustums->setEnabled(
false);
459 _ui->checkBox_showOdomFrustums->setChecked(
false);
463 #if CV_MAJOR_VERSION < 3 || (CV_MAJOR_VERSION == 3 && (CV_MINOR_VERSION <4 || (CV_MINOR_VERSION ==4 && CV_SUBMINOR_VERSION<2)))
464 _ui->ArucoDictionary->setItemData(17, 0, Qt::UserRole - 1);
465 _ui->ArucoDictionary->setItemData(18, 0, Qt::UserRole - 1);
466 _ui->ArucoDictionary->setItemData(19, 0, Qt::UserRole - 1);
467 _ui->ArucoDictionary->setItemData(20, 0, Qt::UserRole - 1);
469 #ifndef HAVE_OPENCV_ARUCO
470 _ui->label_markerDetection->setText(
_ui->label_markerDetection->text()+
" This option works only if OpenCV has been built with \"aruco\" module.");
473 #ifndef RTABMAP_MADGWICK
474 _ui->comboBox_imuFilter_strategy->setItemData(1, 0, Qt::UserRole - 1);
478 UASSERT(
_ui->odom_registration->count() == 4);
491 _ui->predictionPlot->showLegend(
false);
493 QButtonGroup * buttonGroup =
new QButtonGroup(
this);
494 buttonGroup->addButton(
_ui->radioButton_basic);
495 buttonGroup->addButton(
_ui->radioButton_advanced);
498 connect(
_ui->buttonBox_global, SIGNAL(
clicked(QAbstractButton *)),
this, SLOT(
closeDialog(QAbstractButton *)));
499 connect(
_ui->buttonBox_local, SIGNAL(
clicked(QAbstractButton *)),
this, SLOT(
resetApply(QAbstractButton *)));
505 connect(
_ui->radioButton_basic, SIGNAL(toggled(
bool)),
this, SLOT(
setupTreeView()));
618 for(
int i=0;
i<2; ++
i)
698 _ui->comboBox_loggerFilter->SetDisplayText(
"Select:");
703 connect(
_ui->general_doubleSpinBox_imgRate, SIGNAL(valueChanged(
double)),
_ui->doubleSpinBox_OdomORBSLAMFps, SLOT(setValue(
double)));
707 _ui->stackedWidget_src->setCurrentIndex(
_ui->comboBox_sourceType->currentIndex());
708 connect(
_ui->comboBox_sourceType, SIGNAL(currentIndexChanged(
int)),
_ui->stackedWidget_src, SLOT(setCurrentIndex(
int)));
714 _ui->stackedWidget_image->setCurrentIndex(
_ui->source_comboBox_image_type->currentIndex());
715 connect(
_ui->source_comboBox_image_type, SIGNAL(currentIndexChanged(
int)),
_ui->stackedWidget_image, SLOT(setCurrentIndex(
int)));
746 connect(
_ui->source_checkBox_stereoToDepthDB, SIGNAL(toggled(
bool)),
_ui->checkbox_stereo_depthGenerated, SLOT(setChecked(
bool)));
747 connect(
_ui->checkbox_stereo_depthGenerated, SIGNAL(toggled(
bool)),
_ui->source_checkBox_stereoToDepthDB, SLOT(setChecked(
bool)));
750 _ui->stackedWidget_rgbd->setCurrentIndex(
_ui->comboBox_cameraRGBD->currentIndex());
751 connect(
_ui->comboBox_cameraRGBD, SIGNAL(currentIndexChanged(
int)),
_ui->stackedWidget_rgbd, SLOT(setCurrentIndex(
int)));
753 _ui->stackedWidget_stereo->setCurrentIndex(
_ui->comboBox_cameraStereo->currentIndex());
754 connect(
_ui->comboBox_cameraStereo, SIGNAL(currentIndexChanged(
int)),
_ui->stackedWidget_stereo, SLOT(setCurrentIndex(
int)));
799 connect(
_ui->lineEdit_cameraRGBDImages_path_rgb, SIGNAL(textChanged(
const QString &)),
this, SLOT(
makeObsoleteSourcePanel()));
800 connect(
_ui->lineEdit_cameraRGBDImages_path_depth, SIGNAL(textChanged(
const QString &)),
this, SLOT(
makeObsoleteSourcePanel()));
808 connect(
_ui->lineEdit_cameraImages_laser_transform, SIGNAL(textChanged(
const QString &)),
this, SLOT(
makeObsoleteSourcePanel()));
816 connect(
_ui->lineEdit_cameraImages_imu_transform, SIGNAL(textChanged(
const QString &)),
this, SLOT(
makeObsoleteSourcePanel()));
826 connect(
_ui->lineEdit_cameraStereoImages_path_left, SIGNAL(textChanged(
const QString &)),
this, SLOT(
makeObsoleteSourcePanel()));
827 connect(
_ui->lineEdit_cameraStereoImages_path_right, SIGNAL(textChanged(
const QString &)),
this, SLOT(
makeObsoleteSourcePanel()));
866 connect(
_ui->comboBox_depthai_subpixel_fractional_bits, SIGNAL(currentIndexChanged(
int)),
this, SLOT(
makeObsoleteSourcePanel()));
907 connect(
_ui->lineEdit_odom_sensor_path_calibration, SIGNAL(textChanged(
const QString &)),
this, SLOT(
makeObsoleteSourcePanel()));
915 connect(
_ui->comboBox_imuFilter_strategy, SIGNAL(currentIndexChanged(
int)),
_ui->stackedWidget_imuFilter, SLOT(setCurrentIndex(
int)));
916 _ui->stackedWidget_imuFilter->setCurrentIndex(
_ui->comboBox_imuFilter_strategy->currentIndex());
921 connect(
_ui->comboBox_lidar_src, SIGNAL(currentIndexChanged(
int)),
_ui->stackedWidget_lidar_src, SLOT(setCurrentIndex(
int)));
922 _ui->stackedWidget_lidar_src->setCurrentIndex(
_ui->comboBox_lidar_src->currentIndex());
931 connect(
_ui->doubleSpinBox_source_scanNormalsForceGroundUp, SIGNAL(valueChanged(
double)),
this, SLOT(
makeObsoleteSourcePanel()));
946 connect(
_ui->general_doubleSpinBox_timeThr, SIGNAL(valueChanged(
double)),
_ui->general_doubleSpinBox_timeThr_2, SLOT(setValue(
double)));
947 connect(
_ui->general_doubleSpinBox_hardThr, SIGNAL(valueChanged(
double)),
_ui->general_doubleSpinBox_hardThr_2, SLOT(setValue(
double)));
948 connect(
_ui->doubleSpinBox_similarityThreshold, SIGNAL(valueChanged(
double)),
_ui->doubleSpinBox_similarityThreshold_2, SLOT(setValue(
double)));
949 connect(
_ui->general_doubleSpinBox_detectionRate, SIGNAL(valueChanged(
double)),
_ui->general_doubleSpinBox_detectionRate_2, SLOT(setValue(
double)));
950 connect(
_ui->general_spinBox_imagesBufferSize, SIGNAL(valueChanged(
int)),
_ui->general_spinBox_imagesBufferSize_2, SLOT(setValue(
int)));
951 connect(
_ui->general_spinBox_maxStMemSize, SIGNAL(valueChanged(
int)),
_ui->general_spinBox_maxStMemSize_2, SLOT(setValue(
int)));
955 connect(
_ui->doubleSpinBox_similarityThreshold_2, SIGNAL(editingFinished()),
this, SLOT(
updateBasicParameter()));
956 connect(
_ui->general_doubleSpinBox_detectionRate_2, SIGNAL(editingFinished()),
this, SLOT(
updateBasicParameter()));
957 connect(
_ui->general_spinBox_imagesBufferSize_2, SIGNAL(editingFinished()),
this, SLOT(
updateBasicParameter()));
968 _ui->groupBox_publishing->setObjectName(Parameters::kRtabmapPublishStats().
c_str());
969 _ui->general_checkBox_publishRawData->setObjectName(Parameters::kRtabmapPublishLastSignature().
c_str());
970 _ui->general_checkBox_publishPdf->setObjectName(Parameters::kRtabmapPublishPdf().
c_str());
971 _ui->general_checkBox_publishLikelihood->setObjectName(Parameters::kRtabmapPublishLikelihood().
c_str());
972 _ui->general_checkBox_publishRMSE->setObjectName(Parameters::kRtabmapComputeRMSE().
c_str());
973 _ui->general_checkBox_saveWMState->setObjectName(Parameters::kRtabmapSaveWMState().
c_str());
974 _ui->general_checkBox_publishRAM->setObjectName(Parameters::kRtabmapPublishRAMUsage().
c_str());
975 _ui->general_checkBox_statisticLogsBufferedInRAM->setObjectName(Parameters::kRtabmapStatisticLogsBufferedInRAM().
c_str());
976 _ui->groupBox_statistics->setObjectName(Parameters::kRtabmapStatisticLogged().
c_str());
977 _ui->general_checkBox_statisticLoggedHeaders->setObjectName(Parameters::kRtabmapStatisticLoggedHeaders().
c_str());
978 _ui->general_doubleSpinBox_timeThr->setObjectName(Parameters::kRtabmapTimeThr().
c_str());
979 _ui->general_spinBox_memoryThr->setObjectName(Parameters::kRtabmapMemoryThr().
c_str());
980 _ui->general_doubleSpinBox_detectionRate->setObjectName(Parameters::kRtabmapDetectionRate().
c_str());
981 _ui->general_spinBox_imagesBufferSize->setObjectName(Parameters::kRtabmapImageBufferSize().
c_str());
982 _ui->general_checkBox_createIntermediateNodes->setObjectName(Parameters::kRtabmapCreateIntermediateNodes().
c_str());
983 _ui->general_spinBox_maxRetrieved->setObjectName(Parameters::kRtabmapMaxRetrieved().
c_str());
984 _ui->general_spinBox_max_republished->setObjectName(Parameters::kRtabmapMaxRepublished().
c_str());
985 _ui->general_checkBox_startNewMapOnLoopClosure->setObjectName(Parameters::kRtabmapStartNewMapOnLoopClosure().
c_str());
986 _ui->general_checkBox_startNewMapOnGoodSignature->setObjectName(Parameters::kRtabmapStartNewMapOnGoodSignature().
c_str());
987 _ui->general_checkBox_imagesAlreadyRectified->setObjectName(Parameters::kRtabmapImagesAlreadyRectified().
c_str());
988 _ui->general_checkBox_rectifyOnlyFeatures->setObjectName(Parameters::kRtabmapRectifyOnlyFeatures().
c_str());
989 _ui->checkBox_rtabmap_loopGPS->setObjectName(Parameters::kRtabmapLoopGPS().
c_str());
990 _ui->lineEdit_workingDirectory->setObjectName(Parameters::kRtabmapWorkingDirectory().
c_str());
994 _ui->general_checkBox_keepRawData->setObjectName(Parameters::kMemImageKept().
c_str());
995 _ui->general_checkBox_keepBinaryData->setObjectName(Parameters::kMemBinDataKept().
c_str());
996 _ui->general_checkBox_saveIntermediateNodeData->setObjectName(Parameters::kMemIntermediateNodeDataKept().
c_str());
997 _ui->lineEdit_rgbCompressionFormat->setObjectName(Parameters::kMemImageCompressionFormat().
c_str());
998 _ui->lineEdit_depthCompressionFormat->setObjectName(Parameters::kMemDepthCompressionFormat().
c_str());
999 _ui->general_checkBox_keepDescriptors->setObjectName(Parameters::kMemRawDescriptorsKept().
c_str());
1000 _ui->general_checkBox_saveDepth16bits->setObjectName(Parameters::kMemSaveDepth16Format().
c_str());
1001 _ui->general_checkBox_compressionParallelized->setObjectName(Parameters::kMemCompressionParallelized().
c_str());
1002 _ui->general_checkBox_reduceGraph->setObjectName(Parameters::kMemReduceGraph().
c_str());
1003 _ui->general_checkBox_keepNotLinkedNodes->setObjectName(Parameters::kMemNotLinkedNodesKept().
c_str());
1004 _ui->general_spinBox_maxStMemSize->setObjectName(Parameters::kMemSTMSize().
c_str());
1005 _ui->doubleSpinBox_similarityThreshold->setObjectName(Parameters::kMemRehearsalSimilarity().
c_str());
1006 _ui->general_checkBox_SLAM_mode->setObjectName(Parameters::kMemIncrementalMemory().
c_str());
1007 _ui->general_checkBox_saveLocalizationData->setObjectName(Parameters::kMemLocalizationDataSaved().
c_str());
1008 _ui->general_doubleSpinBox_recentWmRatio->setObjectName(Parameters::kMemRecentWmRatio().
c_str());
1009 _ui->general_checkBox_transferSortingByWeightId->setObjectName(Parameters::kMemTransferSortingByWeightId().
c_str());
1010 _ui->general_checkBox_RehearsalIdUpdatedToNewOne->setObjectName(Parameters::kMemRehearsalIdUpdatedToNewOne().
c_str());
1011 _ui->general_checkBox_generateIds->setObjectName(Parameters::kMemGenerateIds().
c_str());
1012 _ui->general_checkBox_badSignaturesIgnored->setObjectName(Parameters::kMemBadSignaturesIgnored().
c_str());
1013 _ui->general_checkBox_createMapLabels->setObjectName(Parameters::kMemMapLabelsAdded().
c_str());
1014 _ui->general_checkBox_initWMWithAllNodes->setObjectName(Parameters::kMemInitWMWithAllNodes().
c_str());
1015 _ui->checkBox_localSpaceScanMatchingIDsSaved->setObjectName(Parameters::kRGBDScanMatchingIdsSavedInLinks().
c_str());
1016 _ui->checkBox_localSpaceCreateGlobalScanMap->setObjectName(Parameters::kRGBDProximityGlobalScanMap().
c_str());
1017 _ui->spinBox_imagePreDecimation->setObjectName(Parameters::kMemImagePreDecimation().
c_str());
1018 _ui->spinBox_imagePostDecimation->setObjectName(Parameters::kMemImagePostDecimation().
c_str());
1019 _ui->general_spinBox_laserScanDownsample->setObjectName(Parameters::kMemLaserScanDownsampleStepSize().
c_str());
1020 _ui->general_doubleSpinBox_laserScanVoxelSize->setObjectName(Parameters::kMemLaserScanVoxelSize().
c_str());
1021 _ui->general_spinBox_laserScanNormalK->setObjectName(Parameters::kMemLaserScanNormalK().
c_str());
1022 _ui->general_doubleSpinBox_laserScanNormalRadius->setObjectName(Parameters::kMemLaserScanNormalRadius().
c_str());
1023 _ui->checkBox_useOdomFeatures->setObjectName(Parameters::kMemUseOdomFeatures().
c_str());
1024 _ui->memCovOffDiagIgnored->setObjectName(Parameters::kMemCovOffDiagIgnored().
c_str());
1025 _ui->general_checkBox_rotateImagesUpsideUp->setObjectName(Parameters::kMemRotateImagesUpsideUp().
c_str());
1028 _ui->checkBox_dbInMemory->setObjectName(Parameters::kDbSqlite3InMemory().
c_str());
1029 _ui->spinBox_dbCacheSize->setObjectName(Parameters::kDbSqlite3CacheSize().
c_str());
1030 _ui->comboBox_dbJournalMode->setObjectName(Parameters::kDbSqlite3JournalMode().
c_str());
1031 _ui->comboBox_dbSynchronous->setObjectName(Parameters::kDbSqlite3Synchronous().
c_str());
1032 _ui->comboBox_dbTempStore->setObjectName(Parameters::kDbSqlite3TempStore().
c_str());
1033 _ui->lineEdit_targetDatabaseVersion->setObjectName(Parameters::kDbTargetVersion().
c_str());
1037 _ui->general_doubleSpinBox_hardThr->setObjectName(Parameters::kRtabmapLoopThr().
c_str());
1038 _ui->general_doubleSpinBox_agressiveThr->setObjectName(Parameters::kRGBDAggressiveLoopThr().
c_str());
1039 _ui->general_doubleSpinBox_loopRatio->setObjectName(Parameters::kRtabmapLoopRatio().
c_str());
1040 _ui->comboBox_virtualPlaceLikelihoodRatio->setObjectName(Parameters::kRtabmapVirtualPlaceLikelihoodRatio().
c_str());
1041 _ui->comboBox_globalDescriptorExtractor->setObjectName(Parameters::kMemGlobalDescriptorStrategy().
c_str());
1045 _ui->general_doubleSpinBox_vp->setObjectName(Parameters::kBayesVirtualPlacePriorThr().
c_str());
1046 _ui->lineEdit_bayes_predictionLC->setObjectName(Parameters::kBayesPredictionLC().
c_str());
1047 _ui->checkBox_bayes_fullPredictionUpdate->setObjectName(Parameters::kBayesFullPredictionUpdate().
c_str());
1048 connect(
_ui->lineEdit_bayes_predictionLC, SIGNAL(textChanged(
const QString &)),
this, SLOT(
updatePredictionPlot()));
1051 _ui->comboBox_dictionary_strategy->setObjectName(Parameters::kKpNNStrategy().
c_str());
1052 _ui->checkBox_dictionary_incremental->setObjectName(Parameters::kKpIncrementalDictionary().
c_str());
1053 _ui->checkBox_kp_incrementalFlann->setObjectName(Parameters::kKpIncrementalFlann().
c_str());
1054 _ui->checkBox_kp_byteToFloat->setObjectName(Parameters::kKpByteToFloat().
c_str());
1055 _ui->surf_doubleSpinBox_rebalancingFactor->setObjectName(Parameters::kKpFlannRebalancingFactor().
c_str());
1056 _ui->comboBox_detector_strategy->setObjectName(Parameters::kKpDetectorStrategy().
c_str());
1057 _ui->surf_doubleSpinBox_nndrRatio->setObjectName(Parameters::kKpNndrRatio().
c_str());
1058 _ui->surf_doubleSpinBox_maxDepth->setObjectName(Parameters::kKpMaxDepth().
c_str());
1059 _ui->surf_doubleSpinBox_minDepth->setObjectName(Parameters::kKpMinDepth().
c_str());
1060 _ui->checkBox_memDepthAsMask->setObjectName(Parameters::kMemDepthAsMask().
c_str());
1061 _ui->doubleSpinBox_memDepthMaskFloorThr->setObjectName(Parameters::kMemDepthMaskFloorThr().
c_str());
1062 _ui->checkBox_memStereoFromMotion->setObjectName(Parameters::kMemStereoFromMotion().
c_str());
1063 _ui->surf_spinBox_wordsPerImageTarget->setObjectName(Parameters::kKpMaxFeatures().
c_str());
1064 _ui->checkBox_kp_ssc->setObjectName(Parameters::kKpSSC().
c_str());
1065 _ui->spinBox_KPGridRows->setObjectName(Parameters::kKpGridRows().
c_str());
1066 _ui->spinBox_KPGridCols->setObjectName(Parameters::kKpGridCols().
c_str());
1067 _ui->surf_doubleSpinBox_ratioBadSign->setObjectName(Parameters::kKpBadSignRatio().
c_str());
1068 _ui->checkBox_kp_tfIdfLikelihoodUsed->setObjectName(Parameters::kKpTfIdfLikelihoodUsed().
c_str());
1069 _ui->checkBox_kp_parallelized->setObjectName(Parameters::kKpParallelized().
c_str());
1070 _ui->lineEdit_kp_roi->setObjectName(Parameters::kKpRoiRatios().
c_str());
1071 _ui->lineEdit_dictionaryPath->setObjectName(Parameters::kKpDictionaryPath().
c_str());
1073 _ui->checkBox_kp_newWordsComparedTogether->setObjectName(Parameters::kKpNewWordsComparedTogether().
c_str());
1074 _ui->subpix_winSize_kp->setObjectName(Parameters::kKpSubPixWinSize().
c_str());
1075 _ui->subpix_iterations_kp->setObjectName(Parameters::kKpSubPixIterations().
c_str());
1076 _ui->subpix_eps_kp->setObjectName(Parameters::kKpSubPixEps().
c_str());
1078 _ui->subpix_winSize->setObjectName(Parameters::kKpSubPixWinSize().
c_str());
1079 _ui->subpix_iterations->setObjectName(Parameters::kKpSubPixIterations().
c_str());
1080 _ui->subpix_eps->setObjectName(Parameters::kKpSubPixEps().
c_str());
1083 _ui->surf_doubleSpinBox_hessianThr->setObjectName(Parameters::kSURFHessianThreshold().
c_str());
1084 _ui->surf_spinBox_octaves->setObjectName(Parameters::kSURFOctaves().
c_str());
1085 _ui->surf_spinBox_octaveLayers->setObjectName(Parameters::kSURFOctaveLayers().
c_str());
1086 _ui->checkBox_surfExtended->setObjectName(Parameters::kSURFExtended().
c_str());
1087 _ui->surf_checkBox_upright->setObjectName(Parameters::kSURFUpright().
c_str());
1088 _ui->surf_checkBox_gpuVersion->setObjectName(Parameters::kSURFGpuVersion().
c_str());
1089 _ui->surf_doubleSpinBox_gpuKeypointsRatio->setObjectName(Parameters::kSURFGpuKeypointsRatio().
c_str());
1092 _ui->sift_spinBox_nOctaveLayers->setObjectName(Parameters::kSIFTNOctaveLayers().
c_str());
1093 _ui->sift_doubleSpinBox_contrastThr->setObjectName(Parameters::kSIFTContrastThreshold().
c_str());
1094 _ui->sift_doubleSpinBox_edgeThr->setObjectName(Parameters::kSIFTEdgeThreshold().
c_str());
1095 _ui->sift_doubleSpinBox_sigma->setObjectName(Parameters::kSIFTSigma().
c_str());
1096 _ui->sift_checkBox_preciseUpscale->setObjectName(Parameters::kSIFTPreciseUpscale().
c_str());
1097 _ui->sift_checkBox_rootsift->setObjectName(Parameters::kSIFTRootSIFT().
c_str());
1098 _ui->sift_checkBox_gpu->setObjectName(Parameters::kSIFTGpu().
c_str());
1099 _ui->sift_doubleSpinBox_gaussianDiffThreshold->setObjectName(Parameters::kSIFTGaussianThreshold().
c_str());
1100 _ui->sift_checkBox_upscale->setObjectName(Parameters::kSIFTUpscale().
c_str());
1103 _ui->briefBytes->setObjectName(Parameters::kBRIEFBytes().
c_str());
1106 _ui->fastSuppressNonMax->setObjectName(Parameters::kFASTNonmaxSuppression().
c_str());
1107 _ui->fastThreshold->setObjectName(Parameters::kFASTThreshold().
c_str());
1108 _ui->fastThresholdMin->setObjectName(Parameters::kFASTMinThreshold().
c_str());
1109 _ui->fastThresholdMax->setObjectName(Parameters::kFASTMaxThreshold().
c_str());
1110 _ui->fastGridRows->setObjectName(Parameters::kFASTGridRows().
c_str());
1111 _ui->fastGridCols->setObjectName(Parameters::kFASTGridCols().
c_str());
1112 _ui->fastGpu->setObjectName(Parameters::kFASTGpu().
c_str());
1113 _ui->fastKeypointRatio->setObjectName(Parameters::kFASTGpuKeypointsRatio().
c_str());
1114 _ui->fastCV->setObjectName(Parameters::kFASTCV().
c_str());
1117 _ui->doubleSpinBox_ORBScaleFactor->setObjectName(Parameters::kORBScaleFactor().
c_str());
1118 _ui->spinBox_ORBNLevels->setObjectName(Parameters::kORBNLevels().
c_str());
1119 _ui->spinBox_ORBEdgeThreshold->setObjectName(Parameters::kORBEdgeThreshold().
c_str());
1120 _ui->spinBox_ORBFirstLevel->setObjectName(Parameters::kORBFirstLevel().
c_str());
1121 _ui->spinBox_ORBWTA_K->setObjectName(Parameters::kORBWTA_K().
c_str());
1122 _ui->spinBox_ORBScoreType->setObjectName(Parameters::kORBScoreType().
c_str());
1123 _ui->spinBox_ORBPatchSize->setObjectName(Parameters::kORBPatchSize().
c_str());
1124 _ui->checkBox_ORBGpu->setObjectName(Parameters::kORBGpu().
c_str());
1127 _ui->checkBox_FREAKOrientationNormalized->setObjectName(Parameters::kFREAKOrientationNormalized().
c_str());
1128 _ui->checkBox_FREAKScaleNormalized->setObjectName(Parameters::kFREAKScaleNormalized().
c_str());
1129 _ui->doubleSpinBox_FREAKPatternScale->setObjectName(Parameters::kFREAKPatternScale().
c_str());
1130 _ui->spinBox_FREAKNOctaves->setObjectName(Parameters::kFREAKNOctaves().
c_str());
1133 _ui->doubleSpinBox_GFTT_qualityLevel->setObjectName(Parameters::kGFTTQualityLevel().
c_str());
1134 _ui->doubleSpinBox_GFTT_minDistance->setObjectName(Parameters::kGFTTMinDistance().
c_str());
1135 _ui->spinBox_GFTT_blockSize->setObjectName(Parameters::kGFTTBlockSize().
c_str());
1136 _ui->checkBox_GFTT_useHarrisDetector->setObjectName(Parameters::kGFTTUseHarrisDetector().
c_str());
1137 _ui->doubleSpinBox_GFTT_k->setObjectName(Parameters::kGFTTK().
c_str());
1138 _ui->checkBox_GFTT_gpu->setObjectName(Parameters::kGFTTGpu().
c_str());
1141 _ui->spinBox_BRISK_thresh->setObjectName(Parameters::kBRISKThresh().
c_str());
1142 _ui->spinBox_BRISK_octaves->setObjectName(Parameters::kBRISKOctaves().
c_str());
1143 _ui->doubleSpinBox_BRISK_patterScale->setObjectName(Parameters::kBRISKPatternScale().
c_str());
1146 _ui->checkBox_kaze_extended->setObjectName(Parameters::kKAZEExtended().
c_str());
1147 _ui->checkBox_kaze_upright->setObjectName(Parameters::kKAZEUpright().
c_str());
1148 _ui->doubleSpinBox_kaze_threshold->setObjectName(Parameters::kKAZEThreshold().
c_str());
1149 _ui->spinBox_kaze_octaves->setObjectName(Parameters::kKAZENOctaves().
c_str());
1150 _ui->spinBox_kaze_octavelayers->setObjectName(Parameters::kKAZENOctaveLayers().
c_str());
1151 _ui->spinBox_kaze_diffusivity->setObjectName(Parameters::kKAZEDiffusivity().
c_str());
1154 _ui->lineEdit_sptorch_path->setObjectName(Parameters::kSuperPointModelPath().
c_str());
1156 _ui->doubleSpinBox_sptorch_threshold->setObjectName(Parameters::kSuperPointThreshold().
c_str());
1157 _ui->checkBox_sptorch_nms->setObjectName(Parameters::kSuperPointNMS().
c_str());
1158 _ui->spinBox_sptorch_minDistance->setObjectName(Parameters::kSuperPointNMSRadius().
c_str());
1159 _ui->checkBox_sptorch_cuda->setObjectName(Parameters::kSuperPointCuda().
c_str());
1162 _ui->lineEdit_pymatcher_path->setObjectName(Parameters::kPyMatcherPath().
c_str());
1164 _ui->pymatcher_matchThreshold->setObjectName(Parameters::kPyMatcherThreshold().
c_str());
1165 _ui->pymatcher_iterations->setObjectName(Parameters::kPyMatcherIterations().
c_str());
1166 _ui->checkBox_pymatcher_cuda->setObjectName(Parameters::kPyMatcherCuda().
c_str());
1167 _ui->lineEdit_pymatcher_model->setObjectName(Parameters::kPyMatcherModel().
c_str());
1171 _ui->lineEdit_pydetector_path->setObjectName(Parameters::kPyDetectorPath().
c_str());
1173 _ui->checkBox_pydetector_cuda->setObjectName(Parameters::kPyDetectorCuda().
c_str());
1176 _ui->checkBox_gms_withRotation->setObjectName(Parameters::kGMSWithRotation().
c_str());
1177 _ui->checkBox_gms_withScale->setObjectName(Parameters::kGMSWithScale().
c_str());
1178 _ui->gms_thresholdFactor->setObjectName(Parameters::kGMSThresholdFactor().
c_str());
1181 _ui->lineEdit_pydescriptor_path->setObjectName(Parameters::kPyDescriptorPath().
c_str());
1183 _ui->pydescriptor_dim->setObjectName(Parameters::kPyDescriptorDim().
c_str());
1186 _ui->groupBox_vh_epipolar2->setObjectName(Parameters::kVhEpEnabled().
c_str());
1187 _ui->surf_spinBox_matchCountMinAccepted->setObjectName(Parameters::kVhEpMatchCountMin().
c_str());
1188 _ui->surf_doubleSpinBox_ransacParam1->setObjectName(Parameters::kVhEpRansacParam1().
c_str());
1189 _ui->surf_doubleSpinBox_ransacParam2->setObjectName(Parameters::kVhEpRansacParam2().
c_str());
1192 _ui->general_checkBox_activateRGBD->setObjectName(Parameters::kRGBDEnabled().
c_str());
1193 _ui->rgdb_linearUpdate->setObjectName(Parameters::kRGBDLinearUpdate().
c_str());
1194 _ui->rgdb_angularUpdate->setObjectName(Parameters::kRGBDAngularUpdate().
c_str());
1195 _ui->rgdb_linearSpeedUpdate->setObjectName(Parameters::kRGBDLinearSpeedUpdate().
c_str());
1196 _ui->rgdb_angularSpeedUpdate->setObjectName(Parameters::kRGBDAngularSpeedUpdate().
c_str());
1197 _ui->rgbd_forceOdom3DoF->setObjectName(Parameters::kRGBDForceOdom3DoF().
c_str());
1198 _ui->rgbd_savedLocalizationIgnored->setObjectName(Parameters::kRGBDStartAtOrigin().
c_str());
1199 _ui->rgdb_rehearsalWeightIgnoredWhileMoving->setObjectName(Parameters::kMemRehearsalWeightIgnoredWhileMoving().
c_str());
1200 _ui->rgdb_newMapOdomChange->setObjectName(Parameters::kRGBDNewMapOdomChangeDistance().
c_str());
1201 _ui->odomScanHistory->setObjectName(Parameters::kRGBDNeighborLinkRefining().
c_str());
1202 _ui->odomGravity->setObjectName(Parameters::kMemUseOdomGravity().
c_str());
1203 _ui->spinBox_maxLocalLocationsRetrieved->setObjectName(Parameters::kRGBDMaxLocalRetrieved().
c_str());
1204 _ui->rgbd_loopCovLimited->setObjectName(Parameters::kRGBDLoopCovLimited().
c_str());
1206 _ui->graphOptimization_type->setObjectName(Parameters::kOptimizerStrategy().
c_str());
1207 _ui->graphOptimization_iterations->setObjectName(Parameters::kOptimizerIterations().
c_str());
1208 _ui->graphOptimization_covarianceIgnored->setObjectName(Parameters::kOptimizerVarianceIgnored().
c_str());
1209 _ui->graphOptimization_fromGraphEnd->setObjectName(Parameters::kRGBDOptimizeFromGraphEnd().
c_str());
1210 _ui->graphOptimization_maxError->setObjectName(Parameters::kRGBDOptimizeMaxError().
c_str());
1211 _ui->graphOptimization_gravitySigma->setObjectName(Parameters::kOptimizerGravitySigma().
c_str());
1212 _ui->graphOptimization_stopEpsilon->setObjectName(Parameters::kOptimizerEpsilon().
c_str());
1213 _ui->graphOptimization_robust->setObjectName(Parameters::kOptimizerRobust().
c_str());
1214 _ui->graphOptimization_priorsIgnored->setObjectName(Parameters::kOptimizerPriorsIgnored().
c_str());
1215 _ui->graphOptimization_landmarksIgnored->setObjectName(Parameters::kOptimizerLandmarksIgnored().
c_str());
1217 _ui->comboBox_g2o_solver->setObjectName(Parameters::kg2oSolver().
c_str());
1218 _ui->comboBox_g2o_optimizer->setObjectName(Parameters::kg2oOptimizer().
c_str());
1219 _ui->doubleSpinBox_g2o_pixelVariance->setObjectName(Parameters::kg2oPixelVariance().
c_str());
1220 _ui->doubleSpinBox_g2o_robustKernelDelta->setObjectName(Parameters::kg2oRobustKernelDelta().
c_str());
1221 _ui->doubleSpinBox_g2o_baseline->setObjectName(Parameters::kg2oBaseline().
c_str());
1223 _ui->comboBox_gtsam_optimizer->setObjectName(Parameters::kGTSAMOptimizer().
c_str());
1224 _ui->gtsam_incremental->setObjectName(Parameters::kGTSAMIncremental().
c_str());
1225 _ui->gtsam_incremental_threshold->setObjectName(Parameters::kGTSAMIncRelinearizeThreshold().
c_str());
1226 _ui->gtsam_incremental_skip->setObjectName(Parameters::kGTSAMIncRelinearizeSkip().
c_str());
1228 _ui->graphPlan_goalReachedRadius->setObjectName(Parameters::kRGBDGoalReachedRadius().
c_str());
1229 _ui->graphPlan_goalsSavedInUserData->setObjectName(Parameters::kRGBDGoalsSavedInUserData().
c_str());
1230 _ui->graphPlan_stuckIterations->setObjectName(Parameters::kRGBDPlanStuckIterations().
c_str());
1231 _ui->graphPlan_linearVelocity->setObjectName(Parameters::kRGBDPlanLinearVelocity().
c_str());
1232 _ui->graphPlan_angularVelocity->setObjectName(Parameters::kRGBDPlanAngularVelocity().
c_str());
1234 _ui->groupBox_localDetection_time->setObjectName(Parameters::kRGBDProximityByTime().
c_str());
1235 _ui->groupBox_localDetection_space->setObjectName(Parameters::kRGBDProximityBySpace().
c_str());
1236 _ui->localDetection_radius->setObjectName(Parameters::kRGBDLocalRadius().
c_str());
1237 _ui->maxLocalizationDistance->setObjectName(Parameters::kRGBDMaxLoopClosureDistance().
c_str());
1238 _ui->localDetection_maxDiffID->setObjectName(Parameters::kRGBDProximityMaxGraphDepth().
c_str());
1239 _ui->localDetection_maxNeighbors->setObjectName(Parameters::kRGBDProximityPathMaxNeighbors().
c_str());
1240 _ui->localDetection_maxPaths->setObjectName(Parameters::kRGBDProximityMaxPaths().
c_str());
1241 _ui->localDetection_pathFilteringRadius->setObjectName(Parameters::kRGBDProximityPathFilteringRadius().
c_str());
1242 _ui->localDetection_angle->setObjectName(Parameters::kRGBDProximityAngle().
c_str());
1243 _ui->localDetection_mergedScanCovFactor->setObjectName(Parameters::kRGBDProximityMergedScanCovFactor().
c_str());
1244 _ui->checkBox_localSpaceOdomGuess->setObjectName(Parameters::kRGBDProximityOdomGuess().
c_str());
1245 _ui->checkBox_localSpacePathOdomPosesUsed->setObjectName(Parameters::kRGBDProximityPathRawPosesUsed().
c_str());
1246 _ui->rgdb_localImmunizationRatio->setObjectName(Parameters::kRGBDLocalImmunizationRatio().
c_str());
1247 _ui->loopClosure_identityGuess->setObjectName(Parameters::kRGBDLoopClosureIdentityGuess().
c_str());
1248 _ui->loopClosure_reextract->setObjectName(Parameters::kRGBDLoopClosureReextractFeatures().
c_str());
1249 _ui->loopClosure_bunlde->setObjectName(Parameters::kRGBDLocalBundleOnLoopClosure().
c_str());
1250 _ui->loopClosure_invertedReg->setObjectName(Parameters::kRGBDInvertedReg().
c_str());
1251 _ui->checkbox_rgbd_createOccupancyGrid->setObjectName(Parameters::kRGBDCreateOccupancyGrid().
c_str());
1252 _ui->RGBDMarkerDetection->setObjectName(Parameters::kRGBDMarkerDetection().
c_str());
1253 _ui->spinBox_maxOdomCacheSize->setObjectName(Parameters::kRGBDMaxOdomCacheSize().
c_str());
1254 _ui->checkbox_localizationSmoothing->setObjectName(Parameters::kRGBDLocalizationSmoothing().
c_str());
1255 _ui->doubleSpinBox_localizationPriorError->setObjectName(Parameters::kRGBDLocalizationPriorError().
c_str());
1258 _ui->reg_repeatOnce->setObjectName(Parameters::kRegRepeatOnce().
c_str());
1259 _ui->comboBox_registrationStrategy->setObjectName(Parameters::kRegStrategy().
c_str());
1260 _ui->loopClosure_bowForce2D->setObjectName(Parameters::kRegForce3DoF().
c_str());
1263 _ui->loopClosure_bowMinInliers->setObjectName(Parameters::kVisMinInliers().
c_str());
1264 _ui->loopClosure_bowInlierDistance->setObjectName(Parameters::kVisInlierDistance().
c_str());
1265 _ui->loopClosure_bowIterations->setObjectName(Parameters::kVisIterations().
c_str());
1266 _ui->loopClosure_bowRefineIterations->setObjectName(Parameters::kVisRefineIterations().
c_str());
1267 _ui->visMeanDistance->setObjectName(Parameters::kVisMeanInliersDistance().
c_str());
1268 _ui->visMinDistribution->setObjectName(Parameters::kVisMinInliersDistribution().
c_str());
1269 _ui->loopClosure_estimationType->setObjectName(Parameters::kVisEstimationType().
c_str());
1270 connect(
_ui->loopClosure_estimationType, SIGNAL(currentIndexChanged(
int)),
_ui->stackedWidget_loopClosureEstimation, SLOT(setCurrentIndex(
int)));
1271 _ui->stackedWidget_loopClosureEstimation->setCurrentIndex(Parameters::defaultVisEstimationType());
1272 _ui->loopClosure_forwardEst->setObjectName(Parameters::kVisForwardEstOnly().
c_str());
1273 _ui->loopClosure_bowEpipolarGeometryVar->setObjectName(Parameters::kVisEpipolarGeometryVar().
c_str());
1274 _ui->loopClosure_pnpReprojError->setObjectName(Parameters::kVisPnPReprojError().
c_str());
1275 _ui->loopClosure_pnpFlags->setObjectName(Parameters::kVisPnPFlags().
c_str());
1276 _ui->loopClosure_pnpRefineIterations->setObjectName(Parameters::kVisPnPRefineIterations().
c_str());
1277 _ui->loopClosure_pnpVarMedianRatio->setObjectName(Parameters::kVisPnPVarianceMedianRatio().
c_str());
1278 _ui->loopClosure_pnpMaxVariance->setObjectName(Parameters::kVisPnPMaxVariance().
c_str());
1279 _ui->loopClosure_pnpSamplingPolicy->setObjectName(Parameters::kVisPnPSamplingPolicy().
c_str());
1280 _ui->loopClosure_pnpSplitLinearCovComponents->setObjectName(Parameters::kVisPnPSplitLinearCovComponents().
c_str());
1281 _ui->reextract_nn->setObjectName(Parameters::kVisCorNNType().
c_str());
1283 _ui->reextract_nndrRatio->setObjectName(Parameters::kVisCorNNDR().
c_str());
1284 _ui->spinBox_visCorGuessWinSize->setObjectName(Parameters::kVisCorGuessWinSize().
c_str());
1285 _ui->checkBox_visCorGuessMatchToProjection->setObjectName(Parameters::kVisCorGuessMatchToProjection().
c_str());
1286 _ui->vis_feature_detector->setObjectName(Parameters::kVisFeatureType().
c_str());
1287 _ui->reextract_maxFeatures->setObjectName(Parameters::kVisMaxFeatures().
c_str());
1288 _ui->checkBox_visSSC->setObjectName(Parameters::kVisSSC().
c_str());
1289 _ui->reextract_gridrows->setObjectName(Parameters::kVisGridRows().
c_str());
1290 _ui->reextract_gridcols->setObjectName(Parameters::kVisGridCols().
c_str());
1291 _ui->loopClosure_bowMaxDepth->setObjectName(Parameters::kVisMaxDepth().
c_str());
1292 _ui->loopClosure_bowMinDepth->setObjectName(Parameters::kVisMinDepth().
c_str());
1293 _ui->checkBox_visDepthAsMask->setObjectName(Parameters::kVisDepthAsMask().
c_str());
1294 _ui->doubleSpinBox_visDepthMaskFloorThr->setObjectName(Parameters::kVisDepthMaskFloorThr().
c_str());
1295 _ui->loopClosure_roi->setObjectName(Parameters::kVisRoiRatios().
c_str());
1296 _ui->subpix_winSize->setObjectName(Parameters::kVisSubPixWinSize().
c_str());
1297 _ui->subpix_iterations->setObjectName(Parameters::kVisSubPixIterations().
c_str());
1298 _ui->subpix_eps->setObjectName(Parameters::kVisSubPixEps().
c_str());
1299 _ui->odom_flow_winSize->setObjectName(Parameters::kVisCorFlowWinSize().
c_str());
1300 _ui->odom_flow_maxLevel->setObjectName(Parameters::kVisCorFlowMaxLevel().
c_str());
1301 _ui->odom_flow_iterations->setObjectName(Parameters::kVisCorFlowIterations().
c_str());
1302 _ui->odom_flow_eps->setObjectName(Parameters::kVisCorFlowEps().
c_str());
1303 _ui->odom_flow_gpu->setObjectName(Parameters::kVisCorFlowGpu().
c_str());
1304 _ui->loopClosure_bundle->setObjectName(Parameters::kVisBundleAdjustment().
c_str());
1307 _ui->comboBox_icpStrategy->setObjectName(Parameters::kIcpStrategy().
c_str());
1308 connect(
_ui->comboBox_icpStrategy, SIGNAL(currentIndexChanged(
int)),
_ui->stackedWidget_icpStrategy, SLOT(setCurrentIndex(
int)));
1309 _ui->comboBox_icpStrategy->setCurrentIndex(Parameters::defaultIcpStrategy());
1310 _ui->globalDetection_icpMaxTranslation->setObjectName(Parameters::kIcpMaxTranslation().
c_str());
1311 _ui->globalDetection_icpMaxRotation->setObjectName(Parameters::kIcpMaxRotation().
c_str());
1312 _ui->loopClosure_icpVoxelSize->setObjectName(Parameters::kIcpVoxelSize().
c_str());
1313 _ui->loopClosure_icpDownsamplingStep->setObjectName(Parameters::kIcpDownsamplingStep().
c_str());
1314 _ui->loopClosure_icpRangeMin->setObjectName(Parameters::kIcpRangeMin().
c_str());
1315 _ui->loopClosure_icpRangeMax->setObjectName(Parameters::kIcpRangeMax().
c_str());
1316 _ui->loopClosure_icpFiltersEnabled->setObjectName(Parameters::kIcpFiltersEnabled().
c_str());
1317 _ui->loopClosure_icpMaxCorrespondenceDistance->setObjectName(Parameters::kIcpMaxCorrespondenceDistance().
c_str());
1318 _ui->loopClosure_icpReciprocalCorrespondences->setObjectName(Parameters::kIcpReciprocalCorrespondences().
c_str());
1319 _ui->loopClosure_icpIterations->setObjectName(Parameters::kIcpIterations().
c_str());
1320 _ui->loopClosure_icpEpsilon->setObjectName(Parameters::kIcpEpsilon().
c_str());
1321 _ui->loopClosure_icpRatio->setObjectName(Parameters::kIcpCorrespondenceRatio().
c_str());
1322 _ui->doubleSpinBox_icpOutlierRatio->setObjectName(Parameters::kIcpOutlierRatio().
c_str());
1323 _ui->loopClosure_icpPointToPlane->setObjectName(Parameters::kIcpPointToPlane().
c_str());
1324 _ui->loopClosure_icpPointToPlaneNormals->setObjectName(Parameters::kIcpPointToPlaneK().
c_str());
1325 _ui->loopClosure_icpPointToPlaneNormalsRadius->setObjectName(Parameters::kIcpPointToPlaneRadius().
c_str());
1326 _ui->loopClosure_icpPointToPlaneGroundNormalsUp->setObjectName(Parameters::kIcpPointToPlaneGroundNormalsUp().
c_str());
1327 _ui->loopClosure_icpPointToPlaneNormalsMinComplexity->setObjectName(Parameters::kIcpPointToPlaneMinComplexity().
c_str());
1328 _ui->loopClosure_icpPointToPlaneLowComplexityStrategy->setObjectName(Parameters::kIcpPointToPlaneLowComplexityStrategy().
c_str());
1329 _ui->loopClosure_icpDebugExportFormat->setObjectName(Parameters::kIcpDebugExportFormat().
c_str());
1331 _ui->lineEdit_IcpPMConfigPath->setObjectName(Parameters::kIcpPMConfig().
c_str());
1333 _ui->spinBox_icpPMMatcherKnn->setObjectName(Parameters::kIcpPMMatcherKnn().
c_str());
1334 _ui->doubleSpinBox_icpPMMatcherEpsilon->setObjectName(Parameters::kIcpPMMatcherEpsilon().
c_str());
1335 _ui->loopClosure_icpPMMatcherIntensity->setObjectName(Parameters::kIcpPMMatcherIntensity().
c_str());
1336 _ui->loopClosure_icpForce4DoF->setObjectName(Parameters::kIcpForce4DoF().
c_str());
1338 _ui->spinBox_icpCCSamplingLimit->setObjectName(Parameters::kIcpCCSamplingLimit().
c_str());
1339 _ui->checkBox_icpCCFilterOutFarthestPoints->setObjectName(Parameters::kIcpCCFilterOutFarthestPoints().
c_str());
1340 _ui->doubleSpinBox_icpCCMaxFinalRMS->setObjectName(Parameters::kIcpCCMaxFinalRMS().
c_str());
1344 _ui->groupBox_grid_3d->setObjectName(Parameters::kGrid3D().
c_str());
1345 _ui->checkBox_grid_groundObstacle->setObjectName(Parameters::kGridGroundIsObstacle().
c_str());
1346 _ui->doubleSpinBox_grid_resolution->setObjectName(Parameters::kGridCellSize().
c_str());
1347 _ui->checkBox_grid_preVoxelFiltering->setObjectName(Parameters::kGridPreVoxelFiltering().
c_str());
1348 _ui->spinBox_grid_decimation->setObjectName(Parameters::kGridDepthDecimation().
c_str());
1349 _ui->doubleSpinBox_grid_maxDepth->setObjectName(Parameters::kGridRangeMax().
c_str());
1350 _ui->doubleSpinBox_grid_minDepth->setObjectName(Parameters::kGridRangeMin().
c_str());
1351 _ui->lineEdit_grid_roi->setObjectName(Parameters::kGridDepthRoiRatios().
c_str());
1352 _ui->checkBox_grid_projRayTracing->setObjectName(Parameters::kGridRayTracing().
c_str());
1353 _ui->doubleSpinBox_grid_footprintLength->setObjectName(Parameters::kGridFootprintLength().
c_str());
1354 _ui->doubleSpinBox_grid_footprintWidth->setObjectName(Parameters::kGridFootprintWidth().
c_str());
1355 _ui->doubleSpinBox_grid_footprintHeight->setObjectName(Parameters::kGridFootprintHeight().
c_str());
1356 _ui->checkBox_grid_flatObstaclesDetected->setObjectName(Parameters::kGridFlatObstacleDetected().
c_str());
1357 _ui->comboBox_grid_sensor->setObjectName(Parameters::kGridSensor().
c_str());
1358 _ui->checkBox_grid_projMapFrame->setObjectName(Parameters::kGridMapFrameProjection().
c_str());
1359 _ui->doubleSpinBox_grid_maxGroundAngle->setObjectName(Parameters::kGridMaxGroundAngle().
c_str());
1360 _ui->spinBox_grid_normalK->setObjectName(Parameters::kGridNormalK().
c_str());
1361 _ui->doubleSpinBox_grid_maxGroundHeight->setObjectName(Parameters::kGridMaxGroundHeight().
c_str());
1362 _ui->doubleSpinBox_grid_maxObstacleHeight->setObjectName(Parameters::kGridMaxObstacleHeight().
c_str());
1363 _ui->doubleSpinBox_grid_clusterRadius->setObjectName(Parameters::kGridClusterRadius().
c_str());
1364 _ui->spinBox_grid_minClusterSize->setObjectName(Parameters::kGridMinClusterSize().
c_str());
1365 _ui->doubleSpinBox_grid_minGroundHeight->setObjectName(Parameters::kGridMinGroundHeight().
c_str());
1366 _ui->spinBox_grid_noiseMinNeighbors->setObjectName(Parameters::kGridNoiseFilteringMinNeighbors().
c_str());
1367 _ui->doubleSpinBox_grid_noiseRadius->setObjectName(Parameters::kGridNoiseFilteringRadius().
c_str());
1368 _ui->groupBox_grid_normalsSegmentation->setObjectName(Parameters::kGridNormalsSegmentation().
c_str());
1369 _ui->checkBox_grid_unknownSpaceFilled->setObjectName(Parameters::kGridScan2dUnknownSpaceFilled().
c_str());
1370 _ui->spinBox_grid_scanDecimation->setObjectName(Parameters::kGridScanDecimation().
c_str());
1372 _ui->doubleSpinBox_grid_updateError->setObjectName(Parameters::kGridGlobalUpdateError().
c_str());
1373 _ui->doubleSpinBox_grid_minMapSize->setObjectName(Parameters::kGridGlobalMinSize().
c_str());
1374 _ui->spinBox_grid_maxNodes->setObjectName(Parameters::kGridGlobalMaxNodes().
c_str());
1375 _ui->doubleSpinBox_grid_altitudeDelta->setObjectName(Parameters::kGridGlobalAltitudeDelta().
c_str());
1376 _ui->doubleSpinBox_grid_footprintRadius->setObjectName(Parameters::kGridGlobalFootprintRadius().
c_str());
1377 _ui->doubleSpinBox_grid_occThr->setObjectName(Parameters::kGridGlobalOccupancyThr().
c_str());
1378 _ui->doubleSpinBox_grid_probHit->setObjectName(Parameters::kGridGlobalProbHit().
c_str());
1379 _ui->doubleSpinBox_grid_probMiss->setObjectName(Parameters::kGridGlobalProbMiss().
c_str());
1380 _ui->doubleSpinBox_grid_clampingMin->setObjectName(Parameters::kGridGlobalProbClampingMin().
c_str());
1381 _ui->doubleSpinBox_grid_clampingMax->setObjectName(Parameters::kGridGlobalProbClampingMax().
c_str());
1382 _ui->checkBox_grid_erode->setObjectName(Parameters::kGridGlobalEroded().
c_str());
1383 _ui->spinBox_grid_floodfilldepth->setObjectName(Parameters::kGridGlobalFloodFillDepth().
c_str());
1386 _ui->odom_strategy->setObjectName(Parameters::kOdomStrategy().
c_str());
1388 _ui->odom_strategy->setCurrentIndex(Parameters::defaultOdomStrategy());
1390 _ui->odom_countdown->setObjectName(Parameters::kOdomResetCountdown().
c_str());
1391 _ui->odom_holonomic->setObjectName(Parameters::kOdomHolonomic().
c_str());
1392 _ui->odom_fillInfoData->setObjectName(Parameters::kOdomFillInfoData().
c_str());
1393 _ui->odom_dataBufferSize->setObjectName(Parameters::kOdomImageBufferSize().
c_str());
1394 _ui->odom_flow_keyframeThr->setObjectName(Parameters::kOdomKeyFrameThr().
c_str());
1395 _ui->odom_VisKeyFrameThr->setObjectName(Parameters::kOdomVisKeyFrameThr().
c_str());
1396 _ui->odom_flow_scanKeyframeThr->setObjectName(Parameters::kOdomScanKeyFrameThr().
c_str());
1397 _ui->odom_flow_guessMotion->setObjectName(Parameters::kOdomGuessMotion().
c_str());
1398 _ui->odom_guess_smoothing_delay->setObjectName(Parameters::kOdomGuessSmoothingDelay().
c_str());
1399 _ui->odom_imageDecimation->setObjectName(Parameters::kOdomImageDecimation().
c_str());
1400 _ui->odom_alignWithGround->setObjectName(Parameters::kOdomAlignWithGround().
c_str());
1401 _ui->odom_lidar_deskewing->setObjectName(Parameters::kOdomDeskewing().
c_str());
1404 _ui->odom_localHistory->setObjectName(Parameters::kOdomF2MMaxSize().
c_str());
1405 _ui->spinBox_odom_f2m_maxNewFeatures->setObjectName(Parameters::kOdomF2MMaxNewFeatures().
c_str());
1406 _ui->spinBox_odom_f2m_scanMaxSize->setObjectName(Parameters::kOdomF2MScanMaxSize().
c_str());
1407 _ui->doubleSpinBox_odom_f2m_scanRadius->setObjectName(Parameters::kOdomF2MScanSubtractRadius().
c_str());
1408 _ui->doubleSpinBox_odom_f2m_scanAngle->setObjectName(Parameters::kOdomF2MScanSubtractAngle().
c_str());
1409 _ui->doubleSpinBox_odom_f2m_scanRange->setObjectName(Parameters::kOdomF2MScanRange().
c_str());
1410 _ui->odom_f2m_validDepthRatio->setObjectName(Parameters::kOdomF2MValidDepthRatio().
c_str());
1411 _ui->odom_f2m_bundleStrategy->setObjectName(Parameters::kOdomF2MBundleAdjustment().
c_str());
1412 _ui->odom_f2m_bundleMaxFrames->setObjectName(Parameters::kOdomF2MBundleAdjustmentMaxFrames().
c_str());
1415 _ui->comboBox_odomf2f_corType->setObjectName(Parameters::kVisCorType().
c_str());
1418 _ui->doubleSpinBox_minFlow->setObjectName(Parameters::kOdomMonoInitMinFlow().
c_str());
1419 _ui->doubleSpinBox_minInitTranslation->setObjectName(Parameters::kOdomMonoInitMinTranslation().
c_str());
1420 _ui->doubleSpinBox_minTranslation->setObjectName(Parameters::kOdomMonoMinTranslation().
c_str());
1421 _ui->doubleSpinBox_maxVariance->setObjectName(Parameters::kOdomMonoMaxVariance().
c_str());
1424 _ui->odom_filteringStrategy->setObjectName(Parameters::kOdomFilteringStrategy().
c_str());
1425 _ui->stackedWidget_odometryFiltering->setCurrentIndex(
_ui->odom_filteringStrategy->currentIndex());
1426 connect(
_ui->odom_filteringStrategy, SIGNAL(currentIndexChanged(
int)),
_ui->stackedWidget_odometryFiltering, SLOT(setCurrentIndex(
int)));
1427 _ui->spinBox_particleSize->setObjectName(Parameters::kOdomParticleSize().
c_str());
1428 _ui->doubleSpinBox_particleNoiseT->setObjectName(Parameters::kOdomParticleNoiseT().
c_str());
1429 _ui->doubleSpinBox_particleLambdaT->setObjectName(Parameters::kOdomParticleLambdaT().
c_str());
1430 _ui->doubleSpinBox_particleNoiseR->setObjectName(Parameters::kOdomParticleNoiseR().
c_str());
1431 _ui->doubleSpinBox_particleLambdaR->setObjectName(Parameters::kOdomParticleLambdaR().
c_str());
1434 _ui->doubleSpinBox_kalmanProcessNoise->setObjectName(Parameters::kOdomKalmanProcessNoise().
c_str());
1435 _ui->doubleSpinBox_kalmanMeasurementNoise->setObjectName(Parameters::kOdomKalmanMeasurementNoise().
c_str());
1438 _ui->spinBox_OdomFovisFeatureWindowSize->setObjectName(Parameters::kOdomFovisFeatureWindowSize().
c_str());
1439 _ui->spinBox_OdomFovisMaxPyramidLevel->setObjectName(Parameters::kOdomFovisMaxPyramidLevel().
c_str());
1440 _ui->spinBox_OdomFovisMinPyramidLevel->setObjectName(Parameters::kOdomFovisMinPyramidLevel().
c_str());
1441 _ui->spinBox_OdomFovisTargetPixelsPerFeature->setObjectName(Parameters::kOdomFovisTargetPixelsPerFeature().
c_str());
1442 _ui->spinBox_OdomFovisFastThreshold->setObjectName(Parameters::kOdomFovisFastThreshold().
c_str());
1443 _ui->checkBox_OdomFovisUseAdaptiveThreshold->setObjectName(Parameters::kOdomFovisUseAdaptiveThreshold().
c_str());
1444 _ui->doubleSpinBox_OdomFovisFastThresholdAdaptiveGain->setObjectName(Parameters::kOdomFovisFastThresholdAdaptiveGain().
c_str());
1445 _ui->checkBox_OdomFovisUseHomographyInitialization->setObjectName(Parameters::kOdomFovisUseHomographyInitialization().
c_str());
1447 _ui->checkBox_OdomFovisUseBucketing->setObjectName(Parameters::kOdomFovisUseBucketing().
c_str());
1448 _ui->spinBox_OdomFovisBucketWidth->setObjectName(Parameters::kOdomFovisBucketWidth().
c_str());
1449 _ui->spinBox_OdomFovisBucketHeight->setObjectName(Parameters::kOdomFovisBucketHeight().
c_str());
1450 _ui->spinBox_OdomFovisMaxKeypointsPerBucket->setObjectName(Parameters::kOdomFovisMaxKeypointsPerBucket().
c_str());
1451 _ui->checkBox_OdomFovisUseImageNormalization->setObjectName(Parameters::kOdomFovisUseImageNormalization().
c_str());
1453 _ui->doubleSpinBox_OdomFovisInlierMaxReprojectionError->setObjectName(Parameters::kOdomFovisInlierMaxReprojectionError().
c_str());
1454 _ui->doubleSpinBox_OdomFovisCliqueInlierThreshold->setObjectName(Parameters::kOdomFovisCliqueInlierThreshold().
c_str());
1455 _ui->spinBox_OdomFovisMinFeaturesForEstimate->setObjectName(Parameters::kOdomFovisMinFeaturesForEstimate().
c_str());
1456 _ui->doubleSpinBox_OdomFovisMaxMeanReprojectionError->setObjectName(Parameters::kOdomFovisMaxMeanReprojectionError().
c_str());
1457 _ui->checkBox_OdomFovisUseSubpixelRefinement->setObjectName(Parameters::kOdomFovisUseSubpixelRefinement().
c_str());
1458 _ui->spinBox_OdomFovisFeatureSearchWindow->setObjectName(Parameters::kOdomFovisFeatureSearchWindow().
c_str());
1459 _ui->checkBox_OdomFovisUpdateTargetFeaturesWithRefined->setObjectName(Parameters::kOdomFovisUpdateTargetFeaturesWithRefined().
c_str());
1461 _ui->checkBox_OdomFovisStereoRequireMutualMatch->setObjectName(Parameters::kOdomFovisStereoRequireMutualMatch().
c_str());
1462 _ui->doubleSpinBox_OdomFovisStereoMaxDistEpipolarLine->setObjectName(Parameters::kOdomFovisStereoMaxDistEpipolarLine().
c_str());
1463 _ui->doubleSpinBox_OdomFovisStereoMaxRefinementDisplacement->setObjectName(Parameters::kOdomFovisStereoMaxRefinementDisplacement().
c_str());
1464 _ui->spinBox_OdomFovisStereoMaxDisparity->setObjectName(Parameters::kOdomFovisStereoMaxDisparity().
c_str());
1467 _ui->spinBox_OdomViso2RansacIters->setObjectName(Parameters::kOdomViso2RansacIters().
c_str());
1468 _ui->doubleSpinBox_OdomViso2InlierThreshold->setObjectName(Parameters::kOdomViso2InlierThreshold().
c_str());
1469 _ui->checkBox_OdomViso2Reweighting->setObjectName(Parameters::kOdomViso2Reweighting().
c_str());
1471 _ui->spinBox_OdomViso2MatchNmsN->setObjectName(Parameters::kOdomViso2MatchNmsN().
c_str());
1472 _ui->spinBox_OdomViso2MatchNmsTau->setObjectName(Parameters::kOdomViso2MatchNmsTau().
c_str());
1473 _ui->spinBox_OdomViso2MatchBinsize->setObjectName(Parameters::kOdomViso2MatchBinsize().
c_str());
1474 _ui->spinBox_OdomViso2MatchRadius->setObjectName(Parameters::kOdomViso2MatchRadius().
c_str());
1475 _ui->spinBox_OdomViso2MatchDispTolerance->setObjectName(Parameters::kOdomViso2MatchDispTolerance().
c_str());
1476 _ui->spinBox_OdomViso2MatchOutlierDispTolerance->setObjectName(Parameters::kOdomViso2MatchOutlierDispTolerance().
c_str());
1477 _ui->spinBox_OdomViso2MatchOutlierFlowTolerance->setObjectName(Parameters::kOdomViso2MatchOutlierFlowTolerance().
c_str());
1478 _ui->checkBox_OdomViso2MatchMultiStage->setObjectName(Parameters::kOdomViso2MatchMultiStage().
c_str());
1479 _ui->checkBox_OdomViso2MatchHalfResolution->setObjectName(Parameters::kOdomViso2MatchHalfResolution().
c_str());
1480 _ui->spinBox_OdomViso2MatchRefinement->setObjectName(Parameters::kOdomViso2MatchRefinement().
c_str());
1482 _ui->spinBox_OdomViso2BucketMaxFeatures->setObjectName(Parameters::kOdomViso2BucketMaxFeatures().
c_str());
1483 _ui->doubleSpinBox_OdomViso2BucketWidth->setObjectName(Parameters::kOdomViso2BucketWidth().
c_str());
1484 _ui->doubleSpinBox_OdomViso2BucketHeight->setObjectName(Parameters::kOdomViso2BucketHeight().
c_str());
1487 _ui->lineEdit_OdomORBSLAMVocPath->setObjectName(Parameters::kOdomORBSLAMVocPath().
c_str());
1489 _ui->doubleSpinBox_OdomORBSLAMBf->setObjectName(Parameters::kOdomORBSLAMBf().
c_str());
1490 _ui->doubleSpinBox_OdomORBSLAMThDepth->setObjectName(Parameters::kOdomORBSLAMThDepth().
c_str());
1491 _ui->doubleSpinBox_OdomORBSLAMFps->setObjectName(Parameters::kOdomORBSLAMFps().
c_str());
1492 _ui->spinBox_OdomORBSLAMMaxFeatures->setObjectName(Parameters::kOdomORBSLAMMaxFeatures().
c_str());
1493 _ui->spinBox_OdomORBSLAMMapSize->setObjectName(Parameters::kOdomORBSLAMMapSize().
c_str());
1494 _ui->groupBox_OdomORBSLAMInertial->setObjectName(Parameters::kOdomORBSLAMInertial().
c_str());
1495 _ui->doubleSpinBox_ORBSLAMGyroNoise->setObjectName(Parameters::kOdomORBSLAMGyroNoise().
c_str());
1496 _ui->doubleSpinBox_ORBSLAMAccNoise->setObjectName(Parameters::kOdomORBSLAMAccNoise().
c_str());
1497 _ui->doubleSpinBox_ORBSLAMGyroWalk->setObjectName(Parameters::kOdomORBSLAMGyroWalk().
c_str());
1498 _ui->doubleSpinBox_ORBSLAMAccWalk->setObjectName(Parameters::kOdomORBSLAMAccWalk().
c_str());
1499 _ui->doubleSpinBox_ORBSLAMSamplingRate->setObjectName(Parameters::kOdomORBSLAMSamplingRate().
c_str());
1502 _ui->lineEdit_OdomOkvisPath->setObjectName(Parameters::kOdomOKVISConfigPath().
c_str());
1506 _ui->odom_loam_sensor->setObjectName(Parameters::kOdomLOAMSensor().
c_str());
1507 _ui->odom_loam_scan_period->setObjectName(Parameters::kOdomLOAMScanPeriod().
c_str());
1508 _ui->odom_loam_resolution->setObjectName(Parameters::kOdomLOAMResolution().
c_str());
1509 _ui->odom_loam_linvar->setObjectName(Parameters::kOdomLOAMLinVar().
c_str());
1510 _ui->odom_loam_angvar->setObjectName(Parameters::kOdomLOAMAngVar().
c_str());
1511 _ui->odom_loam_localMapping->setObjectName(Parameters::kOdomLOAMLocalMapping().
c_str());
1514 _ui->OdomMSCKFGridRow->setObjectName(Parameters::kOdomMSCKFGridRow().
c_str());
1515 _ui->OdomMSCKFGridCol->setObjectName(Parameters::kOdomMSCKFGridCol().
c_str());
1516 _ui->OdomMSCKFGridMinFeatureNum->setObjectName(Parameters::kOdomMSCKFGridMinFeatureNum().
c_str());
1517 _ui->OdomMSCKFGridMaxFeatureNum->setObjectName(Parameters::kOdomMSCKFGridMaxFeatureNum().
c_str());
1518 _ui->OdomMSCKFPyramidLevels->setObjectName(Parameters::kOdomMSCKFPyramidLevels().
c_str());
1519 _ui->OdomMSCKFPatchSize->setObjectName(Parameters::kOdomMSCKFPatchSize().
c_str());
1520 _ui->OdomMSCKFFastThreshold->setObjectName(Parameters::kOdomMSCKFFastThreshold().
c_str());
1521 _ui->OdomMSCKFMaxIteration->setObjectName(Parameters::kOdomMSCKFMaxIteration().
c_str());
1522 _ui->OdomMSCKFMaxCamStateSize->setObjectName(Parameters::kOdomMSCKFMaxCamStateSize().
c_str());
1523 _ui->OdomMSCKFTrackPrecision->setObjectName(Parameters::kOdomMSCKFTrackPrecision().
c_str());
1524 _ui->OdomMSCKFRansacThreshold->setObjectName(Parameters::kOdomMSCKFRansacThreshold().
c_str());
1525 _ui->OdomMSCKFStereoThreshold->setObjectName(Parameters::kOdomMSCKFStereoThreshold().
c_str());
1526 _ui->OdomMSCKFPositionStdThreshold->setObjectName(Parameters::kOdomMSCKFPositionStdThreshold().
c_str());
1527 _ui->OdomMSCKFRotationThreshold->setObjectName(Parameters::kOdomMSCKFRotationThreshold().
c_str());
1528 _ui->OdomMSCKFTranslationThreshold->setObjectName(Parameters::kOdomMSCKFTranslationThreshold().
c_str());
1529 _ui->OdomMSCKFTrackingRateThreshold->setObjectName(Parameters::kOdomMSCKFTrackingRateThreshold().
c_str());
1530 _ui->OdomMSCKFOptTranslationThreshold->setObjectName(Parameters::kOdomMSCKFOptTranslationThreshold().
c_str());
1531 _ui->OdomMSCKFNoiseGyro->setObjectName(Parameters::kOdomMSCKFNoiseGyro().
c_str());
1532 _ui->OdomMSCKFNoiseAcc->setObjectName(Parameters::kOdomMSCKFNoiseAcc().
c_str());
1533 _ui->OdomMSCKFNoiseGyroBias->setObjectName(Parameters::kOdomMSCKFNoiseGyroBias().
c_str());
1534 _ui->OdomMSCKFNoiseAccBias->setObjectName(Parameters::kOdomMSCKFNoiseAccBias().
c_str());
1535 _ui->OdomMSCKFNoiseFeature->setObjectName(Parameters::kOdomMSCKFNoiseFeature().
c_str());
1536 _ui->OdomMSCKFInitCovVel->setObjectName(Parameters::kOdomMSCKFInitCovVel().
c_str());
1537 _ui->OdomMSCKFInitCovGyroBias->setObjectName(Parameters::kOdomMSCKFInitCovGyroBias().
c_str());
1538 _ui->OdomMSCKFInitCovAccBias->setObjectName(Parameters::kOdomMSCKFInitCovAccBias().
c_str());
1539 _ui->OdomMSCKFInitCovExRot->setObjectName(Parameters::kOdomMSCKFInitCovExRot().
c_str());
1540 _ui->OdomMSCKFInitCovExTrans->setObjectName(Parameters::kOdomMSCKFInitCovExTrans().
c_str());
1543 _ui->lineEdit_OdomVinsPath->setObjectName(Parameters::kOdomVINSConfigPath().
c_str());
1547 _ui->checkBox_OdomOpenVINSUseStereo->setObjectName(Parameters::kOdomOpenVINSUseStereo().
c_str());
1548 _ui->checkBox_OdomOpenVINSUseKLT->setObjectName(Parameters::kOdomOpenVINSUseKLT().
c_str());
1549 _ui->spinBox_OdomOpenVINSNumPts->setObjectName(Parameters::kOdomOpenVINSNumPts().
c_str());
1550 _ui->spinBox_OdomOpenVINSMinPxDist->setObjectName(Parameters::kOdomOpenVINSMinPxDist().
c_str());
1551 _ui->checkBox_OdomOpenVINSFiTriangulate1d->setObjectName(Parameters::kOdomOpenVINSFiTriangulate1d().
c_str());
1552 _ui->checkBox_OdomOpenVINSFiRefineFeatures->setObjectName(Parameters::kOdomOpenVINSFiRefineFeatures().
c_str());
1553 _ui->spinBox_OdomOpenVINSFiMaxRuns->setObjectName(Parameters::kOdomOpenVINSFiMaxRuns().
c_str());
1554 _ui->doubleSpinBox_OdomOpenVINSFiMaxBaseline->setObjectName(Parameters::kOdomOpenVINSFiMaxBaseline().
c_str());
1555 _ui->doubleSpinBox_OdomOpenVINSFiMaxCondNumber->setObjectName(Parameters::kOdomOpenVINSFiMaxCondNumber().
c_str());
1557 _ui->checkBox_OdomOpenVINSUseFEJ->setObjectName(Parameters::kOdomOpenVINSUseFEJ().
c_str());
1558 _ui->comboBox_OdomOpenVINSIntegration->setObjectName(Parameters::kOdomOpenVINSIntegration().
c_str());
1559 _ui->checkBox_OdomOpenVINSCalibCamExtrinsics->setObjectName(Parameters::kOdomOpenVINSCalibCamExtrinsics().
c_str());
1560 _ui->checkBox_OdomOpenVINSCalibCamIntrinsics->setObjectName(Parameters::kOdomOpenVINSCalibCamIntrinsics().
c_str());
1561 _ui->checkBox_OdomOpenVINSCalibCamTimeoffset->setObjectName(Parameters::kOdomOpenVINSCalibCamTimeoffset().
c_str());
1562 _ui->checkBox_OdomOpenVINSCalibIMUIntrinsics->setObjectName(Parameters::kOdomOpenVINSCalibIMUIntrinsics().
c_str());
1563 _ui->checkBox_OdomOpenVINSCalibIMUGSensitivity->setObjectName(Parameters::kOdomOpenVINSCalibIMUGSensitivity().
c_str());
1564 _ui->spinBox_OdomOpenVINSMaxClones->setObjectName(Parameters::kOdomOpenVINSMaxClones().
c_str());
1565 _ui->spinBox_OdomOpenVINSMaxSLAM->setObjectName(Parameters::kOdomOpenVINSMaxSLAM().
c_str());
1566 _ui->spinBox_OdomOpenVINSMaxSLAMInUpdate->setObjectName(Parameters::kOdomOpenVINSMaxSLAMInUpdate().
c_str());
1567 _ui->spinBox_OdomOpenVINSMaxMSCKFInUpdate->setObjectName(Parameters::kOdomOpenVINSMaxMSCKFInUpdate().
c_str());
1568 _ui->comboBox_OdomOpenVINSFeatRepMSCKF->setObjectName(Parameters::kOdomOpenVINSFeatRepMSCKF().
c_str());
1569 _ui->comboBox_OdomOpenVINSFeatRepSLAM->setObjectName(Parameters::kOdomOpenVINSFeatRepSLAM().
c_str());
1570 _ui->doubleSpinBox_OdomOpenVINSDtSLAMDelay->setObjectName(Parameters::kOdomOpenVINSDtSLAMDelay().
c_str());
1571 _ui->doubleSpinBox_OdomOpenVINSGravityMag->setObjectName(Parameters::kOdomOpenVINSGravityMag().
c_str());
1572 _ui->lineEdit_OdomOpenVINSLeftMaskPath->setObjectName(Parameters::kOdomOpenVINSLeftMaskPath().
c_str());
1574 _ui->lineEdit_OdomOpenVINSRightMaskPath->setObjectName(Parameters::kOdomOpenVINSRightMaskPath().
c_str());
1577 _ui->doubleSpinBox_OdomOpenVINSInitWindowTime->setObjectName(Parameters::kOdomOpenVINSInitWindowTime().
c_str());
1578 _ui->doubleSpinBox_OdomOpenVINSInitIMUThresh->setObjectName(Parameters::kOdomOpenVINSInitIMUThresh().
c_str());
1579 _ui->doubleSpinBox_OdomOpenVINSInitMaxDisparity->setObjectName(Parameters::kOdomOpenVINSInitMaxDisparity().
c_str());
1580 _ui->spinBox_OdomOpenVINSInitMaxFeatures->setObjectName(Parameters::kOdomOpenVINSInitMaxFeatures().
c_str());
1581 _ui->checkBox_OdomOpenVINSInitDynUse->setObjectName(Parameters::kOdomOpenVINSInitDynUse().
c_str());
1582 _ui->checkBox_OdomOpenVINSInitDynMLEOptCalib->setObjectName(Parameters::kOdomOpenVINSInitDynMLEOptCalib().
c_str());
1583 _ui->spinBox_OdomOpenVINSInitDynMLEMaxIter->setObjectName(Parameters::kOdomOpenVINSInitDynMLEMaxIter().
c_str());
1584 _ui->doubleSpinBox_OdomOpenVINSInitDynMLEMaxTime->setObjectName(Parameters::kOdomOpenVINSInitDynMLEMaxTime().
c_str());
1585 _ui->spinBox_OdomOpenVINSInitDynMLEMaxThreads->setObjectName(Parameters::kOdomOpenVINSInitDynMLEMaxThreads().
c_str());
1586 _ui->spinBox_OdomOpenVINSInitDynNumPose->setObjectName(Parameters::kOdomOpenVINSInitDynNumPose().
c_str());
1587 _ui->doubleSpinBox_OdomOpenVINSInitDynMinDeg->setObjectName(Parameters::kOdomOpenVINSInitDynMinDeg().
c_str());
1588 _ui->doubleSpinBox_OdomOpenVINSInitDynInflationOri->setObjectName(Parameters::kOdomOpenVINSInitDynInflationOri().
c_str());
1589 _ui->doubleSpinBox_OdomOpenVINSInitDynInflationVel->setObjectName(Parameters::kOdomOpenVINSInitDynInflationVel().
c_str());
1590 _ui->doubleSpinBox_OdomOpenVINSInitDynInflationBg->setObjectName(Parameters::kOdomOpenVINSInitDynInflationBg().
c_str());
1591 _ui->doubleSpinBox_OdomOpenVINSInitDynInflationBa->setObjectName(Parameters::kOdomOpenVINSInitDynInflationBa().
c_str());
1592 _ui->doubleSpinBox_OdomOpenVINSInitDynMinRecCond->setObjectName(Parameters::kOdomOpenVINSInitDynMinRecCond().
c_str());
1594 _ui->checkBox_OdomOpenVINSTryZUPT->setObjectName(Parameters::kOdomOpenVINSTryZUPT().
c_str());
1595 _ui->doubleSpinBox_OdomOpenVINSZUPTChi2Multiplier->setObjectName(Parameters::kOdomOpenVINSZUPTChi2Multiplier().
c_str());
1596 _ui->doubleSpinBox_OdomOpenVINSZUPTMaxVelodicy->setObjectName(Parameters::kOdomOpenVINSZUPTMaxVelodicy().
c_str());
1597 _ui->doubleSpinBox_OdomOpenVINSZUPTNoiseMultiplier->setObjectName(Parameters::kOdomOpenVINSZUPTNoiseMultiplier().
c_str());
1598 _ui->doubleSpinBox_OdomOpenVINSZUPTMaxDisparity->setObjectName(Parameters::kOdomOpenVINSZUPTMaxDisparity().
c_str());
1599 _ui->checkBox_OdomOpenVINSZUPTOnlyAtBeginning->setObjectName(Parameters::kOdomOpenVINSZUPTOnlyAtBeginning().
c_str());
1601 _ui->doubleSpinBox_OdomOpenVINSAccelerometerNoiseDensity->setObjectName(Parameters::kOdomOpenVINSAccelerometerNoiseDensity().
c_str());
1602 _ui->doubleSpinBox_OdomOpenVINSAccelerometerRandomWalk->setObjectName(Parameters::kOdomOpenVINSAccelerometerRandomWalk().
c_str());
1603 _ui->doubleSpinBox_OdomOpenVINSGyroscopeNoiseDensity->setObjectName(Parameters::kOdomOpenVINSGyroscopeNoiseDensity().
c_str());
1604 _ui->doubleSpinBox_OdomOpenVINSGyroscopeRandomWalk->setObjectName(Parameters::kOdomOpenVINSGyroscopeRandomWalk().
c_str());
1605 _ui->doubleSpinBox_OdomOpenVINSUpMSCKFSigmaPx->setObjectName(Parameters::kOdomOpenVINSUpMSCKFSigmaPx().
c_str());
1606 _ui->doubleSpinBox_OdomOpenVINSUpMSCKFChi2Multiplier->setObjectName(Parameters::kOdomOpenVINSUpMSCKFChi2Multiplier().
c_str());
1607 _ui->doubleSpinBox_OdomOpenVINSUpSLAMSigmaPx->setObjectName(Parameters::kOdomOpenVINSUpSLAMSigmaPx().
c_str());
1608 _ui->doubleSpinBox_OdomOpenVINSUpSLAMChi2Multiplier->setObjectName(Parameters::kOdomOpenVINSUpSLAMChi2Multiplier().
c_str());
1611 _ui->stereo_winWidth->setObjectName(Parameters::kStereoWinWidth().
c_str());
1612 _ui->stereo_winHeight->setObjectName(Parameters::kStereoWinHeight().
c_str());
1613 _ui->stereo_maxLevel->setObjectName(Parameters::kStereoMaxLevel().
c_str());
1614 _ui->stereo_iterations->setObjectName(Parameters::kStereoIterations().
c_str());
1615 _ui->stereo_minDisparity->setObjectName(Parameters::kStereoMinDisparity().
c_str());
1616 _ui->stereo_maxDisparity->setObjectName(Parameters::kStereoMaxDisparity().
c_str());
1617 _ui->stereo_ssd->setObjectName(Parameters::kStereoSSD().
c_str());
1618 _ui->stereo_flow_eps->setObjectName(Parameters::kStereoEps().
c_str());
1619 _ui->stereo_opticalFlow->setObjectName(Parameters::kStereoOpticalFlow().
c_str());
1620 _ui->stereo_flow_gpu->setObjectName(Parameters::kStereoGpu().
c_str());
1624 _ui->odom_open3d_method->setObjectName(Parameters::kOdomOpen3DMethod().
c_str());
1625 _ui->odom_open3d_max_depth->setObjectName(Parameters::kOdomOpen3DMaxDepth().
c_str());
1628 _ui->comboBox_stereoDense_strategy->setObjectName(Parameters::kStereoDenseStrategy().
c_str());
1629 connect(
_ui->comboBox_stereoDense_strategy, SIGNAL(currentIndexChanged(
int)),
_ui->stackedWidget_stereoDense, SLOT(setCurrentIndex(
int)));
1630 _ui->comboBox_stereoDense_strategy->setCurrentIndex(Parameters::defaultStereoDenseStrategy());
1631 _ui->stackedWidget_stereoDense->setCurrentIndex(Parameters::defaultStereoDenseStrategy());
1634 _ui->stereobm_blockSize->setObjectName(Parameters::kStereoBMBlockSize().
c_str());
1635 _ui->stereobm_minDisparity->setObjectName(Parameters::kStereoBMMinDisparity().
c_str());
1636 _ui->stereobm_numDisparities->setObjectName(Parameters::kStereoBMNumDisparities().
c_str());
1637 _ui->stereobm_preFilterCap->setObjectName(Parameters::kStereoBMPreFilterCap().
c_str());
1638 _ui->stereobm_preFilterSize->setObjectName(Parameters::kStereoBMPreFilterSize().
c_str());
1639 _ui->stereobm_speckleRange->setObjectName(Parameters::kStereoBMSpeckleRange().
c_str());
1640 _ui->stereobm_speckleWinSize->setObjectName(Parameters::kStereoBMSpeckleWindowSize().
c_str());
1641 _ui->stereobm_tetureThreshold->setObjectName(Parameters::kStereoBMTextureThreshold().
c_str());
1642 _ui->stereobm_uniquessRatio->setObjectName(Parameters::kStereoBMUniquenessRatio().
c_str());
1643 _ui->stereobm_disp12MaxDiff->setObjectName(Parameters::kStereoBMDisp12MaxDiff().
c_str());
1646 _ui->stereosgbm_blockSize->setObjectName(Parameters::kStereoSGBMBlockSize().
c_str());
1647 _ui->stereosgbm_minDisparity->setObjectName(Parameters::kStereoSGBMMinDisparity().
c_str());
1648 _ui->stereosgbm_numDisparities->setObjectName(Parameters::kStereoSGBMNumDisparities().
c_str());
1649 _ui->stereosgbm_preFilterCap->setObjectName(Parameters::kStereoSGBMPreFilterCap().
c_str());
1650 _ui->stereosgbm_speckleRange->setObjectName(Parameters::kStereoSGBMSpeckleRange().
c_str());
1651 _ui->stereosgbm_speckleWinSize->setObjectName(Parameters::kStereoSGBMSpeckleWindowSize().
c_str());
1652 _ui->stereosgbm_uniquessRatio->setObjectName(Parameters::kStereoSGBMUniquenessRatio().
c_str());
1653 _ui->stereosgbm_disp12MaxDiff->setObjectName(Parameters::kStereoSGBMDisp12MaxDiff().
c_str());
1654 _ui->stereosgbm_p1->setObjectName(Parameters::kStereoSGBMP1().
c_str());
1655 _ui->stereosgbm_p2->setObjectName(Parameters::kStereoSGBMP2().
c_str());
1656 _ui->stereosgbm_mode->setObjectName(Parameters::kStereoSGBMMode().
c_str());
1659 _ui->ArucoDictionary->setObjectName(Parameters::kMarkerDictionary().
c_str());
1660 _ui->ArucoMarkerLength->setObjectName(Parameters::kMarkerLength().
c_str());
1661 _ui->ArucoMaxDepthError->setObjectName(Parameters::kMarkerMaxDepthError().
c_str());
1662 _ui->ArucoVarianceLinear->setObjectName(Parameters::kMarkerVarianceLinear().
c_str());
1663 _ui->ArucoVarianceAngular->setObjectName(Parameters::kMarkerVarianceAngular().
c_str());
1664 _ui->ArucoMarkerRangeMin->setObjectName(Parameters::kMarkerMinRange().
c_str());
1665 _ui->ArucoMarkerRangeMax->setObjectName(Parameters::kMarkerMaxRange().
c_str());
1666 _ui->ArucoMarkerPriors->setObjectName(Parameters::kMarkerPriors().
c_str());
1667 _ui->ArucoPriorsVarianceLinear->setObjectName(Parameters::kMarkerPriorsVarianceLinear().
c_str());
1668 _ui->ArucoPriorsVarianceAngular->setObjectName(Parameters::kMarkerPriorsVarianceAngular().
c_str());
1669 _ui->ArucoCornerRefinementMethod->setObjectName(Parameters::kMarkerCornerRefinementMethod().
c_str());
1672 _ui->doubleSpinBox_imuFilterMadgwickGain->setObjectName(Parameters::kImuFilterMadgwickGain().
c_str());
1673 _ui->doubleSpinBox_imuFilterMadgwickZeta->setObjectName(Parameters::kImuFilterMadgwickZeta().
c_str());
1674 _ui->doubleSpinBox_imuFilterComplementaryGainAcc->setObjectName(Parameters::kImuFilterComplementaryGainAcc().
c_str());
1675 _ui->doubleSpinBox_imuFilterComplementaryBiasAlpha->setObjectName(Parameters::kImuFilterComplementaryBiasAlpha().
c_str());
1676 _ui->checkBox_imuFilterComplementaryDoAdaptiveGain->setObjectName(Parameters::kImuFilterComplementaryDoAdpativeGain().
c_str());
1677 _ui->checkBox_imuFilterComplementaryDoBiasEstimation->setObjectName(Parameters::kImuFilterComplementaryDoBiasEstimation().
c_str());
1689 connect(
_ui->doubleSpinBox_kp_roi0, SIGNAL(valueChanged(
double)),
this, SLOT(
updateKpROI()));
1690 connect(
_ui->doubleSpinBox_kp_roi1, SIGNAL(valueChanged(
double)),
this, SLOT(
updateKpROI()));
1691 connect(
_ui->doubleSpinBox_kp_roi2, SIGNAL(valueChanged(
double)),
this, SLOT(
updateKpROI()));
1692 connect(
_ui->doubleSpinBox_kp_roi3, SIGNAL(valueChanged(
double)),
this, SLOT(
updateKpROI()));
1693 connect(
_ui->checkBox_useOdomFeatures, SIGNAL(toggled(
bool)),
this, SLOT(
useOdomFeatures()));
1697 _ui->stackedWidget->setCurrentIndex(0);
1717 for(ParametersMap::const_iterator
iter=defaults.begin();
iter!=defaults.end(); ++
iter)
1732 for(
int i =0;
i<boxes.size();++
i)
1734 if(boxes[
i] ==
_ui->groupBox_source0)
1736 _ui->stackedWidget->setCurrentIndex(
i);
1752 _ui->treeView->setModel(0);
1758 if(
_ui->radioButton_basic->isChecked())
1760 boxes = boxes.mid(0,7);
1767 QStandardItem * parentItem =
_indexModel->invisibleRootItem();
1769 this->
parseModel(boxes, parentItem, 0, index);
1770 if(
_ui->radioButton_advanced->isChecked() && index !=
_ui->stackedWidget->count()-1)
1772 ULOGGER_ERROR(
"The tree model is not the same size of the stacked widgets...%d vs %d advanced stacks", index,
_ui->stackedWidget->count()-1);
1774 int currentIndex =
_ui->stackedWidget->currentIndex();
1775 if(
_ui->radioButton_basic->isChecked())
1777 if(currentIndex >= 6)
1779 _ui->stackedWidget->setCurrentIndex(6);
1785 if(currentIndex == 6)
1787 _ui->stackedWidget->setCurrentIndex(7);
1791 _ui->treeView->expandToDepth(1);
1794 connect(
_ui->treeView->selectionModel(), SIGNAL(currentChanged(
const QModelIndex &,
const QModelIndex &)),
this, SLOT(
clicked(
const QModelIndex &,
const QModelIndex &)));
1806 QStandardItem * currentItem = 0;
1807 while(absoluteIndex < boxes.size())
1809 QString objectName = boxes.at(absoluteIndex)->objectName();
1810 QString title = boxes.at(absoluteIndex)->title();
1812 int lvl = QString(objectName.at(objectName.size()-1)).toInt(&ok);
1815 ULOGGER_ERROR(
"Error while parsing the first number of the QGroupBox title (%s), the first character must be the number in the hierarchy", title.toStdString().c_str());
1820 if(lvl == currentLevel)
1822 QStandardItem * item =
new QStandardItem(title);
1823 item->setData(absoluteIndex);
1826 parentItem->appendRow(item);
1829 else if(lvl > currentLevel)
1831 if(lvl>currentLevel+1)
1833 ULOGGER_ERROR(
"Intermediary lvl doesn't exist, lvl %d to %d, indexes %d and %d", currentLevel, lvl, absoluteIndex-1, absoluteIndex);
1838 parseModel(boxes, currentItem, currentLevel+1, absoluteIndex);
1852 for(rtabmap::ParametersMap::const_iterator
iter=parameters.begin();
iter!=parameters.end(); ++
iter)
1854 QWidget * obj =
_ui->stackedWidget->findChild<QWidget*>((*iter).first.c_str());
1858 obj->setToolTip(tr(
"%1 (Default=\"%2\")").arg(
iter->first.c_str()).arg(
iter->second.c_str()));
1860 QSpinBox * spin = qobject_cast<QSpinBox *>(obj);
1861 QDoubleSpinBox * doubleSpin = qobject_cast<QDoubleSpinBox *>(obj);
1862 QComboBox * combo = qobject_cast<QComboBox *>(obj);
1863 QCheckBox *
check = qobject_cast<QCheckBox *>(obj);
1864 QRadioButton * radio = qobject_cast<QRadioButton *>(obj);
1865 QLineEdit * lineEdit = qobject_cast<QLineEdit *>(obj);
1866 QGroupBox * groupBox = qobject_cast<QGroupBox *>(obj);
1869 connect(spin, SIGNAL(valueChanged(
int)),
this, SLOT(
addParameter(
int)));
1873 connect(doubleSpin, SIGNAL(valueChanged(
double)),
this, SLOT(
addParameter(
double)));
1877 connect(combo, SIGNAL(currentIndexChanged(
int)),
this, SLOT(
addParameter(
int)));
1885 connect(radio, SIGNAL(toggled(
bool)),
this, SLOT(
addParameter(
bool)));
1889 connect(lineEdit, SIGNAL(textChanged(
const QString &)),
this, SLOT(
addParameter(
const QString &)));
1893 connect(groupBox, SIGNAL(toggled(
bool)),
this, SLOT(
addParameter(
bool)));
1897 ULOGGER_WARN(
"QWidget called %s can't be cast to a supported widget", (*iter).first.c_str());
1902 ULOGGER_WARN(
"Can't find the related QWidget for parameter %s", (*iter).first.c_str());
1909 QStandardItem * item =
_indexModel->itemFromIndex(current);
1910 if(item && item->isEnabled())
1912 int index = item->data().toInt();
1913 if(
_ui->radioButton_advanced->isChecked() && index >= 6)
1917 _ui->stackedWidget->setCurrentIndex(index);
1918 _ui->scrollArea->horizontalScrollBar()->setValue(0);
1919 _ui->scrollArea->verticalScrollBar()->setValue(0);
1937 QDialogButtonBox::ButtonRole role =
_ui->buttonBox_global->buttonRole(button);
1940 case QDialogButtonBox::RejectRole:
1948 case QDialogButtonBox::AcceptRole:
1971 QDialogButtonBox::ButtonRole role =
_ui->buttonBox_local->buttonRole(button);
1974 case QDialogButtonBox::ApplyRole:
1982 case QDialogButtonBox::ResetRole:
1993 if(groupBox->objectName() ==
_ui->groupBox_generalSettingsGui0->objectName())
1995 _ui->general_checkBox_imagesKept->setChecked(
true);
1996 _ui->general_checkBox_missing_cache_republished->setChecked(
true);
1997 _ui->general_checkBox_cloudsKept->setChecked(
true);
1998 _ui->checkBox_beep->setChecked(
false);
1999 _ui->checkBox_stamps->setChecked(
true);
2000 _ui->checkBox_cacheStatistics->setChecked(
true);
2001 _ui->checkBox_notifyWhenNewGlobalPathIsReceived->setChecked(
false);
2002 _ui->checkBox_verticalLayoutUsed->setChecked(
true);
2003 _ui->checkBox_imageRejectedShown->setChecked(
true);
2004 _ui->checkBox_imageHighestHypShown->setChecked(
false);
2005 _ui->spinBox_odomQualityWarnThr->setValue(50);
2006 _ui->checkBox_odom_onlyInliersShown->setChecked(
false);
2007 _ui->radioButton_posteriorGraphView->setChecked(
true);
2008 _ui->radioButton_wordsGraphView->setChecked(
false);
2009 _ui->radioButton_localizationsGraphView->setChecked(
false);
2010 _ui->radioButton_localizationsGraphViewOdomCache->setChecked(
false);
2011 _ui->radioButton_nochangeGraphView->setChecked(
false);
2012 _ui->checkbox_odomDisabled->setChecked(
false);
2013 _ui->checkbox_groundTruthAlign->setChecked(
true);
2015 else if(groupBox->objectName() ==
_ui->groupBox_cloudRendering1->objectName())
2017 for(
int i=0;
i<2; ++
i)
2042 _ui->doubleSpinBox_voxel->setValue(0);
2043 _ui->doubleSpinBox_noiseRadius->setValue(0);
2044 _ui->spinBox_noiseMinNeighbors->setValue(5);
2046 _ui->doubleSpinBox_ceilingFilterHeight->setValue(0);
2047 _ui->doubleSpinBox_floorFilterHeight->setValue(0);
2048 _ui->spinBox_normalKSearch->setValue(10);
2049 _ui->doubleSpinBox_normalRadiusSearch->setValue(0.0);
2051 _ui->doubleSpinBox_ceilingFilterHeight_scan->setValue(0);
2052 _ui->doubleSpinBox_floorFilterHeight_scan->setValue(0);
2053 _ui->spinBox_normalKSearch_scan->setValue(0);
2054 _ui->doubleSpinBox_normalRadiusSearch_scan->setValue(0.0);
2056 _ui->checkBox_showGraphs->setChecked(
true);
2057 _ui->checkBox_showLabels->setChecked(
false);
2058 _ui->checkBox_showFrames->setChecked(
false);
2059 _ui->checkBox_showLandmarks->setChecked(
true);
2060 _ui->doubleSpinBox_landmarkSize->setValue(0);
2061 _ui->checkBox_showIMUGravity->setChecked(
false);
2062 _ui->checkBox_showIMUAcc->setChecked(
false);
2064 _ui->doubleSpinBox_mesh_angleTolerance->setValue(15.0);
2065 _ui->groupBox_organized->setChecked(
false);
2066 #if PCL_VERSION_COMPARE(>=, 1, 7, 2)
2067 _ui->checkBox_mesh_quad->setChecked(
true);
2069 _ui->checkBox_mesh_quad->setChecked(
false);
2071 _ui->checkBox_mesh_texture->setChecked(
false);
2072 _ui->spinBox_mesh_triangleSize->setValue(2);
2074 else if(groupBox->objectName() ==
_ui->groupBox_filtering2->objectName())
2076 _ui->radioButton_noFiltering->setChecked(
true);
2077 _ui->radioButton_nodeFiltering->setChecked(
false);
2078 _ui->radioButton_subtractFiltering->setChecked(
false);
2079 _ui->doubleSpinBox_cloudFilterRadius->setValue(0.1);
2080 _ui->doubleSpinBox_cloudFilterAngle->setValue(30);
2081 _ui->spinBox_subtractFilteringMinPts->setValue(5);
2082 _ui->doubleSpinBox_subtractFilteringRadius->setValue(0.02);
2083 _ui->doubleSpinBox_subtractFilteringAngle->setValue(0);
2085 else if(groupBox->objectName() ==
_ui->groupBox_gridMap2->objectName())
2087 _ui->doubleSpinBox_map_resolution->setValue(0);
2088 _ui->checkBox_map_shown->setChecked(
false);
2089 _ui->doubleSpinBox_map_opacity->setValue(0.75);
2090 _ui->checkBox_elevation_shown->setCheckState(Qt::Unchecked);
2092 _ui->groupBox_octomap->setChecked(
false);
2093 _ui->spinBox_octomap_treeDepth->setValue(16);
2094 _ui->checkBox_octomap_2dgrid->setChecked(
true);
2095 _ui->checkBox_octomap_show3dMap->setChecked(
true);
2096 _ui->comboBox_octomap_renderingType->setCurrentIndex(0);
2097 _ui->spinBox_octomap_pointSize->setValue(5);
2099 else if(groupBox->objectName() ==
_ui->groupBox_logging1->objectName())
2101 _ui->comboBox_loggerLevel->setCurrentIndex(2);
2102 _ui->comboBox_loggerEventLevel->setCurrentIndex(3);
2103 _ui->comboBox_loggerPauseLevel->setCurrentIndex(3);
2104 _ui->checkBox_logger_printTime->setChecked(
true);
2105 _ui->checkBox_logger_printThreadId->setChecked(
false);
2106 _ui->comboBox_loggerType->setCurrentIndex(1);
2107 for(
int i=0;
i<
_ui->comboBox_loggerFilter->count(); ++
i)
2109 _ui->comboBox_loggerFilter->setItemChecked(
i,
false);
2112 else if(groupBox->objectName() ==
_ui->groupBox_source0->objectName())
2114 _ui->general_doubleSpinBox_imgRate->setValue(0.0);
2115 _ui->source_mirroring->setChecked(
false);
2116 _ui->lineEdit_calibrationFile->clear();
2117 _ui->comboBox_sourceType->setCurrentIndex(
kSrcRGBD);
2118 _ui->lineEdit_sourceDevice->setText(
"");
2119 _ui->lineEdit_sourceLocalTransform->setText(
"0 0 0 0 0 0");
2122 _ui->source_images_spinBox_startPos->setValue(0);
2123 _ui->source_images_spinBox_maxFrames->setValue(0);
2124 _ui->spinBox_usbcam_streamWidth->setValue(0);
2125 _ui->spinBox_usbcam_streamHeight->setValue(0);
2126 _ui->checkBox_rgb_rectify->setChecked(
false);
2127 _ui->comboBox_cameraImages_bayerMode->setCurrentIndex(0);
2129 _ui->source_checkBox_ignoreOdometry->setChecked(
false);
2130 _ui->source_checkBox_ignoreGoalDelay->setChecked(
true);
2131 _ui->source_checkBox_ignoreGoals->setChecked(
true);
2132 _ui->source_checkBox_ignoreLandmarks->setChecked(
true);
2133 _ui->source_checkBox_ignoreFeatures->setChecked(
true);
2134 _ui->source_checkBox_ignorePriors->setChecked(
false);
2135 _ui->source_spinBox_databaseStartId->setValue(0);
2136 _ui->source_spinBox_databaseStopId->setValue(0);
2137 _ui->source_spinBox_database_cameraIndex->setValue(-1);
2138 _ui->source_checkBox_useDbStamps->setChecked(
true);
2169 _ui->checkbox_rgbd_colorOnly->setChecked(
false);
2170 _ui->spinBox_source_imageDecimation->setValue(1);
2171 _ui->comboBox_source_histogramMethod->setCurrentIndex(0);
2172 _ui->checkbox_source_feature_detection->setChecked(
false);
2173 _ui->checkbox_stereo_depthGenerated->setChecked(
false);
2174 _ui->checkBox_stereo_exposureCompensation->setChecked(
false);
2175 _ui->openni2_autoWhiteBalance->setChecked(
true);
2176 _ui->openni2_autoExposure->setChecked(
true);
2177 _ui->openni2_exposure->setValue(0);
2178 _ui->openni2_gain->setValue(100);
2179 _ui->openni2_mirroring->setChecked(
false);
2180 _ui->openni2_stampsIdsUsed->setChecked(
false);
2181 _ui->openni2_hshift->setValue(0);
2182 _ui->openni2_vshift->setValue(0);
2183 _ui->openni2_depth_decimation->setValue(1);
2184 _ui->comboBox_freenect2Format->setCurrentIndex(1);
2185 _ui->doubleSpinBox_freenect2MinDepth->setValue(0.3);
2186 _ui->doubleSpinBox_freenect2MaxDepth->setValue(12.0);
2187 _ui->checkBox_freenect2BilateralFiltering->setChecked(
true);
2188 _ui->checkBox_freenect2EdgeAwareFiltering->setChecked(
true);
2189 _ui->checkBox_freenect2NoiseFiltering->setChecked(
true);
2190 _ui->lineEdit_freenect2Pipeline->setText(
"");
2191 _ui->comboBox_k4w2Format->setCurrentIndex(1);
2192 _ui->comboBox_realsensePresetRGB->setCurrentIndex(0);
2193 _ui->comboBox_realsensePresetDepth->setCurrentIndex(2);
2194 _ui->checkbox_realsenseOdom->setChecked(
false);
2195 _ui->checkbox_realsenseDepthScaledToRGBSize->setChecked(
false);
2196 _ui->comboBox_realsenseRGBSource->setCurrentIndex(0);
2197 _ui->checkbox_rs2_emitter->setChecked(
true);
2198 _ui->checkbox_rs2_irMode->setChecked(
false);
2199 _ui->checkbox_rs2_irDepth->setChecked(
true);
2200 _ui->spinBox_rs2_width->setValue(848);
2201 _ui->spinBox_rs2_height->setValue(480);
2202 _ui->spinBox_rs2_rate->setValue(60);
2203 _ui->spinBox_rs2_width_depth->setValue(640);
2204 _ui->spinBox_rs2_height_depth->setValue(480);
2205 _ui->spinBox_rs2_rate_depth->setValue(30);
2206 _ui->checkbox_rs2_globalTimeStync->setChecked(
true);
2207 _ui->lineEdit_rs2_jsonFile->clear();
2208 _ui->lineEdit_openniOniPath->clear();
2209 _ui->lineEdit_openni2OniPath->clear();
2210 _ui->comboBox_k4a_rgb_resolution->setCurrentIndex(0);
2211 _ui->comboBox_k4a_framerate->setCurrentIndex(2);
2212 _ui->comboBox_k4a_depth_resolution->setCurrentIndex(2);
2213 _ui->checkbox_k4a_irDepth->setChecked(
false);
2214 _ui->lineEdit_k4a_mkv->clear();
2215 _ui->source_checkBox_useMKVStamps->setChecked(
true);
2216 _ui->lineEdit_cameraRGBDImages_path_rgb->setText(
"");
2217 _ui->lineEdit_cameraRGBDImages_path_depth->setText(
"");
2218 _ui->doubleSpinBox_cameraRGBDImages_scale->setValue(1.0);
2219 _ui->spinBox_cameraRGBDImages_startIndex->setValue(0);
2220 _ui->spinBox_cameraRGBDImages_maxFrames->setValue(0);
2221 _ui->lineEdit_source_distortionModel->setText(
"");
2222 _ui->groupBox_bilateral->setChecked(
false);
2223 _ui->doubleSpinBox_bilateral_sigmaS->setValue(10.0);
2224 _ui->doubleSpinBox_bilateral_sigmaR->setValue(0.1);
2227 _ui->lineEdit_cameraStereoImages_path_left->setText(
"");
2228 _ui->lineEdit_cameraStereoImages_path_right->setText(
"");
2229 _ui->checkBox_stereo_rectify->setChecked(
false);
2230 _ui->spinBox_cameraStereoImages_startIndex->setValue(0);
2231 _ui->spinBox_cameraStereoImages_maxFrames->setValue(0);
2232 _ui->lineEdit_cameraStereoVideo_path->setText(
"");
2233 _ui->lineEdit_cameraStereoVideo_path_2->setText(
"");
2234 _ui->spinBox_stereo_right_device->setValue(-1);
2235 _ui->spinBox_stereousbcam_streamWidth->setValue(0);
2236 _ui->spinBox_stereousbcam_streamHeight->setValue(0);
2237 _ui->comboBox_stereoZed_resolution->setCurrentIndex(0);
2238 _ui->comboBox_stereoZed_quality->setCurrentIndex(1);
2239 _ui->checkbox_stereoZed_selfCalibration->setChecked(
true);
2240 _ui->comboBox_stereoZed_sensingMode->setCurrentIndex(0);
2241 _ui->spinBox_stereoZed_confidenceThr->setValue(100);
2242 _ui->spinBox_stereoZed_texturenessConfidenceThr->setValue(90);
2243 _ui->lineEdit_zedSvoPath->clear();
2244 _ui->comboBox_stereoZedOC_resolution->setCurrentIndex(3);
2245 _ui->checkbox_stereoMyntEye_rectify->setChecked(
false);
2246 _ui->checkbox_stereoMyntEye_depth->setChecked(
false);
2247 _ui->checkbox_stereoMyntEye_autoExposure->setChecked(
true);
2248 _ui->spinBox_stereoMyntEye_gain->setValue(24);
2249 _ui->spinBox_stereoMyntEye_brightness->setValue(120);
2250 _ui->spinBox_stereoMyntEye_contrast->setValue(116);
2251 _ui->spinBox_stereoMyntEye_irControl->setValue(0);
2252 _ui->comboBox_depthai_resolution->setCurrentIndex(1);
2253 _ui->comboBox_depthai_output_mode->setCurrentIndex(0);
2254 _ui->spinBox_depthai_conf_threshold->setValue(200);
2255 _ui->checkBox_depthai_extended_disparity->setChecked(
false);
2256 _ui->comboBox_depthai_subpixel_fractional_bits->setCurrentIndex(2);
2257 _ui->comboBox_depthai_disparity_companding->setCurrentIndex(1);
2258 _ui->spinBox_depthai_lrc_threshold->setValue(5);
2259 _ui->checkBox_depthai_use_spec_translation->setChecked(
false);
2260 _ui->doubleSpinBox_depthai_alpha_scaling->setValue(-1);
2261 _ui->checkBox_depthai_imu_published->setChecked(
true);
2262 _ui->doubleSpinBox_depthai_dot_intensity->setValue(0.0);
2263 _ui->doubleSpinBox_depthai_flood_intensity->setValue(0.0);
2264 _ui->comboBox_depthai_detect_features->setCurrentIndex(0);
2265 _ui->lineEdit_depthai_blob_path->clear();
2267 _ui->checkBox_cameraImages_configForEachFrame->setChecked(
false);
2268 _ui->checkBox_cameraImages_timestamps->setChecked(
false);
2269 _ui->checkBox_cameraImages_syncTimeStamps->setChecked(
true);
2270 _ui->lineEdit_cameraImages_timestamps->setText(
"");
2271 _ui->lineEdit_cameraImages_path_scans->setText(
"");
2272 _ui->lineEdit_cameraImages_laser_transform->setText(
"0 0 0 0 0 0");
2273 _ui->spinBox_cameraImages_max_scan_pts->setValue(0);
2274 _ui->lineEdit_cameraImages_odom->setText(
"");
2275 _ui->comboBox_cameraImages_odomFormat->setCurrentIndex(0);
2276 _ui->lineEdit_cameraImages_gt->setText(
"");
2277 _ui->comboBox_cameraImages_gtFormat->setCurrentIndex(0);
2278 _ui->doubleSpinBox_maxPoseTimeDiff->setValue(0.02);
2279 _ui->lineEdit_cameraImages_path_imu->setText(
"");
2280 _ui->lineEdit_cameraImages_imu_transform->setText(
"0 0 1 0 -1 0 1 0 0");
2281 _ui->spinBox_cameraImages_max_imu_rate->setValue(0);
2283 _ui->comboBox_odom_sensor->setCurrentIndex(0);
2284 _ui->lineEdit_odom_sensor_extrinsics->setText(
"-0.000622602 0.0303752 0.031389 -0.00272485 0.00749254 0.0");
2285 _ui->lineEdit_odom_sensor_path_calibration->setText(
"");
2286 _ui->lineEdit_odomSourceDevice->setText(
"");
2287 _ui->doubleSpinBox_odom_sensor_time_offset->setValue(0.0);
2288 _ui->doubleSpinBox_odom_sensor_scale_factor->setValue(1);
2289 _ui->doubleSpinBox_odom_sensor_wait_time->setValue(100);
2290 _ui->checkBox_odom_sensor_use_as_gt->setChecked(
false);
2292 _ui->comboBox_imuFilter_strategy->setCurrentIndex(2);
2293 _ui->doubleSpinBox_imuFilterMadgwickGain->setValue(Parameters::defaultImuFilterMadgwickGain());
2294 _ui->doubleSpinBox_imuFilterMadgwickZeta->setValue(Parameters::defaultImuFilterMadgwickZeta());
2295 _ui->doubleSpinBox_imuFilterComplementaryGainAcc->setValue(Parameters::defaultImuFilterComplementaryGainAcc());
2296 _ui->doubleSpinBox_imuFilterComplementaryBiasAlpha->setValue(Parameters::defaultImuFilterComplementaryBiasAlpha());
2297 _ui->checkBox_imuFilterComplementaryDoAdaptiveGain->setChecked(Parameters::defaultImuFilterComplementaryDoAdpativeGain());
2298 _ui->checkBox_imuFilterComplementaryDoBiasEstimation->setChecked(Parameters::defaultImuFilterComplementaryDoBiasEstimation());
2299 _ui->checkBox_imuFilter_baseFrameConversion->setChecked(
true);
2300 _ui->checkbox_publishInterIMU->setChecked(
false);
2302 _ui->comboBox_lidar_src->setCurrentIndex(0);
2303 _ui->checkBox_source_scanDeskewing->setChecked(
false);
2304 _ui->checkBox_source_scanFromDepth->setChecked(
false);
2305 _ui->spinBox_source_scanDownsampleStep->setValue(1);
2306 _ui->doubleSpinBox_source_scanRangeMin->setValue(0);
2307 _ui->doubleSpinBox_source_scanRangeMax->setValue(0);
2308 _ui->doubleSpinBox_source_scanVoxelSize->setValue(0.0
f);
2309 _ui->spinBox_source_scanNormalsK->setValue(0);
2310 _ui->doubleSpinBox_source_scanNormalsRadius->setValue(0.0);
2311 _ui->doubleSpinBox_source_scanNormalsForceGroundUp->setValue(0);
2313 _ui->lineEdit_lidar_local_transform->setText(
"0 0 0 0 0 0");
2314 _ui->lineEdit_vlp16_pcap_path->clear();
2315 _ui->spinBox_vlp16_ip1->setValue(192);
2316 _ui->spinBox_vlp16_ip2->setValue(168);
2317 _ui->spinBox_vlp16_ip3->setValue(1);
2318 _ui->spinBox_vlp16_ip4->setValue(201);
2319 _ui->spinBox_vlp16_port->setValue(2368);
2320 _ui->checkBox_vlp16_organized->setChecked(
false);
2321 _ui->checkBox_vlp16_hostTime->setChecked(
true);
2322 _ui->checkBox_vlp16_stamp_last->setChecked(
true);
2324 _ui->groupBox_depthFromScan->setChecked(
false);
2325 _ui->groupBox_depthFromScan_fillHoles->setChecked(
true);
2326 _ui->radioButton_depthFromScan_vertical->setChecked(
true);
2327 _ui->radioButton_depthFromScan_horizontal->setChecked(
false);
2328 _ui->checkBox_depthFromScan_fillBorders->setChecked(
false);
2330 else if(groupBox->objectName() ==
_ui->groupBox_rtabmap_basic0->objectName())
2332 _ui->general_doubleSpinBox_timeThr_2->setValue(Parameters::defaultRtabmapTimeThr());
2333 _ui->general_doubleSpinBox_hardThr_2->setValue(Parameters::defaultRtabmapLoopThr());
2334 _ui->doubleSpinBox_similarityThreshold_2->setValue(Parameters::defaultMemRehearsalSimilarity());
2335 _ui->general_spinBox_imagesBufferSize_2->setValue(Parameters::defaultRtabmapImageBufferSize());
2336 _ui->general_spinBox_maxStMemSize_2->setValue(Parameters::defaultMemSTMSize());
2337 _ui->general_checkBox_publishStats_2->setChecked(Parameters::defaultRtabmapPublishStats());
2338 _ui->general_checkBox_activateRGBD_2->setChecked(Parameters::defaultRGBDEnabled());
2339 _ui->general_checkBox_SLAM_mode_2->setChecked(Parameters::defaultMemIncrementalMemory());
2340 _ui->general_doubleSpinBox_detectionRate_2->setValue(Parameters::defaultRtabmapDetectionRate());
2342 _ui->general_doubleSpinBox_timeThr->setValue(Parameters::defaultRtabmapTimeThr());
2343 _ui->general_doubleSpinBox_hardThr->setValue(Parameters::defaultRtabmapLoopThr());
2344 _ui->doubleSpinBox_similarityThreshold->setValue(Parameters::defaultMemRehearsalSimilarity());
2345 _ui->general_spinBox_imagesBufferSize->setValue(Parameters::defaultRtabmapImageBufferSize());
2346 _ui->general_spinBox_maxStMemSize->setValue(Parameters::defaultMemSTMSize());
2347 _ui->general_doubleSpinBox_detectionRate->setValue(Parameters::defaultRtabmapDetectionRate());
2351 QObjectList children = groupBox->children();
2354 for(
int i=0;
i<children.size(); ++
i)
2356 key = children.at(
i)->objectName().toStdString();
2359 if(
key.compare(Parameters::kRtabmapWorkingDirectory().c_str()) == 0)
2367 if(qobject_cast<const QGroupBox*>(children.at(
i)))
2372 else if(qobject_cast<const QGroupBox*>(children.at(
i)))
2376 else if(qobject_cast<const QStackedWidget*>(children.at(
i)))
2378 QStackedWidget * stackedWidget = (QStackedWidget*)children.at(
i);
2379 for(
int j=0;
j<stackedWidget->count(); ++
j)
2381 const QObjectList & children2 = stackedWidget->widget(
j)->children();
2382 for(
int k=0; k<children2.size(); ++k)
2384 if(qobject_cast<QGroupBox *>(children2.at(k)))
2393 if(groupBox->findChild<QLineEdit*>(
_ui->lineEdit_kp_roi->objectName()))
2398 if(groupBox->objectName() ==
_ui->groupBox_odometry1->objectName())
2400 _ui->odom_registration->setCurrentIndex(3);
2401 _ui->odom_f2m_gravitySigma->setValue(-1);
2409 if(panelNumber >= 0 && panelNumber < boxes.size())
2413 else if(panelNumber == -1)
2415 for(QList<QGroupBox*>::iterator
iter = boxes.begin();
iter!=boxes.end(); ++
iter)
2422 ULOGGER_WARN(
"panel number and the number of stacked widget doesn't match");
2429 return _ui->lineEdit_workingDirectory->text();
2434 QString privatePath = QDir::homePath() +
"/.rtabmap";
2435 if(!QDir(privatePath).exists())
2437 QDir::home().mkdir(
".rtabmap");
2439 return privatePath +
"/rtabmap.ini";
2449 QString
path = QFileDialog::getOpenFileName(
this, tr(
"Load settings..."), this->
getWorkingDirectory(),
"*.ini");
2467 QStandardItem * parentItem =
_indexModel->invisibleRootItem();
2470 for(
int i=1;
i<parentItem->rowCount(); ++
i)
2472 parentItem->child(
i)->setEnabled(
false);
2475 _ui->radioButton_basic->setEnabled(
false);
2476 _ui->radioButton_advanced->setEnabled(
false);
2481 QStandardItem * parentItem =
_indexModel->invisibleRootItem();
2484 for(
int i=0;
i<parentItem->rowCount(); ++
i)
2486 parentItem->child(
i)->setEnabled(
true);
2489 _ui->radioButton_basic->setEnabled(
true);
2490 _ui->radioButton_advanced->setEnabled(
true);
2497 if(!filePath.isEmpty())
2501 QSettings settings(
path, QSettings::IniFormat);
2502 settings.beginGroup(
"Gui");
2503 settings.beginGroup(
"General");
2504 _ui->general_checkBox_imagesKept->setChecked(settings.value(
"imagesKept",
_ui->general_checkBox_imagesKept->isChecked()).toBool());
2505 _ui->general_checkBox_missing_cache_republished->setChecked(settings.value(
"missingRepublished",
_ui->general_checkBox_missing_cache_republished->isChecked()).toBool());
2506 _ui->general_checkBox_cloudsKept->setChecked(settings.value(
"cloudsKept",
_ui->general_checkBox_cloudsKept->isChecked()).toBool());
2507 _ui->comboBox_loggerLevel->setCurrentIndex(settings.value(
"loggerLevel",
_ui->comboBox_loggerLevel->currentIndex()).toInt());
2508 _ui->comboBox_loggerEventLevel->setCurrentIndex(settings.value(
"loggerEventLevel",
_ui->comboBox_loggerEventLevel->currentIndex()).toInt());
2509 _ui->comboBox_loggerPauseLevel->setCurrentIndex(settings.value(
"loggerPauseLevel",
_ui->comboBox_loggerPauseLevel->currentIndex()).toInt());
2510 _ui->comboBox_loggerType->setCurrentIndex(settings.value(
"loggerType",
_ui->comboBox_loggerType->currentIndex()).toInt());
2511 _ui->checkBox_logger_printTime->setChecked(settings.value(
"loggerPrintTime",
_ui->checkBox_logger_printTime->isChecked()).toBool());
2512 _ui->checkBox_logger_printThreadId->setChecked(settings.value(
"loggerPrintThreadId",
_ui->checkBox_logger_printThreadId->isChecked()).toBool());
2513 _ui->checkBox_verticalLayoutUsed->setChecked(settings.value(
"verticalLayoutUsed",
_ui->checkBox_verticalLayoutUsed->isChecked()).toBool());
2514 _ui->checkBox_imageRejectedShown->setChecked(settings.value(
"imageRejectedShown",
_ui->checkBox_imageRejectedShown->isChecked()).toBool());
2515 _ui->checkBox_imageHighestHypShown->setChecked(settings.value(
"imageHighestHypShown",
_ui->checkBox_imageHighestHypShown->isChecked()).toBool());
2516 _ui->checkBox_beep->setChecked(settings.value(
"beep",
_ui->checkBox_beep->isChecked()).toBool());
2517 _ui->checkBox_stamps->setChecked(settings.value(
"figure_time",
_ui->checkBox_stamps->isChecked()).toBool());
2518 _ui->checkBox_cacheStatistics->setChecked(settings.value(
"figure_cache",
_ui->checkBox_cacheStatistics->isChecked()).toBool());
2519 _ui->checkBox_notifyWhenNewGlobalPathIsReceived->setChecked(settings.value(
"notifyNewGlobalPath",
_ui->checkBox_notifyWhenNewGlobalPathIsReceived->isChecked()).toBool());
2520 _ui->spinBox_odomQualityWarnThr->setValue(settings.value(
"odomQualityThr",
_ui->spinBox_odomQualityWarnThr->value()).toInt());
2521 _ui->checkBox_odom_onlyInliersShown->setChecked(settings.value(
"odomOnlyInliersShown",
_ui->checkBox_odom_onlyInliersShown->isChecked()).toBool());
2522 _ui->radioButton_posteriorGraphView->setChecked(settings.value(
"posteriorGraphView",
_ui->radioButton_posteriorGraphView->isChecked()).toBool());
2523 _ui->radioButton_wordsGraphView->setChecked(settings.value(
"wordsGraphView",
_ui->radioButton_wordsGraphView->isChecked()).toBool());
2524 _ui->radioButton_localizationsGraphView->setChecked(settings.value(
"localizationsGraphView",
_ui->radioButton_localizationsGraphView->isChecked()).toBool());
2525 _ui->radioButton_localizationsGraphViewOdomCache->setChecked(settings.value(
"localizationsGraphViewOdomCache",
_ui->radioButton_localizationsGraphViewOdomCache->isChecked()).toBool());
2526 _ui->radioButton_nochangeGraphView->setChecked(settings.value(
"nochangeGraphView",
_ui->radioButton_nochangeGraphView->isChecked()).toBool());
2527 _ui->checkbox_odomDisabled->setChecked(settings.value(
"odomDisabled",
_ui->checkbox_odomDisabled->isChecked()).toBool());
2528 _ui->odom_registration->setCurrentIndex(settings.value(
"odomRegistration",
_ui->odom_registration->currentIndex()).toInt());
2529 _ui->odom_f2m_gravitySigma->setValue(settings.value(
"odomF2MGravitySigma",
_ui->odom_f2m_gravitySigma->value()).toDouble());
2530 _ui->checkbox_groundTruthAlign->setChecked(settings.value(
"gtAlign",
_ui->checkbox_groundTruthAlign->isChecked()).toBool());
2532 for(
int i=0;
i<2; ++
i)
2558 _ui->doubleSpinBox_voxel->setValue(settings.value(
"cloudVoxel",
_ui->doubleSpinBox_voxel->value()).toDouble());
2559 _ui->doubleSpinBox_noiseRadius->setValue(settings.value(
"cloudNoiseRadius",
_ui->doubleSpinBox_noiseRadius->value()).toDouble());
2560 _ui->spinBox_noiseMinNeighbors->setValue(settings.value(
"cloudNoiseMinNeighbors",
_ui->spinBox_noiseMinNeighbors->value()).toInt());
2561 _ui->doubleSpinBox_ceilingFilterHeight->setValue(settings.value(
"cloudCeilingHeight",
_ui->doubleSpinBox_ceilingFilterHeight->value()).toDouble());
2562 _ui->doubleSpinBox_floorFilterHeight->setValue(settings.value(
"cloudFloorHeight",
_ui->doubleSpinBox_floorFilterHeight->value()).toDouble());
2563 _ui->spinBox_normalKSearch->setValue(settings.value(
"normalKSearch",
_ui->spinBox_normalKSearch->value()).toInt());
2564 _ui->doubleSpinBox_normalRadiusSearch->setValue(settings.value(
"normalRadiusSearch",
_ui->doubleSpinBox_normalRadiusSearch->value()).toDouble());
2565 _ui->doubleSpinBox_ceilingFilterHeight_scan->setValue(settings.value(
"scanCeilingHeight",
_ui->doubleSpinBox_ceilingFilterHeight_scan->value()).toDouble());
2566 _ui->doubleSpinBox_floorFilterHeight_scan->setValue(settings.value(
"scanFloorHeight",
_ui->doubleSpinBox_floorFilterHeight_scan->value()).toDouble());
2567 _ui->spinBox_normalKSearch_scan->setValue(settings.value(
"scanNormalKSearch",
_ui->spinBox_normalKSearch_scan->value()).toInt());
2568 _ui->doubleSpinBox_normalRadiusSearch_scan->setValue(settings.value(
"scanNormalRadiusSearch",
_ui->doubleSpinBox_normalRadiusSearch_scan->value()).toDouble());
2570 _ui->checkBox_showGraphs->setChecked(settings.value(
"showGraphs",
_ui->checkBox_showGraphs->isChecked()).toBool());
2571 _ui->checkBox_showLabels->setChecked(settings.value(
"showLabels",
_ui->checkBox_showLabels->isChecked()).toBool());
2572 _ui->checkBox_showFrames->setChecked(settings.value(
"showFrames",
_ui->checkBox_showFrames->isChecked()).toBool());
2573 _ui->checkBox_showLandmarks->setChecked(settings.value(
"showLandmarks",
_ui->checkBox_showLandmarks->isChecked()).toBool());
2574 _ui->doubleSpinBox_landmarkSize->setValue(settings.value(
"landmarkSize",
_ui->doubleSpinBox_landmarkSize->value()).toDouble());
2575 _ui->checkBox_showIMUGravity->setChecked(settings.value(
"showIMUGravity",
_ui->checkBox_showIMUGravity->isChecked()).toBool());
2576 _ui->checkBox_showIMUAcc->setChecked(settings.value(
"showIMUAcc",
_ui->checkBox_showIMUAcc->isChecked()).toBool());
2578 _ui->radioButton_noFiltering->setChecked(settings.value(
"noFiltering",
_ui->radioButton_noFiltering->isChecked()).toBool());
2579 _ui->radioButton_nodeFiltering->setChecked(settings.value(
"cloudFiltering",
_ui->radioButton_nodeFiltering->isChecked()).toBool());
2580 _ui->doubleSpinBox_cloudFilterRadius->setValue(settings.value(
"cloudFilteringRadius",
_ui->doubleSpinBox_cloudFilterRadius->value()).toDouble());
2581 _ui->doubleSpinBox_cloudFilterAngle->setValue(settings.value(
"cloudFilteringAngle",
_ui->doubleSpinBox_cloudFilterAngle->value()).toDouble());
2582 _ui->radioButton_subtractFiltering->setChecked(settings.value(
"subtractFiltering",
_ui->radioButton_subtractFiltering->isChecked()).toBool());
2583 _ui->spinBox_subtractFilteringMinPts->setValue(settings.value(
"subtractFilteringMinPts",
_ui->spinBox_subtractFilteringMinPts->value()).toInt());
2584 _ui->doubleSpinBox_subtractFilteringRadius->setValue(settings.value(
"subtractFilteringRadius",
_ui->doubleSpinBox_subtractFilteringRadius->value()).toDouble());
2585 _ui->doubleSpinBox_subtractFilteringAngle->setValue(settings.value(
"subtractFilteringAngle",
_ui->doubleSpinBox_subtractFilteringAngle->value()).toDouble());
2587 _ui->doubleSpinBox_map_resolution->setValue(settings.value(
"gridUIResolution",
_ui->doubleSpinBox_map_resolution->value()).toDouble());
2588 _ui->checkBox_map_shown->setChecked(settings.value(
"gridMapShown",
_ui->checkBox_map_shown->isChecked()).toBool());
2589 _ui->doubleSpinBox_map_opacity->setValue(settings.value(
"gridMapOpacity",
_ui->doubleSpinBox_map_opacity->value()).toDouble());
2590 _ui->checkBox_elevation_shown->setCheckState((Qt::CheckState)settings.value(
"elevationMapShown",
_ui->checkBox_elevation_shown->checkState()).toInt());
2592 _ui->groupBox_octomap->setChecked(settings.value(
"octomap",
_ui->groupBox_octomap->isChecked()).toBool());
2593 _ui->spinBox_octomap_treeDepth->setValue(settings.value(
"octomap_depth",
_ui->spinBox_octomap_treeDepth->value()).toInt());
2594 _ui->checkBox_octomap_2dgrid->setChecked(settings.value(
"octomap_2dgrid",
_ui->checkBox_octomap_2dgrid->isChecked()).toBool());
2595 _ui->checkBox_octomap_show3dMap->setChecked(settings.value(
"octomap_3dmap",
_ui->checkBox_octomap_show3dMap->isChecked()).toBool());
2596 _ui->comboBox_octomap_renderingType->setCurrentIndex(settings.value(
"octomap_rendering_type",
_ui->comboBox_octomap_renderingType->currentIndex()).toInt());
2597 _ui->spinBox_octomap_pointSize->setValue(settings.value(
"octomap_point_size",
_ui->spinBox_octomap_pointSize->value()).toInt());
2599 _ui->groupBox_organized->setChecked(settings.value(
"meshing",
_ui->groupBox_organized->isChecked()).toBool());
2600 _ui->doubleSpinBox_mesh_angleTolerance->setValue(settings.value(
"meshing_angle",
_ui->doubleSpinBox_mesh_angleTolerance->value()).toDouble());
2601 _ui->checkBox_mesh_quad->setChecked(settings.value(
"meshing_quad",
_ui->checkBox_mesh_quad->isChecked()).toBool());
2602 _ui->checkBox_mesh_texture->setChecked(settings.value(
"meshing_texture",
_ui->checkBox_mesh_texture->isChecked()).toBool());
2603 _ui->spinBox_mesh_triangleSize->setValue(settings.value(
"meshing_triangle_size",
_ui->spinBox_mesh_triangleSize->value()).toInt());
2605 settings.endGroup();
2607 settings.endGroup();
2613 if(!filePath.isEmpty())
2617 QSettings settings(
path, QSettings::IniFormat);
2619 settings.beginGroup(
"Camera");
2620 _ui->general_doubleSpinBox_imgRate->setValue(settings.value(
"imgRate",
_ui->general_doubleSpinBox_imgRate->value()).toDouble());
2621 _ui->source_mirroring->setChecked(settings.value(
"mirroring",
_ui->source_mirroring->isChecked()).toBool());
2622 _ui->lineEdit_calibrationFile->setText(settings.value(
"calibrationName",
_ui->lineEdit_calibrationFile->text()).toString());
2623 _ui->comboBox_sourceType->setCurrentIndex(settings.value(
"type",
_ui->comboBox_sourceType->currentIndex()).toInt());
2624 _ui->lineEdit_sourceDevice->setText(settings.value(
"device",
_ui->lineEdit_sourceDevice->text()).toString());
2625 _ui->lineEdit_sourceLocalTransform->setText(settings.value(
"localTransform",
_ui->lineEdit_sourceLocalTransform->text()).toString());
2626 _ui->spinBox_source_imageDecimation->setValue(settings.value(
"imageDecimation",
_ui->spinBox_source_imageDecimation->value()).toInt());
2627 _ui->comboBox_source_histogramMethod->setCurrentIndex(settings.value(
"histogramMethod",
_ui->comboBox_source_histogramMethod->currentIndex()).toInt());
2628 _ui->checkbox_source_feature_detection->setChecked(settings.value(
"featureDetection",
_ui->checkbox_source_feature_detection->isChecked()).toBool());
2630 if(
_ui->lineEdit_sourceLocalTransform->text().compare(
"0 0 1 -1 0 0 0 -1 0") == 0)
2632 UWARN(
"From 0.20.11, the local transform of the camera should not contain optical rotation (read=\"%s\"). Resetting to default Identity for convenience.",
_ui->lineEdit_sourceLocalTransform->text().toStdString().c_str());
2633 _ui->lineEdit_sourceLocalTransform->setText(
"0 0 0 0 0 0");
2636 settings.beginGroup(
"rgbd");
2637 _ui->comboBox_cameraRGBD->setCurrentIndex(settings.value(
"driver",
_ui->comboBox_cameraRGBD->currentIndex()).toInt());
2638 _ui->checkbox_rgbd_colorOnly->setChecked(settings.value(
"rgbdColorOnly",
_ui->checkbox_rgbd_colorOnly->isChecked()).toBool());
2639 _ui->lineEdit_source_distortionModel->setText(settings.value(
"distortion_model",
_ui->lineEdit_source_distortionModel->text()).toString());
2640 _ui->groupBox_bilateral->setChecked(settings.value(
"bilateral",
_ui->groupBox_bilateral->isChecked()).toBool());
2641 _ui->doubleSpinBox_bilateral_sigmaS->setValue(settings.value(
"bilateral_sigma_s",
_ui->doubleSpinBox_bilateral_sigmaS->value()).toDouble());
2642 _ui->doubleSpinBox_bilateral_sigmaR->setValue(settings.value(
"bilateral_sigma_r",
_ui->doubleSpinBox_bilateral_sigmaR->value()).toDouble());
2643 settings.endGroup();
2645 settings.beginGroup(
"stereo");
2646 _ui->comboBox_cameraStereo->setCurrentIndex(settings.value(
"driver",
_ui->comboBox_cameraStereo->currentIndex()).toInt());
2647 _ui->checkbox_stereo_depthGenerated->setChecked(settings.value(
"depthGenerated",
_ui->checkbox_stereo_depthGenerated->isChecked()).toBool());
2648 _ui->checkBox_stereo_exposureCompensation->setChecked(settings.value(
"exposureCompensation",
_ui->checkBox_stereo_exposureCompensation->isChecked()).toBool());
2649 settings.endGroup();
2651 settings.beginGroup(
"rgb");
2652 _ui->source_comboBox_image_type->setCurrentIndex(settings.value(
"driver",
_ui->source_comboBox_image_type->currentIndex()).toInt());
2653 _ui->checkBox_rgb_rectify->setChecked(settings.value(
"rectify",
_ui->checkBox_rgb_rectify->isChecked()).toBool());
2654 settings.endGroup();
2656 settings.beginGroup(
"Openni");
2657 _ui->lineEdit_openniOniPath->setText(settings.value(
"oniPath",
_ui->lineEdit_openniOniPath->text()).toString());
2658 settings.endGroup();
2660 settings.beginGroup(
"Openni2");
2661 _ui->openni2_autoWhiteBalance->setChecked(settings.value(
"autoWhiteBalance",
_ui->openni2_autoWhiteBalance->isChecked()).toBool());
2662 _ui->openni2_autoExposure->setChecked(settings.value(
"autoExposure",
_ui->openni2_autoExposure->isChecked()).toBool());
2663 _ui->openni2_exposure->setValue(settings.value(
"exposure",
_ui->openni2_exposure->value()).toInt());
2664 _ui->openni2_gain->setValue(settings.value(
"gain",
_ui->openni2_gain->value()).toInt());
2665 _ui->openni2_mirroring->setChecked(settings.value(
"mirroring",
_ui->openni2_mirroring->isChecked()).toBool());
2666 _ui->openni2_stampsIdsUsed->setChecked(settings.value(
"stampsIdsUsed",
_ui->openni2_stampsIdsUsed->isChecked()).toBool());
2667 _ui->lineEdit_openni2OniPath->setText(settings.value(
"oniPath",
_ui->lineEdit_openni2OniPath->text()).toString());
2668 _ui->openni2_hshift->setValue(settings.value(
"hshift",
_ui->openni2_hshift->value()).toInt());
2669 _ui->openni2_vshift->setValue(settings.value(
"vshift",
_ui->openni2_vshift->value()).toInt());
2670 _ui->openni2_depth_decimation->setValue(settings.value(
"depthDecimation",
_ui->openni2_depth_decimation->value()).toInt());
2671 settings.endGroup();
2673 settings.beginGroup(
"Freenect2");
2674 _ui->comboBox_freenect2Format->setCurrentIndex(settings.value(
"format",
_ui->comboBox_freenect2Format->currentIndex()).toInt());
2675 _ui->doubleSpinBox_freenect2MinDepth->setValue(settings.value(
"minDepth",
_ui->doubleSpinBox_freenect2MinDepth->value()).toDouble());
2676 _ui->doubleSpinBox_freenect2MaxDepth->setValue(settings.value(
"maxDepth",
_ui->doubleSpinBox_freenect2MaxDepth->value()).toDouble());
2677 _ui->checkBox_freenect2BilateralFiltering->setChecked(settings.value(
"bilateralFiltering",
_ui->checkBox_freenect2BilateralFiltering->isChecked()).toBool());
2678 _ui->checkBox_freenect2EdgeAwareFiltering->setChecked(settings.value(
"edgeAwareFiltering",
_ui->checkBox_freenect2EdgeAwareFiltering->isChecked()).toBool());
2679 _ui->checkBox_freenect2NoiseFiltering->setChecked(settings.value(
"noiseFiltering",
_ui->checkBox_freenect2NoiseFiltering->isChecked()).toBool());
2680 _ui->lineEdit_freenect2Pipeline->setText(settings.value(
"pipeline",
_ui->lineEdit_freenect2Pipeline->text()).toString());
2681 settings.endGroup();
2683 settings.beginGroup(
"K4W2");
2684 _ui->comboBox_k4w2Format->setCurrentIndex(settings.value(
"format",
_ui->comboBox_k4w2Format->currentIndex()).toInt());
2685 settings.endGroup();
2687 settings.beginGroup(
"K4A");
2688 _ui->comboBox_k4a_rgb_resolution->setCurrentIndex(settings.value(
"rgb_resolution",
_ui->comboBox_k4a_rgb_resolution->currentIndex()).toInt());
2689 _ui->comboBox_k4a_framerate->setCurrentIndex(settings.value(
"framerate",
_ui->comboBox_k4a_framerate->currentIndex()).toInt());
2690 _ui->comboBox_k4a_depth_resolution->setCurrentIndex(settings.value(
"depth_resolution",
_ui->comboBox_k4a_depth_resolution->currentIndex()).toInt());
2691 _ui->checkbox_k4a_irDepth->setChecked(settings.value(
"ir",
_ui->checkbox_k4a_irDepth->isChecked()).toBool());
2692 _ui->lineEdit_k4a_mkv->setText(settings.value(
"mkvPath",
_ui->lineEdit_k4a_mkv->text()).toString());
2693 _ui->source_checkBox_useMKVStamps->setChecked(settings.value(
"useMkvStamps",
_ui->source_checkBox_useMKVStamps->isChecked()).toBool());
2694 settings.endGroup();
2696 settings.beginGroup(
"RealSense");
2697 _ui->comboBox_realsensePresetRGB->setCurrentIndex(settings.value(
"presetRGB",
_ui->comboBox_realsensePresetRGB->currentIndex()).toInt());
2698 _ui->comboBox_realsensePresetDepth->setCurrentIndex(settings.value(
"presetDepth",
_ui->comboBox_realsensePresetDepth->currentIndex()).toInt());
2699 _ui->checkbox_realsenseOdom->setChecked(settings.value(
"odom",
_ui->checkbox_realsenseOdom->isChecked()).toBool());
2700 _ui->checkbox_realsenseDepthScaledToRGBSize->setChecked(settings.value(
"depthScaled",
_ui->checkbox_realsenseDepthScaledToRGBSize->isChecked()).toBool());
2701 _ui->comboBox_realsenseRGBSource->setCurrentIndex(settings.value(
"rgbSource",
_ui->comboBox_realsenseRGBSource->currentIndex()).toInt());
2702 settings.endGroup();
2704 settings.beginGroup(
"RealSense2");
2705 _ui->checkbox_rs2_emitter->setChecked(settings.value(
"emitter",
_ui->checkbox_rs2_emitter->isChecked()).toBool());
2706 _ui->checkbox_rs2_irMode->setChecked(settings.value(
"ir",
_ui->checkbox_rs2_irMode->isChecked()).toBool());
2707 _ui->checkbox_rs2_irDepth->setChecked(settings.value(
"irdepth",
_ui->checkbox_rs2_irDepth->isChecked()).toBool());
2708 _ui->spinBox_rs2_width->setValue(settings.value(
"width",
_ui->spinBox_rs2_width->value()).toInt());
2709 _ui->spinBox_rs2_height->setValue(settings.value(
"height",
_ui->spinBox_rs2_height->value()).toInt());
2710 _ui->spinBox_rs2_rate->setValue(settings.value(
"rate",
_ui->spinBox_rs2_rate->value()).toInt());
2711 _ui->spinBox_rs2_width_depth->setValue(settings.value(
"width_depth",
_ui->spinBox_rs2_width_depth->value()).toInt());
2712 _ui->spinBox_rs2_height_depth->setValue(settings.value(
"height_depth",
_ui->spinBox_rs2_height_depth->value()).toInt());
2713 _ui->spinBox_rs2_rate_depth->setValue(settings.value(
"rate_depth",
_ui->spinBox_rs2_rate_depth->value()).toInt());
2714 _ui->checkbox_rs2_globalTimeStync->setChecked(settings.value(
"global_time_sync",
_ui->checkbox_rs2_globalTimeStync->isChecked()).toBool());
2715 _ui->lineEdit_rs2_jsonFile->setText(settings.value(
"json_preset",
_ui->lineEdit_rs2_jsonFile->text()).toString());
2716 settings.endGroup();
2718 settings.beginGroup(
"RGBDImages");
2719 _ui->lineEdit_cameraRGBDImages_path_rgb->setText(settings.value(
"path_rgb",
_ui->lineEdit_cameraRGBDImages_path_rgb->text()).toString());
2720 _ui->lineEdit_cameraRGBDImages_path_depth->setText(settings.value(
"path_depth",
_ui->lineEdit_cameraRGBDImages_path_depth->text()).toString());
2721 _ui->doubleSpinBox_cameraRGBDImages_scale->setValue(settings.value(
"scale",
_ui->doubleSpinBox_cameraRGBDImages_scale->value()).toDouble());
2722 _ui->spinBox_cameraRGBDImages_startIndex->setValue(settings.value(
"start_index",
_ui->spinBox_cameraRGBDImages_startIndex->value()).toInt());
2723 _ui->spinBox_cameraRGBDImages_maxFrames->setValue(settings.value(
"max_frames",
_ui->spinBox_cameraRGBDImages_maxFrames->value()).toInt());
2724 settings.endGroup();
2726 settings.beginGroup(
"StereoImages");
2727 _ui->lineEdit_cameraStereoImages_path_left->setText(settings.value(
"path_left",
_ui->lineEdit_cameraStereoImages_path_left->text()).toString());
2728 _ui->lineEdit_cameraStereoImages_path_right->setText(settings.value(
"path_right",
_ui->lineEdit_cameraStereoImages_path_right->text()).toString());
2729 _ui->checkBox_stereo_rectify->setChecked(settings.value(
"rectify",
_ui->checkBox_stereo_rectify->isChecked()).toBool());
2730 _ui->spinBox_cameraStereoImages_startIndex->setValue(settings.value(
"start_index",
_ui->spinBox_cameraStereoImages_startIndex->value()).toInt());
2731 _ui->spinBox_cameraStereoImages_maxFrames->setValue(settings.value(
"max_frames",
_ui->spinBox_cameraStereoImages_maxFrames->value()).toInt());
2732 settings.endGroup();
2734 settings.beginGroup(
"StereoVideo");
2735 _ui->lineEdit_cameraStereoVideo_path->setText(settings.value(
"path",
_ui->lineEdit_cameraStereoVideo_path->text()).toString());
2736 _ui->lineEdit_cameraStereoVideo_path_2->setText(settings.value(
"path2",
_ui->lineEdit_cameraStereoVideo_path_2->text()).toString());
2737 _ui->spinBox_stereo_right_device->setValue(settings.value(
"device2",
_ui->spinBox_stereo_right_device->value()).toInt());
2738 _ui->spinBox_stereousbcam_streamWidth->setValue(settings.value(
"width",
_ui->spinBox_stereousbcam_streamWidth->value()).toInt());
2739 _ui->spinBox_stereousbcam_streamHeight->setValue(settings.value(
"height",
_ui->spinBox_stereousbcam_streamHeight->value()).toInt());
2740 _ui->lineEdit_stereousbcam_fourcc->setText(settings.value(
"fourcc",
_ui->lineEdit_stereousbcam_fourcc->text()).toString());
2741 settings.endGroup();
2743 settings.beginGroup(
"StereoZed");
2744 _ui->comboBox_stereoZed_resolution->setCurrentIndex(settings.value(
"resolution",
_ui->comboBox_stereoZed_resolution->currentIndex()).toInt());
2745 _ui->comboBox_stereoZed_quality->setCurrentIndex(settings.value(
"quality",
_ui->comboBox_stereoZed_quality->currentIndex()).toInt());
2746 _ui->checkbox_stereoZed_selfCalibration->setChecked(settings.value(
"self_calibration",
_ui->checkbox_stereoZed_selfCalibration->isChecked()).toBool());
2747 _ui->comboBox_stereoZed_sensingMode->setCurrentIndex(settings.value(
"sensing_mode",
_ui->comboBox_stereoZed_sensingMode->currentIndex()).toInt());
2748 _ui->spinBox_stereoZed_confidenceThr->setValue(settings.value(
"confidence_thr",
_ui->spinBox_stereoZed_confidenceThr->value()).toInt());
2749 _ui->spinBox_stereoZed_texturenessConfidenceThr->setValue(settings.value(
"textureness_confidence_thr",
_ui->spinBox_stereoZed_texturenessConfidenceThr->value()).toInt());
2750 _ui->lineEdit_zedSvoPath->setText(settings.value(
"svo_path",
_ui->lineEdit_zedSvoPath->text()).toString());
2751 settings.endGroup();
2753 settings.beginGroup(
"MyntEye");
2754 _ui->checkbox_stereoMyntEye_rectify->setChecked(settings.value(
"rectify",
_ui->checkbox_stereoMyntEye_rectify->isChecked()).toBool());
2755 _ui->checkbox_stereoMyntEye_depth->setChecked(settings.value(
"depth",
_ui->checkbox_stereoMyntEye_depth->isChecked()).toBool());
2756 _ui->checkbox_stereoMyntEye_autoExposure->setChecked(settings.value(
"auto_exposure",
_ui->checkbox_stereoMyntEye_autoExposure->isChecked()).toBool());
2757 _ui->spinBox_stereoMyntEye_gain->setValue(settings.value(
"gain",
_ui->spinBox_stereoMyntEye_gain->value()).toInt());
2758 _ui->spinBox_stereoMyntEye_brightness->setValue(settings.value(
"brightness",
_ui->spinBox_stereoMyntEye_brightness->value()).toInt());
2759 _ui->spinBox_stereoMyntEye_contrast->setValue(settings.value(
"contrast",
_ui->spinBox_stereoMyntEye_contrast->value()).toInt());
2760 _ui->spinBox_stereoMyntEye_irControl->setValue(settings.value(
"ir_control",
_ui->spinBox_stereoMyntEye_irControl->value()).toInt());
2761 settings.endGroup();
2763 settings.beginGroup(
"DepthAI");
2764 _ui->comboBox_depthai_resolution->setCurrentIndex(settings.value(
"resolution",
_ui->comboBox_depthai_resolution->currentIndex()).toInt());
2765 _ui->comboBox_depthai_output_mode->setCurrentIndex(settings.value(
"output_mode",
_ui->comboBox_depthai_output_mode->currentIndex()).toInt());
2766 _ui->spinBox_depthai_conf_threshold->setValue(settings.value(
"conf_threshold",
_ui->spinBox_depthai_conf_threshold->value()).toInt());
2767 _ui->spinBox_depthai_lrc_threshold->setValue(settings.value(
"lrc_threshold",
_ui->spinBox_depthai_lrc_threshold->value()).toInt());
2768 _ui->checkBox_depthai_extended_disparity->setChecked(settings.value(
"extended_disparity",
_ui->checkBox_depthai_extended_disparity->isChecked()).toBool());
2769 _ui->comboBox_depthai_subpixel_fractional_bits->setCurrentIndex(settings.value(
"subpixel_fractional_bits",
_ui->comboBox_depthai_subpixel_fractional_bits->currentIndex()).toInt());
2770 _ui->comboBox_depthai_disparity_companding->setCurrentIndex(settings.value(
"companding",
_ui->comboBox_depthai_disparity_companding->currentIndex()).toInt());
2771 _ui->checkBox_depthai_use_spec_translation->setChecked(settings.value(
"use_spec_translation",
_ui->checkBox_depthai_use_spec_translation->isChecked()).toBool());
2772 _ui->doubleSpinBox_depthai_alpha_scaling->setValue(settings.value(
"alpha_scaling",
_ui->doubleSpinBox_depthai_alpha_scaling->value()).toDouble());
2773 _ui->checkBox_depthai_imu_published->setChecked(settings.value(
"imu_published",
_ui->checkBox_depthai_imu_published->isChecked()).toBool());
2774 _ui->doubleSpinBox_depthai_dot_intensity->setValue(settings.value(
"dot_intensity",
_ui->doubleSpinBox_depthai_dot_intensity->value()).toDouble());
2775 _ui->doubleSpinBox_depthai_flood_intensity->setValue(settings.value(
"flood_intensity",
_ui->doubleSpinBox_depthai_flood_intensity->value()).toDouble());
2776 _ui->comboBox_depthai_detect_features->setCurrentIndex(settings.value(
"detect_features",
_ui->comboBox_depthai_detect_features->currentIndex()).toInt());
2777 _ui->lineEdit_depthai_blob_path->setText(settings.value(
"blob_path",
_ui->lineEdit_depthai_blob_path->text()).toString());
2778 settings.endGroup();
2780 settings.beginGroup(
"Images");
2781 _ui->source_images_lineEdit_path->setText(settings.value(
"path",
_ui->source_images_lineEdit_path->text()).toString());
2782 _ui->source_images_spinBox_startPos->setValue(settings.value(
"startPos",
_ui->source_images_spinBox_startPos->value()).toInt());
2783 _ui->source_images_spinBox_maxFrames->setValue(settings.value(
"maxFrames",
_ui->source_images_spinBox_maxFrames->value()).toInt());
2784 _ui->comboBox_cameraImages_bayerMode->setCurrentIndex(settings.value(
"bayerMode",
_ui->comboBox_cameraImages_bayerMode->currentIndex()).toInt());
2786 _ui->checkBox_cameraImages_configForEachFrame->setChecked(settings.value(
"config_each_frame",
_ui->checkBox_cameraImages_configForEachFrame->isChecked()).toBool());
2787 _ui->checkBox_cameraImages_timestamps->setChecked(settings.value(
"filenames_as_stamps",
_ui->checkBox_cameraImages_timestamps->isChecked()).toBool());
2788 _ui->checkBox_cameraImages_syncTimeStamps->setChecked(settings.value(
"sync_stamps",
_ui->checkBox_cameraImages_syncTimeStamps->isChecked()).toBool());
2789 _ui->lineEdit_cameraImages_timestamps->setText(settings.value(
"stamps",
_ui->lineEdit_cameraImages_timestamps->text()).toString());
2790 _ui->lineEdit_cameraImages_path_scans->setText(settings.value(
"path_scans",
_ui->lineEdit_cameraImages_path_scans->text()).toString());
2791 _ui->lineEdit_cameraImages_laser_transform->setText(settings.value(
"scan_transform",
_ui->lineEdit_cameraImages_laser_transform->text()).toString());
2792 _ui->spinBox_cameraImages_max_scan_pts->setValue(settings.value(
"scan_max_pts",
_ui->spinBox_cameraImages_max_scan_pts->value()).toInt());
2793 _ui->lineEdit_cameraImages_odom->setText(settings.value(
"odom_path",
_ui->lineEdit_cameraImages_odom->text()).toString());
2794 _ui->comboBox_cameraImages_odomFormat->setCurrentIndex(settings.value(
"odom_format",
_ui->comboBox_cameraImages_odomFormat->currentIndex()).toInt());
2795 _ui->lineEdit_cameraImages_gt->setText(settings.value(
"gt_path",
_ui->lineEdit_cameraImages_gt->text()).toString());
2796 _ui->comboBox_cameraImages_gtFormat->setCurrentIndex(settings.value(
"gt_format",
_ui->comboBox_cameraImages_gtFormat->currentIndex()).toInt());
2797 _ui->doubleSpinBox_maxPoseTimeDiff->setValue(settings.value(
"max_pose_time_diff",
_ui->doubleSpinBox_maxPoseTimeDiff->value()).toDouble());
2799 _ui->lineEdit_cameraImages_path_imu->setText(settings.value(
"imu_path",
_ui->lineEdit_cameraImages_path_imu->text()).toString());
2800 _ui->lineEdit_cameraImages_imu_transform->setText(settings.value(
"imu_local_transform",
_ui->lineEdit_cameraImages_imu_transform->text()).toString());
2801 _ui->spinBox_cameraImages_max_imu_rate->setValue(settings.value(
"imu_rate",
_ui->spinBox_cameraImages_max_imu_rate->value()).toInt());
2802 settings.endGroup();
2804 settings.beginGroup(
"OdomSensor");
2805 _ui->comboBox_odom_sensor->setCurrentIndex(settings.value(
"odom_sensor",
_ui->comboBox_odom_sensor->currentIndex()).toInt());
2806 _ui->lineEdit_odom_sensor_extrinsics->setText(settings.value(
"odom_sensor_extrinsics",
_ui->lineEdit_odom_sensor_extrinsics->text()).toString());
2807 _ui->lineEdit_odom_sensor_path_calibration->setText(settings.value(
"odom_sensor_calibration_path",
_ui->lineEdit_odom_sensor_path_calibration->text()).toString());
2808 _ui->lineEdit_odomSourceDevice->setText(settings.value(
"odom_sensor_device",
_ui->lineEdit_odomSourceDevice->text()).toString());
2809 _ui->doubleSpinBox_odom_sensor_time_offset->setValue(settings.value(
"odom_sensor_offset_time",
_ui->doubleSpinBox_odom_sensor_time_offset->value()).toDouble());
2810 _ui->doubleSpinBox_odom_sensor_scale_factor->setValue(settings.value(
"odom_sensor_scale_factor",
_ui->doubleSpinBox_odom_sensor_scale_factor->value()).toDouble());
2811 _ui->doubleSpinBox_odom_sensor_wait_time->setValue(settings.value(
"odom_sensor_wait_time",
_ui->doubleSpinBox_odom_sensor_wait_time->value()).toDouble());
2812 _ui->checkBox_odom_sensor_use_as_gt->setChecked(settings.value(
"odom_sensor_odom_as_gt",
_ui->checkBox_odom_sensor_use_as_gt->isChecked()).toBool());
2813 settings.endGroup();
2815 settings.beginGroup(
"UsbCam");
2816 _ui->spinBox_usbcam_streamWidth->setValue(settings.value(
"width",
_ui->spinBox_usbcam_streamWidth->value()).toInt());
2817 _ui->spinBox_usbcam_streamHeight->setValue(settings.value(
"height",
_ui->spinBox_usbcam_streamHeight->value()).toInt());
2818 _ui->lineEdit_usbcam_fourcc->setText(settings.value(
"fourcc",
_ui->lineEdit_usbcam_fourcc->text()).toString());
2819 settings.endGroup();
2821 settings.beginGroup(
"Video");
2822 _ui->source_video_lineEdit_path->setText(settings.value(
"path",
_ui->source_video_lineEdit_path->text()).toString());
2823 settings.endGroup();
2825 settings.beginGroup(
"IMU");
2826 _ui->comboBox_imuFilter_strategy->setCurrentIndex(settings.value(
"strategy",
_ui->comboBox_imuFilter_strategy->currentIndex()).toInt());
2827 _ui->doubleSpinBox_imuFilterMadgwickGain->setValue(settings.value(
"madgwick_gain",
_ui->doubleSpinBox_imuFilterMadgwickGain->value()).toDouble());
2828 _ui->doubleSpinBox_imuFilterMadgwickZeta->setValue(settings.value(
"madgwick_zeta",
_ui->doubleSpinBox_imuFilterMadgwickZeta->value()).toDouble());
2829 _ui->doubleSpinBox_imuFilterComplementaryGainAcc->setValue(settings.value(
"complementary_gain_acc",
_ui->doubleSpinBox_imuFilterComplementaryGainAcc->value()).toDouble());
2830 _ui->doubleSpinBox_imuFilterComplementaryBiasAlpha->setValue(settings.value(
"complementary_bias_alpha",
_ui->doubleSpinBox_imuFilterComplementaryBiasAlpha->value()).toDouble());
2831 _ui->checkBox_imuFilterComplementaryDoAdaptiveGain->setChecked(settings.value(
"complementary_adaptive_gain",
_ui->checkBox_imuFilterComplementaryDoAdaptiveGain->isChecked()).toBool());
2832 _ui->checkBox_imuFilterComplementaryDoBiasEstimation->setChecked(settings.value(
"complementary_biais_estimation",
_ui->checkBox_imuFilterComplementaryDoBiasEstimation->isChecked()).toBool());
2833 _ui->checkBox_imuFilter_baseFrameConversion->setChecked(settings.value(
"base_frame_conversion",
_ui->checkBox_imuFilter_baseFrameConversion->isChecked()).toBool());
2834 _ui->checkbox_publishInterIMU->setChecked(settings.value(
"publish_inter_imu",
_ui->checkbox_publishInterIMU->isChecked()).toBool());
2835 settings.endGroup();
2837 settings.beginGroup(
"Scan");
2838 _ui->comboBox_lidar_src->setCurrentIndex(settings.value(
"source",
_ui->comboBox_lidar_src->currentIndex()).toInt());
2839 _ui->checkBox_source_scanDeskewing->setChecked(settings.value(
"deskewing",
_ui->checkBox_source_scanDeskewing->isChecked()).toBool());
2840 _ui->checkBox_source_scanFromDepth->setChecked(settings.value(
"fromDepth",
_ui->checkBox_source_scanFromDepth->isChecked()).toBool());
2841 _ui->spinBox_source_scanDownsampleStep->setValue(settings.value(
"downsampleStep",
_ui->spinBox_source_scanDownsampleStep->value()).toInt());
2842 _ui->doubleSpinBox_source_scanRangeMin->setValue(settings.value(
"rangeMin",
_ui->doubleSpinBox_source_scanRangeMin->value()).toDouble());
2843 _ui->doubleSpinBox_source_scanRangeMax->setValue(settings.value(
"rangeMax",
_ui->doubleSpinBox_source_scanRangeMax->value()).toDouble());
2844 _ui->doubleSpinBox_source_scanVoxelSize->setValue(settings.value(
"voxelSize",
_ui->doubleSpinBox_source_scanVoxelSize->value()).toDouble());
2845 _ui->spinBox_source_scanNormalsK->setValue(settings.value(
"normalsK",
_ui->spinBox_source_scanNormalsK->value()).toInt());
2846 _ui->doubleSpinBox_source_scanNormalsRadius->setValue(settings.value(
"normalsRadius",
_ui->doubleSpinBox_source_scanNormalsRadius->value()).toDouble());
2847 _ui->doubleSpinBox_source_scanNormalsForceGroundUp->setValue(settings.value(
"normalsUpF",
_ui->doubleSpinBox_source_scanNormalsForceGroundUp->value()).toDouble());
2848 settings.endGroup();
2850 settings.beginGroup(
"DepthFromScan");
2851 _ui->groupBox_depthFromScan->setChecked(settings.value(
"depthFromScan",
_ui->groupBox_depthFromScan->isChecked()).toBool());
2852 _ui->groupBox_depthFromScan_fillHoles->setChecked(settings.value(
"depthFromScanFillHoles",
_ui->groupBox_depthFromScan_fillHoles->isChecked()).toBool());
2853 _ui->radioButton_depthFromScan_vertical->setChecked(settings.value(
"depthFromScanVertical",
_ui->radioButton_depthFromScan_vertical->isChecked()).toBool());
2854 _ui->radioButton_depthFromScan_horizontal->setChecked(settings.value(
"depthFromScanHorizontal",
_ui->radioButton_depthFromScan_horizontal->isChecked()).toBool());
2855 _ui->checkBox_depthFromScan_fillBorders->setChecked(settings.value(
"depthFromScanFillBorders",
_ui->checkBox_depthFromScan_fillBorders->isChecked()).toBool());
2856 settings.endGroup();
2858 settings.beginGroup(
"Database");
2859 _ui->source_database_lineEdit_path->setText(settings.value(
"path",
_ui->source_database_lineEdit_path->text()).toString());
2860 _ui->source_checkBox_ignoreOdometry->setChecked(settings.value(
"ignoreOdometry",
_ui->source_checkBox_ignoreOdometry->isChecked()).toBool());
2861 _ui->source_checkBox_ignoreGoalDelay->setChecked(settings.value(
"ignoreGoalDelay",
_ui->source_checkBox_ignoreGoalDelay->isChecked()).toBool());
2862 _ui->source_checkBox_ignoreGoals->setChecked(settings.value(
"ignoreGoals",
_ui->source_checkBox_ignoreGoals->isChecked()).toBool());
2863 _ui->source_checkBox_ignoreLandmarks->setChecked(settings.value(
"ignoreLandmarks",
_ui->source_checkBox_ignoreLandmarks->isChecked()).toBool());
2864 _ui->source_checkBox_ignoreFeatures->setChecked(settings.value(
"ignoreFeatures",
_ui->source_checkBox_ignoreFeatures->isChecked()).toBool());
2865 _ui->source_checkBox_ignorePriors->setChecked(settings.value(
"ignorePriors",
_ui->source_checkBox_ignorePriors->isChecked()).toBool());
2866 _ui->source_spinBox_databaseStartId->setValue(settings.value(
"startId",
_ui->source_spinBox_databaseStartId->value()).toInt());
2867 _ui->source_spinBox_databaseStopId->setValue(settings.value(
"stopId",
_ui->source_spinBox_databaseStopId->value()).toInt());
2868 _ui->source_spinBox_database_cameraIndex->setValue(settings.value(
"cameraIndex",
_ui->source_spinBox_database_cameraIndex->value()).toInt());
2869 _ui->source_checkBox_useDbStamps->setChecked(settings.value(
"useDatabaseStamps",
_ui->source_checkBox_useDbStamps->isChecked()).toBool());
2870 settings.endGroup();
2872 settings.endGroup();
2874 settings.beginGroup(
"Lidar");
2876 settings.beginGroup(
"VLP16");
2877 _ui->lineEdit_lidar_local_transform->setText(settings.value(
"localTransform",
_ui->lineEdit_lidar_local_transform->text()).toString());
2878 _ui->lineEdit_vlp16_pcap_path->setText(settings.value(
"pcapPath",
_ui->lineEdit_vlp16_pcap_path->text()).toString());
2879 _ui->spinBox_vlp16_ip1->setValue(settings.value(
"ip1",
_ui->spinBox_vlp16_ip1->value()).toInt());
2880 _ui->spinBox_vlp16_ip2->setValue(settings.value(
"ip2",
_ui->spinBox_vlp16_ip2->value()).toInt());
2881 _ui->spinBox_vlp16_ip3->setValue(settings.value(
"ip3",
_ui->spinBox_vlp16_ip3->value()).toInt());
2882 _ui->spinBox_vlp16_ip4->setValue(settings.value(
"ip4",
_ui->spinBox_vlp16_ip4->value()).toInt());
2883 _ui->spinBox_vlp16_port->setValue(settings.value(
"port",
_ui->spinBox_vlp16_port->value()).toInt());
2884 _ui->checkBox_vlp16_organized->setChecked(settings.value(
"organized",
_ui->checkBox_vlp16_organized->isChecked()).toBool());
2885 _ui->checkBox_vlp16_hostTime->setChecked(settings.value(
"hostTime",
_ui->checkBox_vlp16_hostTime->isChecked()).toBool());
2886 _ui->checkBox_vlp16_stamp_last->setChecked(settings.value(
"stampLast",
_ui->checkBox_vlp16_stamp_last->isChecked()).toBool());
2887 settings.endGroup();
2889 settings.endGroup();
2903 if(!filePath.isEmpty())
2910 if(!QFile::exists(
path))
2912 QMessageBox::information(
this, tr(
"INI file doesn't exist..."), tr(
"The configuration file \"%1\" does not exist, it will be created with default parameters.").
arg(
path));
2918 for(rtabmap::ParametersMap::const_iterator
iter = parameters.begin();
iter!=parameters.end(); ++
iter)
2921 if(
iter->first.compare(Parameters::kRtabmapWorkingDirectory()) == 0)
2925 UWARN(
"Reading config: Working directory is empty. Keeping old one (\"%s\").",
2935 UWARN(
"Reading config: Not existing working directory \"%s\". Keeping old one (\"%s\").",
2937 this->getWorkingDirectory().toStdString().c_str());
2943 UWARN(
"Reading config: Not existing working directory \"%s\". Using default one (\"%s\").",
2945 defaultWorkingDir.c_str());
2946 value = defaultWorkingDir;
2952 if(
iter->first.compare(Parameters::kIcpStrategy()) == 0)
2954 if(
value.compare(
"true") == 0)
2958 else if(
value.compare(
"false") == 0)
2968 if(parameters.find(Parameters::kRtabmapWorkingDirectory()) == parameters.end())
2972 QMessageBox::information(
this,
2973 tr(
"Working directory"),
2974 tr(
"RTAB-Map needs a working directory to put the database.\n\n"
2975 "By default, the directory \"%1\" is used.\n\n"
2976 "The working directory can be changed any time in the "
2988 QString
path = QFileDialog::getSaveFileName(
this, tr(
"Save settings..."), this->
getWorkingDirectory()+QDir::separator()+
"config.ini",
"*.ini");
3001 int button = QMessageBox::warning(
this,
3002 tr(
"Reset settings..."),
3003 tr(
"This will reset all settings. Restore all settings to default without saving them first?"),
3004 QMessageBox::Cancel | QMessageBox::Yes | QMessageBox::Save,
3005 QMessageBox::Cancel);
3006 if(button == QMessageBox::Yes ||
3018 if(!presetHexHeader.empty())
3026 parameters.erase(Parameters::kRtabmapWorkingDirectory());
3027 for(ParametersMap::iterator
iter=parameters.begin();
iter!=parameters.end(); ++
iter)
3035 if(sender() ==
_ui->pushButton_presets_camera_tof_icp)
3039 else if(sender() ==
_ui->pushButton_presets_lidar_3d_icp)
3045 UERROR(
"Unknown sender!");
3048 QMessageBox::information(
this,
3050 tr(
"Loaded \"%1\" preset!").
arg(((QPushButton*)sender())->
text()),
3076 bool different =
true;
3100 if(!filePath.isEmpty())
3104 QSettings settings(
path, QSettings::IniFormat);
3105 settings.beginGroup(
"Gui");
3107 settings.beginGroup(
"General");
3108 settings.remove(
"");
3109 settings.setValue(
"imagesKept",
_ui->general_checkBox_imagesKept->isChecked());
3110 settings.setValue(
"missingRepublished",
_ui->general_checkBox_missing_cache_republished->isChecked());
3111 settings.setValue(
"cloudsKept",
_ui->general_checkBox_cloudsKept->isChecked());
3112 settings.setValue(
"loggerLevel",
_ui->comboBox_loggerLevel->currentIndex());
3113 settings.setValue(
"loggerEventLevel",
_ui->comboBox_loggerEventLevel->currentIndex());
3114 settings.setValue(
"loggerPauseLevel",
_ui->comboBox_loggerPauseLevel->currentIndex());
3115 settings.setValue(
"loggerType",
_ui->comboBox_loggerType->currentIndex());
3116 settings.setValue(
"loggerPrintTime",
_ui->checkBox_logger_printTime->isChecked());
3117 settings.setValue(
"loggerPrintThreadId",
_ui->checkBox_logger_printThreadId->isChecked());
3118 settings.setValue(
"verticalLayoutUsed",
_ui->checkBox_verticalLayoutUsed->isChecked());
3119 settings.setValue(
"imageRejectedShown",
_ui->checkBox_imageRejectedShown->isChecked());
3120 settings.setValue(
"imageHighestHypShown",
_ui->checkBox_imageHighestHypShown->isChecked());
3121 settings.setValue(
"beep",
_ui->checkBox_beep->isChecked());
3122 settings.setValue(
"figure_time",
_ui->checkBox_stamps->isChecked());
3123 settings.setValue(
"figure_cache",
_ui->checkBox_cacheStatistics->isChecked());
3124 settings.setValue(
"notifyNewGlobalPath",
_ui->checkBox_notifyWhenNewGlobalPathIsReceived->isChecked());
3125 settings.setValue(
"odomQualityThr",
_ui->spinBox_odomQualityWarnThr->value());
3126 settings.setValue(
"odomOnlyInliersShown",
_ui->checkBox_odom_onlyInliersShown->isChecked());
3127 settings.setValue(
"posteriorGraphView",
_ui->radioButton_posteriorGraphView->isChecked());
3128 settings.setValue(
"wordsGraphView",
_ui->radioButton_wordsGraphView->isChecked());
3129 settings.setValue(
"localizationsGraphView",
_ui->radioButton_localizationsGraphView->isChecked());
3130 settings.setValue(
"localizationsGraphViewOdomCache",
_ui->radioButton_localizationsGraphViewOdomCache->isChecked());
3131 settings.setValue(
"nochangeGraphView",
_ui->radioButton_nochangeGraphView->isChecked());
3132 settings.setValue(
"odomDisabled",
_ui->checkbox_odomDisabled->isChecked());
3133 settings.setValue(
"odomRegistration",
_ui->odom_registration->currentIndex());
3134 settings.setValue(
"odomF2MGravitySigma",
_ui->odom_f2m_gravitySigma->value());
3135 settings.setValue(
"gtAlign",
_ui->checkbox_groundTruthAlign->isChecked());
3137 for(
int i=0;
i<2; ++
i)
3162 settings.setValue(
"cloudVoxel",
_ui->doubleSpinBox_voxel->value());
3163 settings.setValue(
"cloudNoiseRadius",
_ui->doubleSpinBox_noiseRadius->value());
3164 settings.setValue(
"cloudNoiseMinNeighbors",
_ui->spinBox_noiseMinNeighbors->value());
3165 settings.setValue(
"cloudCeilingHeight",
_ui->doubleSpinBox_ceilingFilterHeight->value());
3166 settings.setValue(
"cloudFloorHeight",
_ui->doubleSpinBox_floorFilterHeight->value());
3167 settings.setValue(
"normalKSearch",
_ui->spinBox_normalKSearch->value());
3168 settings.setValue(
"normalRadiusSearch",
_ui->doubleSpinBox_normalRadiusSearch->value());
3169 settings.setValue(
"scanCeilingHeight",
_ui->doubleSpinBox_ceilingFilterHeight_scan->value());
3170 settings.setValue(
"scanFloorHeight",
_ui->doubleSpinBox_floorFilterHeight_scan->value());
3171 settings.setValue(
"scanNormalKSearch",
_ui->spinBox_normalKSearch_scan->value());
3172 settings.setValue(
"scanNormalRadiusSearch",
_ui->doubleSpinBox_normalRadiusSearch_scan->value());
3174 settings.setValue(
"showGraphs",
_ui->checkBox_showGraphs->isChecked());
3175 settings.setValue(
"showLabels",
_ui->checkBox_showLabels->isChecked());
3176 settings.setValue(
"showFrames",
_ui->checkBox_showFrames->isChecked());
3177 settings.setValue(
"showLandmarks",
_ui->checkBox_showLandmarks->isChecked());
3178 settings.setValue(
"landmarkSize",
_ui->doubleSpinBox_landmarkSize->value());
3179 settings.setValue(
"showIMUGravity",
_ui->checkBox_showIMUGravity->isChecked());
3180 settings.setValue(
"showIMUAcc",
_ui->checkBox_showIMUAcc->isChecked());
3183 settings.setValue(
"noFiltering",
_ui->radioButton_noFiltering->isChecked());
3184 settings.setValue(
"cloudFiltering",
_ui->radioButton_nodeFiltering->isChecked());
3185 settings.setValue(
"cloudFilteringRadius",
_ui->doubleSpinBox_cloudFilterRadius->value());
3186 settings.setValue(
"cloudFilteringAngle",
_ui->doubleSpinBox_cloudFilterAngle->value());
3187 settings.setValue(
"subtractFiltering",
_ui->radioButton_subtractFiltering->isChecked());
3188 settings.setValue(
"subtractFilteringMinPts",
_ui->spinBox_subtractFilteringMinPts->value());
3189 settings.setValue(
"subtractFilteringRadius",
_ui->doubleSpinBox_subtractFilteringRadius->value());
3190 settings.setValue(
"subtractFilteringAngle",
_ui->doubleSpinBox_subtractFilteringAngle->value());
3192 settings.setValue(
"gridUIResolution",
_ui->doubleSpinBox_map_resolution->value());
3193 settings.setValue(
"gridMapShown",
_ui->checkBox_map_shown->isChecked());
3194 settings.setValue(
"gridMapOpacity",
_ui->doubleSpinBox_map_opacity->value());
3195 settings.setValue(
"elevationMapShown",
_ui->checkBox_elevation_shown->checkState());
3198 settings.setValue(
"octomap",
_ui->groupBox_octomap->isChecked());
3199 settings.setValue(
"octomap_depth",
_ui->spinBox_octomap_treeDepth->value());
3200 settings.setValue(
"octomap_2dgrid",
_ui->checkBox_octomap_2dgrid->isChecked());
3201 settings.setValue(
"octomap_3dmap",
_ui->checkBox_octomap_show3dMap->isChecked());
3202 settings.setValue(
"octomap_rendering_type",
_ui->comboBox_octomap_renderingType->currentIndex());
3203 settings.setValue(
"octomap_point_size",
_ui->spinBox_octomap_pointSize->value());
3206 settings.setValue(
"meshing",
_ui->groupBox_organized->isChecked());
3207 settings.setValue(
"meshing_angle",
_ui->doubleSpinBox_mesh_angleTolerance->value());
3208 settings.setValue(
"meshing_quad",
_ui->checkBox_mesh_quad->isChecked());
3209 settings.setValue(
"meshing_texture",
_ui->checkBox_mesh_texture->isChecked());
3210 settings.setValue(
"meshing_triangle_size",
_ui->spinBox_mesh_triangleSize->value());
3212 settings.endGroup();
3214 settings.endGroup();
3220 if(!filePath.isEmpty())
3224 QSettings settings(
path, QSettings::IniFormat);
3226 settings.beginGroup(
"Camera");
3227 settings.remove(
"");
3228 settings.setValue(
"imgRate",
_ui->general_doubleSpinBox_imgRate->value());
3229 settings.setValue(
"mirroring",
_ui->source_mirroring->isChecked());
3230 settings.setValue(
"calibrationName",
_ui->lineEdit_calibrationFile->text());
3231 settings.setValue(
"type",
_ui->comboBox_sourceType->currentIndex());
3232 settings.setValue(
"device",
_ui->lineEdit_sourceDevice->text());
3233 settings.setValue(
"localTransform",
_ui->lineEdit_sourceLocalTransform->text());
3234 settings.setValue(
"imageDecimation",
_ui->spinBox_source_imageDecimation->value());
3235 settings.setValue(
"histogramMethod",
_ui->comboBox_source_histogramMethod->currentIndex());
3236 settings.setValue(
"featureDetection",
_ui->checkbox_source_feature_detection->isChecked());
3238 settings.beginGroup(
"rgbd");
3239 settings.setValue(
"driver",
_ui->comboBox_cameraRGBD->currentIndex());
3240 settings.setValue(
"rgbdColorOnly",
_ui->checkbox_rgbd_colorOnly->isChecked());
3241 settings.setValue(
"distortion_model",
_ui->lineEdit_source_distortionModel->text());
3242 settings.setValue(
"bilateral",
_ui->groupBox_bilateral->isChecked());
3243 settings.setValue(
"bilateral_sigma_s",
_ui->doubleSpinBox_bilateral_sigmaS->value());
3244 settings.setValue(
"bilateral_sigma_r",
_ui->doubleSpinBox_bilateral_sigmaR->value());
3245 settings.endGroup();
3247 settings.beginGroup(
"stereo");
3248 settings.setValue(
"driver",
_ui->comboBox_cameraStereo->currentIndex());
3249 settings.setValue(
"depthGenerated",
_ui->checkbox_stereo_depthGenerated->isChecked());
3250 settings.setValue(
"exposureCompensation",
_ui->checkBox_stereo_exposureCompensation->isChecked());
3251 settings.endGroup();
3253 settings.beginGroup(
"rgb");
3254 settings.setValue(
"driver",
_ui->source_comboBox_image_type->currentIndex());
3255 settings.setValue(
"rectify",
_ui->checkBox_rgb_rectify->isChecked());
3256 settings.endGroup();
3258 settings.beginGroup(
"Openni");
3259 settings.setValue(
"oniPath",
_ui->lineEdit_openniOniPath->text());
3260 settings.endGroup();
3262 settings.beginGroup(
"Openni2");
3263 settings.setValue(
"autoWhiteBalance",
_ui->openni2_autoWhiteBalance->isChecked());
3264 settings.setValue(
"autoExposure",
_ui->openni2_autoExposure->isChecked());
3265 settings.setValue(
"exposure",
_ui->openni2_exposure->value());
3266 settings.setValue(
"gain",
_ui->openni2_gain->value());
3267 settings.setValue(
"mirroring",
_ui->openni2_mirroring->isChecked());
3268 settings.setValue(
"stampsIdsUsed",
_ui->openni2_stampsIdsUsed->isChecked());
3269 settings.setValue(
"oniPath",
_ui->lineEdit_openni2OniPath->text());
3270 settings.setValue(
"hshift",
_ui->openni2_hshift->value());
3271 settings.setValue(
"vshift",
_ui->openni2_vshift->value());
3272 settings.setValue(
"depthDecimation",
_ui->openni2_depth_decimation->value());
3273 settings.endGroup();
3275 settings.beginGroup(
"Freenect2");
3276 settings.setValue(
"format",
_ui->comboBox_freenect2Format->currentIndex());
3277 settings.setValue(
"minDepth",
_ui->doubleSpinBox_freenect2MinDepth->value());
3278 settings.setValue(
"maxDepth",
_ui->doubleSpinBox_freenect2MaxDepth->value());
3279 settings.setValue(
"bilateralFiltering",
_ui->checkBox_freenect2BilateralFiltering->isChecked());
3280 settings.setValue(
"edgeAwareFiltering",
_ui->checkBox_freenect2EdgeAwareFiltering->isChecked());
3281 settings.setValue(
"noiseFiltering",
_ui->checkBox_freenect2NoiseFiltering->isChecked());
3282 settings.setValue(
"pipeline",
_ui->lineEdit_freenect2Pipeline->text());
3283 settings.endGroup();
3285 settings.beginGroup(
"K4W2");
3286 settings.setValue(
"format",
_ui->comboBox_k4w2Format->currentIndex());
3287 settings.endGroup();
3289 settings.beginGroup(
"K4A");
3290 settings.setValue(
"rgb_resolution",
_ui->comboBox_k4a_rgb_resolution->currentIndex());
3291 settings.setValue(
"framerate",
_ui->comboBox_k4a_framerate->currentIndex());
3292 settings.setValue(
"depth_resolution",
_ui->comboBox_k4a_depth_resolution->currentIndex());
3293 settings.setValue(
"ir",
_ui->checkbox_k4a_irDepth->isChecked());
3294 settings.setValue(
"mkvPath",
_ui->lineEdit_k4a_mkv->text());
3295 settings.setValue(
"useMkvStamps",
_ui->source_checkBox_useMKVStamps->isChecked());
3296 settings.endGroup();
3298 settings.beginGroup(
"RealSense");
3299 settings.setValue(
"presetRGB",
_ui->comboBox_realsensePresetRGB->currentIndex());
3300 settings.setValue(
"presetDepth",
_ui->comboBox_realsensePresetDepth->currentIndex());
3301 settings.setValue(
"odom",
_ui->checkbox_realsenseOdom->isChecked());
3302 settings.setValue(
"depthScaled",
_ui->checkbox_realsenseDepthScaledToRGBSize->isChecked());
3303 settings.setValue(
"rgbSource",
_ui->comboBox_realsenseRGBSource->currentIndex());
3304 settings.endGroup();
3306 settings.beginGroup(
"RealSense2");
3307 settings.setValue(
"emitter",
_ui->checkbox_rs2_emitter->isChecked());
3308 settings.setValue(
"ir",
_ui->checkbox_rs2_irMode->isChecked());
3309 settings.setValue(
"irdepth",
_ui->checkbox_rs2_irDepth->isChecked());
3310 settings.setValue(
"width",
_ui->spinBox_rs2_width->value());
3311 settings.setValue(
"height",
_ui->spinBox_rs2_height->value());
3312 settings.setValue(
"rate",
_ui->spinBox_rs2_rate->value());
3313 settings.setValue(
"width_depth",
_ui->spinBox_rs2_width_depth->value());
3314 settings.setValue(
"height_depth",
_ui->spinBox_rs2_height_depth->value());
3315 settings.setValue(
"rate_depth",
_ui->spinBox_rs2_rate_depth->value());
3316 settings.setValue(
"global_time_sync",
_ui->checkbox_rs2_globalTimeStync->isChecked());
3317 settings.setValue(
"json_preset",
_ui->lineEdit_rs2_jsonFile->text());
3318 settings.endGroup();
3320 settings.beginGroup(
"RGBDImages");
3321 settings.setValue(
"path_rgb",
_ui->lineEdit_cameraRGBDImages_path_rgb->text());
3322 settings.setValue(
"path_depth",
_ui->lineEdit_cameraRGBDImages_path_depth->text());
3323 settings.setValue(
"scale",
_ui->doubleSpinBox_cameraRGBDImages_scale->value());
3324 settings.setValue(
"start_index",
_ui->spinBox_cameraRGBDImages_startIndex->value());
3325 settings.setValue(
"max_frames",
_ui->spinBox_cameraRGBDImages_maxFrames->value());
3326 settings.endGroup();
3328 settings.beginGroup(
"StereoImages");
3329 settings.setValue(
"path_left",
_ui->lineEdit_cameraStereoImages_path_left->text());
3330 settings.setValue(
"path_right",
_ui->lineEdit_cameraStereoImages_path_right->text());
3331 settings.setValue(
"rectify",
_ui->checkBox_stereo_rectify->isChecked());
3332 settings.setValue(
"start_index",
_ui->spinBox_cameraStereoImages_startIndex->value());
3333 settings.setValue(
"max_frames",
_ui->spinBox_cameraStereoImages_maxFrames->value());
3334 settings.endGroup();
3336 settings.beginGroup(
"StereoVideo");
3337 settings.setValue(
"path",
_ui->lineEdit_cameraStereoVideo_path->text());
3338 settings.setValue(
"path2",
_ui->lineEdit_cameraStereoVideo_path_2->text());
3339 settings.setValue(
"device2",
_ui->spinBox_stereo_right_device->value());
3340 settings.setValue(
"width",
_ui->spinBox_stereousbcam_streamWidth->value());
3341 settings.setValue(
"height",
_ui->spinBox_stereousbcam_streamHeight->value());
3342 settings.setValue(
"fourcc",
_ui->lineEdit_stereousbcam_fourcc->text());
3343 settings.endGroup();
3345 settings.beginGroup(
"StereoZed");
3346 settings.setValue(
"resolution",
_ui->comboBox_stereoZed_resolution->currentIndex());
3347 settings.setValue(
"quality",
_ui->comboBox_stereoZed_quality->currentIndex());
3348 settings.setValue(
"self_calibration",
_ui->checkbox_stereoZed_selfCalibration->isChecked());
3349 settings.setValue(
"sensing_mode",
_ui->comboBox_stereoZed_sensingMode->currentIndex());
3350 settings.setValue(
"confidence_thr",
_ui->spinBox_stereoZed_confidenceThr->value());
3351 settings.setValue(
"textureness_confidence_thr",
_ui->spinBox_stereoZed_texturenessConfidenceThr->value());
3352 settings.setValue(
"svo_path",
_ui->lineEdit_zedSvoPath->text());
3353 settings.endGroup();
3355 settings.beginGroup(
"MyntEye");
3356 settings.setValue(
"rectify",
_ui->checkbox_stereoMyntEye_rectify->isChecked());
3357 settings.setValue(
"depth",
_ui->checkbox_stereoMyntEye_depth->isChecked());
3358 settings.setValue(
"auto_exposure",
_ui->checkbox_stereoMyntEye_autoExposure->isChecked());
3359 settings.setValue(
"gain",
_ui->spinBox_stereoMyntEye_gain->value());
3360 settings.setValue(
"brightness",
_ui->spinBox_stereoMyntEye_brightness->value());
3361 settings.setValue(
"contrast",
_ui->spinBox_stereoMyntEye_contrast->value());
3362 settings.setValue(
"ir_control",
_ui->spinBox_stereoMyntEye_irControl->value());
3363 settings.endGroup();
3365 settings.beginGroup(
"DepthAI");
3366 settings.setValue(
"resolution",
_ui->comboBox_depthai_resolution->currentIndex());
3367 settings.setValue(
"output_mode",
_ui->comboBox_depthai_output_mode->currentIndex());
3368 settings.setValue(
"conf_threshold",
_ui->spinBox_depthai_conf_threshold->value());
3369 settings.setValue(
"lrc_threshold",
_ui->spinBox_depthai_lrc_threshold->value());
3370 settings.setValue(
"extended_disparity",
_ui->checkBox_depthai_extended_disparity->isChecked());
3371 settings.setValue(
"subpixel_fractional_bits",
_ui->comboBox_depthai_subpixel_fractional_bits->currentIndex());
3372 settings.setValue(
"companding",
_ui->comboBox_depthai_disparity_companding->currentIndex());
3373 settings.setValue(
"use_spec_translation",
_ui->checkBox_depthai_use_spec_translation->isChecked());
3374 settings.setValue(
"alpha_scaling",
_ui->doubleSpinBox_depthai_alpha_scaling->value());
3375 settings.setValue(
"imu_published",
_ui->checkBox_depthai_imu_published->isChecked());
3376 settings.setValue(
"dot_intensity",
_ui->doubleSpinBox_depthai_dot_intensity->value());
3377 settings.setValue(
"flood_intensity",
_ui->doubleSpinBox_depthai_flood_intensity->value());
3378 settings.setValue(
"detect_features",
_ui->comboBox_depthai_detect_features->currentIndex());
3379 settings.setValue(
"blob_path",
_ui->lineEdit_depthai_blob_path->text());
3380 settings.endGroup();
3382 settings.beginGroup(
"Images");
3383 settings.setValue(
"path",
_ui->source_images_lineEdit_path->text());
3384 settings.setValue(
"startPos",
_ui->source_images_spinBox_startPos->value());
3385 settings.setValue(
"maxFrames",
_ui->source_images_spinBox_maxFrames->value());
3386 settings.setValue(
"bayerMode",
_ui->comboBox_cameraImages_bayerMode->currentIndex());
3387 settings.setValue(
"config_each_frame",
_ui->checkBox_cameraImages_configForEachFrame->isChecked());
3388 settings.setValue(
"filenames_as_stamps",
_ui->checkBox_cameraImages_timestamps->isChecked());
3389 settings.setValue(
"sync_stamps",
_ui->checkBox_cameraImages_syncTimeStamps->isChecked());
3390 settings.setValue(
"stamps",
_ui->lineEdit_cameraImages_timestamps->text());
3391 settings.setValue(
"path_scans",
_ui->lineEdit_cameraImages_path_scans->text());
3392 settings.setValue(
"scan_transform",
_ui->lineEdit_cameraImages_laser_transform->text());
3393 settings.setValue(
"scan_max_pts",
_ui->spinBox_cameraImages_max_scan_pts->value());
3394 settings.setValue(
"odom_path",
_ui->lineEdit_cameraImages_odom->text());
3395 settings.setValue(
"odom_format",
_ui->comboBox_cameraImages_odomFormat->currentIndex());
3396 settings.setValue(
"gt_path",
_ui->lineEdit_cameraImages_gt->text());
3397 settings.setValue(
"gt_format",
_ui->comboBox_cameraImages_gtFormat->currentIndex());
3398 settings.setValue(
"max_pose_time_diff",
_ui->doubleSpinBox_maxPoseTimeDiff->value());
3399 settings.setValue(
"imu_path",
_ui->lineEdit_cameraImages_path_imu->text());
3400 settings.setValue(
"imu_local_transform",
_ui->lineEdit_cameraImages_imu_transform->text());
3401 settings.setValue(
"imu_rate",
_ui->spinBox_cameraImages_max_imu_rate->value());
3402 settings.endGroup();
3404 settings.beginGroup(
"OdomSensor");
3405 settings.setValue(
"odom_sensor",
_ui->comboBox_odom_sensor->currentIndex());
3406 settings.setValue(
"odom_sensor_extrinsics",
_ui->lineEdit_odom_sensor_extrinsics->text());
3407 settings.setValue(
"odom_sensor_calibration_path",
_ui->lineEdit_odom_sensor_path_calibration->text());
3408 settings.setValue(
"odom_sensor_device",
_ui->lineEdit_odomSourceDevice->text());
3409 settings.setValue(
"odom_sensor_offset_time",
_ui->doubleSpinBox_odom_sensor_time_offset->value());
3410 settings.setValue(
"odom_sensor_scale_factor",
_ui->doubleSpinBox_odom_sensor_scale_factor->value());
3411 settings.setValue(
"odom_sensor_wait_time",
_ui->doubleSpinBox_odom_sensor_wait_time->value());
3412 settings.setValue(
"odom_sensor_odom_as_gt",
_ui->checkBox_odom_sensor_use_as_gt->isChecked());
3413 settings.endGroup();
3415 settings.beginGroup(
"UsbCam");
3416 settings.setValue(
"width",
_ui->spinBox_usbcam_streamWidth->value());
3417 settings.setValue(
"height",
_ui->spinBox_usbcam_streamHeight->value());
3418 settings.setValue(
"fourcc",
_ui->lineEdit_usbcam_fourcc->text());
3419 settings.endGroup();
3421 settings.beginGroup(
"Video");
3422 settings.setValue(
"path",
_ui->source_video_lineEdit_path->text());
3423 settings.endGroup();
3425 settings.beginGroup(
"IMU");
3426 settings.setValue(
"strategy",
_ui->comboBox_imuFilter_strategy->currentIndex());
3427 settings.setValue(
"madgwick_gain",
_ui->doubleSpinBox_imuFilterMadgwickGain->value());
3428 settings.setValue(
"madgwick_zeta",
_ui->doubleSpinBox_imuFilterMadgwickZeta->value());
3429 settings.setValue(
"complementary_gain_acc",
_ui->doubleSpinBox_imuFilterComplementaryGainAcc->value());
3430 settings.setValue(
"complementary_bias_alpha",
_ui->doubleSpinBox_imuFilterComplementaryBiasAlpha->value());
3431 settings.setValue(
"complementary_adaptive_gain",
_ui->checkBox_imuFilterComplementaryDoAdaptiveGain->isChecked());
3432 settings.setValue(
"complementary_biais_estimation",
_ui->checkBox_imuFilterComplementaryDoBiasEstimation->isChecked());
3433 settings.setValue(
"base_frame_conversion",
_ui->checkBox_imuFilter_baseFrameConversion->isChecked());
3434 settings.setValue(
"publish_inter_imu",
_ui->checkbox_publishInterIMU->isChecked());
3435 settings.endGroup();
3437 settings.beginGroup(
"Scan");
3438 settings.setValue(
"source",
_ui->comboBox_lidar_src->currentIndex());
3439 settings.setValue(
"deskewing",
_ui->checkBox_source_scanDeskewing->isChecked());
3440 settings.setValue(
"fromDepth",
_ui->checkBox_source_scanFromDepth->isChecked());
3441 settings.setValue(
"downsampleStep",
_ui->spinBox_source_scanDownsampleStep->value());
3442 settings.setValue(
"rangeMin",
_ui->doubleSpinBox_source_scanRangeMin->value());
3443 settings.setValue(
"rangeMax",
_ui->doubleSpinBox_source_scanRangeMax->value());
3444 settings.setValue(
"voxelSize",
_ui->doubleSpinBox_source_scanVoxelSize->value());
3445 settings.setValue(
"normalsK",
_ui->spinBox_source_scanNormalsK->value());
3446 settings.setValue(
"normalsRadius",
_ui->doubleSpinBox_source_scanNormalsRadius->value());
3447 settings.setValue(
"normalsUpF",
_ui->doubleSpinBox_source_scanNormalsForceGroundUp->value());
3448 settings.endGroup();
3450 settings.beginGroup(
"DepthFromScan");
3451 settings.setValue(
"depthFromScan",
_ui->groupBox_depthFromScan->isChecked());
3452 settings.setValue(
"depthFromScanFillHoles",
_ui->groupBox_depthFromScan_fillHoles->isChecked());
3453 settings.setValue(
"depthFromScanVertical",
_ui->radioButton_depthFromScan_vertical->isChecked());
3454 settings.setValue(
"depthFromScanHorizontal",
_ui->radioButton_depthFromScan_horizontal->isChecked());
3455 settings.setValue(
"depthFromScanFillBorders",
_ui->checkBox_depthFromScan_fillBorders->isChecked());
3456 settings.endGroup();
3458 settings.beginGroup(
"Database");
3459 settings.setValue(
"path",
_ui->source_database_lineEdit_path->text());
3460 settings.setValue(
"ignoreOdometry",
_ui->source_checkBox_ignoreOdometry->isChecked());
3461 settings.setValue(
"ignoreGoalDelay",
_ui->source_checkBox_ignoreGoalDelay->isChecked());
3462 settings.setValue(
"ignoreGoals",
_ui->source_checkBox_ignoreGoals->isChecked());
3463 settings.setValue(
"ignoreLandmarks",
_ui->source_checkBox_ignoreLandmarks->isChecked());
3464 settings.setValue(
"ignoreFeatures",
_ui->source_checkBox_ignoreFeatures->isChecked());
3465 settings.setValue(
"ignorePriors",
_ui->source_checkBox_ignorePriors->isChecked());
3466 settings.setValue(
"startId",
_ui->source_spinBox_databaseStartId->value());
3467 settings.setValue(
"stopId",
_ui->source_spinBox_databaseStopId->value());
3468 settings.setValue(
"cameraIndex",
_ui->source_spinBox_database_cameraIndex->value());
3469 settings.setValue(
"useDatabaseStamps",
_ui->source_checkBox_useDbStamps->isChecked());
3470 settings.endGroup();
3472 settings.endGroup();
3474 settings.beginGroup(
"Lidar");
3476 settings.beginGroup(
"VLP16");
3477 settings.setValue(
"localTransform",
_ui->lineEdit_lidar_local_transform->text());
3478 settings.setValue(
"pcapPath",
_ui->lineEdit_vlp16_pcap_path->text());
3479 settings.setValue(
"ip1",
_ui->spinBox_vlp16_ip1->value());
3480 settings.setValue(
"ip2",
_ui->spinBox_vlp16_ip2->value());
3481 settings.setValue(
"ip3",
_ui->spinBox_vlp16_ip3->value());
3482 settings.setValue(
"ip4",
_ui->spinBox_vlp16_ip4->value());
3483 settings.setValue(
"port",
_ui->spinBox_vlp16_port->value());
3484 settings.setValue(
"organized",
_ui->checkBox_vlp16_organized->isChecked());
3485 settings.setValue(
"hostTime",
_ui->checkBox_vlp16_hostTime->isChecked());
3486 settings.setValue(
"stampLast",
_ui->checkBox_vlp16_stamp_last->isChecked());
3487 settings.endGroup();
3489 settings.endGroup();
3497 if(!filePath.isEmpty())
3507 #if CV_MAJOR_VERSION < 3 || (CV_MAJOR_VERSION == 4 && CV_MINOR_VERSION <= 3) || (CV_MAJOR_VERSION == 3 && (CV_MINOR_VERSION < 4 || (CV_MINOR_VERSION==4 && CV_SUBMINOR_VERSION<11)))
3508 #ifndef RTABMAP_NONFREE
3511 if(
_ui->comboBox_detector_strategy->currentIndex() <= 1 ||
_ui->comboBox_detector_strategy->currentIndex() == 12)
3513 QMessageBox::warning(
this, tr(
"Parameter warning"),
3514 tr(
"Selected feature type (SURF/SIFT) is not available. RTAB-Map is not built "
3515 "with the nonfree module from OpenCV. ORB is set instead for the bag-of-words dictionary."));
3519 if(
_ui->vis_feature_detector->currentIndex() <= 1 ||
_ui->vis_feature_detector->currentIndex() == 12)
3521 QMessageBox::warning(
this, tr(
"Parameter warning"),
3522 tr(
"Selected feature type (SURF/SIFT) is not available. RTAB-Map is not built "
3523 "with the nonfree module from OpenCV. Fast/Brief is set instead for the re-extraction "
3524 "of features on loop closure."));
3528 #else //>= 4.4.0 >= 3.4.11
3529 #ifndef RTABMAP_NONFREE
3532 if(
_ui->comboBox_detector_strategy->currentIndex() < 1 ||
_ui->comboBox_detector_strategy->currentIndex() == 12)
3534 QMessageBox::warning(
this, tr(
"Parameter warning"),
3535 tr(
"Selected feature type (SURF) is not available. RTAB-Map is not built "
3536 "with the nonfree module from OpenCV. SIFT is set instead for the bag-of-words dictionary."));
3540 if(
_ui->vis_feature_detector->currentIndex() < 1 ||
_ui->vis_feature_detector->currentIndex() == 12)
3542 QMessageBox::warning(
this, tr(
"Parameter warning"),
3543 tr(
"Selected feature type (SURF) is not available. RTAB-Map is not built "
3544 "with the nonfree module from OpenCV. Fast/Brief is set instead for the re-extraction "
3545 "of features on loop closure."));
3551 #if CV_MAJOR_VERSION < 3
3554 #ifdef RTABMAP_NONFREE
3555 QMessageBox::warning(
this, tr(
"Parameter warning"),
3556 tr(
"Selected feature type (KAZE) is not available on OpenCV2. SURF is set instead "
3557 "for the bag-of-words dictionary."));
3560 QMessageBox::warning(
this, tr(
"Parameter warning"),
3561 tr(
"Selected feature type (KAZE) is not available on OpenCV2. ORB is set instead "
3562 "for the bag-of-words dictionary."));
3568 #ifdef RTABMAP_NONFREE
3569 QMessageBox::warning(
this, tr(
"Parameter warning"),
3570 tr(
"Selected feature type (KAZE) is not available on OpenCV2. SURF is set instead "
3571 "for the re-extraction of features on loop closure."));
3574 QMessageBox::warning(
this, tr(
"Parameter warning"),
3575 tr(
"Selected feature type (KAZE) is not available on OpenCV2. ORB is set instead "
3576 "for the re-extraction of features on loop closure."));
3582 #ifndef RTABMAP_ORB_OCTREE
3585 QMessageBox::warning(
this, tr(
"Parameter warning"),
3586 tr(
"Selected feature type (ORB Octree) is not available. ORB is set instead "
3587 "for the bag-of-words dictionary."));
3592 QMessageBox::warning(
this, tr(
"Parameter warning"),
3593 tr(
"Selected feature type (ORB Octree) is not available on OpenCV2. ORB is set instead "
3594 "for the re-extraction of features on loop closure."));
3604 QMessageBox::warning(
this, tr(
"Parameter warning"),
3605 tr(
"Selected graph optimization strategy (TORO) is not available. RTAB-Map is not built "
3606 "with TORO. GTSAM is set instead for graph optimization strategy."));
3609 #ifndef RTABMAP_ORB_SLAM
3612 QMessageBox::warning(
this, tr(
"Parameter warning"),
3613 tr(
"Selected graph optimization strategy (TORO) is not available. RTAB-Map is not built "
3614 "with TORO. g2o is set instead for graph optimization strategy."));
3619 #ifdef RTABMAP_ORB_SLAM
3620 if(
_ui->graphOptimization_type->currentIndex() == 1)
3627 QMessageBox::warning(
this, tr(
"Parameter warning"),
3628 tr(
"Selected graph optimization strategy (g2o) is not available. RTAB-Map is not built "
3629 "with g2o. GTSAM is set instead for graph optimization strategy."));
3634 QMessageBox::warning(
this, tr(
"Parameter warning"),
3635 tr(
"Selected graph optimization strategy (g2o) is not available. RTAB-Map is not built "
3636 "with g2o. TORO is set instead for graph optimization strategy."));
3642 #ifndef RTABMAP_ORB_SLAM
3645 QMessageBox::warning(
this, tr(
"Parameter warning"),
3646 tr(
"Selected graph optimization strategy (GTSAM) is not available. RTAB-Map is not built "
3647 "with GTSAM. g2o is set instead for graph optimization strategy."));
3654 QMessageBox::warning(
this, tr(
"Parameter warning"),
3655 tr(
"Selected graph optimization strategy (GTSAM) is not available. RTAB-Map is not built "
3656 "with GTSAM. TORO is set instead for graph optimization strategy."));
3664 QMessageBox::warning(
this, tr(
"Parameter warning"),
3665 tr(
"Selected visual registration bundle adjustment optimization strategy (g2o) is not available. RTAB-Map is not built "
3666 "with g2o. Bundle adjustment is disabled."));
3667 _ui->loopClosure_bundle->setCurrentIndex(0);
3671 QMessageBox::warning(
this, tr(
"Parameter warning"),
3672 tr(
"Selected visual registration bundle adjustment optimization strategy (cvsba) is not available. RTAB-Map is not built "
3673 "with cvsba. Bundle adjustment is disabled."));
3674 _ui->loopClosure_bundle->setCurrentIndex(0);
3678 QMessageBox::warning(
this, tr(
"Parameter warning"),
3679 tr(
"Selected visual registration bundle adjustment optimization strategy (Ceres) is not available. RTAB-Map is not built "
3680 "with cERES. Bundle adjustment is disabled."));
3681 _ui->loopClosure_bundle->setCurrentIndex(0);
3687 QMessageBox::warning(
this, tr(
"Parameter warning"),
3688 tr(
"Selected odometry local bundle adjustment optimization strategy (g2o) is not available. RTAB-Map is not built "
3689 "with g2o. Bundle adjustment is disabled."));
3690 _ui->odom_f2m_bundleStrategy->setCurrentIndex(0);
3694 QMessageBox::warning(
this, tr(
"Parameter warning"),
3695 tr(
"Selected odometry local bundle adjustment optimization strategy (cvsba) is not available. RTAB-Map is not built "
3696 "with cvsba. Bundle adjustment is disabled."));
3697 _ui->odom_f2m_bundleStrategy->setCurrentIndex(0);
3701 QMessageBox::warning(
this, tr(
"Parameter warning"),
3702 tr(
"Selected odometry local bundle adjustment optimization strategy (Ceres) is not available. RTAB-Map is not built "
3703 "with Ceres. Bundle adjustment is disabled."));
3704 _ui->odom_f2m_bundleStrategy->setCurrentIndex(0);
3708 if(
_ui->graphOptimization_robust->isChecked() &&
_ui->graphOptimization_maxError->value()>0.0)
3710 QMessageBox::warning(
this, tr(
"Parameter warning"),
3711 tr(
"Robust graph optimization and maximum optimization error threshold cannot be "
3712 "both used at the same time. Disabling robust optimization."));
3713 _ui->graphOptimization_robust->setChecked(
false);
3720 QMessageBox::warning(
this, tr(
"Parameter warning"),
3721 tr(
"With the selected feature type (SURF or SIFT), parameter \"Visual word->Nearest Neighbor\" "
3722 "cannot be LSH (used for binary descriptor). KD-tree is set instead for the bag-of-words dictionary."));
3729 QMessageBox::warning(
this, tr(
"Parameter warning"),
3730 tr(
"With the selected feature type (SURF or SIFT), parameter \"Visual word->Nearest Neighbor\" "
3731 "cannot be LSH (used for binary descriptor). KD-tree is set instead for the re-extraction "
3732 "of features on loop closure."));
3736 if(
_ui->doubleSpinBox_freenect2MinDepth->value() >=
_ui->doubleSpinBox_freenect2MaxDepth->value())
3738 QMessageBox::warning(
this, tr(
"Parameter warning"),
3739 tr(
"Freenect2 minimum depth (%1 m) should be lower than maximum depth (%2 m). Setting maximum depth to %3 m.")
3740 .
arg(
_ui->doubleSpinBox_freenect2MinDepth->value())
3741 .
arg(
_ui->doubleSpinBox_freenect2MaxDepth->value())
3742 .arg(
_ui->doubleSpinBox_freenect2MaxDepth->value()+1));
3743 _ui->doubleSpinBox_freenect2MaxDepth->setValue(
_ui->doubleSpinBox_freenect2MaxDepth->value()+1);
3746 if(
_ui->surf_doubleSpinBox_maxDepth->value() > 0.0 &&
3747 _ui->surf_doubleSpinBox_minDepth->value() >=
_ui->surf_doubleSpinBox_maxDepth->value())
3749 QMessageBox::warning(
this, tr(
"Parameter warning"),
3750 tr(
"Visual word minimum depth (%1 m) should be lower than maximum depth (%2 m). Setting maximum depth to %3 m.")
3751 .
arg(
_ui->surf_doubleSpinBox_minDepth->value())
3752 .
arg(
_ui->surf_doubleSpinBox_maxDepth->value())
3753 .arg(
_ui->surf_doubleSpinBox_maxDepth->value()+1));
3754 _ui->doubleSpinBox_freenect2MinDepth->setValue(0);
3757 if(
_ui->loopClosure_bowMaxDepth->value() > 0.0 &&
3758 _ui->loopClosure_bowMinDepth->value() >=
_ui->loopClosure_bowMaxDepth->value())
3760 QMessageBox::warning(
this, tr(
"Parameter warning"),
3761 tr(
"Visual registration word minimum depth (%1 m) should be lower than maximum depth (%2 m). Setting maximum depth to %3 m.")
3762 .
arg(
_ui->loopClosure_bowMinDepth->value())
3763 .
arg(
_ui->loopClosure_bowMaxDepth->value())
3764 .arg(
_ui->loopClosure_bowMaxDepth->value()+1));
3765 _ui->loopClosure_bowMinDepth->setValue(0);
3768 if(
_ui->fastThresholdMax->value() <
_ui->fastThresholdMin->value())
3770 QMessageBox::warning(
this, tr(
"Parameter warning"),
3771 tr(
"FAST minimum threshold cannot be lower than maximum threshold. Setting minimum to 1."));
3772 _ui->fastThresholdMin->setValue(1);
3774 if(
_ui->fastThreshold->value() >
_ui->fastThresholdMax->value())
3776 QMessageBox::warning(
this, tr(
"Parameter warning"),
3777 tr(
"FAST threshold cannot be higher than maximum threshold. Maximum value set to current threshold."));
3778 _ui->fastThresholdMax->setValue(
_ui->fastThreshold->value());
3780 if(
_ui->fastThreshold->value() <
_ui->fastThresholdMin->value())
3782 QMessageBox::warning(
this, tr(
"Parameter warning"),
3783 tr(
"FAST threshold cannot be lower than minimum threshold. Minimum value set to current threshold."));
3784 _ui->fastThresholdMin->setValue(
_ui->fastThreshold->value());
3787 if(
_ui->checkbox_odomDisabled->isChecked() &&
3788 _ui->general_checkBox_SLAM_mode->isChecked() &&
3789 _ui->general_checkBox_activateRGBD->isChecked())
3791 QMessageBox::warning(
this, tr(
"Parameter warning"),
3792 tr(
"Odometry is disabled but incremental RGB-D SLAM is activated! Re-enabling odometry."));
3793 _ui->checkbox_odomDisabled->setChecked(
false);
3796 #if CV_MAJOR_VERSION < 3 || (CV_MAJOR_VERSION == 3 && (CV_MINOR_VERSION <4 || (CV_MINOR_VERSION ==4 && CV_SUBMINOR_VERSION<2)))
3797 if(
_ui->ArucoDictionary->currentIndex()>=17)
3799 QMessageBox::warning(
this, tr(
"Parameter warning"),
3800 tr(
"ArUco dictionary: cannot select AprilTag dictionary, OpenCV version should be at least 3.4.2. Setting back to 0."));
3801 _ui->ArucoDictionary->setCurrentIndex(0);
3810 return tr(
"Reading parameters from the configuration file...");
3818 _ui->lineEdit_dictionaryPath->setEnabled(
false);
3819 _ui->toolButton_dictionaryPath->setEnabled(
false);
3820 _ui->label_dictionaryPath->setEnabled(
false);
3822 _ui->groupBox_source0->setEnabled(
false);
3823 _ui->groupBox_odometry1->setEnabled(
false);
3825 this->setWindowTitle(tr(
"Preferences [Monitoring mode]"));
3829 _ui->lineEdit_dictionaryPath->setEnabled(
true);
3830 _ui->toolButton_dictionaryPath->setEnabled(
true);
3831 _ui->label_dictionaryPath->setEnabled(
true);
3833 _ui->groupBox_source0->setEnabled(
true);
3834 _ui->groupBox_odometry1->setEnabled(
true);
3836 this->setWindowTitle(tr(
"Preferences"));
3842 std::set<std::string> threadsCheckedSet(threadsChecked.begin(), threadsChecked.end());
3843 _ui->comboBox_loggerFilter->clear();
3844 for(std::map<std::string, unsigned long>::iterator
iter=threads.begin();
iter!=threads.end(); ++
iter)
3846 if(threadsCheckedSet.find(
iter->first.c_str()) != threadsCheckedSet.end())
3848 _ui->comboBox_loggerFilter->addItem(QString(
iter->first.c_str()), QVariant(
true));
3852 _ui->comboBox_loggerFilter->addItem(QString(
iter->first.c_str()), QVariant(
false));
3870 QApplication::processEvents();
3875 if(this->isVisible())
3888 if(!window->objectName().isEmpty() && !window->isMaximized())
3891 settings.beginGroup(
"Gui");
3892 settings.beginGroup(window->objectName());
3893 settings.setValue(
"geometry", window->saveGeometry());
3894 settings.endGroup();
3895 settings.endGroup();
3898 settingsTmp.beginGroup(
"Gui");
3899 settingsTmp.beginGroup(window->objectName());
3900 settingsTmp.setValue(
"geometry", window->saveGeometry());
3901 settingsTmp.endGroup();
3902 settingsTmp.endGroup();
3908 if(!window->objectName().isEmpty())
3912 settings.beginGroup(
"Gui");
3913 settings.beginGroup(window->objectName());
3914 bytes = settings.value(
"geometry", QByteArray()).toByteArray();
3915 if(!
bytes.isEmpty())
3917 window->restoreGeometry(
bytes);
3919 settings.endGroup();
3920 settings.endGroup();
3923 settingsTmp.beginGroup(
"Gui");
3924 settingsTmp.beginGroup(window->objectName());
3925 settingsTmp.setValue(
"geometry", window->saveGeometry());
3926 settingsTmp.endGroup();
3927 settingsTmp.endGroup();
3933 if(!mainWindow->objectName().isEmpty())
3938 settings.beginGroup(
"Gui");
3939 settings.beginGroup(mainWindow->objectName());
3940 settings.setValue(
"state", mainWindow->saveState());
3941 settings.setValue(
"maximized", mainWindow->isMaximized());
3942 settings.setValue(
"status_bar", mainWindow->statusBar()->isVisible());
3943 settings.endGroup();
3944 settings.endGroup();
3947 settingsTmp.beginGroup(
"Gui");
3948 settingsTmp.beginGroup(mainWindow->objectName());
3949 settingsTmp.setValue(
"state", mainWindow->saveState());
3950 settingsTmp.setValue(
"maximized", mainWindow->isMaximized());
3951 settingsTmp.setValue(
"status_bar", mainWindow->statusBar()->isVisible());
3952 settingsTmp.endGroup();
3953 settingsTmp.endGroup();
3959 if(!mainWindow->objectName().isEmpty())
3965 settings.beginGroup(
"Gui");
3966 settings.beginGroup(mainWindow->objectName());
3967 bytes = settings.value(
"state", QByteArray()).toByteArray();
3968 if(!
bytes.isEmpty())
3970 mainWindow->restoreState(
bytes);
3972 maximized = settings.value(
"maximized",
false).toBool();
3973 statusBarShown = settings.value(
"status_bar",
false).toBool();
3974 mainWindow->statusBar()->setVisible(statusBarShown);
3975 settings.endGroup();
3976 settings.endGroup();
3979 settingsTmp.beginGroup(
"Gui");
3980 settingsTmp.beginGroup(mainWindow->objectName());
3981 settingsTmp.setValue(
"state", mainWindow->saveState());
3982 settingsTmp.setValue(
"maximized", maximized);
3983 settingsTmp.setValue(
"status_bar", statusBarShown);
3984 settingsTmp.endGroup();
3985 settingsTmp.endGroup();
3991 if(!widget->objectName().isEmpty())
3994 settings.beginGroup(
"Gui");
3995 settings.beginGroup(widget->objectName());
3998 settingsTmp.beginGroup(
"Gui");
3999 settingsTmp.beginGroup(widget->objectName());
4001 const CloudViewer * cloudViewer = qobject_cast<const CloudViewer*>(widget);
4002 const ImageView * imageView = qobject_cast<const ImageView*>(widget);
4003 const ExportCloudsDialog * exportCloudsDialog = qobject_cast<const ExportCloudsDialog*>(widget);
4004 const ExportBundlerDialog * exportBundlerDialog = qobject_cast<const ExportBundlerDialog*>(widget);
4005 const PostProcessingDialog * postProcessingDialog = qobject_cast<const PostProcessingDialog *>(widget);
4006 const GraphViewer * graphViewer = qobject_cast<const GraphViewer *>(widget);
4007 const CalibrationDialog * calibrationDialog = qobject_cast<const CalibrationDialog *>(widget);
4008 const DepthCalibrationDialog * depthCalibrationDialog = qobject_cast<const DepthCalibrationDialog *>(widget);
4020 else if(exportCloudsDialog)
4025 else if(exportBundlerDialog)
4030 else if(postProcessingDialog)
4035 else if(graphViewer)
4040 else if(calibrationDialog)
4045 else if(depthCalibrationDialog)
4052 UERROR(
"Widget \"%s\" cannot be exported in config file.", widget->objectName().toStdString().c_str());
4055 settings.endGroup();
4056 settings.endGroup();
4057 settingsTmp.endGroup();
4058 settingsTmp.endGroup();
4064 if(!widget->objectName().isEmpty())
4068 settings.beginGroup(
"Gui");
4069 settings.beginGroup(widget->objectName());
4072 settingsTmp.beginGroup(
"Gui");
4073 settingsTmp.beginGroup(widget->objectName());
4075 CloudViewer * cloudViewer = qobject_cast<CloudViewer*>(widget);
4076 ImageView * imageView = qobject_cast<ImageView*>(widget);
4080 GraphViewer * graphViewer = qobject_cast<GraphViewer *>(widget);
4081 CalibrationDialog * calibrationDialog = qobject_cast<CalibrationDialog *>(widget);
4094 else if(exportCloudsDialog)
4099 else if(exportBundlerDialog)
4104 else if(postProcessingDialog)
4109 else if(graphViewer)
4114 else if(calibrationDialog)
4119 else if(depthCalibrationDialog)
4126 UERROR(
"Widget \"%s\" cannot be loaded from config file.", widget->objectName().toStdString().c_str());
4129 settings.endGroup();
4130 settings.endGroup();
4131 settingsTmp.endGroup();
4132 settingsTmp.endGroup();
4140 settings.beginGroup(
"Gui");
4141 settings.beginGroup(section);
4143 settings.endGroup();
4144 settings.endGroup();
4147 settingsTmp.beginGroup(
"Gui");
4148 settingsTmp.beginGroup(section);
4150 settingsTmp.endGroup();
4151 settingsTmp.endGroup();
4158 settings.beginGroup(
"Gui");
4159 settings.beginGroup(section);
4160 value = settings.value(
key, QString()).toString();
4161 settings.endGroup();
4162 settings.endGroup();
4165 settingsTmp.beginGroup(
"Gui");
4166 settingsTmp.beginGroup(section);
4168 settingsTmp.endGroup();
4169 settingsTmp.endGroup();
4199 if(parameters.size())
4201 for(rtabmap::ParametersMap::const_iterator
iter = parameters.begin();
iter!=parameters.end(); ++
iter)
4205 if(setOtherParametersToDefault)
4211 if(parameters.find(
iter->first) == parameters.end() &&
4212 iter->first.compare(Parameters::kRtabmapWorkingDirectory())!=0)
4218 if(!this->isVisible())
4230 if(
_ui->comboBox_imuFilter_strategy->currentIndex()==0)
4232 _ui->comboBox_imuFilter_strategy->setCurrentIndex(2);
4239 _ui->comboBox_sourceType->setCurrentIndex(0);
4240 _ui->comboBox_cameraRGBD->setCurrentIndex(src -
kSrcRGBD);
4243 _ui->lineEdit_openniOniPath->clear();
4247 _ui->lineEdit_openni2OniPath->clear();
4251 _ui->lineEdit_k4a_mkv->clear();
4259 _ui->spinBox_rs2_width->setValue(1280);
4260 _ui->spinBox_rs2_height->setValue(720);
4261 _ui->spinBox_rs2_rate->setValue(30);
4262 _ui->checkbox_rs2_irMode->setChecked(
false);
4263 _ui->checkbox_rs2_emitter->setChecked(
true);
4267 _ui->spinBox_rs2_width->setValue(848);
4268 _ui->spinBox_rs2_height->setValue(480);
4269 _ui->spinBox_rs2_rate->setValue(60);
4270 _ui->checkbox_rs2_irMode->setChecked(
true);
4271 _ui->checkbox_rs2_emitter->setChecked(
false);
4277 _ui->comboBox_sourceType->setCurrentIndex(1);
4278 _ui->comboBox_cameraStereo->setCurrentIndex(src -
kSrcStereo);
4283 _ui->comboBox_imuFilter_strategy->setCurrentIndex(0);
4287 _ui->checkBox_depthai_imu_published->setChecked(variant >= 1);
4288 _ui->comboBox_depthai_resolution->setCurrentIndex(variant >= 1?1:3);
4289 _ui->comboBox_depthai_output_mode->setCurrentIndex(variant==2?2:0);
4290 _ui->doubleSpinBox_depthai_dot_intensity->setValue(variant==2?1:0);
4295 _ui->comboBox_sourceType->setCurrentIndex(2);
4296 _ui->source_comboBox_image_type->setCurrentIndex(src -
kSrcRGB);
4300 _ui->comboBox_sourceType->setCurrentIndex(3);
4308 QMessageBox::question(
this, tr(
"Camera Source..."),
4309 tr(
"Do you want to use default camera settings?"),
4310 QMessageBox::Yes | QMessageBox::No, QMessageBox::Yes) == QMessageBox::Yes)
4313 _ui->comboBox_lidar_src->setCurrentIndex(0);
4314 _ui->comboBox_odom_sensor->setCurrentIndex(0);
4317 QMessageBox::question(
this, tr(
"LiDAR Source..."),
4318 tr(
"Do you want to use \"LiDAR 3D ICP\" preset?"),
4319 QMessageBox::Yes | QMessageBox::No, QMessageBox::Yes) == QMessageBox::Yes)
4322 _ui->comboBox_sourceType->setCurrentIndex(4);
4323 _ui->comboBox_odom_sensor->setCurrentIndex(0);
4346 QString dir =
_ui->source_database_lineEdit_path->text();
4351 QStringList paths = QFileDialog::getOpenFileNames(
this, tr(
"Select file"), dir, tr(
"RTAB-Map database files (*.db)"));
4354 int r = QMessageBox::question(
this, tr(
"Odometry in database..."), tr(
"Use odometry saved in database (if some saved)?"), QMessageBox::Yes | QMessageBox::No, QMessageBox::Yes);
4355 _ui->source_checkBox_ignoreOdometry->setChecked(r != QMessageBox::Yes);
4357 if (
_ui->general_doubleSpinBox_detectionRate->value() != 0 &&
_ui->general_spinBox_imagesBufferSize->value() != 0)
4359 r = QMessageBox::question(
this, tr(
"Detection rate..."),
4360 tr(
"Do you want to process all frames? \n\nClicking \"Yes\" will set "
4361 "RTAB-Map's detection rate (%1 Hz) and buffer size (%2) to 0 to make "
4362 "sure that all frames are processed.")
4363 .
arg(
_ui->general_doubleSpinBox_detectionRate->value())
4364 .
arg(
_ui->general_spinBox_imagesBufferSize->value()),
4365 QMessageBox::Yes | QMessageBox::No, QMessageBox::Yes);
4366 if (r == QMessageBox::Yes)
4368 _ui->general_doubleSpinBox_detectionRate->setValue(0.0);
4369 _ui->general_spinBox_imagesBufferSize->setValue(0);
4373 if(paths.size() > 1)
4375 std::vector<std::string> vFileNames(paths.size());
4376 for(
int i=0;
i<paths.size(); ++
i)
4378 vFileNames[
i] = paths[
i].toStdString();
4380 std::sort(vFileNames.begin(), vFileNames.end(),
sortCallback);
4381 for(
int i=0;
i<paths.size(); ++
i)
4383 paths[
i] = vFileNames[
i].c_str();
4387 _ui->source_database_lineEdit_path->setText(paths.size()==1?paths.front():paths.join(
";"));
4388 _ui->source_spinBox_databaseStartId->setValue(0);
4389 _ui->source_spinBox_databaseStopId->setValue(0);
4390 _ui->source_spinBox_database_cameraIndex->setValue(-1);
4397 viewer->setWindowModality(Qt::WindowModal);
4398 viewer->setAttribute(Qt::WA_DeleteOnClose,
true);
4412 if(!
_ui->lineEdit_source_distortionModel->text().isEmpty() &&
4413 QFileInfo(
_ui->lineEdit_source_distortionModel->text()).exists())
4416 model.load(
_ui->lineEdit_source_distortionModel->text().toStdString());
4420 QString
name = QFileInfo(
_ui->lineEdit_source_distortionModel->text()).baseName()+
".png";
4421 cv::imwrite(
name.toStdString(),
img);
4422 QDesktopServices::openUrl(QUrl::fromLocalFile(
name));
4426 QMessageBox::warning(
this, tr(
"Distortion Model"), tr(
"Model loaded from \"%1\" is not valid!").
arg(
_ui->lineEdit_source_distortionModel->text()));
4431 QMessageBox::warning(
this, tr(
"Distortion Model"), tr(
"File \"%1\" doesn't exist!").
arg(
_ui->lineEdit_source_distortionModel->text()));
4437 QString dir =
_ui->lineEdit_calibrationFile->text();
4442 else if(!dir.contains(
'.'))
4446 QString
path = QFileDialog::getOpenFileName(
this, tr(
"Select file"), dir, tr(
"Calibration file (*.yaml)"));
4449 _ui->lineEdit_calibrationFile->setText(
path);
4455 QString dir =
_ui->lineEdit_odom_sensor_path_calibration->text();
4460 else if(!dir.contains(
'.'))
4464 QString
path = QFileDialog::getOpenFileName(
this, tr(
"Select file"), dir, tr(
"Calibration file (*.yaml)"));
4467 _ui->lineEdit_odom_sensor_path_calibration->setText(
path);
4473 QString dir =
_ui->lineEdit_cameraImages_timestamps->text();
4478 QString
path = QFileDialog::getOpenFileName(
this, tr(
"Select file"), dir, tr(
"Timestamps file (*.txt)"));
4481 _ui->lineEdit_cameraImages_timestamps->setText(
path);
4487 QString dir =
_ui->lineEdit_cameraRGBDImages_path_rgb->text();
4492 QString
path = QFileDialog::getExistingDirectory(
this, tr(
"Select RGB images directory"), dir);
4495 _ui->lineEdit_cameraRGBDImages_path_rgb->setText(
path);
4502 QString dir =
_ui->lineEdit_cameraImages_path_scans->text();
4507 QString
path = QFileDialog::getExistingDirectory(
this, tr(
"Select scans directory"), dir);
4510 _ui->lineEdit_cameraImages_path_scans->setText(
path);
4516 QString dir =
_ui->lineEdit_cameraImages_path_imu->text();
4521 QString
path = QFileDialog::getOpenFileName(
this, tr(
"Select file "), dir, tr(
"EuRoC IMU file (*.csv)"));
4524 _ui->lineEdit_cameraImages_path_imu->setText(
path);
4531 QString dir =
_ui->lineEdit_cameraRGBDImages_path_depth->text();
4536 QString
path = QFileDialog::getExistingDirectory(
this, tr(
"Select depth images directory"), dir);
4539 _ui->lineEdit_cameraRGBDImages_path_depth->setText(
path);
4545 QString dir =
_ui->lineEdit_cameraImages_odom->text();
4550 QString
path = QFileDialog::getOpenFileName(
this, tr(
"Select file"), dir, tr(
"Odometry (*.txt *.log *.toro *.g2o *.csv)"));
4554 for(
int i=0;
i<
_ui->comboBox_cameraImages_odomFormat->count(); ++
i)
4556 list.push_back(
_ui->comboBox_cameraImages_odomFormat->itemText(
i));
4558 QString item = QInputDialog::getItem(
this, tr(
"Odometry Format"), tr(
"Format:"),
list,
_ui->comboBox_cameraImages_odomFormat->currentIndex(),
false);
4561 _ui->lineEdit_cameraImages_odom->setText(
path);
4562 _ui->comboBox_cameraImages_odomFormat->setCurrentIndex(
_ui->comboBox_cameraImages_odomFormat->findText(item));
4569 QString dir =
_ui->lineEdit_cameraImages_gt->text();
4574 QString
path = QFileDialog::getOpenFileName(
this, tr(
"Select file"), dir, tr(
"Ground Truth (*.txt *.log *.toro *.g2o *.csv)"));
4578 for(
int i=0;
i<
_ui->comboBox_cameraImages_gtFormat->count(); ++
i)
4580 list.push_back(
_ui->comboBox_cameraImages_gtFormat->itemText(
i));
4582 QString item = QInputDialog::getItem(
this, tr(
"Ground Truth Format"), tr(
"Format:"),
list,
_ui->comboBox_cameraImages_gtFormat->currentIndex(),
false);
4585 _ui->lineEdit_cameraImages_gt->setText(
path);
4586 _ui->comboBox_cameraImages_gtFormat->setCurrentIndex(
_ui->comboBox_cameraImages_gtFormat->findText(item));
4593 QString dir =
_ui->lineEdit_cameraStereoImages_path_left->text();
4598 QString
path = QFileDialog::getExistingDirectory(
this, tr(
"Select left images directory"), dir);
4601 _ui->lineEdit_cameraStereoImages_path_left->setText(
path);
4607 QString dir =
_ui->lineEdit_cameraStereoImages_path_right->text();
4612 QString
path = QFileDialog::getExistingDirectory(
this, tr(
"Select right images directory"), dir);
4615 _ui->lineEdit_cameraStereoImages_path_right->setText(
path);
4621 QString dir =
_ui->source_images_lineEdit_path->text();
4626 QString
path = QFileDialog::getExistingDirectory(
this, tr(
"Select images directory"),
_ui->source_images_lineEdit_path->text());
4629 _ui->source_images_lineEdit_path->setText(
path);
4630 _ui->source_images_spinBox_startPos->setValue(0);
4631 _ui->source_images_spinBox_maxFrames->setValue(0);
4637 QString dir =
_ui->source_video_lineEdit_path->text();
4642 QString
path = QFileDialog::getOpenFileName(
this, tr(
"Select file"), dir, tr(
"Videos (*.avi *.mpg *.mp4 *.mov *.mkv)"));
4645 _ui->source_video_lineEdit_path->setText(
path);
4651 QString dir =
_ui->lineEdit_cameraStereoVideo_path->text();
4656 QString
path = QFileDialog::getOpenFileName(
this, tr(
"Select file"), dir, tr(
"Videos (*.avi *.mpg *.mp4 *.mov *.mkv)"));
4659 _ui->lineEdit_cameraStereoVideo_path->setText(
path);
4665 QString dir =
_ui->lineEdit_cameraStereoVideo_path_2->text();
4670 QString
path = QFileDialog::getOpenFileName(
this, tr(
"Select file"), dir, tr(
"Videos (*.avi *.mpg *.mp4 *.mov *.mkv)"));
4673 _ui->lineEdit_cameraStereoVideo_path_2->setText(
path);
4679 QString dir =
_ui->lineEdit_source_distortionModel->text();
4684 QString
path = QFileDialog::getOpenFileName(
this, tr(
"Select file"), dir, tr(
"Distortion model (*.bin *.txt)"));
4687 _ui->lineEdit_source_distortionModel->setText(
path);
4693 QString dir =
_ui->lineEdit_openniOniPath->text();
4698 QString
path = QFileDialog::getOpenFileName(
this, tr(
"Select file"), dir, tr(
"OpenNI (*.oni)"));
4701 _ui->lineEdit_openniOniPath->setText(
path);
4707 QString dir =
_ui->lineEdit_openni2OniPath->text();
4712 QString
path = QFileDialog::getOpenFileName(
this, tr(
"Select file"), dir, tr(
"OpenNI (*.oni)"));
4715 _ui->lineEdit_openni2OniPath->setText(
path);
4721 QString dir =
_ui->lineEdit_k4a_mkv->text();
4726 QString
path = QFileDialog::getOpenFileName(
this, tr(
"Select file"), dir, tr(
"K4A recording (*.mkv)"));
4727 if (!
path.isEmpty())
4729 _ui->lineEdit_k4a_mkv->setText(
path);
4735 QString dir =
_ui->lineEdit_zedSvoPath->text();
4740 QString
path = QFileDialog::getOpenFileName(
this, tr(
"Select file"), dir, tr(
"ZED (*.svo)"));
4743 _ui->lineEdit_zedSvoPath->setText(
path);
4749 QString dir =
_ui->lineEdit_rs2_jsonFile->text();
4754 QString
path = QFileDialog::getOpenFileName(
this, tr(
"Select RealSense2 preset"), dir, tr(
"JSON (*.json)"));
4757 _ui->lineEdit_rs2_jsonFile->setText(
path);
4763 QString dir =
_ui->lineEdit_depthai_blob_path->text();
4768 QString
path = QFileDialog::getOpenFileName(
this, tr(
"Select file"), dir, tr(
"MyriadX blob (*.blob)"));
4771 _ui->lineEdit_depthai_blob_path->setText(
path);
4777 QString dir =
_ui->lineEdit_vlp16_pcap_path->text();
4782 QString
path = QFileDialog::getOpenFileName(
this, tr(
"Select file"), dir, tr(
"Velodyne recording (*.pcap)"));
4783 if (!
path.isEmpty())
4785 _ui->lineEdit_vlp16_pcap_path->setText(
path);
4792 QWidget * obj =
_ui->stackedWidget->findChild<QWidget*>(
key.c_str());
4797 QSpinBox * spin = qobject_cast<QSpinBox *>(obj);
4798 QDoubleSpinBox * doubleSpin = qobject_cast<QDoubleSpinBox *>(obj);
4799 QComboBox * combo = qobject_cast<QComboBox *>(obj);
4800 QCheckBox *
check = qobject_cast<QCheckBox *>(obj);
4801 QRadioButton * radio = qobject_cast<QRadioButton *>(obj);
4802 QLineEdit * lineEdit = qobject_cast<QLineEdit *>(obj);
4803 QGroupBox * groupBox = qobject_cast<QGroupBox *>(obj);
4807 spin->setValue(QString(
value.c_str()).toInt(&ok));
4810 UERROR(
"Conversion failed from \"%s\" for parameter %s",
value.c_str(),
key.c_str());
4815 doubleSpin->setValue(QString(
value.c_str()).toDouble(&ok));
4818 UERROR(
"Conversion failed from \"%s\" for parameter %s",
value.c_str(),
key.c_str());
4824 std::string valueCpy =
value;
4825 if(
key.compare(Parameters::kIcpStrategy()) == 0 ||
4826 key.compare(Parameters::kGridSensor()) == 0)
4828 if(
value.compare(
"true") == 0)
4832 else if(
value.compare(
"false") == 0)
4838 int valueInt = QString(valueCpy.c_str()).toInt(&ok);
4841 UERROR(
"Conversion failed from \"%s\" for parameter %s", valueCpy.c_str(),
key.c_str());
4845 #ifndef RTABMAP_NONFREE
4847 (combo->objectName().toStdString().compare(Parameters::kKpDetectorStrategy()) == 0 ||
4848 combo->objectName().toStdString().compare(Parameters::kVisFeatureType()) == 0))
4850 UWARN(
"Trying to set \"%s\" to SURF but RTAB-Map isn't built "
4851 "with the nonfree module from OpenCV. Keeping default combo value: %s.",
4852 combo->objectName().toStdString().c_str(),
4853 combo->currentText().toStdString().c_str());
4856 #if CV_MAJOR_VERSION < 3 || (CV_MAJOR_VERSION == 4 && CV_MINOR_VERSION <= 3) || (CV_MAJOR_VERSION == 3 && (CV_MINOR_VERSION < 4 || (CV_MINOR_VERSION==4 && CV_SUBMINOR_VERSION<11)))
4858 (combo->objectName().toStdString().compare(Parameters::kKpDetectorStrategy()) == 0 ||
4859 combo->objectName().toStdString().compare(Parameters::kVisFeatureType()) == 0))
4861 UWARN(
"Trying to set \"%s\" to SIFT but RTAB-Map isn't built "
4862 "with the nonfree module from OpenCV. Keeping default combo value: %s.",
4863 combo->objectName().toStdString().c_str(),
4864 combo->currentText().toStdString().c_str());
4869 #ifndef RTABMAP_ORB_SLAM
4873 if(valueInt==1 && combo->objectName().toStdString().compare(Parameters::kOptimizerStrategy()) == 0)
4876 UWARN(
"Trying to set \"%s\" to g2o but RTAB-Map isn't built "
4877 "with g2o. Falling back to GTSAM.",
4878 combo->objectName().toStdString().c_str());
4883 UWARN(
"Trying to set \"%s\" to g2o but RTAB-Map isn't built "
4884 "with g2o. Keeping default combo value: %s.",
4885 combo->objectName().toStdString().c_str(),
4886 combo->currentText().toStdString().c_str());
4893 if(valueInt==2 && combo->objectName().toStdString().compare(Parameters::kOptimizerStrategy()) == 0)
4896 #ifndef RTABMAP_ORB_SLAM
4902 UWARN(
"Trying to set \"%s\" to GTSAM but RTAB-Map isn't built "
4903 "with GTSAM. Falling back to g2o.",
4904 combo->objectName().toStdString().c_str());
4909 UWARN(
"Trying to set \"%s\" to GTSAM but RTAB-Map isn't built "
4910 "with GTSAM. Keeping default combo value: %s.",
4911 combo->objectName().toStdString().c_str(),
4912 combo->currentText().toStdString().c_str());
4919 combo->setCurrentIndex(valueInt);
4926 _ui->checkBox_useOdomFeatures->blockSignals(
true);
4928 _ui->checkBox_useOdomFeatures->blockSignals(
false);
4936 lineEdit->setText(
value.c_str());
4944 ULOGGER_WARN(
"QObject called %s can't be cast to a supported widget",
key.c_str());
4949 ULOGGER_WARN(
"Can't find the related QObject for parameter %s",
key.c_str());
4961 ULOGGER_ERROR(
"This slot must be triggered by a signal, not a direct call...");
4973 ULOGGER_ERROR(
"This slot must be triggered by a signal, not a direct call...");
4985 ULOGGER_ERROR(
"This slot must be triggered by a signal, not a direct call...");
4997 ULOGGER_ERROR(
"This slot must be triggered by a signal, not a direct call...");
5005 const QComboBox * comboBox = qobject_cast<const QComboBox*>(
object);
5006 const QSpinBox * spinbox = qobject_cast<const QSpinBox*>(
object);
5007 if(comboBox || spinbox)
5015 UWARN(
"Undefined object \"%s\"",
object->objectName().toStdString().c_str());
5029 const QCheckBox * checkbox = qobject_cast<const QCheckBox*>(
object);
5030 const QRadioButton * radio = qobject_cast<const QRadioButton*>(
object);
5031 const QGroupBox * groupBox = qobject_cast<const QGroupBox*>(
object);
5032 if(checkbox || radio || groupBox)
5040 UWARN(
"Undefined object \"%s\"",
object->objectName().toStdString().c_str());
5054 UDEBUG(
"modify param %s=%f",
object->objectName().toStdString().c_str(),
value);
5067 UDEBUG(
"modify param %s=%s",
object->objectName().toStdString().c_str(),
value.toStdString().c_str());
5079 for(
int i=0;
i<children.size(); ++
i)
5081 const QSpinBox * spin = qobject_cast<const QSpinBox *>(children[
i]);
5082 const QDoubleSpinBox * doubleSpin = qobject_cast<const QDoubleSpinBox *>(children[
i]);
5083 const QComboBox * combo = qobject_cast<const QComboBox *>(children[
i]);
5084 const QCheckBox *
check = qobject_cast<const QCheckBox *>(children[
i]);
5085 const QRadioButton * radio = qobject_cast<const QRadioButton *>(children[
i]);
5086 const QLineEdit * lineEdit = qobject_cast<const QLineEdit *>(children[
i]);
5087 const QGroupBox * groupBox = qobject_cast<const QGroupBox *>(children[
i]);
5088 const QStackedWidget * stackedWidget = qobject_cast<const QStackedWidget *>(children[
i]);
5115 if(groupBox->isCheckable())
5124 else if(stackedWidget)
5137 for(
int i=0;
i<stackedWidget->count(); ++
i)
5139 const QObjectList & children = stackedWidget->widget(
i)->children();
5146 const QObjectList & children = stackedWidget->widget(panel)->children();
5156 const QObjectList & children =
box->children();
5168 if(sender() ==
_ui->general_doubleSpinBox_timeThr_2)
5170 _ui->general_doubleSpinBox_timeThr->setValue(
_ui->general_doubleSpinBox_timeThr_2->value());
5172 else if(sender() ==
_ui->general_doubleSpinBox_hardThr_2)
5174 _ui->general_doubleSpinBox_hardThr->setValue(
_ui->general_doubleSpinBox_hardThr_2->value());
5176 else if(sender() ==
_ui->general_doubleSpinBox_detectionRate_2)
5178 _ui->general_doubleSpinBox_detectionRate->setValue(
_ui->general_doubleSpinBox_detectionRate_2->value());
5180 else if(sender() ==
_ui->general_spinBox_imagesBufferSize_2)
5182 _ui->general_spinBox_imagesBufferSize->setValue(
_ui->general_spinBox_imagesBufferSize_2->value());
5184 else if(sender() ==
_ui->general_spinBox_maxStMemSize_2)
5186 _ui->general_spinBox_maxStMemSize->setValue(
_ui->general_spinBox_maxStMemSize_2->value());
5188 else if(sender() ==
_ui->groupBox_publishing)
5190 _ui->general_checkBox_publishStats_2->setChecked(
_ui->groupBox_publishing->isChecked());
5192 else if(sender() ==
_ui->general_checkBox_publishStats_2)
5194 _ui->groupBox_publishing->setChecked(
_ui->general_checkBox_publishStats_2->isChecked());
5196 else if(sender() ==
_ui->doubleSpinBox_similarityThreshold_2)
5198 _ui->doubleSpinBox_similarityThreshold->setValue(
_ui->doubleSpinBox_similarityThreshold_2->value());
5200 else if(sender() ==
_ui->general_checkBox_activateRGBD)
5202 _ui->general_checkBox_activateRGBD_2->blockSignals(
true);
5203 _ui->general_checkBox_activateRGBD_2->setChecked(
_ui->general_checkBox_activateRGBD->isChecked());
5204 _ui->general_checkBox_activateRGBD_2->blockSignals(
false);
5206 else if(sender() ==
_ui->general_checkBox_activateRGBD_2)
5208 _ui->general_checkBox_activateRGBD->blockSignals(
true);
5209 _ui->general_checkBox_activateRGBD->setChecked(
_ui->general_checkBox_activateRGBD_2->isChecked());
5210 addParameter(
_ui->general_checkBox_activateRGBD,
_ui->general_checkBox_activateRGBD->isChecked());
5211 _ui->general_checkBox_activateRGBD->blockSignals(
false);
5213 else if(sender() ==
_ui->general_checkBox_SLAM_mode)
5215 _ui->general_checkBox_SLAM_mode_2->blockSignals(
true);
5216 _ui->general_checkBox_SLAM_mode_2->setChecked(
_ui->general_checkBox_SLAM_mode->isChecked());
5217 _ui->general_checkBox_SLAM_mode_2->blockSignals(
false);
5219 else if(sender() ==
_ui->general_checkBox_SLAM_mode_2)
5221 _ui->general_checkBox_SLAM_mode->blockSignals(
true);
5222 _ui->general_checkBox_SLAM_mode->setChecked(
_ui->general_checkBox_SLAM_mode_2->isChecked());
5223 addParameter(
_ui->general_checkBox_SLAM_mode,
_ui->general_checkBox_SLAM_mode->isChecked());
5224 _ui->general_checkBox_SLAM_mode->blockSignals(
false);
5229 _ui->general_doubleSpinBox_timeThr->setValue(
_ui->general_doubleSpinBox_timeThr_2->value());
5230 _ui->general_doubleSpinBox_hardThr->setValue(
_ui->general_doubleSpinBox_hardThr_2->value());
5231 _ui->general_doubleSpinBox_detectionRate->setValue(
_ui->general_doubleSpinBox_detectionRate_2->value());
5232 _ui->general_spinBox_imagesBufferSize->setValue(
_ui->general_spinBox_imagesBufferSize_2->value());
5233 _ui->general_spinBox_maxStMemSize->setValue(
_ui->general_spinBox_maxStMemSize_2->value());
5234 _ui->doubleSpinBox_similarityThreshold->setValue(
_ui->doubleSpinBox_similarityThreshold_2->value());
5270 QList<QGroupBox*> boxes;
5271 for(
int i=0;
i<
_ui->stackedWidget->count(); ++
i)
5274 const QObjectList & children =
_ui->stackedWidget->widget(
i)->children();
5275 for(
int j=0;
j<children.size(); ++
j)
5277 if((gb = qobject_cast<QGroupBox *>(children.at(
j))))
5289 ULOGGER_ERROR(
"A QGroupBox must be included in the first level of children in stacked widget, index=%d",
i);
5297 QStringList
values =
_ui->lineEdit_bayes_predictionLC->text().simplified().split(
' ');
5300 UERROR(
"Error parsing prediction (must have at least 2 items) : %s",
5301 _ui->lineEdit_bayes_predictionLC->text().toStdString().c_str());
5304 QVector<qreal> dataX((
values.
size()-2)*2 + 1);
5305 QVector<qreal> dataY((
values.
size()-2)*2 + 1);
5311 int loopClosureIndex = (dataX.size()-1)/2;
5317 UERROR(
"Error parsing prediction : \"%s\"",
values.
at(
i).toStdString().c_str());
5327 dataY[loopClosureIndex] =
value;
5328 dataX[loopClosureIndex] = 0;
5332 dataY[loopClosureIndex-lvl] =
value;
5333 dataX[loopClosureIndex-lvl] = -lvl;
5334 dataY[loopClosureIndex+lvl] =
value;
5335 dataX[loopClosureIndex+lvl] = lvl;
5340 _ui->label_prediction_sum->setNum(sum);
5343 _ui->label_prediction_sum->setText(QString(
"<font color=#FF0000>") +
_ui->label_prediction_sum->text() +
"</font>");
5347 _ui->label_prediction_sum->setText(QString(
"<font color=#00FF00>") +
_ui->label_prediction_sum->text() +
"</font>");
5351 _ui->label_prediction_sum->setText(QString(
"<font color=#FFa500>") +
_ui->label_prediction_sum->text() +
"</font>");
5355 _ui->label_prediction_sum->setText(QString(
"<font color=#000000>") +
_ui->label_prediction_sum->text() +
"</font>");
5358 _ui->predictionPlot->removeCurves();
5359 _ui->predictionPlot->addCurve(
new UPlotCurve(
"Prediction", dataX, dataY,
_ui->predictionPlot));
5364 QStringList strings =
_ui->lineEdit_kp_roi->text().split(
' ');
5365 if(strings.size()!=4)
5367 UERROR(
"ROI must have 4 values (%s)",
_ui->lineEdit_kp_roi->text().toStdString().c_str());
5370 _ui->doubleSpinBox_kp_roi0->setValue(strings[0].toDouble()*100.0);
5371 _ui->doubleSpinBox_kp_roi1->setValue(strings[1].toDouble()*100.0);
5372 _ui->doubleSpinBox_kp_roi2->setValue(strings[2].toDouble()*100.0);
5373 _ui->doubleSpinBox_kp_roi3->setValue(strings[3].toDouble()*100.0);
5378 QStringList strings;
5379 strings.append(QString::number(
_ui->doubleSpinBox_kp_roi0->value()/100.0));
5380 strings.append(QString::number(
_ui->doubleSpinBox_kp_roi1->value()/100.0));
5381 strings.append(QString::number(
_ui->doubleSpinBox_kp_roi2->value()/100.0));
5382 strings.append(QString::number(
_ui->doubleSpinBox_kp_roi3->value()/100.0));
5383 _ui->lineEdit_kp_roi->setText(strings.join(
" "));
5389 _ui->checkbox_stereo_depthGenerated->setVisible(
5391 _ui->comboBox_stereoZed_quality->currentIndex() == 0);
5392 _ui->label_stereo_depthGenerated->setVisible(
5394 _ui->comboBox_stereoZed_quality->currentIndex() == 0);
5396 _ui->checkBox_stereo_rectify->setEnabled(
5403 _ui->checkBox_stereo_rectify->setVisible(
_ui->checkBox_stereo_rectify->isEnabled());
5404 _ui->label_stereo_rectify->setVisible(
_ui->checkBox_stereo_rectify->isEnabled());
5409 _ui->groupBox_pymatcher->setVisible(
_ui->reextract_nn->currentIndex() == 6);
5410 _ui->groupBox_gms->setVisible(
_ui->reextract_nn->currentIndex() == 7);
5415 _ui->groupBox_pydescriptor->setVisible(
_ui->comboBox_globalDescriptorExtractor->currentIndex() == 1);
5422 _ui->stackedWidget_odometryType->setCurrentIndex(7);
5426 _ui->stackedWidget_odometryType->setCurrentIndex(index);
5428 _ui->groupBox_odomF2M->setVisible(index==0);
5429 _ui->groupBox_odomF2F->setVisible(index==1);
5430 _ui->groupBox_odomFovis->setVisible(index==2);
5431 _ui->groupBox_odomViso2->setVisible(index==3);
5432 _ui->groupBox_odomDVO->setVisible(index==4);
5433 _ui->groupBox_odomORBSLAM->setVisible(index==5);
5434 _ui->groupBox_odomOKVIS->setVisible(index==6);
5435 _ui->groupBox_odomLOAM->setVisible(index==7);
5436 _ui->groupBox_odomMSCKF->setVisible(index==8);
5437 _ui->groupBox_odomVINS->setVisible(index==9);
5438 _ui->groupBox_odomOpenVINS->setVisible(index==10);
5439 _ui->groupBox_odomOpen3D->setVisible(index==12);
5444 if(this->isVisible() &&
_ui->checkBox_useOdomFeatures->isChecked())
5446 int r = QMessageBox::question(
this, tr(
"Using odometry features for vocabulary..."),
5447 tr(
"Do you want to match vocabulary feature parameters "
5448 "with corresponding ones used for odometry?"), QMessageBox::Yes | QMessageBox::No, QMessageBox::Yes);
5450 if(r == QMessageBox::Yes)
5452 _ui->comboBox_detector_strategy->setCurrentIndex(
_ui->vis_feature_detector->currentIndex());
5453 _ui->surf_doubleSpinBox_maxDepth->setValue(
_ui->loopClosure_bowMaxDepth->value());
5454 _ui->surf_doubleSpinBox_minDepth->setValue(
_ui->loopClosure_bowMinDepth->value());
5455 _ui->surf_spinBox_wordsPerImageTarget->setValue(
_ui->reextract_maxFeatures->value());
5456 _ui->checkBox_kp_ssc->setChecked(
_ui->checkBox_visSSC->isChecked());
5457 _ui->spinBox_KPGridRows->setValue(
_ui->reextract_gridrows->value());
5458 _ui->spinBox_KPGridCols->setValue(
_ui->reextract_gridcols->value());
5459 _ui->lineEdit_kp_roi->setText(
_ui->loopClosure_roi->text());
5460 _ui->subpix_winSize_kp->setValue(
_ui->subpix_winSize->value());
5461 _ui->subpix_iterations_kp->setValue(
_ui->subpix_iterations->value());
5462 _ui->subpix_eps_kp->setValue(
_ui->subpix_eps->value());
5469 QString directory = QFileDialog::getExistingDirectory(
this, tr(
"Working directory"),
_ui->lineEdit_workingDirectory->text());
5470 if(!directory.isEmpty())
5472 ULOGGER_DEBUG(
"New working directory = %s", directory.toStdString().c_str());
5473 _ui->lineEdit_workingDirectory->setText(directory);
5480 if(
_ui->lineEdit_dictionaryPath->text().isEmpty())
5482 path = QFileDialog::getOpenFileName(
this, tr(
"Dictionary"), this->
getWorkingDirectory(), tr(
"Dictionary (*.txt *.db)"));
5486 path = QFileDialog::getOpenFileName(
this, tr(
"Dictionary"),
_ui->lineEdit_dictionaryPath->text(), tr(
"Dictionary (*.txt *.db)"));
5490 _ui->lineEdit_dictionaryPath->setText(
path);
5497 if(
_ui->lineEdit_OdomORBSLAMVocPath->text().isEmpty())
5499 path = QFileDialog::getOpenFileName(
this, tr(
"ORBSLAM Vocabulary"), this->
getWorkingDirectory(), tr(
"Vocabulary (*.txt)"));
5503 path = QFileDialog::getOpenFileName(
this, tr(
"ORBSLAM Vocabulary"),
_ui->lineEdit_OdomORBSLAMVocPath->text(), tr(
"Vocabulary (*.txt)"));
5507 _ui->lineEdit_OdomORBSLAMVocPath->setText(
path);
5514 if(
_ui->lineEdit_OdomOkvisPath->text().isEmpty())
5516 path = QFileDialog::getOpenFileName(
this, tr(
"OKVIS Config"), this->
getWorkingDirectory(), tr(
"OKVIS config (*.yaml)"));
5520 path = QFileDialog::getOpenFileName(
this, tr(
"OKVIS Config"),
_ui->lineEdit_OdomOkvisPath->text(), tr(
"OKVIS config (*.yaml)"));
5524 _ui->lineEdit_OdomOkvisPath->setText(
path);
5531 if(
_ui->lineEdit_OdomVinsPath->text().isEmpty())
5533 path = QFileDialog::getOpenFileName(
this, tr(
"VINS-Fusion Config"), this->
getWorkingDirectory(), tr(
"VINS-Fusion config (*.yaml)"));
5537 path = QFileDialog::getOpenFileName(
this, tr(
"VINS-Fusion Config"),
_ui->lineEdit_OdomVinsPath->text(), tr(
"VINS-Fusion config (*.yaml)"));
5541 _ui->lineEdit_OdomVinsPath->setText(
path);
5548 if(
_ui->lineEdit_OdomOpenVINSLeftMaskPath->text().isEmpty())
5550 path = QFileDialog::getOpenFileName(
this, tr(
"Select Left Mask"), this->
getWorkingDirectory(), tr(
"Image mask (*.jpg *.png)"));
5554 path = QFileDialog::getOpenFileName(
this, tr(
"Select Left Mask"),
_ui->lineEdit_OdomOpenVINSLeftMaskPath->text(), tr(
"Image mask (*.jpg *.png)"));
5558 _ui->lineEdit_OdomOpenVINSLeftMaskPath->setText(
path);
5565 if(
_ui->lineEdit_OdomOpenVINSRightMaskPath->text().isEmpty())
5567 path = QFileDialog::getOpenFileName(
this, tr(
"Select Right Mask"), this->
getWorkingDirectory(), tr(
"Image mask (*.jpg *.png)"));
5571 path = QFileDialog::getOpenFileName(
this, tr(
"Select Right Mask"),
_ui->lineEdit_OdomOpenVINSRightMaskPath->text(), tr(
"Image mask (*.jpg *.png)"));
5575 _ui->lineEdit_OdomOpenVINSRightMaskPath->setText(
path);
5582 if(
_ui->lineEdit_IcpPMConfigPath->text().isEmpty())
5584 path = QFileDialog::getOpenFileName(
this, tr(
"Select file"), this->
getWorkingDirectory(), tr(
"libpointmatcher (*.yaml)"));
5588 path = QFileDialog::getOpenFileName(
this, tr(
"Select file"),
_ui->lineEdit_IcpPMConfigPath->text(), tr(
"libpointmatcher (*.yaml)"));
5592 _ui->lineEdit_IcpPMConfigPath->setText(
path);
5599 if(
_ui->lineEdit_sptorch_path->text().isEmpty())
5601 path = QFileDialog::getOpenFileName(
this, tr(
"Select file"), this->
getWorkingDirectory(), tr(
"SuperPoint weights (*.pt)"));
5605 path = QFileDialog::getOpenFileName(
this, tr(
"Select file"),
_ui->lineEdit_sptorch_path->text(), tr(
"SuperPoint weights (*.pt)"));
5609 _ui->lineEdit_sptorch_path->setText(
path);
5616 if(
_ui->lineEdit_pymatcher_path->text().isEmpty())
5618 path = QFileDialog::getOpenFileName(
this, tr(
"Select file"), this->
getWorkingDirectory(), tr(
"Python wrapper (*.py)"));
5622 path = QFileDialog::getOpenFileName(
this, tr(
"Select file"),
_ui->lineEdit_pymatcher_path->text(), tr(
"Python wrapper (*.py)"));
5626 _ui->lineEdit_pymatcher_path->setText(
path);
5633 if(
_ui->lineEdit_pymatcher_model->text().isEmpty())
5635 path = QFileDialog::getOpenFileName(
this, tr(
"Select file"), this->
getWorkingDirectory(), tr(
"PyTorch model (*.pth *.pt)"));
5639 path = QFileDialog::getOpenFileName(
this, tr(
"Select file"),
_ui->lineEdit_pymatcher_model->text(), tr(
"PyTorch model (*.pth *.pt)"));
5643 _ui->lineEdit_pymatcher_model->setText(
path);
5650 if(
_ui->lineEdit_pydescriptor_path->text().isEmpty())
5652 path = QFileDialog::getOpenFileName(
this, tr(
"Select file"), this->
getWorkingDirectory(), tr(
"Python wrapper (*.py)"));
5656 path = QFileDialog::getOpenFileName(
this, tr(
"Select file"),
_ui->lineEdit_pydescriptor_path->text(), tr(
"Python wrapper (*.py)"));
5660 _ui->lineEdit_pydescriptor_path->setText(
path);
5666 if(
_ui->lineEdit_pydetector_path->text().isEmpty())
5668 path = QFileDialog::getOpenFileName(
this, tr(
"Select file"), this->
getWorkingDirectory(), tr(
"Python wrapper (*.py)"));
5672 path = QFileDialog::getOpenFileName(
this, tr(
"Select file"),
_ui->lineEdit_pydetector_path->text(), tr(
"Python wrapper (*.py)"));
5676 _ui->lineEdit_pydetector_path->setText(
path);
5682 _ui->stackedWidget_src->setVisible(
_ui->comboBox_sourceType->currentIndex() != 4);
5683 _ui->frame_camera_sensor->setVisible(
_ui->comboBox_sourceType->currentIndex() != 4);
5685 _ui->groupBox_sourceRGBD->setVisible(
_ui->comboBox_sourceType->currentIndex() == 0);
5686 _ui->groupBox_sourceStereo->setVisible(
_ui->comboBox_sourceType->currentIndex() == 1);
5687 _ui->groupBox_sourceRGB->setVisible(
_ui->comboBox_sourceType->currentIndex() == 2);
5688 _ui->groupBox_sourceDatabase->setVisible(
_ui->comboBox_sourceType->currentIndex() == 3);
5690 _ui->stackedWidget_rgbd->setVisible(
_ui->comboBox_sourceType->currentIndex() == 0 &&
5700 _ui->groupBox_openni2->setVisible(
_ui->comboBox_sourceType->currentIndex() == 0 &&
_ui->comboBox_cameraRGBD->currentIndex() ==
kSrcOpenNI2-
kSrcRGBD);
5701 _ui->groupBox_freenect2->setVisible(
_ui->comboBox_sourceType->currentIndex() == 0 &&
_ui->comboBox_cameraRGBD->currentIndex() ==
kSrcFreenect2-
kSrcRGBD);
5702 _ui->groupBox_k4w2->setVisible(
_ui->comboBox_sourceType->currentIndex() == 0 &&
_ui->comboBox_cameraRGBD->currentIndex() ==
kSrcK4W2 -
kSrcRGBD);
5703 _ui->groupBox_k4a->setVisible(
_ui->comboBox_sourceType->currentIndex() == 0 &&
_ui->comboBox_cameraRGBD->currentIndex() ==
kSrcK4A -
kSrcRGBD);
5704 _ui->groupBox_realsense->setVisible(
_ui->comboBox_sourceType->currentIndex() == 0 &&
_ui->comboBox_cameraRGBD->currentIndex() ==
kSrcRealSense -
kSrcRGBD);
5705 _ui->groupBox_realsense2->setVisible(
_ui->comboBox_sourceType->currentIndex() == 0 &&
_ui->comboBox_cameraRGBD->currentIndex() ==
kSrcRealSense2 -
kSrcRGBD);
5706 _ui->groupBox_cameraRGBDImages->setVisible(
_ui->comboBox_sourceType->currentIndex() == 0 &&
_ui->comboBox_cameraRGBD->currentIndex() ==
kSrcRGBDImages-
kSrcRGBD);
5707 _ui->groupBox_openni->setVisible(
_ui->comboBox_sourceType->currentIndex() == 0 &&
_ui->comboBox_cameraRGBD->currentIndex() ==
kSrcOpenNI_PCL -
kSrcRGBD);
5709 _ui->stackedWidget_stereo->setVisible(
_ui->comboBox_sourceType->currentIndex() == 1 &&
5718 _ui->groupBox_cameraStereoVideo->setVisible(
_ui->comboBox_sourceType->currentIndex() == 1 &&
_ui->comboBox_cameraStereo->currentIndex() ==
kSrcStereoVideo -
kSrcStereo);
5719 _ui->groupBox_cameraStereoUsb->setVisible(
_ui->comboBox_sourceType->currentIndex() == 1 &&
_ui->comboBox_cameraStereo->currentIndex() ==
kSrcStereoUsb -
kSrcStereo);
5720 _ui->groupBox_cameraStereoZed->setVisible(
_ui->comboBox_sourceType->currentIndex() == 1 &&
_ui->comboBox_cameraStereo->currentIndex() ==
kSrcStereoZed -
kSrcStereo);
5722 _ui->groupBox_cameraStereoZedOC->setVisible(
_ui->comboBox_sourceType->currentIndex() == 1 &&
_ui->comboBox_cameraStereo->currentIndex() ==
kSrcStereoZedOC -
kSrcStereo);
5725 _ui->stackedWidget_image->setVisible(
_ui->comboBox_sourceType->currentIndex() == 2 &&
5729 _ui->source_groupBox_images->setVisible(
_ui->comboBox_sourceType->currentIndex() == 2 &&
_ui->source_comboBox_image_type->currentIndex() ==
kSrcImages-
kSrcRGB);
5730 _ui->source_groupBox_video->setVisible(
_ui->comboBox_sourceType->currentIndex() == 2 &&
_ui->source_comboBox_image_type->currentIndex() ==
kSrcVideo-
kSrcRGB);
5731 _ui->source_groupBox_usbcam->setVisible(
_ui->comboBox_sourceType->currentIndex() == 2 &&
_ui->source_comboBox_image_type->currentIndex() ==
kSrcUsbDevice-
kSrcRGB);
5733 _ui->groupBox_sourceImages_optional->setVisible(
5736 (
_ui->comboBox_sourceType->currentIndex() == 2 &&
_ui->source_comboBox_image_type->currentIndex() ==
kSrcImages-
kSrcRGB));
5738 _ui->groupBox_depthImageFiltering->setEnabled(
5739 _ui->comboBox_sourceType->currentIndex() == 0 ||
5740 _ui->comboBox_sourceType->currentIndex() == 3);
5741 _ui->groupBox_depthImageFiltering->setVisible(
_ui->groupBox_depthImageFiltering->isEnabled());
5743 _ui->groupBox_depthFromScan->setVisible(
_ui->comboBox_sourceType->currentIndex() == 2 &&
_ui->source_comboBox_image_type->currentIndex() ==
kSrcImages-
kSrcRGB);
5747 _ui->groupBox_odom_sensor->setVisible(
_ui->comboBox_sourceType->currentIndex() != 3);
5750 _ui->comboBox_lidar_src->setEnabled(
_ui->comboBox_sourceType->currentIndex() != 3);
5751 if(!
_ui->comboBox_lidar_src->isEnabled() &&
_ui->comboBox_lidar_src->currentIndex() != 0)
5753 _ui->comboBox_lidar_src->setCurrentIndex(0);
5755 _ui->checkBox_source_scanFromDepth->setEnabled(
_ui->comboBox_sourceType->currentIndex() <= 1 ||
_ui->comboBox_sourceType->currentIndex() == 3);
5756 _ui->label_source_scanFromDepth->setEnabled(
_ui->checkBox_source_scanFromDepth->isEnabled());
5757 if(!
_ui->checkBox_source_scanFromDepth->isEnabled())
5759 _ui->checkBox_source_scanFromDepth->setChecked(
false);
5761 _ui->stackedWidget_lidar_src->setVisible(
_ui->comboBox_lidar_src->currentIndex() > 0);
5763 _ui->frame_lidar_sensor->setVisible(
_ui->comboBox_lidar_src->currentIndex() > 0 ||
_ui->checkBox_source_scanFromDepth->isChecked());
5764 _ui->pushButton_test_lidar->setEnabled(
_ui->comboBox_lidar_src->currentIndex() > 0);
5767 _ui->groupBox_imuFiltering->setEnabled(
5770 (
_ui->comboBox_sourceType->currentIndex() == 2 &&
_ui->source_comboBox_image_type->currentIndex() ==
kSrcImages-
kSrcRGB) ||
5772 (
_ui->comboBox_sourceType->currentIndex() == 0 &&
_ui->comboBox_cameraRGBD->currentIndex() ==
kSrcK4A -
kSrcRGBD) ||
5781 _ui->stackedWidget_imuFilter->setVisible(
_ui->comboBox_imuFilter_strategy->currentIndex() > 0);
5782 _ui->groupBox_madgwickfilter->setVisible(
_ui->comboBox_imuFilter_strategy->currentIndex() == 1);
5783 _ui->groupBox_complementaryfilter->setVisible(
_ui->comboBox_imuFilter_strategy->currentIndex() == 2);
5784 _ui->groupBox_imuFiltering->setVisible(
_ui->groupBox_imuFiltering->isEnabled());
5791 return _ui->comboBox_loggerLevel->currentIndex();
5795 return _ui->comboBox_loggerEventLevel->currentIndex();
5799 return _ui->comboBox_loggerPauseLevel->currentIndex();
5803 return _ui->comboBox_loggerType->currentIndex();
5807 return _ui->checkBox_logger_printTime->isChecked();
5811 return _ui->checkBox_logger_printThreadId->isChecked();
5815 std::vector<std::string> threads;
5816 for(
int i=0;
i<
_ui->comboBox_loggerFilter->count(); ++
i)
5818 if(
_ui->comboBox_loggerFilter->itemData(
i).toBool())
5820 threads.push_back(
_ui->comboBox_loggerFilter->itemText(
i).toStdString());
5827 return _ui->checkBox_verticalLayoutUsed->isChecked();
5831 return _ui->checkBox_imageRejectedShown->isChecked();
5835 return _ui->checkBox_imageHighestHypShown->isChecked();
5839 return _ui->checkBox_beep->isChecked();
5843 return _ui->checkBox_stamps->isChecked();
5847 return _ui->checkBox_cacheStatistics->isChecked();
5851 return _ui->checkBox_notifyWhenNewGlobalPathIsReceived->isChecked();
5855 return _ui->spinBox_odomQualityWarnThr->value();
5859 return _ui->checkBox_odom_onlyInliersShown->isChecked();
5863 return _ui->radioButton_posteriorGraphView->isChecked();
5867 return _ui->radioButton_wordsGraphView->isChecked();
5871 return _ui->radioButton_localizationsGraphView->isChecked();
5875 return _ui->radioButton_localizationsGraphViewOdomCache->isChecked();
5879 return _ui->checkbox_odomDisabled->isChecked();
5883 return _ui->checkBox_odom_sensor_use_as_gt->isChecked();
5887 return _ui->odom_registration->currentIndex();
5891 return _ui->odom_f2m_gravitySigma->value();
5895 return _ui->checkbox_groundTruthAlign->isChecked();
5900 UASSERT(index >= 0 && index <= 1);
5905 #ifdef RTABMAP_OCTOMAP
5906 return _ui->groupBox_octomap->isChecked();
5912 #ifdef RTABMAP_OCTOMAP
5913 return _ui->groupBox_octomap->isChecked() &&
_ui->checkBox_octomap_show3dMap->isChecked();
5919 return _ui->comboBox_octomap_renderingType->currentIndex();
5923 #ifdef RTABMAP_OCTOMAP
5924 return _ui->groupBox_octomap->isChecked() &&
_ui->checkBox_octomap_2dgrid->isChecked();
5930 return _ui->spinBox_octomap_treeDepth->value();
5934 return _ui->spinBox_octomap_pointSize->value();
5939 return _ui->doubleSpinBox_voxel->value();
5943 return _ui->doubleSpinBox_noiseRadius->value();
5947 return _ui->spinBox_noiseMinNeighbors->value();
5951 return _ui->doubleSpinBox_ceilingFilterHeight->value();
5955 return _ui->doubleSpinBox_floorFilterHeight->value();
5959 return _ui->spinBox_normalKSearch->value();
5963 return _ui->doubleSpinBox_normalRadiusSearch->value();
5967 return _ui->doubleSpinBox_ceilingFilterHeight_scan->value();
5971 return _ui->doubleSpinBox_floorFilterHeight_scan->value();
5975 return _ui->spinBox_normalKSearch_scan->value();
5979 return _ui->doubleSpinBox_normalRadiusSearch_scan->value();
5984 return _ui->checkBox_showGraphs->isChecked();
5988 return _ui->checkBox_showLabels->isChecked();
5992 return _ui->checkBox_showFrames->isChecked();
5996 return _ui->checkBox_showLandmarks->isChecked();
6000 return _ui->doubleSpinBox_landmarkSize->value();
6004 UASSERT(index >= 0 && index <= 1);
6009 UASSERT(index >= 0 && index <= 1);
6014 return _ui->checkBox_showIMUAcc->isChecked();
6018 return _ui->RGBDMarkerDetection->isChecked();
6022 return _ui->ArucoMarkerLength->value();
6026 return _ui->groupBox_organized->isChecked();
6030 return _ui->doubleSpinBox_mesh_angleTolerance->value()*
M_PI/180.0;
6034 return _ui->checkBox_mesh_quad->isChecked();
6038 return _ui->checkBox_mesh_texture->isChecked();
6042 return _ui->spinBox_mesh_triangleSize->value();
6046 UASSERT(index >= 0 && index <= 1);
6051 UASSERT(index >= 0 && index <= 1);
6056 UASSERT(index >= 0 && index <= 1);
6061 UASSERT(index >= 0 && index <= 1);
6062 std::vector<float> roiRatios;
6068 roiRatios.resize(4);
6079 UASSERT(index >= 0 && index <= 1);
6084 UASSERT(index >= 0 && index <= 1);
6089 UASSERT(index >= 0 && index <= 1);
6095 UASSERT(index >= 0 && index <= 1);
6100 UASSERT(index >= 0 && index <= 1);
6105 UASSERT(index >= 0 && index <= 1);
6110 UASSERT(index >= 0 && index <= 1);
6115 UASSERT(index >= 0 && index <= 1);
6120 UASSERT(index >= 0 && index <= 1);
6125 UASSERT(index >= 0 && index <= 1);
6130 UASSERT(index >= 0 && index <= 1);
6136 UASSERT(index >= 0 && index <= 1);
6141 UASSERT(index >= 0 && index <= 1);
6146 UASSERT(index >= 0 && index <= 1);
6152 return _ui->radioButton_nodeFiltering->isChecked();
6156 return _ui->radioButton_subtractFiltering->isChecked();
6160 return _ui->doubleSpinBox_cloudFilterRadius->value();
6164 return _ui->doubleSpinBox_cloudFilterAngle->value();
6168 return _ui->spinBox_subtractFilteringMinPts->value();
6172 return _ui->doubleSpinBox_subtractFilteringRadius->value();
6176 return _ui->doubleSpinBox_subtractFilteringAngle->value()*
M_PI/180.0;
6180 return _ui->doubleSpinBox_map_resolution->value();
6184 return _ui->checkBox_map_shown->isChecked();
6188 return _ui->checkBox_elevation_shown->checkState();
6192 return _ui->comboBox_grid_sensor->currentIndex();
6196 return _ui->checkBox_grid_projMapFrame->isChecked();
6200 return _ui->doubleSpinBox_grid_maxGroundAngle->value()*
M_PI/180.0;
6204 return _ui->doubleSpinBox_grid_maxGroundHeight->value();
6208 return _ui->spinBox_grid_minClusterSize->value();
6212 return _ui->doubleSpinBox_grid_maxObstacleHeight->value();
6216 return _ui->checkBox_grid_flatObstaclesDetected->isChecked();
6220 return _ui->doubleSpinBox_map_opacity->value();
6227 return _ui->general_doubleSpinBox_imgRate->value();
6231 return _ui->source_mirroring->isChecked();
6235 int index =
_ui->comboBox_sourceType->currentIndex();
6280 return _ui->comboBox_cameraRGBD->currentText();
6284 return _ui->comboBox_cameraStereo->currentText();
6288 return _ui->source_comboBox_image_type->currentText();
6299 return _ui->lineEdit_sourceDevice->text();
6304 if(
_ui->comboBox_odom_sensor->currentIndex() == 1)
6309 else if(
_ui->comboBox_odom_sensor->currentIndex() == 2)
6314 else if(
_ui->comboBox_odom_sensor->currentIndex() == 3)
6319 else if(
_ui->comboBox_odom_sensor->currentIndex() != 0)
6321 UERROR(
"Not implemented!");
6328 if(
_ui->comboBox_lidar_src->currentIndex() == 0)
6357 return _ui->lineEdit_cameraImages_path_imu->text();
6370 return _ui->spinBox_cameraImages_max_imu_rate->value();
6375 return _ui->source_checkBox_useDbStamps->isChecked();
6379 return _ui->checkbox_rgbd_colorOnly->isChecked();
6383 return _ui->comboBox_imuFilter_strategy->currentIndex();
6387 return _ui->checkBox_imuFilter_baseFrameConversion->isChecked();
6391 return _ui->groupBox_depthImageFiltering->isEnabled();
6395 return _ui->lineEdit_source_distortionModel->text();
6399 return _ui->groupBox_bilateral->isChecked();
6403 return _ui->doubleSpinBox_bilateral_sigmaS->value();
6407 return _ui->doubleSpinBox_bilateral_sigmaR->value();
6411 return _ui->spinBox_source_imageDecimation->value();
6415 return _ui->comboBox_source_histogramMethod->currentIndex();
6419 return _ui->checkbox_source_feature_detection->isChecked();
6423 return _ui->checkbox_stereo_depthGenerated->isChecked();
6427 return _ui->checkBox_stereo_exposureCompensation->isChecked();
6431 return _ui->checkBox_source_scanFromDepth->isChecked();
6435 return _ui->checkBox_source_scanDeskewing->isChecked();
6439 return _ui->spinBox_source_scanDownsampleStep->value();
6443 return _ui->doubleSpinBox_source_scanRangeMin->value();
6447 return _ui->doubleSpinBox_source_scanRangeMax->value();
6451 return _ui->doubleSpinBox_source_scanVoxelSize->value();
6455 return _ui->spinBox_source_scanNormalsK->value();
6459 return _ui->doubleSpinBox_source_scanNormalsRadius->value();
6463 return _ui->doubleSpinBox_source_scanNormalsForceGroundUp->value();
6470 _ui->lineEdit_sourceDevice->text(),
6471 _ui->lineEdit_calibrationFile->text(),
6481 const QString & calibrationPath,
6485 bool odomSensorExtrinsicsCalib)
6489 QMessageBox::warning(
this, tr(
"Odometry Sensor"),
6490 tr(
"Driver %1 cannot support odometry only mode.").
arg(driver), QMessageBox::Ok);
6500 QMessageBox::warning(
this, tr(
"Calibration"),
6501 tr(
"Using raw images for \"OpenNI\" driver is not yet supported. "
6502 "Factory calibration loaded from OpenNI is used."), QMessageBox::Ok);
6508 _ui->lineEdit_openniOniPath->text().isEmpty()?
device.toStdString():
_ui->lineEdit_openniOniPath->text().toStdString(),
6509 this->getGeneralInputRate(),
6510 this->getSourceLocalTransform());
6516 _ui->lineEdit_openni2OniPath->text().isEmpty()?
device.toStdString():
_ui->lineEdit_openni2OniPath->text().toStdString(),
6518 this->getGeneralInputRate(),
6519 this->getSourceLocalTransform());
6526 this->getGeneralInputRate(),
6527 this->getSourceLocalTransform());
6534 QMessageBox::warning(
this, tr(
"Calibration"),
6535 tr(
"Using raw images for \"OpenNI\" driver is not yet supported. "
6536 "Factory calibration loaded from OpenNI is used."), QMessageBox::Ok);
6552 this->getGeneralInputRate(),
6553 this->getSourceLocalTransform(),
6554 _ui->doubleSpinBox_freenect2MinDepth->value(),
6555 _ui->doubleSpinBox_freenect2MaxDepth->value(),
6556 _ui->checkBox_freenect2BilateralFiltering->isChecked(),
6557 _ui->checkBox_freenect2EdgeAwareFiltering->isChecked(),
6558 _ui->checkBox_freenect2NoiseFiltering->isChecked(),
6559 _ui->lineEdit_freenect2Pipeline->text().toStdString());
6564 device.isEmpty() ? 0 : atoi(
device.toStdString().c_str()),
6566 this->getGeneralInputRate(),
6567 this->getSourceLocalTransform());
6571 if (!
_ui->lineEdit_k4a_mkv->text().isEmpty())
6575 _ui->lineEdit_k4a_mkv->text().toStdString().c_str(),
6576 _ui->source_checkBox_useMKVStamps->isChecked() ? -1 :
this->getGeneralInputRate(),
6577 this->getSourceLocalTransform());
6582 device.isEmpty() ? 0 : atoi(
device.toStdString().c_str()),
6583 this->getGeneralInputRate(),
6584 this->getSourceLocalTransform());
6588 ((
CameraK4A*)
camera)->setPreferences(
_ui->comboBox_k4a_rgb_resolution->currentIndex(),
6589 _ui->comboBox_k4a_framerate->currentIndex(),
6590 _ui->comboBox_k4a_depth_resolution->currentIndex());
6594 if(useRawImages &&
_ui->comboBox_realsenseRGBSource->currentIndex()!=2)
6596 QMessageBox::warning(
this, tr(
"Calibration"),
6597 tr(
"Using raw images for \"RealSense\" driver is not yet supported for color and infrared streams. "
6598 "Factory calibration loaded from RealSense is used."), QMessageBox::Ok);
6604 device.isEmpty() ? 0 : atoi(
device.toStdString().c_str()),
6605 _ui->comboBox_realsensePresetRGB->currentIndex(),
6606 _ui->comboBox_realsensePresetDepth->currentIndex(),
6607 _ui->checkbox_realsenseOdom->isChecked(),
6608 this->getGeneralInputRate(),
6609 this->getSourceLocalTransform());
6618 QMessageBox::warning(
this, tr(
"Calibration"),
6619 tr(
"Using raw images for \"RealSense\" driver is not yet supported. "
6620 "Factory calibration loaded from RealSense2 is used."), QMessageBox::Ok);
6627 this->getGeneralInputRate(),
6628 this->getSourceLocalTransform());
6630 _ui->checkbox_publishInterIMU->isChecked(),
6635 ((
CameraRealSense2*)
camera)->setImagesRectified((
_ui->checkBox_stereo_rectify->isEnabled() &&
_ui->checkBox_stereo_rectify->isChecked()) && !useRawImages);
6643 ((
CameraRealSense2*)
camera)->setDepthResolution(
_ui->spinBox_rs2_width_depth->value(),
_ui->spinBox_rs2_height_depth->value(),
_ui->spinBox_rs2_rate_depth->value());
6654 QMessageBox::warning(
this, tr(
"Calibration"),
6655 tr(
"Using raw images for \"MyntEye\" driver is not yet supported. "
6656 "Factory calibration loaded from MyntEye is used."), QMessageBox::Ok);
6663 _ui->checkbox_stereoMyntEye_rectify->isChecked(),
6664 _ui->checkbox_stereoMyntEye_depth->isChecked(),
6665 this->getGeneralInputRate(),
6666 this->getSourceLocalTransform());
6668 if(
_ui->checkbox_stereoMyntEye_autoExposure->isChecked())
6675 _ui->spinBox_stereoMyntEye_gain->value(),
6676 _ui->spinBox_stereoMyntEye_brightness->value(),
6677 _ui->spinBox_stereoMyntEye_contrast->value());
6680 _ui->spinBox_stereoMyntEye_irControl->value());
6686 _ui->lineEdit_cameraRGBDImages_path_rgb->text().append(QDir::separator()).toStdString(),
6687 _ui->lineEdit_cameraRGBDImages_path_depth->text().append(QDir::separator()).toStdString(),
6688 _ui->doubleSpinBox_cameraRGBDImages_scale->value(),
6689 this->getGeneralInputRate(),
6690 this->getSourceLocalTransform());
6694 ((
CameraRGBDImages*)
camera)->setOdometryPath(
_ui->lineEdit_cameraImages_odom->text().toStdString(),
_ui->comboBox_cameraImages_odomFormat->currentIndex());
6695 ((
CameraRGBDImages*)
camera)->setGroundTruthPath(
_ui->lineEdit_cameraImages_gt->text().toStdString(),
_ui->comboBox_cameraImages_gtFormat->currentIndex());
6698 _ui->lineEdit_cameraImages_path_scans->text().isEmpty()?
"":
_ui->lineEdit_cameraImages_path_scans->text().append(QDir::separator()).toStdString(),
6699 _ui->spinBox_cameraImages_max_scan_pts->value(),
6702 _ui->checkBox_cameraImages_timestamps->isChecked(),
6703 _ui->lineEdit_cameraImages_timestamps->text().toStdString(),
6704 _ui->checkBox_cameraImages_syncTimeStamps->isChecked());
6717 QMessageBox::warning(
this, tr(
"Calibration"),
6718 tr(
"Using raw images for \"FlyCapture2\" driver is not yet supported. "
6719 "Factory calibration loaded from FlyCapture2 is used."), QMessageBox::Ok);
6732 _ui->lineEdit_cameraStereoImages_path_left->text().append(QDir::separator()).toStdString(),
6733 _ui->lineEdit_cameraStereoImages_path_right->text().append(QDir::separator()).toStdString(),
6734 (
_ui->checkBox_stereo_rectify->isEnabled() &&
_ui->checkBox_stereo_rectify->isChecked()) && !useRawImages,
6735 this->getGeneralInputRate(),
6736 this->getSourceLocalTransform());
6740 ((
CameraStereoImages*)
camera)->setOdometryPath(
_ui->lineEdit_cameraImages_odom->text().toStdString(),
_ui->comboBox_cameraImages_odomFormat->currentIndex());
6741 ((
CameraStereoImages*)
camera)->setGroundTruthPath(
_ui->lineEdit_cameraImages_gt->text().toStdString(),
_ui->comboBox_cameraImages_gtFormat->currentIndex());
6744 _ui->lineEdit_cameraImages_path_scans->text().isEmpty()?
"":
_ui->lineEdit_cameraImages_path_scans->text().append(QDir::separator()).toStdString(),
6745 _ui->spinBox_cameraImages_max_scan_pts->value(),
6748 _ui->checkBox_cameraImages_timestamps->isChecked(),
6749 _ui->lineEdit_cameraImages_timestamps->text().toStdString(),
6750 _ui->checkBox_cameraImages_syncTimeStamps->isChecked());
6756 if(
_ui->spinBox_stereo_right_device->value()>=0)
6759 device.isEmpty() ? 0 : atoi(
device.toStdString().c_str()),
6760 _ui->spinBox_stereo_right_device->value(),
6761 (
_ui->checkBox_stereo_rectify->isEnabled() &&
_ui->checkBox_stereo_rectify->isChecked()) && !useRawImages,
6762 this->getGeneralInputRate(),
6763 this->getSourceLocalTransform());
6768 device.isEmpty() ? 0 : atoi(
device.toStdString().c_str()),
6769 (
_ui->checkBox_stereo_rectify->isEnabled() &&
_ui->checkBox_stereo_rectify->isChecked()) && !useRawImages,
6770 this->getGeneralInputRate(),
6771 this->getSourceLocalTransform());
6773 ((
CameraStereoVideo*)
camera)->setResolution(
_ui->spinBox_stereousbcam_streamWidth->value(),
_ui->spinBox_stereousbcam_streamHeight->value());
6774 if(!
_ui->lineEdit_stereousbcam_fourcc->text().isEmpty())
6781 if(!
_ui->lineEdit_cameraStereoVideo_path_2->text().isEmpty())
6785 _ui->lineEdit_cameraStereoVideo_path->text().toStdString(),
6786 _ui->lineEdit_cameraStereoVideo_path_2->text().toStdString(),
6787 (
_ui->checkBox_stereo_rectify->isEnabled() &&
_ui->checkBox_stereo_rectify->isChecked()) && !useRawImages,
6788 this->getGeneralInputRate(),
6789 this->getSourceLocalTransform());
6795 _ui->lineEdit_cameraStereoVideo_path->text().toStdString(),
6796 (
_ui->checkBox_stereo_rectify->isEnabled() &&
_ui->checkBox_stereo_rectify->isChecked()) && !useRawImages,
6797 this->getGeneralInputRate(),
6798 this->getSourceLocalTransform());
6807 (
_ui->checkBox_stereo_rectify->isEnabled() &&
_ui->checkBox_stereo_rectify->isChecked()) && !useRawImages,
6808 this->getGeneralInputRate(),
6809 this->getSourceLocalTransform());
6815 if(!
_ui->lineEdit_zedSvoPath->text().isEmpty())
6818 _ui->lineEdit_zedSvoPath->text().toStdString(),
6819 _ui->comboBox_stereoZed_quality->currentIndex(),
6820 _ui->comboBox_stereoZed_sensingMode->currentIndex(),
6821 _ui->spinBox_stereoZed_confidenceThr->value(),
6825 _ui->checkbox_stereoZed_selfCalibration->isChecked(),
6826 _ui->loopClosure_bowForce2D->isChecked(),
6827 _ui->spinBox_stereoZed_texturenessConfidenceThr->value());
6833 _ui->comboBox_stereoZed_resolution->currentIndex()-1,
6835 _ui->comboBox_stereoZed_quality->currentIndex()==0&&odomOnly?1:
_ui->comboBox_stereoZed_quality->currentIndex(),
6836 _ui->comboBox_stereoZed_sensingMode->currentIndex(),
6837 _ui->spinBox_stereoZed_confidenceThr->value(),
6841 _ui->checkbox_stereoZed_selfCalibration->isChecked(),
6842 _ui->loopClosure_bowForce2D->isChecked(),
6843 _ui->spinBox_stereoZed_texturenessConfidenceThr->value());
6846 _ui->checkbox_publishInterIMU->isChecked(),
6854 device.isEmpty()?-1:atoi(
device.toStdString().c_str()),
6855 _ui->comboBox_stereoZedOC_resolution->currentIndex(),
6856 this->getGeneralInputRate(),
6857 this->getSourceLocalTransform());
6863 device.toStdString().c_str(),
6864 _ui->comboBox_depthai_resolution->currentIndex(),
6865 this->getGeneralInputRate(),
6866 this->getSourceLocalTransform());
6868 ((
CameraDepthAI*)
camera)->setDepthProfile(
_ui->spinBox_depthai_conf_threshold->value(),
_ui->spinBox_depthai_lrc_threshold->value());
6870 ((
CameraDepthAI*)
camera)->setSubpixelMode(
_ui->comboBox_depthai_subpixel_fractional_bits->currentIndex()!=0,
_ui->comboBox_depthai_subpixel_fractional_bits->currentIndex()==2?4:
_ui->comboBox_depthai_subpixel_fractional_bits->currentIndex()==3?5:3);
6871 ((
CameraDepthAI*)
camera)->setCompanding(
_ui->comboBox_depthai_disparity_companding->currentIndex()!=0,
_ui->comboBox_depthai_disparity_companding->currentIndex()==1?64:96);
6872 ((
CameraDepthAI*)
camera)->setRectification(
_ui->checkBox_depthai_use_spec_translation->isChecked(),
_ui->doubleSpinBox_depthai_alpha_scaling->value(), !useRawImages);
6873 ((
CameraDepthAI*)
camera)->setIMU(
_ui->checkBox_depthai_imu_published->isChecked(),
_ui->checkbox_publishInterIMU->isChecked());
6874 ((
CameraDepthAI*)
camera)->setIrIntensity(
_ui->doubleSpinBox_depthai_dot_intensity->value(),
_ui->doubleSpinBox_depthai_flood_intensity->value());
6877 if(
_ui->comboBox_depthai_detect_features->currentIndex() == 1)
6879 ((
CameraDepthAI*)
camera)->setGFTTDetector(
_ui->checkBox_GFTT_useHarrisDetector->isChecked(),
_ui->doubleSpinBox_GFTT_minDistance->value(),
_ui->reextract_maxFeatures->value());
6881 else if(
_ui->comboBox_depthai_detect_features->currentIndex() >= 2)
6883 ((
CameraDepthAI*)
camera)->setSuperPointDetector(
_ui->doubleSpinBox_sptorch_threshold->value(),
_ui->checkBox_sptorch_nms->isChecked(),
_ui->spinBox_sptorch_minDistance->value());
6894 _ui->checkbox_publishInterIMU->isChecked(),
6902 (
_ui->checkBox_rgb_rectify->isEnabled() &&
_ui->checkBox_rgb_rectify->isChecked()) && !useRawImages,
6903 this->getGeneralInputRate(),
6904 this->getSourceLocalTransform());
6905 ((
CameraVideo*)
camera)->setResolution(
_ui->spinBox_usbcam_streamWidth->value(),
_ui->spinBox_usbcam_streamHeight->value());
6906 if(!
_ui->lineEdit_usbcam_fourcc->text().isEmpty())
6914 _ui->source_video_lineEdit_path->text().toStdString(),
6915 (
_ui->checkBox_rgb_rectify->isEnabled() &&
_ui->checkBox_rgb_rectify->isChecked()) && !useRawImages,
6916 this->getGeneralInputRate(),
6917 this->getSourceLocalTransform());
6922 _ui->source_images_lineEdit_path->text().toStdString(),
6923 this->getGeneralInputRate(),
6924 this->getSourceLocalTransform());
6928 ((
CameraImages*)
camera)->setImagesRectified((
_ui->checkBox_rgb_rectify->isEnabled() &&
_ui->checkBox_rgb_rectify->isChecked()) && !useRawImages);
6932 _ui->lineEdit_cameraImages_odom->text().toStdString(),
6933 _ui->comboBox_cameraImages_odomFormat->currentIndex());
6935 _ui->lineEdit_cameraImages_gt->text().toStdString(),
6936 _ui->comboBox_cameraImages_gtFormat->currentIndex());
6939 _ui->lineEdit_cameraImages_path_scans->text().isEmpty()?
"":
_ui->lineEdit_cameraImages_path_scans->text().append(QDir::separator()).toStdString(),
6940 _ui->spinBox_cameraImages_max_scan_pts->value(),
6943 _ui->groupBox_depthFromScan->isChecked(),
6944 !
_ui->groupBox_depthFromScan_fillHoles->isChecked()?0:
_ui->radioButton_depthFromScan_vertical->isChecked()?1:-1,
6945 _ui->checkBox_depthFromScan_fillBorders->isChecked());
6947 _ui->checkBox_cameraImages_timestamps->isChecked(),
6948 _ui->lineEdit_cameraImages_timestamps->text().toStdString(),
6949 _ui->checkBox_cameraImages_syncTimeStamps->isChecked());
6955 _ui->source_checkBox_useDbStamps->isChecked()?-1:
this->getGeneralInputRate(),
6956 _ui->source_checkBox_ignoreOdometry->isChecked(),
6957 _ui->source_checkBox_ignoreGoalDelay->isChecked(),
6958 _ui->source_checkBox_ignoreGoals->isChecked(),
6959 _ui->source_spinBox_databaseStartId->value(),
6960 _ui->source_spinBox_database_cameraIndex->value(),
6961 _ui->source_spinBox_databaseStopId->value(),
6962 !
_ui->general_checkBox_createIntermediateNodes->isChecked(),
6963 _ui->source_checkBox_ignoreLandmarks->isChecked(),
6964 _ui->source_checkBox_ignoreFeatures->isChecked(),
6967 _ui->source_checkBox_ignorePriors->isChecked());
6971 UFATAL(
"Source driver undefined (%d)!", driver);
6978 QString calibrationFile = calibrationPath;
6981 calibrationFile.remove(
"_left.yaml").remove(
"_right.yaml").remove(
"_pose.yaml").remove(
"_rgb.yaml").remove(
"_depth.yaml");
6983 QString
name = QFileInfo(calibrationFile.remove(
".yaml")).fileName();
6984 if(!calibrationPath.isEmpty())
6986 QDir
d = QFileInfo(calibrationPath).dir();
6987 QString tmp = calibrationPath;
6988 if(!tmp.remove(QFileInfo(calibrationPath).baseName()).isEmpty())
6990 dir =
d.absolutePath();
6994 UDEBUG(
"useRawImages=%d dir=%s", useRawImages?1:0, dir.toStdString().c_str());
6996 if(!
camera->
init(useRawImages?
"":dir.toStdString(),
name.toStdString()))
6998 UWARN(
"init camera failed... ");
6999 QMessageBox::warning(
this,
7001 tr(
"Camera initialization failed..."));
7036 _ui->lineEdit_odomSourceDevice->text().compare(
_ui->lineEdit_sourceDevice->text()) == 0)
7038 QMessageBox::warning(
this, tr(
"Odometry Sensor"),
7039 tr(
"Cannot create an odometry sensor with same driver than camera AND with same "
7040 "device. Change device ID of the odometry or camera sensor. To use odometry option "
7041 "from a single camera, look at the parameters of that driver to enable it, "
7042 "then disable odometry sensor. "), QMessageBox::Ok);
7046 extrinsics =
Transform::fromString(
_ui->lineEdit_odom_sensor_extrinsics->text().replace(
"PI_2", QString::number(3.141592/2.0)).toStdString());
7047 timeOffset =
_ui->doubleSpinBox_odom_sensor_time_offset->value()/1000.0;
7048 scaleFactor = (
float)
_ui->doubleSpinBox_odom_sensor_scale_factor->value();
7049 waitTime =
_ui->doubleSpinBox_odom_sensor_wait_time->value()/1000.0;
7051 return createCamera(driver,
_ui->lineEdit_odomSourceDevice->text(),
_ui->lineEdit_odom_sensor_path_calibration->text(),
false,
true,
true,
false);
7062 #if PCL_VERSION_COMPARE(>=, 1, 8, 0)
7064 if(localTransform.
isNull())
7066 UWARN(
"Failed to parse lidar local transfor string \"%s\"!",
7067 _ui->lineEdit_lidar_local_transform->text().toStdString().c_str());
7070 if(!
_ui->lineEdit_vlp16_pcap_path->text().isEmpty())
7074 _ui->lineEdit_vlp16_pcap_path->text().toStdString(),
7075 _ui->checkBox_vlp16_organized->isChecked(),
7076 _ui->checkBox_vlp16_stamp_last->isChecked(),
7077 this->getGeneralInputRate(),
7085 boost::asio::ip::address_v4::from_string(
uFormat(
"%ld.%ld.%ld.%ld",
7086 (
size_t)
_ui->spinBox_vlp16_ip1->value(),
7087 (
size_t)
_ui->spinBox_vlp16_ip2->value(),
7088 (
size_t)
_ui->spinBox_vlp16_ip3->value(),
7089 (
size_t)
_ui->spinBox_vlp16_ip4->value())),
7090 _ui->spinBox_vlp16_port->value(),
7091 _ui->checkBox_vlp16_organized->isChecked(),
7092 _ui->checkBox_vlp16_hostTime->isChecked(),
7093 _ui->checkBox_vlp16_stamp_last->isChecked(),
7094 this->getGeneralInputRate(),
7100 UWARN(
"init lidar failed... ");
7101 QMessageBox::warning(
this,
7103 tr(
"Lidar initialization failed..."));
7108 UWARN(
"Lidar cannot be used with rtabmap built with PCL < 1.8... ");
7109 QMessageBox::warning(
this,
7111 tr(
"Lidar initialization failed..."));
7119 return _ui->groupBox_publishing->isChecked();
7123 return _ui->general_doubleSpinBox_hardThr->value();
7127 return _ui->general_doubleSpinBox_vp->value();
7131 return _ui->doubleSpinBox_similarityThreshold->value();
7135 return _ui->odom_strategy->currentIndex();
7139 return _ui->odom_dataBufferSize->value();
7149 return _ui->general_checkBox_imagesKept->isChecked();
7153 return _ui->general_checkBox_missing_cache_republished->isChecked();
7157 return _ui->general_checkBox_cloudsKept->isChecked();
7161 return _ui->general_doubleSpinBox_timeThr->value();
7165 return _ui->general_doubleSpinBox_detectionRate->value();
7169 return _ui->general_checkBox_SLAM_mode->isChecked();
7173 return _ui->general_checkBox_activateRGBD->isChecked();
7177 return _ui->surf_spinBox_wordsPerImageTarget->value();
7181 return _ui->graphOptimization_priorsIgnored->isChecked();
7188 if(
_ui->general_doubleSpinBox_imgRate->value() !=
value)
7190 _ui->general_doubleSpinBox_imgRate->setValue(
value);
7205 if(
_ui->general_doubleSpinBox_detectionRate->value() !=
value)
7207 _ui->general_doubleSpinBox_detectionRate->setValue(
value);
7222 if(
_ui->general_doubleSpinBox_timeThr->value() !=
value)
7224 _ui->general_doubleSpinBox_timeThr->setValue(
value);
7239 if(
_ui->general_checkBox_SLAM_mode->isChecked() != enabled)
7241 _ui->general_checkBox_SLAM_mode->setChecked(enabled);
7266 !
_ui->lineEdit_cameraImages_path_imu->text().isEmpty())
7268 imuThread =
new IMUThread(
_ui->spinBox_cameraImages_max_imu_rate->value(),
this->getIMULocalTransform());
7273 if(!imuThread->
init(
_ui->lineEdit_cameraImages_path_imu->text().toStdString()))
7275 QMessageBox::warning(
this, tr(
"Source IMU Path"),
7276 tr(
"Initialization of IMU data has failed! Path=%1.").
arg(
_ui->lineEdit_cameraImages_path_imu->text()), QMessageBox::Ok);
7288 int odomStrategy = Parameters::defaultOdomStrategy();
7290 if(odomStrategy != 1)
7293 parameters.erase(Parameters::kVisCorType());
7300 _ui->odom_dataBufferSize->value());
7304 _ui->spinBox_decimation_odom->value(),
7306 _ui->doubleSpinBox_maxDepth_odom->value(),
7307 this->getOdomQualityWarnThr(),
7309 this->getAllParameters());
7310 odomViewer->setWindowTitle(tr(
"Odometry viewer"));
7311 odomViewer->resize(1280, 480+QPushButton().minimumHeight());
7319 if(
_ui->checkbox_source_feature_detection->isChecked())
7326 _ui->checkBox_source_scanFromDepth->isChecked(),
7327 _ui->spinBox_source_scanDownsampleStep->value(),
7328 _ui->doubleSpinBox_source_scanRangeMin->value(),
7329 _ui->doubleSpinBox_source_scanRangeMax->value(),
7330 _ui->doubleSpinBox_source_scanVoxelSize->value(),
7331 _ui->spinBox_source_scanNormalsK->value(),
7332 _ui->doubleSpinBox_source_scanNormalsRadius->value(),
7333 (
float)
_ui->doubleSpinBox_source_scanNormalsForceGroundUp->value(),
7334 _ui->checkBox_source_scanDeskewing->isChecked());
7335 if(
_ui->comboBox_imuFilter_strategy->currentIndex()>0 &&
dynamic_cast<DBReader*
>(
camera) == 0)
7337 cameraThread.
enableIMUFiltering(
_ui->comboBox_imuFilter_strategy->currentIndex()-1,
this->getAllParameters(),
_ui->checkBox_imuFilter_baseFrameConversion->isChecked());
7341 if(
_ui->groupBox_bilateral->isChecked())
7344 _ui->doubleSpinBox_bilateral_sigmaS->value(),
7345 _ui->doubleSpinBox_bilateral_sigmaR->value());
7347 if(!
_ui->lineEdit_source_distortionModel->text().isEmpty())
7362 cameraThread.
start();
7374 imuThread->
join(
true);
7377 cameraThread.
join(
true);
7378 odomThread.
join(
true);
7384 window->setWindowTitle(tr(
"Camera viewer"));
7385 window->resize(1280, 480+QPushButton().minimumHeight());
7396 if(
_ui->checkbox_source_feature_detection->isChecked())
7403 _ui->checkBox_source_scanFromDepth->isChecked(),
7404 _ui->spinBox_source_scanDownsampleStep->value(),
7405 _ui->doubleSpinBox_source_scanRangeMin->value(),
7406 _ui->doubleSpinBox_source_scanRangeMax->value(),
7407 _ui->doubleSpinBox_source_scanVoxelSize->value(),
7408 _ui->spinBox_source_scanNormalsK->value(),
7409 _ui->doubleSpinBox_source_scanNormalsRadius->value(),
7410 (
float)
_ui->doubleSpinBox_source_scanNormalsForceGroundUp->value(),
7411 _ui->checkBox_source_scanDeskewing->isChecked());
7412 if(
_ui->comboBox_imuFilter_strategy->currentIndex()>0 &&
dynamic_cast<DBReader*
>(
camera) == 0)
7414 cameraThread.
enableIMUFiltering(
_ui->comboBox_imuFilter_strategy->currentIndex()-1,
this->getAllParameters(),
_ui->checkBox_imuFilter_baseFrameConversion->isChecked());
7418 if(
_ui->groupBox_bilateral->isChecked())
7421 _ui->doubleSpinBox_bilateral_sigmaS->value(),
7422 _ui->doubleSpinBox_bilateral_sigmaR->value());
7424 if(!
_ui->lineEdit_source_distortionModel->text().isEmpty())
7431 cameraThread.
start();
7434 cameraThread.
join(
true);
7446 QMessageBox::warning(
this,
7448 tr(
"Cannot calibrate database source!"));
7458 if(!dir.mkpath(
this->getCameraInfoDir()))
7469 QMessageBox::StandardButton button = QMessageBox::question(
this, tr(
"Calibration"),
7470 tr(
"With \"%1\" driver, Color and IR cameras cannot be streamed at the "
7471 "same time. A 3-steps calibration is required (Color -> IR -> extrinsics). We will "
7472 "start with the Color camera calibration. Do you want to continue?").
arg(this->
getSourceDriverStr()),
7473 QMessageBox::Yes | QMessageBox::No | QMessageBox::Ignore, QMessageBox::Yes);
7475 if(button == QMessageBox::Yes || button == QMessageBox::Ignore)
7482 if(button != QMessageBox::Ignore)
7495 cameraThread.
start();
7498 cameraThread.
join(
true);
7502 button = QMessageBox::question(
this, tr(
"Calibration"),
7503 tr(
"We will now calibrate the IR camera. Hide the IR projector with a Post-It and "
7504 "make sure you have enough ambient IR light (e.g., external IR source or sunlight!) to see the "
7505 "checkerboard with the IR camera. Do you want to continue?"),
7506 QMessageBox::Yes | QMessageBox::No | QMessageBox::Ignore, QMessageBox::Yes);
7507 if(button == QMessageBox::Yes || button == QMessageBox::Ignore)
7510 if(button != QMessageBox::Ignore)
7523 cameraThread.
start();
7526 cameraThread.
join(
true);
7530 button = QMessageBox::question(
this, tr(
"Calibration"),
7531 tr(
"We will now calibrate the extrinsics. Important: Make sure "
7532 "the cameras and the checkerboard don't move and that both "
7533 "cameras can see the checkerboard. We will repeat this "
7534 "multiple times. Each time, you will have to move the camera (or "
7535 "checkerboard) for a different point of view. Do you want to "
7537 QMessageBox::Yes | QMessageBox::No, QMessageBox::Yes);
7540 int totalSamples = 0;
7541 if(button == QMessageBox::Yes)
7543 totalSamples = QInputDialog::getInt(
this, tr(
"Calibration"), tr(
"Samples: "), 1, 1, 99, 1, &ok);
7557 for(;
count < totalSamples && button == QMessageBox::Yes; )
7588 if(
count < totalSamples)
7590 button = QMessageBox::question(
this, tr(
"Calibration"),
7591 tr(
"A stereo pair has been taken (total=%1/%2). Move the checkerboard or "
7592 "camera to another position. Press \"Yes\" when you are ready "
7593 "for the next capture.").
arg(
count).
arg(totalSamples),
7594 QMessageBox::Yes | QMessageBox::Abort, QMessageBox::Yes);
7599 button = QMessageBox::question(
this, tr(
"Calibration"),
7600 tr(
"Could not detect the checkerboard on both images or "
7601 "the point of view didn't change enough. Try again?"),
7602 QMessageBox::Yes | QMessageBox::No, QMessageBox::Yes);
7607 button = QMessageBox::question(
this, tr(
"Calibration"),
7608 tr(
"Failed to start the camera. Try again?"), QMessageBox::Yes | QMessageBox::No, QMessageBox::Yes);
7611 if(
count == totalSamples && button == QMessageBox::Yes)
7614 stereoModel.
setName(stereoModel.
name(),
"depth",
"rgb");
7617 QMessageBox::warning(
this, tr(
"Calibration"),
7618 tr(
"Extrinsic calibration has failed! Look on the terminal "
7619 "for possible error messages. Make sure corresponding calibration files exist "
7620 "in \"%1\" folder for camera \"%2\" or calibration name set. If not, re-do "
7621 "step 1 and 2 and make sure to export the calibration files.").
arg(this->
getCameraInfoDir()).
arg(serial.c_str()), QMessageBox::Ok);
7625 QMessageBox::information(
this, tr(
"Calibration"),
7626 tr(
"Calibration is completed! Extrinsics have been saved to \"%1/%2_pose.yaml\"").
arg(this->
getCameraInfoDir()).
arg(stereoModel.
name().c_str()), QMessageBox::Ok);
7642 bool rgbDepth = freenect2 || (driver==
kSrcStereoDepthAI &&
_ui->comboBox_depthai_output_mode->currentIndex() == 2);
7656 cameraThread.
start();
7661 cameraThread.
join(
true);
7679 QMessageBox::warning(
this,
7681 tr(
"Cannot calibrate database source!"));
7691 if(!dir.mkpath(
this->getCameraInfoDir()))
7701 QMessageBox::warning(
this,
7703 tr(
"No odometry sensor selected!"));
7709 QMessageBox::StandardButton button = QMessageBox::question(
this, tr(
"Calibration"),
7710 tr(
"We will calibrate the extrinsics. Important: Make sure "
7711 "the cameras and the checkerboard don't move and that both "
7712 "cameras can see the checkerboard. We will repeat this "
7713 "multiple times. Each time, you will have to move the camera (or "
7714 "checkerboard) for a different point of view. Do you want to "
7716 QMessageBox::Yes | QMessageBox::No, QMessageBox::Yes);
7718 if(button == QMessageBox::Yes)
7723 int totalSamples = 0;
7724 if(button == QMessageBox::Yes)
7726 QDialog dialog(
this);
7727 QFormLayout form(&dialog);
7730 QSpinBox *
samples =
new QSpinBox(&dialog);
7734 QSpinBox * boardWidth =
new QSpinBox(&dialog);
7735 boardWidth->setMinimum(2);
7736 boardWidth->setMaximum(99);
7738 QSpinBox * boardHeight =
new QSpinBox(&dialog);
7739 boardHeight->setMinimum(2);
7740 boardHeight->setMaximum(99);
7742 QDoubleSpinBox * squareSize =
new QDoubleSpinBox(&dialog);
7743 squareSize->setDecimals(4);
7744 squareSize->setMinimum(0.0001);
7745 squareSize->setMaximum(9);
7747 squareSize->setSuffix(
" m");
7748 form.addRow(
"Samples: ",
samples);
7749 form.addRow(
"Checkerboard Width: ", boardWidth);
7750 form.addRow(
"Checkerboard Height: ", boardHeight);
7751 form.addRow(
"Checkerboard Square Size: ", squareSize);
7754 QDialogButtonBox buttonBox(QDialogButtonBox::Ok | QDialogButtonBox::Cancel,
7756 form.addRow(&buttonBox);
7757 QObject::connect(&buttonBox, SIGNAL(accepted()), &dialog, SLOT(accept()));
7758 QObject::connect(&buttonBox, SIGNAL(rejected()), &dialog, SLOT(reject()));
7761 if (dialog.exec() == QDialog::Accepted) {
7765 totalSamples =
samples->value();
7782 for(;
count < totalSamples && button == QMessageBox::Yes; )
7787 _ui->lineEdit_odomSourceDevice->text(),
7788 _ui->lineEdit_odom_sensor_path_calibration->text(),
7789 false,
true,
false,
true);
7797 tr(
"Odom sensor is not calibrated. Camera and odometry sensor should be individually calibrated (intrinsics) before calibrating the extrinsics between them. Aborting..."), QMessageBox::Ok);
7810 int currentIndex =
_ui->comboBox_odom_sensor->currentIndex();
7811 _ui->comboBox_odom_sensor->setCurrentIndex(0);
7813 _ui->comboBox_odom_sensor->setCurrentIndex(currentIndex);
7821 tr(
"Odom sensor is not calibrated. Camera and odometry sensor should be individually calibrated (intrinsics) before calibrating the extrinsics between them. Aborting..."), QMessageBox::Ok);
7842 if(
count < totalSamples)
7845 tr(
"A stereo pair has been taken (total=%1/%2). Move the checkerboard or "
7846 "camera to another position. Press \"Yes\" when you are ready "
7847 "for the next capture.").
arg(
count).
arg(totalSamples),
7848 QMessageBox::Yes | QMessageBox::Abort, QMessageBox::Yes);
7854 tr(
"Could not detect the checkerboard on both images or "
7855 "the point of view didn't change enough. Try again?"),
7856 QMessageBox::Yes | QMessageBox::No, QMessageBox::Yes);
7862 tr(
"Failed to start the camera. Try again?"), QMessageBox::Yes | QMessageBox::No, QMessageBox::Yes);
7865 if(
count == totalSamples && button == QMessageBox::Yes)
7869 odomSensorModel =
CameraModel(
"odom_sensor", odomSensorModel.
imageSize(), odomSensorModel.
K(), cv::Mat::zeros(1,5,CV_64FC1), cv::Mat(), cv::Mat(), odomSensorModel.
localTransform());
7872 stereoModel.
setName(stereoModel.
name(),
"camera",
"odom_sensor");
7876 tr(
"Extrinsic calibration has failed! Look on the terminal "
7877 "for possible error messages."), QMessageBox::Ok);
7878 std::cout <<
"stereoModel: " << stereoModel << std::endl;
7886 UINFO(
"Odom sensor frame to camera frame: %s",
t.prettyPrint().c_str());
7890 _ui->lineEdit_odom_sensor_extrinsics->setText(QString(
"%1 %2 %3 %4 %5 %6")
7894 tr(
"Calibration is completed! Extrinsics have been computed: %1. "
7895 "You can close the calibration dialog.").
arg(
t.prettyPrint().c_str()), QMessageBox::Ok);
7905 window->setWindowTitle(tr(
"Lidar viewer"));
7906 window->setWindowFlags(Qt::Window);
7907 window->resize(1280, 480+QPushButton().minimumHeight());
7916 _ui->checkBox_source_scanFromDepth->isChecked(),
7917 _ui->spinBox_source_scanDownsampleStep->value(),
7918 _ui->doubleSpinBox_source_scanRangeMin->value(),
7919 _ui->doubleSpinBox_source_scanRangeMax->value(),
7920 _ui->doubleSpinBox_source_scanVoxelSize->value(),
7921 _ui->spinBox_source_scanNormalsK->value(),
7922 _ui->doubleSpinBox_source_scanNormalsRadius->value(),
7923 (
float)
_ui->doubleSpinBox_source_scanNormalsForceGroundUp->value(),
7924 _ui->checkBox_source_scanDeskewing->isChecked());
7928 lidarThread.
start();
7931 lidarThread.
join(
true);