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)));
745 connect(
_ui->source_lineEdit_databaseCameraIndex, SIGNAL(textChanged(
const QString &)),
this, SLOT(
makeObsoleteSourcePanel()));
746 connect(
_ui->source_checkBox_stereoToDepthDB, SIGNAL(toggled(
bool)),
_ui->checkbox_stereo_depthGenerated, SLOT(setChecked(
bool)));
747 connect(
_ui->checkbox_stereo_depthGenerated, SIGNAL(toggled(
bool)),
_ui->source_checkBox_stereoToDepthDB, SLOT(setChecked(
bool)));
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()));
867 connect(
_ui->comboBox_depthai_subpixel_fractional_bits, SIGNAL(currentIndexChanged(
int)),
this, SLOT(
makeObsoleteSourcePanel()));
910 connect(
_ui->lineEdit_odom_sensor_path_calibration, SIGNAL(textChanged(
const QString &)),
this, SLOT(
makeObsoleteSourcePanel()));
918 connect(
_ui->comboBox_imuFilter_strategy, SIGNAL(currentIndexChanged(
int)),
_ui->stackedWidget_imuFilter, SLOT(setCurrentIndex(
int)));
919 _ui->stackedWidget_imuFilter->setCurrentIndex(
_ui->comboBox_imuFilter_strategy->currentIndex());
924 connect(
_ui->comboBox_lidar_src, SIGNAL(currentIndexChanged(
int)),
_ui->stackedWidget_lidar_src, SLOT(setCurrentIndex(
int)));
925 _ui->stackedWidget_lidar_src->setCurrentIndex(
_ui->comboBox_lidar_src->currentIndex());
934 connect(
_ui->doubleSpinBox_source_scanNormalsForceGroundUp, SIGNAL(valueChanged(
double)),
this, SLOT(
makeObsoleteSourcePanel()));
949 connect(
_ui->general_doubleSpinBox_timeThr, SIGNAL(valueChanged(
double)),
_ui->general_doubleSpinBox_timeThr_2, SLOT(setValue(
double)));
950 connect(
_ui->general_doubleSpinBox_hardThr, SIGNAL(valueChanged(
double)),
_ui->general_doubleSpinBox_hardThr_2, SLOT(setValue(
double)));
951 connect(
_ui->doubleSpinBox_similarityThreshold, SIGNAL(valueChanged(
double)),
_ui->doubleSpinBox_similarityThreshold_2, SLOT(setValue(
double)));
952 connect(
_ui->general_doubleSpinBox_detectionRate, SIGNAL(valueChanged(
double)),
_ui->general_doubleSpinBox_detectionRate_2, SLOT(setValue(
double)));
953 connect(
_ui->general_spinBox_imagesBufferSize, SIGNAL(valueChanged(
int)),
_ui->general_spinBox_imagesBufferSize_2, SLOT(setValue(
int)));
954 connect(
_ui->general_spinBox_maxStMemSize, SIGNAL(valueChanged(
int)),
_ui->general_spinBox_maxStMemSize_2, SLOT(setValue(
int)));
958 connect(
_ui->doubleSpinBox_similarityThreshold_2, SIGNAL(editingFinished()),
this, SLOT(
updateBasicParameter()));
959 connect(
_ui->general_doubleSpinBox_detectionRate_2, SIGNAL(editingFinished()),
this, SLOT(
updateBasicParameter()));
960 connect(
_ui->general_spinBox_imagesBufferSize_2, SIGNAL(editingFinished()),
this, SLOT(
updateBasicParameter()));
971 _ui->groupBox_publishing->setObjectName(Parameters::kRtabmapPublishStats().
c_str());
972 _ui->general_checkBox_publishRawData->setObjectName(Parameters::kRtabmapPublishLastSignature().
c_str());
973 _ui->general_checkBox_publishPdf->setObjectName(Parameters::kRtabmapPublishPdf().
c_str());
974 _ui->general_checkBox_publishLikelihood->setObjectName(Parameters::kRtabmapPublishLikelihood().
c_str());
975 _ui->general_checkBox_publishRMSE->setObjectName(Parameters::kRtabmapComputeRMSE().
c_str());
976 _ui->general_checkBox_saveWMState->setObjectName(Parameters::kRtabmapSaveWMState().
c_str());
977 _ui->general_checkBox_publishRAM->setObjectName(Parameters::kRtabmapPublishRAMUsage().
c_str());
978 _ui->general_checkBox_statisticLogsBufferedInRAM->setObjectName(Parameters::kRtabmapStatisticLogsBufferedInRAM().
c_str());
979 _ui->groupBox_statistics->setObjectName(Parameters::kRtabmapStatisticLogged().
c_str());
980 _ui->general_checkBox_statisticLoggedHeaders->setObjectName(Parameters::kRtabmapStatisticLoggedHeaders().
c_str());
981 _ui->general_doubleSpinBox_timeThr->setObjectName(Parameters::kRtabmapTimeThr().
c_str());
982 _ui->general_spinBox_memoryThr->setObjectName(Parameters::kRtabmapMemoryThr().
c_str());
983 _ui->general_doubleSpinBox_detectionRate->setObjectName(Parameters::kRtabmapDetectionRate().
c_str());
984 _ui->general_spinBox_imagesBufferSize->setObjectName(Parameters::kRtabmapImageBufferSize().
c_str());
985 _ui->general_checkBox_createIntermediateNodes->setObjectName(Parameters::kRtabmapCreateIntermediateNodes().
c_str());
986 _ui->general_spinBox_maxRetrieved->setObjectName(Parameters::kRtabmapMaxRetrieved().
c_str());
987 _ui->general_spinBox_max_republished->setObjectName(Parameters::kRtabmapMaxRepublished().
c_str());
988 _ui->general_checkBox_startNewMapOnLoopClosure->setObjectName(Parameters::kRtabmapStartNewMapOnLoopClosure().
c_str());
989 _ui->general_checkBox_startNewMapOnGoodSignature->setObjectName(Parameters::kRtabmapStartNewMapOnGoodSignature().
c_str());
990 _ui->general_checkBox_imagesAlreadyRectified->setObjectName(Parameters::kRtabmapImagesAlreadyRectified().
c_str());
991 _ui->general_checkBox_rectifyOnlyFeatures->setObjectName(Parameters::kRtabmapRectifyOnlyFeatures().
c_str());
992 _ui->checkBox_rtabmap_loopGPS->setObjectName(Parameters::kRtabmapLoopGPS().
c_str());
993 _ui->lineEdit_workingDirectory->setObjectName(Parameters::kRtabmapWorkingDirectory().
c_str());
997 _ui->general_checkBox_keepRawData->setObjectName(Parameters::kMemImageKept().
c_str());
998 _ui->general_checkBox_keepBinaryData->setObjectName(Parameters::kMemBinDataKept().
c_str());
999 _ui->general_checkBox_saveIntermediateNodeData->setObjectName(Parameters::kMemIntermediateNodeDataKept().
c_str());
1000 _ui->lineEdit_rgbCompressionFormat->setObjectName(Parameters::kMemImageCompressionFormat().
c_str());
1001 _ui->lineEdit_depthCompressionFormat->setObjectName(Parameters::kMemDepthCompressionFormat().
c_str());
1002 _ui->general_checkBox_keepDescriptors->setObjectName(Parameters::kMemRawDescriptorsKept().
c_str());
1003 _ui->general_checkBox_saveDepth16bits->setObjectName(Parameters::kMemSaveDepth16Format().
c_str());
1004 _ui->general_checkBox_compressionParallelized->setObjectName(Parameters::kMemCompressionParallelized().
c_str());
1005 _ui->general_checkBox_reduceGraph->setObjectName(Parameters::kMemReduceGraph().
c_str());
1006 _ui->general_checkBox_keepNotLinkedNodes->setObjectName(Parameters::kMemNotLinkedNodesKept().
c_str());
1007 _ui->general_spinBox_maxStMemSize->setObjectName(Parameters::kMemSTMSize().
c_str());
1008 _ui->doubleSpinBox_similarityThreshold->setObjectName(Parameters::kMemRehearsalSimilarity().
c_str());
1009 _ui->general_checkBox_SLAM_mode->setObjectName(Parameters::kMemIncrementalMemory().
c_str());
1010 _ui->general_checkBox_saveLocalizationData->setObjectName(Parameters::kMemLocalizationDataSaved().
c_str());
1011 _ui->general_doubleSpinBox_recentWmRatio->setObjectName(Parameters::kMemRecentWmRatio().
c_str());
1012 _ui->general_checkBox_transferSortingByWeightId->setObjectName(Parameters::kMemTransferSortingByWeightId().
c_str());
1013 _ui->general_checkBox_RehearsalIdUpdatedToNewOne->setObjectName(Parameters::kMemRehearsalIdUpdatedToNewOne().
c_str());
1014 _ui->general_checkBox_generateIds->setObjectName(Parameters::kMemGenerateIds().
c_str());
1015 _ui->general_checkBox_badSignaturesIgnored->setObjectName(Parameters::kMemBadSignaturesIgnored().
c_str());
1016 _ui->general_checkBox_createMapLabels->setObjectName(Parameters::kMemMapLabelsAdded().
c_str());
1017 _ui->general_checkBox_initWMWithAllNodes->setObjectName(Parameters::kMemInitWMWithAllNodes().
c_str());
1018 _ui->checkBox_localSpaceScanMatchingIDsSaved->setObjectName(Parameters::kRGBDScanMatchingIdsSavedInLinks().
c_str());
1019 _ui->checkBox_localSpaceCreateGlobalScanMap->setObjectName(Parameters::kRGBDProximityGlobalScanMap().
c_str());
1020 _ui->spinBox_imagePreDecimation->setObjectName(Parameters::kMemImagePreDecimation().
c_str());
1021 _ui->spinBox_imagePostDecimation->setObjectName(Parameters::kMemImagePostDecimation().
c_str());
1022 _ui->general_spinBox_laserScanDownsample->setObjectName(Parameters::kMemLaserScanDownsampleStepSize().
c_str());
1023 _ui->general_doubleSpinBox_laserScanVoxelSize->setObjectName(Parameters::kMemLaserScanVoxelSize().
c_str());
1024 _ui->general_spinBox_laserScanNormalK->setObjectName(Parameters::kMemLaserScanNormalK().
c_str());
1025 _ui->general_doubleSpinBox_laserScanNormalRadius->setObjectName(Parameters::kMemLaserScanNormalRadius().
c_str());
1026 _ui->checkBox_useOdomFeatures->setObjectName(Parameters::kMemUseOdomFeatures().
c_str());
1027 _ui->memCovOffDiagIgnored->setObjectName(Parameters::kMemCovOffDiagIgnored().
c_str());
1028 _ui->general_checkBox_rotateImagesUpsideUp->setObjectName(Parameters::kMemRotateImagesUpsideUp().
c_str());
1031 _ui->checkBox_dbInMemory->setObjectName(Parameters::kDbSqlite3InMemory().
c_str());
1032 _ui->spinBox_dbCacheSize->setObjectName(Parameters::kDbSqlite3CacheSize().
c_str());
1033 _ui->comboBox_dbJournalMode->setObjectName(Parameters::kDbSqlite3JournalMode().
c_str());
1034 _ui->comboBox_dbSynchronous->setObjectName(Parameters::kDbSqlite3Synchronous().
c_str());
1035 _ui->comboBox_dbTempStore->setObjectName(Parameters::kDbSqlite3TempStore().
c_str());
1036 _ui->lineEdit_targetDatabaseVersion->setObjectName(Parameters::kDbTargetVersion().
c_str());
1040 _ui->general_doubleSpinBox_hardThr->setObjectName(Parameters::kRtabmapLoopThr().
c_str());
1041 _ui->general_doubleSpinBox_agressiveThr->setObjectName(Parameters::kRGBDAggressiveLoopThr().
c_str());
1042 _ui->general_doubleSpinBox_loopRatio->setObjectName(Parameters::kRtabmapLoopRatio().
c_str());
1043 _ui->comboBox_virtualPlaceLikelihoodRatio->setObjectName(Parameters::kRtabmapVirtualPlaceLikelihoodRatio().
c_str());
1044 _ui->comboBox_globalDescriptorExtractor->setObjectName(Parameters::kMemGlobalDescriptorStrategy().
c_str());
1048 _ui->general_doubleSpinBox_vp->setObjectName(Parameters::kBayesVirtualPlacePriorThr().
c_str());
1049 _ui->lineEdit_bayes_predictionLC->setObjectName(Parameters::kBayesPredictionLC().
c_str());
1050 _ui->checkBox_bayes_fullPredictionUpdate->setObjectName(Parameters::kBayesFullPredictionUpdate().
c_str());
1051 connect(
_ui->lineEdit_bayes_predictionLC, SIGNAL(textChanged(
const QString &)),
this, SLOT(
updatePredictionPlot()));
1054 _ui->comboBox_dictionary_strategy->setObjectName(Parameters::kKpNNStrategy().
c_str());
1055 _ui->checkBox_dictionary_incremental->setObjectName(Parameters::kKpIncrementalDictionary().
c_str());
1056 _ui->checkBox_kp_incrementalFlann->setObjectName(Parameters::kKpIncrementalFlann().
c_str());
1057 _ui->checkBox_kp_byteToFloat->setObjectName(Parameters::kKpByteToFloat().
c_str());
1058 _ui->surf_doubleSpinBox_rebalancingFactor->setObjectName(Parameters::kKpFlannRebalancingFactor().
c_str());
1059 _ui->comboBox_detector_strategy->setObjectName(Parameters::kKpDetectorStrategy().
c_str());
1060 _ui->surf_doubleSpinBox_nndrRatio->setObjectName(Parameters::kKpNndrRatio().
c_str());
1061 _ui->surf_doubleSpinBox_maxDepth->setObjectName(Parameters::kKpMaxDepth().
c_str());
1062 _ui->surf_doubleSpinBox_minDepth->setObjectName(Parameters::kKpMinDepth().
c_str());
1063 _ui->checkBox_memDepthAsMask->setObjectName(Parameters::kMemDepthAsMask().
c_str());
1064 _ui->doubleSpinBox_memDepthMaskFloorThr->setObjectName(Parameters::kMemDepthMaskFloorThr().
c_str());
1065 _ui->checkBox_memStereoFromMotion->setObjectName(Parameters::kMemStereoFromMotion().
c_str());
1066 _ui->surf_spinBox_wordsPerImageTarget->setObjectName(Parameters::kKpMaxFeatures().
c_str());
1067 _ui->checkBox_kp_ssc->setObjectName(Parameters::kKpSSC().
c_str());
1068 _ui->spinBox_KPGridRows->setObjectName(Parameters::kKpGridRows().
c_str());
1069 _ui->spinBox_KPGridCols->setObjectName(Parameters::kKpGridCols().
c_str());
1070 _ui->surf_doubleSpinBox_ratioBadSign->setObjectName(Parameters::kKpBadSignRatio().
c_str());
1071 _ui->checkBox_kp_tfIdfLikelihoodUsed->setObjectName(Parameters::kKpTfIdfLikelihoodUsed().
c_str());
1072 _ui->checkBox_kp_parallelized->setObjectName(Parameters::kKpParallelized().
c_str());
1073 _ui->lineEdit_kp_roi->setObjectName(Parameters::kKpRoiRatios().
c_str());
1074 _ui->lineEdit_dictionaryPath->setObjectName(Parameters::kKpDictionaryPath().
c_str());
1076 _ui->checkBox_kp_newWordsComparedTogether->setObjectName(Parameters::kKpNewWordsComparedTogether().
c_str());
1077 _ui->subpix_winSize_kp->setObjectName(Parameters::kKpSubPixWinSize().
c_str());
1078 _ui->subpix_iterations_kp->setObjectName(Parameters::kKpSubPixIterations().
c_str());
1079 _ui->subpix_eps_kp->setObjectName(Parameters::kKpSubPixEps().
c_str());
1081 _ui->subpix_winSize->setObjectName(Parameters::kKpSubPixWinSize().
c_str());
1082 _ui->subpix_iterations->setObjectName(Parameters::kKpSubPixIterations().
c_str());
1083 _ui->subpix_eps->setObjectName(Parameters::kKpSubPixEps().
c_str());
1086 _ui->surf_doubleSpinBox_hessianThr->setObjectName(Parameters::kSURFHessianThreshold().
c_str());
1087 _ui->surf_spinBox_octaves->setObjectName(Parameters::kSURFOctaves().
c_str());
1088 _ui->surf_spinBox_octaveLayers->setObjectName(Parameters::kSURFOctaveLayers().
c_str());
1089 _ui->checkBox_surfExtended->setObjectName(Parameters::kSURFExtended().
c_str());
1090 _ui->surf_checkBox_upright->setObjectName(Parameters::kSURFUpright().
c_str());
1091 _ui->surf_checkBox_gpuVersion->setObjectName(Parameters::kSURFGpuVersion().
c_str());
1092 _ui->surf_doubleSpinBox_gpuKeypointsRatio->setObjectName(Parameters::kSURFGpuKeypointsRatio().
c_str());
1095 _ui->sift_spinBox_nOctaveLayers->setObjectName(Parameters::kSIFTNOctaveLayers().
c_str());
1096 _ui->sift_doubleSpinBox_contrastThr->setObjectName(Parameters::kSIFTContrastThreshold().
c_str());
1097 _ui->sift_doubleSpinBox_edgeThr->setObjectName(Parameters::kSIFTEdgeThreshold().
c_str());
1098 _ui->sift_doubleSpinBox_sigma->setObjectName(Parameters::kSIFTSigma().
c_str());
1099 _ui->sift_checkBox_preciseUpscale->setObjectName(Parameters::kSIFTPreciseUpscale().
c_str());
1100 _ui->sift_checkBox_rootsift->setObjectName(Parameters::kSIFTRootSIFT().
c_str());
1101 _ui->sift_checkBox_gpu->setObjectName(Parameters::kSIFTGpu().
c_str());
1102 _ui->sift_doubleSpinBox_gaussianDiffThreshold->setObjectName(Parameters::kSIFTGaussianThreshold().
c_str());
1103 _ui->sift_checkBox_upscale->setObjectName(Parameters::kSIFTUpscale().
c_str());
1106 _ui->briefBytes->setObjectName(Parameters::kBRIEFBytes().
c_str());
1109 _ui->fastSuppressNonMax->setObjectName(Parameters::kFASTNonmaxSuppression().
c_str());
1110 _ui->fastThreshold->setObjectName(Parameters::kFASTThreshold().
c_str());
1111 _ui->fastThresholdMin->setObjectName(Parameters::kFASTMinThreshold().
c_str());
1112 _ui->fastThresholdMax->setObjectName(Parameters::kFASTMaxThreshold().
c_str());
1113 _ui->fastGridRows->setObjectName(Parameters::kFASTGridRows().
c_str());
1114 _ui->fastGridCols->setObjectName(Parameters::kFASTGridCols().
c_str());
1115 _ui->fastGpu->setObjectName(Parameters::kFASTGpu().
c_str());
1116 _ui->fastKeypointRatio->setObjectName(Parameters::kFASTGpuKeypointsRatio().
c_str());
1117 _ui->fastCV->setObjectName(Parameters::kFASTCV().
c_str());
1120 _ui->doubleSpinBox_ORBScaleFactor->setObjectName(Parameters::kORBScaleFactor().
c_str());
1121 _ui->spinBox_ORBNLevels->setObjectName(Parameters::kORBNLevels().
c_str());
1122 _ui->spinBox_ORBEdgeThreshold->setObjectName(Parameters::kORBEdgeThreshold().
c_str());
1123 _ui->spinBox_ORBFirstLevel->setObjectName(Parameters::kORBFirstLevel().
c_str());
1124 _ui->spinBox_ORBWTA_K->setObjectName(Parameters::kORBWTA_K().
c_str());
1125 _ui->spinBox_ORBScoreType->setObjectName(Parameters::kORBScoreType().
c_str());
1126 _ui->spinBox_ORBPatchSize->setObjectName(Parameters::kORBPatchSize().
c_str());
1127 _ui->checkBox_ORBGpu->setObjectName(Parameters::kORBGpu().
c_str());
1130 _ui->checkBox_FREAKOrientationNormalized->setObjectName(Parameters::kFREAKOrientationNormalized().
c_str());
1131 _ui->checkBox_FREAKScaleNormalized->setObjectName(Parameters::kFREAKScaleNormalized().
c_str());
1132 _ui->doubleSpinBox_FREAKPatternScale->setObjectName(Parameters::kFREAKPatternScale().
c_str());
1133 _ui->spinBox_FREAKNOctaves->setObjectName(Parameters::kFREAKNOctaves().
c_str());
1136 _ui->doubleSpinBox_GFTT_qualityLevel->setObjectName(Parameters::kGFTTQualityLevel().
c_str());
1137 _ui->doubleSpinBox_GFTT_minDistance->setObjectName(Parameters::kGFTTMinDistance().
c_str());
1138 _ui->spinBox_GFTT_blockSize->setObjectName(Parameters::kGFTTBlockSize().
c_str());
1139 _ui->checkBox_GFTT_useHarrisDetector->setObjectName(Parameters::kGFTTUseHarrisDetector().
c_str());
1140 _ui->doubleSpinBox_GFTT_k->setObjectName(Parameters::kGFTTK().
c_str());
1141 _ui->checkBox_GFTT_gpu->setObjectName(Parameters::kGFTTGpu().
c_str());
1144 _ui->spinBox_BRISK_thresh->setObjectName(Parameters::kBRISKThresh().
c_str());
1145 _ui->spinBox_BRISK_octaves->setObjectName(Parameters::kBRISKOctaves().
c_str());
1146 _ui->doubleSpinBox_BRISK_patterScale->setObjectName(Parameters::kBRISKPatternScale().
c_str());
1149 _ui->checkBox_kaze_extended->setObjectName(Parameters::kKAZEExtended().
c_str());
1150 _ui->checkBox_kaze_upright->setObjectName(Parameters::kKAZEUpright().
c_str());
1151 _ui->doubleSpinBox_kaze_threshold->setObjectName(Parameters::kKAZEThreshold().
c_str());
1152 _ui->spinBox_kaze_octaves->setObjectName(Parameters::kKAZENOctaves().
c_str());
1153 _ui->spinBox_kaze_octavelayers->setObjectName(Parameters::kKAZENOctaveLayers().
c_str());
1154 _ui->spinBox_kaze_diffusivity->setObjectName(Parameters::kKAZEDiffusivity().
c_str());
1157 _ui->lineEdit_sptorch_path->setObjectName(Parameters::kSuperPointModelPath().
c_str());
1159 _ui->doubleSpinBox_sptorch_threshold->setObjectName(Parameters::kSuperPointThreshold().
c_str());
1160 _ui->checkBox_sptorch_nms->setObjectName(Parameters::kSuperPointNMS().
c_str());
1161 _ui->spinBox_sptorch_minDistance->setObjectName(Parameters::kSuperPointNMSRadius().
c_str());
1162 _ui->checkBox_sptorch_cuda->setObjectName(Parameters::kSuperPointCuda().
c_str());
1165 _ui->lineEdit_pymatcher_path->setObjectName(Parameters::kPyMatcherPath().
c_str());
1167 _ui->pymatcher_matchThreshold->setObjectName(Parameters::kPyMatcherThreshold().
c_str());
1168 _ui->pymatcher_iterations->setObjectName(Parameters::kPyMatcherIterations().
c_str());
1169 _ui->checkBox_pymatcher_cuda->setObjectName(Parameters::kPyMatcherCuda().
c_str());
1170 _ui->lineEdit_pymatcher_model->setObjectName(Parameters::kPyMatcherModel().
c_str());
1174 _ui->lineEdit_pydetector_path->setObjectName(Parameters::kPyDetectorPath().
c_str());
1176 _ui->checkBox_pydetector_cuda->setObjectName(Parameters::kPyDetectorCuda().
c_str());
1179 _ui->checkBox_gms_withRotation->setObjectName(Parameters::kGMSWithRotation().
c_str());
1180 _ui->checkBox_gms_withScale->setObjectName(Parameters::kGMSWithScale().
c_str());
1181 _ui->gms_thresholdFactor->setObjectName(Parameters::kGMSThresholdFactor().
c_str());
1184 _ui->lineEdit_pydescriptor_path->setObjectName(Parameters::kPyDescriptorPath().
c_str());
1186 _ui->pydescriptor_dim->setObjectName(Parameters::kPyDescriptorDim().
c_str());
1189 _ui->groupBox_vh_epipolar2->setObjectName(Parameters::kVhEpEnabled().
c_str());
1190 _ui->surf_spinBox_matchCountMinAccepted->setObjectName(Parameters::kVhEpMatchCountMin().
c_str());
1191 _ui->surf_doubleSpinBox_ransacParam1->setObjectName(Parameters::kVhEpRansacParam1().
c_str());
1192 _ui->surf_doubleSpinBox_ransacParam2->setObjectName(Parameters::kVhEpRansacParam2().
c_str());
1195 _ui->general_checkBox_activateRGBD->setObjectName(Parameters::kRGBDEnabled().
c_str());
1196 _ui->rgdb_linearUpdate->setObjectName(Parameters::kRGBDLinearUpdate().
c_str());
1197 _ui->rgdb_angularUpdate->setObjectName(Parameters::kRGBDAngularUpdate().
c_str());
1198 _ui->rgdb_linearSpeedUpdate->setObjectName(Parameters::kRGBDLinearSpeedUpdate().
c_str());
1199 _ui->rgdb_angularSpeedUpdate->setObjectName(Parameters::kRGBDAngularSpeedUpdate().
c_str());
1200 _ui->rgbd_forceOdom3DoF->setObjectName(Parameters::kRGBDForceOdom3DoF().
c_str());
1201 _ui->rgbd_savedLocalizationIgnored->setObjectName(Parameters::kRGBDStartAtOrigin().
c_str());
1202 _ui->rgdb_rehearsalWeightIgnoredWhileMoving->setObjectName(Parameters::kMemRehearsalWeightIgnoredWhileMoving().
c_str());
1203 _ui->rgdb_newMapOdomChange->setObjectName(Parameters::kRGBDNewMapOdomChangeDistance().
c_str());
1204 _ui->odomScanHistory->setObjectName(Parameters::kRGBDNeighborLinkRefining().
c_str());
1205 _ui->odomGravity->setObjectName(Parameters::kMemUseOdomGravity().
c_str());
1206 _ui->spinBox_maxLocalLocationsRetrieved->setObjectName(Parameters::kRGBDMaxLocalRetrieved().
c_str());
1207 _ui->rgbd_loopCovLimited->setObjectName(Parameters::kRGBDLoopCovLimited().
c_str());
1209 _ui->graphOptimization_type->setObjectName(Parameters::kOptimizerStrategy().
c_str());
1210 _ui->graphOptimization_iterations->setObjectName(Parameters::kOptimizerIterations().
c_str());
1211 _ui->graphOptimization_covarianceIgnored->setObjectName(Parameters::kOptimizerVarianceIgnored().
c_str());
1212 _ui->graphOptimization_fromGraphEnd->setObjectName(Parameters::kRGBDOptimizeFromGraphEnd().
c_str());
1213 _ui->graphOptimization_maxError->setObjectName(Parameters::kRGBDOptimizeMaxError().
c_str());
1214 _ui->graphOptimization_gravitySigma->setObjectName(Parameters::kOptimizerGravitySigma().
c_str());
1215 _ui->graphOptimization_stopEpsilon->setObjectName(Parameters::kOptimizerEpsilon().
c_str());
1216 _ui->graphOptimization_robust->setObjectName(Parameters::kOptimizerRobust().
c_str());
1217 _ui->graphOptimization_priorsIgnored->setObjectName(Parameters::kOptimizerPriorsIgnored().
c_str());
1218 _ui->graphOptimization_landmarksIgnored->setObjectName(Parameters::kOptimizerLandmarksIgnored().
c_str());
1220 _ui->comboBox_g2o_solver->setObjectName(Parameters::kg2oSolver().
c_str());
1221 _ui->comboBox_g2o_optimizer->setObjectName(Parameters::kg2oOptimizer().
c_str());
1222 _ui->doubleSpinBox_g2o_pixelVariance->setObjectName(Parameters::kg2oPixelVariance().
c_str());
1223 _ui->doubleSpinBox_g2o_robustKernelDelta->setObjectName(Parameters::kg2oRobustKernelDelta().
c_str());
1224 _ui->doubleSpinBox_g2o_baseline->setObjectName(Parameters::kg2oBaseline().
c_str());
1226 _ui->comboBox_gtsam_optimizer->setObjectName(Parameters::kGTSAMOptimizer().
c_str());
1227 _ui->gtsam_incremental->setObjectName(Parameters::kGTSAMIncremental().
c_str());
1228 _ui->gtsam_incremental_threshold->setObjectName(Parameters::kGTSAMIncRelinearizeThreshold().
c_str());
1229 _ui->gtsam_incremental_skip->setObjectName(Parameters::kGTSAMIncRelinearizeSkip().
c_str());
1231 _ui->graphPlan_goalReachedRadius->setObjectName(Parameters::kRGBDGoalReachedRadius().
c_str());
1232 _ui->graphPlan_goalsSavedInUserData->setObjectName(Parameters::kRGBDGoalsSavedInUserData().
c_str());
1233 _ui->graphPlan_stuckIterations->setObjectName(Parameters::kRGBDPlanStuckIterations().
c_str());
1234 _ui->graphPlan_linearVelocity->setObjectName(Parameters::kRGBDPlanLinearVelocity().
c_str());
1235 _ui->graphPlan_angularVelocity->setObjectName(Parameters::kRGBDPlanAngularVelocity().
c_str());
1237 _ui->groupBox_localDetection_time->setObjectName(Parameters::kRGBDProximityByTime().
c_str());
1238 _ui->groupBox_localDetection_space->setObjectName(Parameters::kRGBDProximityBySpace().
c_str());
1239 _ui->localDetection_radius->setObjectName(Parameters::kRGBDLocalRadius().
c_str());
1240 _ui->maxLocalizationDistance->setObjectName(Parameters::kRGBDMaxLoopClosureDistance().
c_str());
1241 _ui->localDetection_maxDiffID->setObjectName(Parameters::kRGBDProximityMaxGraphDepth().
c_str());
1242 _ui->localDetection_maxNeighbors->setObjectName(Parameters::kRGBDProximityPathMaxNeighbors().
c_str());
1243 _ui->localDetection_maxPaths->setObjectName(Parameters::kRGBDProximityMaxPaths().
c_str());
1244 _ui->localDetection_pathFilteringRadius->setObjectName(Parameters::kRGBDProximityPathFilteringRadius().
c_str());
1245 _ui->localDetection_angle->setObjectName(Parameters::kRGBDProximityAngle().
c_str());
1246 _ui->localDetection_mergedScanCovFactor->setObjectName(Parameters::kRGBDProximityMergedScanCovFactor().
c_str());
1247 _ui->checkBox_localSpaceOdomGuess->setObjectName(Parameters::kRGBDProximityOdomGuess().
c_str());
1248 _ui->checkBox_localSpacePathOdomPosesUsed->setObjectName(Parameters::kRGBDProximityPathRawPosesUsed().
c_str());
1249 _ui->rgdb_localImmunizationRatio->setObjectName(Parameters::kRGBDLocalImmunizationRatio().
c_str());
1250 _ui->loopClosure_identityGuess->setObjectName(Parameters::kRGBDLoopClosureIdentityGuess().
c_str());
1251 _ui->loopClosure_reextract->setObjectName(Parameters::kRGBDLoopClosureReextractFeatures().
c_str());
1252 _ui->loopClosure_bunlde->setObjectName(Parameters::kRGBDLocalBundleOnLoopClosure().
c_str());
1253 _ui->loopClosure_invertedReg->setObjectName(Parameters::kRGBDInvertedReg().
c_str());
1254 _ui->checkbox_rgbd_createOccupancyGrid->setObjectName(Parameters::kRGBDCreateOccupancyGrid().
c_str());
1255 _ui->RGBDMarkerDetection->setObjectName(Parameters::kRGBDMarkerDetection().
c_str());
1256 _ui->spinBox_maxOdomCacheSize->setObjectName(Parameters::kRGBDMaxOdomCacheSize().
c_str());
1257 _ui->checkbox_localizationSmoothing->setObjectName(Parameters::kRGBDLocalizationSmoothing().
c_str());
1258 _ui->doubleSpinBox_localizationPriorError->setObjectName(Parameters::kRGBDLocalizationPriorError().
c_str());
1261 _ui->reg_repeatOnce->setObjectName(Parameters::kRegRepeatOnce().
c_str());
1262 _ui->comboBox_registrationStrategy->setObjectName(Parameters::kRegStrategy().
c_str());
1263 _ui->loopClosure_bowForce2D->setObjectName(Parameters::kRegForce3DoF().
c_str());
1266 _ui->loopClosure_bowMinInliers->setObjectName(Parameters::kVisMinInliers().
c_str());
1267 _ui->loopClosure_bowInlierDistance->setObjectName(Parameters::kVisInlierDistance().
c_str());
1268 _ui->loopClosure_bowIterations->setObjectName(Parameters::kVisIterations().
c_str());
1269 _ui->loopClosure_bowRefineIterations->setObjectName(Parameters::kVisRefineIterations().
c_str());
1270 _ui->visMeanDistance->setObjectName(Parameters::kVisMeanInliersDistance().
c_str());
1271 _ui->visMinDistribution->setObjectName(Parameters::kVisMinInliersDistribution().
c_str());
1272 _ui->loopClosure_estimationType->setObjectName(Parameters::kVisEstimationType().
c_str());
1273 connect(
_ui->loopClosure_estimationType, SIGNAL(currentIndexChanged(
int)),
_ui->stackedWidget_loopClosureEstimation, SLOT(setCurrentIndex(
int)));
1274 _ui->stackedWidget_loopClosureEstimation->setCurrentIndex(Parameters::defaultVisEstimationType());
1275 _ui->loopClosure_bowEpipolarGeometryVar->setObjectName(Parameters::kVisEpipolarGeometryVar().
c_str());
1276 _ui->loopClosure_pnpReprojError->setObjectName(Parameters::kVisPnPReprojError().
c_str());
1277 _ui->loopClosure_pnpFlags->setObjectName(Parameters::kVisPnPFlags().
c_str());
1278 _ui->loopClosure_pnpRefineIterations->setObjectName(Parameters::kVisPnPRefineIterations().
c_str());
1279 _ui->loopClosure_pnpVarMedianRatio->setObjectName(Parameters::kVisPnPVarianceMedianRatio().
c_str());
1280 _ui->loopClosure_pnpMaxVariance->setObjectName(Parameters::kVisPnPMaxVariance().
c_str());
1281 _ui->loopClosure_pnpSamplingPolicy->setObjectName(Parameters::kVisPnPSamplingPolicy().
c_str());
1282 _ui->loopClosure_pnpSplitLinearCovComponents->setObjectName(Parameters::kVisPnPSplitLinearCovComponents().
c_str());
1283 _ui->reextract_nn->setObjectName(Parameters::kVisCorNNType().
c_str());
1285 _ui->reextract_nndrRatio->setObjectName(Parameters::kVisCorNNDR().
c_str());
1286 _ui->spinBox_visCorGuessWinSize->setObjectName(Parameters::kVisCorGuessWinSize().
c_str());
1287 _ui->checkBox_visCorGuessMatchToProjection->setObjectName(Parameters::kVisCorGuessMatchToProjection().
c_str());
1288 _ui->vis_feature_detector->setObjectName(Parameters::kVisFeatureType().
c_str());
1289 _ui->reextract_maxFeatures->setObjectName(Parameters::kVisMaxFeatures().
c_str());
1290 _ui->checkBox_visSSC->setObjectName(Parameters::kVisSSC().
c_str());
1291 _ui->reextract_gridrows->setObjectName(Parameters::kVisGridRows().
c_str());
1292 _ui->reextract_gridcols->setObjectName(Parameters::kVisGridCols().
c_str());
1293 _ui->loopClosure_bowMaxDepth->setObjectName(Parameters::kVisMaxDepth().
c_str());
1294 _ui->loopClosure_bowMinDepth->setObjectName(Parameters::kVisMinDepth().
c_str());
1295 _ui->checkBox_visDepthAsMask->setObjectName(Parameters::kVisDepthAsMask().
c_str());
1296 _ui->doubleSpinBox_visDepthMaskFloorThr->setObjectName(Parameters::kVisDepthMaskFloorThr().
c_str());
1297 _ui->loopClosure_roi->setObjectName(Parameters::kVisRoiRatios().
c_str());
1298 _ui->subpix_winSize->setObjectName(Parameters::kVisSubPixWinSize().
c_str());
1299 _ui->subpix_iterations->setObjectName(Parameters::kVisSubPixIterations().
c_str());
1300 _ui->subpix_eps->setObjectName(Parameters::kVisSubPixEps().
c_str());
1301 _ui->odom_flow_winSize->setObjectName(Parameters::kVisCorFlowWinSize().
c_str());
1302 _ui->odom_flow_maxLevel->setObjectName(Parameters::kVisCorFlowMaxLevel().
c_str());
1303 _ui->odom_flow_iterations->setObjectName(Parameters::kVisCorFlowIterations().
c_str());
1304 _ui->odom_flow_eps->setObjectName(Parameters::kVisCorFlowEps().
c_str());
1305 _ui->odom_flow_gpu->setObjectName(Parameters::kVisCorFlowGpu().
c_str());
1306 _ui->loopClosure_bundle->setObjectName(Parameters::kVisBundleAdjustment().
c_str());
1309 _ui->comboBox_icpStrategy->setObjectName(Parameters::kIcpStrategy().
c_str());
1310 connect(
_ui->comboBox_icpStrategy, SIGNAL(currentIndexChanged(
int)),
_ui->stackedWidget_icpStrategy, SLOT(setCurrentIndex(
int)));
1311 _ui->comboBox_icpStrategy->setCurrentIndex(Parameters::defaultIcpStrategy());
1312 _ui->globalDetection_icpMaxTranslation->setObjectName(Parameters::kIcpMaxTranslation().
c_str());
1313 _ui->globalDetection_icpMaxRotation->setObjectName(Parameters::kIcpMaxRotation().
c_str());
1314 _ui->loopClosure_icpVoxelSize->setObjectName(Parameters::kIcpVoxelSize().
c_str());
1315 _ui->loopClosure_icpDownsamplingStep->setObjectName(Parameters::kIcpDownsamplingStep().
c_str());
1316 _ui->loopClosure_icpRangeMin->setObjectName(Parameters::kIcpRangeMin().
c_str());
1317 _ui->loopClosure_icpRangeMax->setObjectName(Parameters::kIcpRangeMax().
c_str());
1318 _ui->loopClosure_icpFiltersEnabled->setObjectName(Parameters::kIcpFiltersEnabled().
c_str());
1319 _ui->loopClosure_icpMaxCorrespondenceDistance->setObjectName(Parameters::kIcpMaxCorrespondenceDistance().
c_str());
1320 _ui->loopClosure_icpReciprocalCorrespondences->setObjectName(Parameters::kIcpReciprocalCorrespondences().
c_str());
1321 _ui->loopClosure_icpIterations->setObjectName(Parameters::kIcpIterations().
c_str());
1322 _ui->loopClosure_icpEpsilon->setObjectName(Parameters::kIcpEpsilon().
c_str());
1323 _ui->loopClosure_icpRatio->setObjectName(Parameters::kIcpCorrespondenceRatio().
c_str());
1324 _ui->doubleSpinBox_icpOutlierRatio->setObjectName(Parameters::kIcpOutlierRatio().
c_str());
1325 _ui->loopClosure_icpPointToPlane->setObjectName(Parameters::kIcpPointToPlane().
c_str());
1326 _ui->loopClosure_icpPointToPlaneNormals->setObjectName(Parameters::kIcpPointToPlaneK().
c_str());
1327 _ui->loopClosure_icpPointToPlaneNormalsRadius->setObjectName(Parameters::kIcpPointToPlaneRadius().
c_str());
1328 _ui->loopClosure_icpPointToPlaneGroundNormalsUp->setObjectName(Parameters::kIcpPointToPlaneGroundNormalsUp().
c_str());
1329 _ui->loopClosure_icpPointToPlaneNormalsMinComplexity->setObjectName(Parameters::kIcpPointToPlaneMinComplexity().
c_str());
1330 _ui->loopClosure_icpPointToPlaneLowComplexityStrategy->setObjectName(Parameters::kIcpPointToPlaneLowComplexityStrategy().
c_str());
1331 _ui->loopClosure_icpDebugExportFormat->setObjectName(Parameters::kIcpDebugExportFormat().
c_str());
1333 _ui->lineEdit_IcpPMConfigPath->setObjectName(Parameters::kIcpPMConfig().
c_str());
1335 _ui->spinBox_icpPMMatcherKnn->setObjectName(Parameters::kIcpPMMatcherKnn().
c_str());
1336 _ui->doubleSpinBox_icpPMMatcherEpsilon->setObjectName(Parameters::kIcpPMMatcherEpsilon().
c_str());
1337 _ui->loopClosure_icpPMMatcherIntensity->setObjectName(Parameters::kIcpPMMatcherIntensity().
c_str());
1338 _ui->loopClosure_icpForce4DoF->setObjectName(Parameters::kIcpForce4DoF().
c_str());
1340 _ui->spinBox_icpCCSamplingLimit->setObjectName(Parameters::kIcpCCSamplingLimit().
c_str());
1341 _ui->checkBox_icpCCFilterOutFarthestPoints->setObjectName(Parameters::kIcpCCFilterOutFarthestPoints().
c_str());
1342 _ui->doubleSpinBox_icpCCMaxFinalRMS->setObjectName(Parameters::kIcpCCMaxFinalRMS().
c_str());
1346 _ui->groupBox_grid_3d->setObjectName(Parameters::kGrid3D().
c_str());
1347 _ui->checkBox_grid_groundObstacle->setObjectName(Parameters::kGridGroundIsObstacle().
c_str());
1348 _ui->doubleSpinBox_grid_resolution->setObjectName(Parameters::kGridCellSize().
c_str());
1349 _ui->checkBox_grid_preVoxelFiltering->setObjectName(Parameters::kGridPreVoxelFiltering().
c_str());
1350 _ui->spinBox_grid_decimation->setObjectName(Parameters::kGridDepthDecimation().
c_str());
1351 _ui->doubleSpinBox_grid_maxDepth->setObjectName(Parameters::kGridRangeMax().
c_str());
1352 _ui->doubleSpinBox_grid_minDepth->setObjectName(Parameters::kGridRangeMin().
c_str());
1353 _ui->lineEdit_grid_roi->setObjectName(Parameters::kGridDepthRoiRatios().
c_str());
1354 _ui->checkBox_grid_projRayTracing->setObjectName(Parameters::kGridRayTracing().
c_str());
1355 _ui->doubleSpinBox_grid_footprintLength->setObjectName(Parameters::kGridFootprintLength().
c_str());
1356 _ui->doubleSpinBox_grid_footprintWidth->setObjectName(Parameters::kGridFootprintWidth().
c_str());
1357 _ui->doubleSpinBox_grid_footprintHeight->setObjectName(Parameters::kGridFootprintHeight().
c_str());
1358 _ui->checkBox_grid_flatObstaclesDetected->setObjectName(Parameters::kGridFlatObstacleDetected().
c_str());
1359 _ui->comboBox_grid_sensor->setObjectName(Parameters::kGridSensor().
c_str());
1360 _ui->checkBox_grid_projMapFrame->setObjectName(Parameters::kGridMapFrameProjection().
c_str());
1361 _ui->doubleSpinBox_grid_maxGroundAngle->setObjectName(Parameters::kGridMaxGroundAngle().
c_str());
1362 _ui->spinBox_grid_normalK->setObjectName(Parameters::kGridNormalK().
c_str());
1363 _ui->doubleSpinBox_grid_maxGroundHeight->setObjectName(Parameters::kGridMaxGroundHeight().
c_str());
1364 _ui->doubleSpinBox_grid_maxObstacleHeight->setObjectName(Parameters::kGridMaxObstacleHeight().
c_str());
1365 _ui->doubleSpinBox_grid_clusterRadius->setObjectName(Parameters::kGridClusterRadius().
c_str());
1366 _ui->spinBox_grid_minClusterSize->setObjectName(Parameters::kGridMinClusterSize().
c_str());
1367 _ui->doubleSpinBox_grid_minGroundHeight->setObjectName(Parameters::kGridMinGroundHeight().
c_str());
1368 _ui->spinBox_grid_noiseMinNeighbors->setObjectName(Parameters::kGridNoiseFilteringMinNeighbors().
c_str());
1369 _ui->doubleSpinBox_grid_noiseRadius->setObjectName(Parameters::kGridNoiseFilteringRadius().
c_str());
1370 _ui->groupBox_grid_normalsSegmentation->setObjectName(Parameters::kGridNormalsSegmentation().
c_str());
1371 _ui->checkBox_grid_unknownSpaceFilled->setObjectName(Parameters::kGridScan2dUnknownSpaceFilled().
c_str());
1372 _ui->spinBox_grid_scanDecimation->setObjectName(Parameters::kGridScanDecimation().
c_str());
1374 _ui->doubleSpinBox_grid_updateError->setObjectName(Parameters::kGridGlobalUpdateError().
c_str());
1375 _ui->doubleSpinBox_grid_minMapSize->setObjectName(Parameters::kGridGlobalMinSize().
c_str());
1376 _ui->spinBox_grid_maxNodes->setObjectName(Parameters::kGridGlobalMaxNodes().
c_str());
1377 _ui->doubleSpinBox_grid_altitudeDelta->setObjectName(Parameters::kGridGlobalAltitudeDelta().
c_str());
1378 _ui->doubleSpinBox_grid_footprintRadius->setObjectName(Parameters::kGridGlobalFootprintRadius().
c_str());
1379 _ui->doubleSpinBox_grid_occThr->setObjectName(Parameters::kGridGlobalOccupancyThr().
c_str());
1380 _ui->doubleSpinBox_grid_probHit->setObjectName(Parameters::kGridGlobalProbHit().
c_str());
1381 _ui->doubleSpinBox_grid_probMiss->setObjectName(Parameters::kGridGlobalProbMiss().
c_str());
1382 _ui->doubleSpinBox_grid_clampingMin->setObjectName(Parameters::kGridGlobalProbClampingMin().
c_str());
1383 _ui->doubleSpinBox_grid_clampingMax->setObjectName(Parameters::kGridGlobalProbClampingMax().
c_str());
1384 _ui->checkBox_grid_erode->setObjectName(Parameters::kGridGlobalEroded().
c_str());
1385 _ui->spinBox_grid_floodfilldepth->setObjectName(Parameters::kGridGlobalFloodFillDepth().
c_str());
1388 _ui->odom_strategy->setObjectName(Parameters::kOdomStrategy().
c_str());
1390 _ui->odom_strategy->setCurrentIndex(Parameters::defaultOdomStrategy());
1392 _ui->odom_countdown->setObjectName(Parameters::kOdomResetCountdown().
c_str());
1393 _ui->odom_holonomic->setObjectName(Parameters::kOdomHolonomic().
c_str());
1394 _ui->odom_fillInfoData->setObjectName(Parameters::kOdomFillInfoData().
c_str());
1395 _ui->odom_dataBufferSize->setObjectName(Parameters::kOdomImageBufferSize().
c_str());
1396 _ui->odom_flow_keyframeThr->setObjectName(Parameters::kOdomKeyFrameThr().
c_str());
1397 _ui->odom_VisKeyFrameThr->setObjectName(Parameters::kOdomVisKeyFrameThr().
c_str());
1398 _ui->odom_flow_scanKeyframeThr->setObjectName(Parameters::kOdomScanKeyFrameThr().
c_str());
1399 _ui->odom_flow_guessMotion->setObjectName(Parameters::kOdomGuessMotion().
c_str());
1400 _ui->odom_guess_smoothing_delay->setObjectName(Parameters::kOdomGuessSmoothingDelay().
c_str());
1401 _ui->odom_imageDecimation->setObjectName(Parameters::kOdomImageDecimation().
c_str());
1402 _ui->odom_alignWithGround->setObjectName(Parameters::kOdomAlignWithGround().
c_str());
1403 _ui->odom_lidar_deskewing->setObjectName(Parameters::kOdomDeskewing().
c_str());
1406 _ui->odom_localHistory->setObjectName(Parameters::kOdomF2MMaxSize().
c_str());
1407 _ui->spinBox_odom_f2m_maxNewFeatures->setObjectName(Parameters::kOdomF2MMaxNewFeatures().
c_str());
1408 _ui->doubleSpinBox_odom_f2m_floorThreshold->setObjectName(Parameters::kOdomF2MFloorThreshold().
c_str());
1409 _ui->spinBox_odom_f2m_scanMaxSize->setObjectName(Parameters::kOdomF2MScanMaxSize().
c_str());
1410 _ui->doubleSpinBox_odom_f2m_scanRadius->setObjectName(Parameters::kOdomF2MScanSubtractRadius().
c_str());
1411 _ui->doubleSpinBox_odom_f2m_scanAngle->setObjectName(Parameters::kOdomF2MScanSubtractAngle().
c_str());
1412 _ui->doubleSpinBox_odom_f2m_scanRange->setObjectName(Parameters::kOdomF2MScanRange().
c_str());
1413 _ui->odom_f2m_validDepthRatio->setObjectName(Parameters::kOdomF2MValidDepthRatio().
c_str());
1414 _ui->odom_f2m_initDepthFactor->setObjectName(Parameters::kOdomF2MInitDepthFactor().
c_str());
1415 _ui->odom_f2m_bundleStrategy->setObjectName(Parameters::kOdomF2MBundleAdjustment().
c_str());
1416 _ui->odom_f2m_bundleMaxFrames->setObjectName(Parameters::kOdomF2MBundleAdjustmentMaxFrames().
c_str());
1417 _ui->odom_f2m_bundleMinMotion->setObjectName(Parameters::kOdomF2MBundleAdjustmentMinMotion().
c_str());
1418 _ui->odom_f2m_bundleMaxKeyFramesPerFeature->setObjectName(Parameters::kOdomF2MBundleAdjustmentMaxKeyFramesPerFeature().
c_str());
1419 _ui->odom_f2m_bundleUpdateFeatureMapOnAllFrames->setObjectName(Parameters::kOdomF2MBundleUpdateFeatureMapOnAllFrames().
c_str());
1422 _ui->comboBox_odomf2f_corType->setObjectName(Parameters::kVisCorType().
c_str());
1425 _ui->doubleSpinBox_minFlow->setObjectName(Parameters::kOdomMonoInitMinFlow().
c_str());
1426 _ui->doubleSpinBox_minInitTranslation->setObjectName(Parameters::kOdomMonoInitMinTranslation().
c_str());
1427 _ui->doubleSpinBox_minTranslation->setObjectName(Parameters::kOdomMonoMinTranslation().
c_str());
1428 _ui->doubleSpinBox_maxVariance->setObjectName(Parameters::kOdomMonoMaxVariance().
c_str());
1431 _ui->odom_filteringStrategy->setObjectName(Parameters::kOdomFilteringStrategy().
c_str());
1432 _ui->stackedWidget_odometryFiltering->setCurrentIndex(
_ui->odom_filteringStrategy->currentIndex());
1433 connect(
_ui->odom_filteringStrategy, SIGNAL(currentIndexChanged(
int)),
_ui->stackedWidget_odometryFiltering, SLOT(setCurrentIndex(
int)));
1434 _ui->spinBox_particleSize->setObjectName(Parameters::kOdomParticleSize().
c_str());
1435 _ui->doubleSpinBox_particleNoiseT->setObjectName(Parameters::kOdomParticleNoiseT().
c_str());
1436 _ui->doubleSpinBox_particleLambdaT->setObjectName(Parameters::kOdomParticleLambdaT().
c_str());
1437 _ui->doubleSpinBox_particleNoiseR->setObjectName(Parameters::kOdomParticleNoiseR().
c_str());
1438 _ui->doubleSpinBox_particleLambdaR->setObjectName(Parameters::kOdomParticleLambdaR().
c_str());
1441 _ui->doubleSpinBox_kalmanProcessNoise->setObjectName(Parameters::kOdomKalmanProcessNoise().
c_str());
1442 _ui->doubleSpinBox_kalmanMeasurementNoise->setObjectName(Parameters::kOdomKalmanMeasurementNoise().
c_str());
1445 _ui->spinBox_OdomFovisFeatureWindowSize->setObjectName(Parameters::kOdomFovisFeatureWindowSize().
c_str());
1446 _ui->spinBox_OdomFovisMaxPyramidLevel->setObjectName(Parameters::kOdomFovisMaxPyramidLevel().
c_str());
1447 _ui->spinBox_OdomFovisMinPyramidLevel->setObjectName(Parameters::kOdomFovisMinPyramidLevel().
c_str());
1448 _ui->spinBox_OdomFovisTargetPixelsPerFeature->setObjectName(Parameters::kOdomFovisTargetPixelsPerFeature().
c_str());
1449 _ui->spinBox_OdomFovisFastThreshold->setObjectName(Parameters::kOdomFovisFastThreshold().
c_str());
1450 _ui->checkBox_OdomFovisUseAdaptiveThreshold->setObjectName(Parameters::kOdomFovisUseAdaptiveThreshold().
c_str());
1451 _ui->doubleSpinBox_OdomFovisFastThresholdAdaptiveGain->setObjectName(Parameters::kOdomFovisFastThresholdAdaptiveGain().
c_str());
1452 _ui->checkBox_OdomFovisUseHomographyInitialization->setObjectName(Parameters::kOdomFovisUseHomographyInitialization().
c_str());
1454 _ui->checkBox_OdomFovisUseBucketing->setObjectName(Parameters::kOdomFovisUseBucketing().
c_str());
1455 _ui->spinBox_OdomFovisBucketWidth->setObjectName(Parameters::kOdomFovisBucketWidth().
c_str());
1456 _ui->spinBox_OdomFovisBucketHeight->setObjectName(Parameters::kOdomFovisBucketHeight().
c_str());
1457 _ui->spinBox_OdomFovisMaxKeypointsPerBucket->setObjectName(Parameters::kOdomFovisMaxKeypointsPerBucket().
c_str());
1458 _ui->checkBox_OdomFovisUseImageNormalization->setObjectName(Parameters::kOdomFovisUseImageNormalization().
c_str());
1460 _ui->doubleSpinBox_OdomFovisInlierMaxReprojectionError->setObjectName(Parameters::kOdomFovisInlierMaxReprojectionError().
c_str());
1461 _ui->doubleSpinBox_OdomFovisCliqueInlierThreshold->setObjectName(Parameters::kOdomFovisCliqueInlierThreshold().
c_str());
1462 _ui->spinBox_OdomFovisMinFeaturesForEstimate->setObjectName(Parameters::kOdomFovisMinFeaturesForEstimate().
c_str());
1463 _ui->doubleSpinBox_OdomFovisMaxMeanReprojectionError->setObjectName(Parameters::kOdomFovisMaxMeanReprojectionError().
c_str());
1464 _ui->checkBox_OdomFovisUseSubpixelRefinement->setObjectName(Parameters::kOdomFovisUseSubpixelRefinement().
c_str());
1465 _ui->spinBox_OdomFovisFeatureSearchWindow->setObjectName(Parameters::kOdomFovisFeatureSearchWindow().
c_str());
1466 _ui->checkBox_OdomFovisUpdateTargetFeaturesWithRefined->setObjectName(Parameters::kOdomFovisUpdateTargetFeaturesWithRefined().
c_str());
1468 _ui->checkBox_OdomFovisStereoRequireMutualMatch->setObjectName(Parameters::kOdomFovisStereoRequireMutualMatch().
c_str());
1469 _ui->doubleSpinBox_OdomFovisStereoMaxDistEpipolarLine->setObjectName(Parameters::kOdomFovisStereoMaxDistEpipolarLine().
c_str());
1470 _ui->doubleSpinBox_OdomFovisStereoMaxRefinementDisplacement->setObjectName(Parameters::kOdomFovisStereoMaxRefinementDisplacement().
c_str());
1471 _ui->spinBox_OdomFovisStereoMaxDisparity->setObjectName(Parameters::kOdomFovisStereoMaxDisparity().
c_str());
1474 _ui->spinBox_OdomViso2RansacIters->setObjectName(Parameters::kOdomViso2RansacIters().
c_str());
1475 _ui->doubleSpinBox_OdomViso2InlierThreshold->setObjectName(Parameters::kOdomViso2InlierThreshold().
c_str());
1476 _ui->checkBox_OdomViso2Reweighting->setObjectName(Parameters::kOdomViso2Reweighting().
c_str());
1478 _ui->spinBox_OdomViso2MatchNmsN->setObjectName(Parameters::kOdomViso2MatchNmsN().
c_str());
1479 _ui->spinBox_OdomViso2MatchNmsTau->setObjectName(Parameters::kOdomViso2MatchNmsTau().
c_str());
1480 _ui->spinBox_OdomViso2MatchBinsize->setObjectName(Parameters::kOdomViso2MatchBinsize().
c_str());
1481 _ui->spinBox_OdomViso2MatchRadius->setObjectName(Parameters::kOdomViso2MatchRadius().
c_str());
1482 _ui->spinBox_OdomViso2MatchDispTolerance->setObjectName(Parameters::kOdomViso2MatchDispTolerance().
c_str());
1483 _ui->spinBox_OdomViso2MatchOutlierDispTolerance->setObjectName(Parameters::kOdomViso2MatchOutlierDispTolerance().
c_str());
1484 _ui->spinBox_OdomViso2MatchOutlierFlowTolerance->setObjectName(Parameters::kOdomViso2MatchOutlierFlowTolerance().
c_str());
1485 _ui->checkBox_OdomViso2MatchMultiStage->setObjectName(Parameters::kOdomViso2MatchMultiStage().
c_str());
1486 _ui->checkBox_OdomViso2MatchHalfResolution->setObjectName(Parameters::kOdomViso2MatchHalfResolution().
c_str());
1487 _ui->spinBox_OdomViso2MatchRefinement->setObjectName(Parameters::kOdomViso2MatchRefinement().
c_str());
1489 _ui->spinBox_OdomViso2BucketMaxFeatures->setObjectName(Parameters::kOdomViso2BucketMaxFeatures().
c_str());
1490 _ui->doubleSpinBox_OdomViso2BucketWidth->setObjectName(Parameters::kOdomViso2BucketWidth().
c_str());
1491 _ui->doubleSpinBox_OdomViso2BucketHeight->setObjectName(Parameters::kOdomViso2BucketHeight().
c_str());
1494 _ui->lineEdit_OdomORBSLAMVocPath->setObjectName(Parameters::kOdomORBSLAMVocPath().
c_str());
1496 _ui->doubleSpinBox_OdomORBSLAMBf->setObjectName(Parameters::kOdomORBSLAMBf().
c_str());
1497 _ui->doubleSpinBox_OdomORBSLAMThDepth->setObjectName(Parameters::kOdomORBSLAMThDepth().
c_str());
1498 _ui->doubleSpinBox_OdomORBSLAMFps->setObjectName(Parameters::kOdomORBSLAMFps().
c_str());
1499 _ui->spinBox_OdomORBSLAMMaxFeatures->setObjectName(Parameters::kOdomORBSLAMMaxFeatures().
c_str());
1500 _ui->spinBox_OdomORBSLAMMapSize->setObjectName(Parameters::kOdomORBSLAMMapSize().
c_str());
1501 _ui->groupBox_OdomORBSLAMInertial->setObjectName(Parameters::kOdomORBSLAMInertial().
c_str());
1502 _ui->doubleSpinBox_ORBSLAMGyroNoise->setObjectName(Parameters::kOdomORBSLAMGyroNoise().
c_str());
1503 _ui->doubleSpinBox_ORBSLAMAccNoise->setObjectName(Parameters::kOdomORBSLAMAccNoise().
c_str());
1504 _ui->doubleSpinBox_ORBSLAMGyroWalk->setObjectName(Parameters::kOdomORBSLAMGyroWalk().
c_str());
1505 _ui->doubleSpinBox_ORBSLAMAccWalk->setObjectName(Parameters::kOdomORBSLAMAccWalk().
c_str());
1506 _ui->doubleSpinBox_ORBSLAMSamplingRate->setObjectName(Parameters::kOdomORBSLAMSamplingRate().
c_str());
1509 _ui->lineEdit_OdomOkvisPath->setObjectName(Parameters::kOdomOKVISConfigPath().
c_str());
1513 _ui->odom_loam_sensor->setObjectName(Parameters::kOdomLOAMSensor().
c_str());
1514 _ui->odom_loam_scan_period->setObjectName(Parameters::kOdomLOAMScanPeriod().
c_str());
1515 _ui->odom_loam_resolution->setObjectName(Parameters::kOdomLOAMResolution().
c_str());
1516 _ui->odom_loam_linvar->setObjectName(Parameters::kOdomLOAMLinVar().
c_str());
1517 _ui->odom_loam_angvar->setObjectName(Parameters::kOdomLOAMAngVar().
c_str());
1518 _ui->odom_loam_localMapping->setObjectName(Parameters::kOdomLOAMLocalMapping().
c_str());
1521 _ui->OdomMSCKFGridRow->setObjectName(Parameters::kOdomMSCKFGridRow().
c_str());
1522 _ui->OdomMSCKFGridCol->setObjectName(Parameters::kOdomMSCKFGridCol().
c_str());
1523 _ui->OdomMSCKFGridMinFeatureNum->setObjectName(Parameters::kOdomMSCKFGridMinFeatureNum().
c_str());
1524 _ui->OdomMSCKFGridMaxFeatureNum->setObjectName(Parameters::kOdomMSCKFGridMaxFeatureNum().
c_str());
1525 _ui->OdomMSCKFPyramidLevels->setObjectName(Parameters::kOdomMSCKFPyramidLevels().
c_str());
1526 _ui->OdomMSCKFPatchSize->setObjectName(Parameters::kOdomMSCKFPatchSize().
c_str());
1527 _ui->OdomMSCKFFastThreshold->setObjectName(Parameters::kOdomMSCKFFastThreshold().
c_str());
1528 _ui->OdomMSCKFMaxIteration->setObjectName(Parameters::kOdomMSCKFMaxIteration().
c_str());
1529 _ui->OdomMSCKFMaxCamStateSize->setObjectName(Parameters::kOdomMSCKFMaxCamStateSize().
c_str());
1530 _ui->OdomMSCKFTrackPrecision->setObjectName(Parameters::kOdomMSCKFTrackPrecision().
c_str());
1531 _ui->OdomMSCKFRansacThreshold->setObjectName(Parameters::kOdomMSCKFRansacThreshold().
c_str());
1532 _ui->OdomMSCKFStereoThreshold->setObjectName(Parameters::kOdomMSCKFStereoThreshold().
c_str());
1533 _ui->OdomMSCKFPositionStdThreshold->setObjectName(Parameters::kOdomMSCKFPositionStdThreshold().
c_str());
1534 _ui->OdomMSCKFRotationThreshold->setObjectName(Parameters::kOdomMSCKFRotationThreshold().
c_str());
1535 _ui->OdomMSCKFTranslationThreshold->setObjectName(Parameters::kOdomMSCKFTranslationThreshold().
c_str());
1536 _ui->OdomMSCKFTrackingRateThreshold->setObjectName(Parameters::kOdomMSCKFTrackingRateThreshold().
c_str());
1537 _ui->OdomMSCKFOptTranslationThreshold->setObjectName(Parameters::kOdomMSCKFOptTranslationThreshold().
c_str());
1538 _ui->OdomMSCKFNoiseGyro->setObjectName(Parameters::kOdomMSCKFNoiseGyro().
c_str());
1539 _ui->OdomMSCKFNoiseAcc->setObjectName(Parameters::kOdomMSCKFNoiseAcc().
c_str());
1540 _ui->OdomMSCKFNoiseGyroBias->setObjectName(Parameters::kOdomMSCKFNoiseGyroBias().
c_str());
1541 _ui->OdomMSCKFNoiseAccBias->setObjectName(Parameters::kOdomMSCKFNoiseAccBias().
c_str());
1542 _ui->OdomMSCKFNoiseFeature->setObjectName(Parameters::kOdomMSCKFNoiseFeature().
c_str());
1543 _ui->OdomMSCKFInitCovVel->setObjectName(Parameters::kOdomMSCKFInitCovVel().
c_str());
1544 _ui->OdomMSCKFInitCovGyroBias->setObjectName(Parameters::kOdomMSCKFInitCovGyroBias().
c_str());
1545 _ui->OdomMSCKFInitCovAccBias->setObjectName(Parameters::kOdomMSCKFInitCovAccBias().
c_str());
1546 _ui->OdomMSCKFInitCovExRot->setObjectName(Parameters::kOdomMSCKFInitCovExRot().
c_str());
1547 _ui->OdomMSCKFInitCovExTrans->setObjectName(Parameters::kOdomMSCKFInitCovExTrans().
c_str());
1550 _ui->lineEdit_OdomVinsPath->setObjectName(Parameters::kOdomVINSConfigPath().
c_str());
1554 _ui->checkBox_OdomOpenVINSUseStereo->setObjectName(Parameters::kOdomOpenVINSUseStereo().
c_str());
1555 _ui->checkBox_OdomOpenVINSUseKLT->setObjectName(Parameters::kOdomOpenVINSUseKLT().
c_str());
1556 _ui->spinBox_OdomOpenVINSNumPts->setObjectName(Parameters::kOdomOpenVINSNumPts().
c_str());
1557 _ui->spinBox_OdomOpenVINSMinPxDist->setObjectName(Parameters::kOdomOpenVINSMinPxDist().
c_str());
1558 _ui->checkBox_OdomOpenVINSFiTriangulate1d->setObjectName(Parameters::kOdomOpenVINSFiTriangulate1d().
c_str());
1559 _ui->checkBox_OdomOpenVINSFiRefineFeatures->setObjectName(Parameters::kOdomOpenVINSFiRefineFeatures().
c_str());
1560 _ui->spinBox_OdomOpenVINSFiMaxRuns->setObjectName(Parameters::kOdomOpenVINSFiMaxRuns().
c_str());
1561 _ui->doubleSpinBox_OdomOpenVINSFiMaxBaseline->setObjectName(Parameters::kOdomOpenVINSFiMaxBaseline().
c_str());
1562 _ui->doubleSpinBox_OdomOpenVINSFiMaxCondNumber->setObjectName(Parameters::kOdomOpenVINSFiMaxCondNumber().
c_str());
1564 _ui->checkBox_OdomOpenVINSUseFEJ->setObjectName(Parameters::kOdomOpenVINSUseFEJ().
c_str());
1565 _ui->comboBox_OdomOpenVINSIntegration->setObjectName(Parameters::kOdomOpenVINSIntegration().
c_str());
1566 _ui->checkBox_OdomOpenVINSCalibCamExtrinsics->setObjectName(Parameters::kOdomOpenVINSCalibCamExtrinsics().
c_str());
1567 _ui->checkBox_OdomOpenVINSCalibCamIntrinsics->setObjectName(Parameters::kOdomOpenVINSCalibCamIntrinsics().
c_str());
1568 _ui->checkBox_OdomOpenVINSCalibCamTimeoffset->setObjectName(Parameters::kOdomOpenVINSCalibCamTimeoffset().
c_str());
1569 _ui->checkBox_OdomOpenVINSCalibIMUIntrinsics->setObjectName(Parameters::kOdomOpenVINSCalibIMUIntrinsics().
c_str());
1570 _ui->checkBox_OdomOpenVINSCalibIMUGSensitivity->setObjectName(Parameters::kOdomOpenVINSCalibIMUGSensitivity().
c_str());
1571 _ui->spinBox_OdomOpenVINSMaxClones->setObjectName(Parameters::kOdomOpenVINSMaxClones().
c_str());
1572 _ui->spinBox_OdomOpenVINSMaxSLAM->setObjectName(Parameters::kOdomOpenVINSMaxSLAM().
c_str());
1573 _ui->spinBox_OdomOpenVINSMaxSLAMInUpdate->setObjectName(Parameters::kOdomOpenVINSMaxSLAMInUpdate().
c_str());
1574 _ui->spinBox_OdomOpenVINSMaxMSCKFInUpdate->setObjectName(Parameters::kOdomOpenVINSMaxMSCKFInUpdate().
c_str());
1575 _ui->comboBox_OdomOpenVINSFeatRepMSCKF->setObjectName(Parameters::kOdomOpenVINSFeatRepMSCKF().
c_str());
1576 _ui->comboBox_OdomOpenVINSFeatRepSLAM->setObjectName(Parameters::kOdomOpenVINSFeatRepSLAM().
c_str());
1577 _ui->doubleSpinBox_OdomOpenVINSDtSLAMDelay->setObjectName(Parameters::kOdomOpenVINSDtSLAMDelay().
c_str());
1578 _ui->doubleSpinBox_OdomOpenVINSGravityMag->setObjectName(Parameters::kOdomOpenVINSGravityMag().
c_str());
1579 _ui->lineEdit_OdomOpenVINSLeftMaskPath->setObjectName(Parameters::kOdomOpenVINSLeftMaskPath().
c_str());
1581 _ui->lineEdit_OdomOpenVINSRightMaskPath->setObjectName(Parameters::kOdomOpenVINSRightMaskPath().
c_str());
1584 _ui->doubleSpinBox_OdomOpenVINSInitWindowTime->setObjectName(Parameters::kOdomOpenVINSInitWindowTime().
c_str());
1585 _ui->doubleSpinBox_OdomOpenVINSInitIMUThresh->setObjectName(Parameters::kOdomOpenVINSInitIMUThresh().
c_str());
1586 _ui->doubleSpinBox_OdomOpenVINSInitMaxDisparity->setObjectName(Parameters::kOdomOpenVINSInitMaxDisparity().
c_str());
1587 _ui->spinBox_OdomOpenVINSInitMaxFeatures->setObjectName(Parameters::kOdomOpenVINSInitMaxFeatures().
c_str());
1588 _ui->checkBox_OdomOpenVINSInitDynUse->setObjectName(Parameters::kOdomOpenVINSInitDynUse().
c_str());
1589 _ui->checkBox_OdomOpenVINSInitDynMLEOptCalib->setObjectName(Parameters::kOdomOpenVINSInitDynMLEOptCalib().
c_str());
1590 _ui->spinBox_OdomOpenVINSInitDynMLEMaxIter->setObjectName(Parameters::kOdomOpenVINSInitDynMLEMaxIter().
c_str());
1591 _ui->doubleSpinBox_OdomOpenVINSInitDynMLEMaxTime->setObjectName(Parameters::kOdomOpenVINSInitDynMLEMaxTime().
c_str());
1592 _ui->spinBox_OdomOpenVINSInitDynMLEMaxThreads->setObjectName(Parameters::kOdomOpenVINSInitDynMLEMaxThreads().
c_str());
1593 _ui->spinBox_OdomOpenVINSInitDynNumPose->setObjectName(Parameters::kOdomOpenVINSInitDynNumPose().
c_str());
1594 _ui->doubleSpinBox_OdomOpenVINSInitDynMinDeg->setObjectName(Parameters::kOdomOpenVINSInitDynMinDeg().
c_str());
1595 _ui->doubleSpinBox_OdomOpenVINSInitDynInflationOri->setObjectName(Parameters::kOdomOpenVINSInitDynInflationOri().
c_str());
1596 _ui->doubleSpinBox_OdomOpenVINSInitDynInflationVel->setObjectName(Parameters::kOdomOpenVINSInitDynInflationVel().
c_str());
1597 _ui->doubleSpinBox_OdomOpenVINSInitDynInflationBg->setObjectName(Parameters::kOdomOpenVINSInitDynInflationBg().
c_str());
1598 _ui->doubleSpinBox_OdomOpenVINSInitDynInflationBa->setObjectName(Parameters::kOdomOpenVINSInitDynInflationBa().
c_str());
1599 _ui->doubleSpinBox_OdomOpenVINSInitDynMinRecCond->setObjectName(Parameters::kOdomOpenVINSInitDynMinRecCond().
c_str());
1601 _ui->checkBox_OdomOpenVINSTryZUPT->setObjectName(Parameters::kOdomOpenVINSTryZUPT().
c_str());
1602 _ui->doubleSpinBox_OdomOpenVINSZUPTChi2Multiplier->setObjectName(Parameters::kOdomOpenVINSZUPTChi2Multiplier().
c_str());
1603 _ui->doubleSpinBox_OdomOpenVINSZUPTMaxVelodicy->setObjectName(Parameters::kOdomOpenVINSZUPTMaxVelodicy().
c_str());
1604 _ui->doubleSpinBox_OdomOpenVINSZUPTNoiseMultiplier->setObjectName(Parameters::kOdomOpenVINSZUPTNoiseMultiplier().
c_str());
1605 _ui->doubleSpinBox_OdomOpenVINSZUPTMaxDisparity->setObjectName(Parameters::kOdomOpenVINSZUPTMaxDisparity().
c_str());
1606 _ui->checkBox_OdomOpenVINSZUPTOnlyAtBeginning->setObjectName(Parameters::kOdomOpenVINSZUPTOnlyAtBeginning().
c_str());
1608 _ui->doubleSpinBox_OdomOpenVINSAccelerometerNoiseDensity->setObjectName(Parameters::kOdomOpenVINSAccelerometerNoiseDensity().
c_str());
1609 _ui->doubleSpinBox_OdomOpenVINSAccelerometerRandomWalk->setObjectName(Parameters::kOdomOpenVINSAccelerometerRandomWalk().
c_str());
1610 _ui->doubleSpinBox_OdomOpenVINSGyroscopeNoiseDensity->setObjectName(Parameters::kOdomOpenVINSGyroscopeNoiseDensity().
c_str());
1611 _ui->doubleSpinBox_OdomOpenVINSGyroscopeRandomWalk->setObjectName(Parameters::kOdomOpenVINSGyroscopeRandomWalk().
c_str());
1612 _ui->doubleSpinBox_OdomOpenVINSUpMSCKFSigmaPx->setObjectName(Parameters::kOdomOpenVINSUpMSCKFSigmaPx().
c_str());
1613 _ui->doubleSpinBox_OdomOpenVINSUpMSCKFChi2Multiplier->setObjectName(Parameters::kOdomOpenVINSUpMSCKFChi2Multiplier().
c_str());
1614 _ui->doubleSpinBox_OdomOpenVINSUpSLAMSigmaPx->setObjectName(Parameters::kOdomOpenVINSUpSLAMSigmaPx().
c_str());
1615 _ui->doubleSpinBox_OdomOpenVINSUpSLAMChi2Multiplier->setObjectName(Parameters::kOdomOpenVINSUpSLAMChi2Multiplier().
c_str());
1618 _ui->stereo_winWidth->setObjectName(Parameters::kStereoWinWidth().
c_str());
1619 _ui->stereo_winHeight->setObjectName(Parameters::kStereoWinHeight().
c_str());
1620 _ui->stereo_maxLevel->setObjectName(Parameters::kStereoMaxLevel().
c_str());
1621 _ui->stereo_iterations->setObjectName(Parameters::kStereoIterations().
c_str());
1622 _ui->stereo_minDisparity->setObjectName(Parameters::kStereoMinDisparity().
c_str());
1623 _ui->stereo_maxDisparity->setObjectName(Parameters::kStereoMaxDisparity().
c_str());
1624 _ui->stereo_ssd->setObjectName(Parameters::kStereoSSD().
c_str());
1625 _ui->stereo_flow_eps->setObjectName(Parameters::kStereoEps().
c_str());
1626 _ui->stereo_opticalFlow->setObjectName(Parameters::kStereoOpticalFlow().
c_str());
1627 _ui->stereo_flow_gpu->setObjectName(Parameters::kStereoGpu().
c_str());
1631 _ui->odom_open3d_method->setObjectName(Parameters::kOdomOpen3DMethod().
c_str());
1632 _ui->odom_open3d_max_depth->setObjectName(Parameters::kOdomOpen3DMaxDepth().
c_str());
1635 _ui->comboBox_stereoDense_strategy->setObjectName(Parameters::kStereoDenseStrategy().
c_str());
1636 connect(
_ui->comboBox_stereoDense_strategy, SIGNAL(currentIndexChanged(
int)),
_ui->stackedWidget_stereoDense, SLOT(setCurrentIndex(
int)));
1637 _ui->comboBox_stereoDense_strategy->setCurrentIndex(Parameters::defaultStereoDenseStrategy());
1638 _ui->stackedWidget_stereoDense->setCurrentIndex(Parameters::defaultStereoDenseStrategy());
1641 _ui->stereobm_blockSize->setObjectName(Parameters::kStereoBMBlockSize().
c_str());
1642 _ui->stereobm_minDisparity->setObjectName(Parameters::kStereoBMMinDisparity().
c_str());
1643 _ui->stereobm_numDisparities->setObjectName(Parameters::kStereoBMNumDisparities().
c_str());
1644 _ui->stereobm_preFilterCap->setObjectName(Parameters::kStereoBMPreFilterCap().
c_str());
1645 _ui->stereobm_preFilterSize->setObjectName(Parameters::kStereoBMPreFilterSize().
c_str());
1646 _ui->stereobm_speckleRange->setObjectName(Parameters::kStereoBMSpeckleRange().
c_str());
1647 _ui->stereobm_speckleWinSize->setObjectName(Parameters::kStereoBMSpeckleWindowSize().
c_str());
1648 _ui->stereobm_tetureThreshold->setObjectName(Parameters::kStereoBMTextureThreshold().
c_str());
1649 _ui->stereobm_uniquessRatio->setObjectName(Parameters::kStereoBMUniquenessRatio().
c_str());
1650 _ui->stereobm_disp12MaxDiff->setObjectName(Parameters::kStereoBMDisp12MaxDiff().
c_str());
1653 _ui->stereosgbm_blockSize->setObjectName(Parameters::kStereoSGBMBlockSize().
c_str());
1654 _ui->stereosgbm_minDisparity->setObjectName(Parameters::kStereoSGBMMinDisparity().
c_str());
1655 _ui->stereosgbm_numDisparities->setObjectName(Parameters::kStereoSGBMNumDisparities().
c_str());
1656 _ui->stereosgbm_preFilterCap->setObjectName(Parameters::kStereoSGBMPreFilterCap().
c_str());
1657 _ui->stereosgbm_speckleRange->setObjectName(Parameters::kStereoSGBMSpeckleRange().
c_str());
1658 _ui->stereosgbm_speckleWinSize->setObjectName(Parameters::kStereoSGBMSpeckleWindowSize().
c_str());
1659 _ui->stereosgbm_uniquessRatio->setObjectName(Parameters::kStereoSGBMUniquenessRatio().
c_str());
1660 _ui->stereosgbm_disp12MaxDiff->setObjectName(Parameters::kStereoSGBMDisp12MaxDiff().
c_str());
1661 _ui->stereosgbm_p1->setObjectName(Parameters::kStereoSGBMP1().
c_str());
1662 _ui->stereosgbm_p2->setObjectName(Parameters::kStereoSGBMP2().
c_str());
1663 _ui->stereosgbm_mode->setObjectName(Parameters::kStereoSGBMMode().
c_str());
1666 _ui->ArucoDictionary->setObjectName(Parameters::kMarkerDictionary().
c_str());
1667 _ui->ArucoMarkerLength->setObjectName(Parameters::kMarkerLength().
c_str());
1668 _ui->ArucoMaxDepthError->setObjectName(Parameters::kMarkerMaxDepthError().
c_str());
1669 _ui->ArucoVarianceLinear->setObjectName(Parameters::kMarkerVarianceLinear().
c_str());
1670 _ui->ArucoVarianceAngular->setObjectName(Parameters::kMarkerVarianceAngular().
c_str());
1671 _ui->ArucoVarianceOrientationIgnored->setObjectName(Parameters::kMarkerVarianceOrientationIgnored().
c_str());
1672 _ui->ArucoMarkerRangeMin->setObjectName(Parameters::kMarkerMinRange().
c_str());
1673 _ui->ArucoMarkerRangeMax->setObjectName(Parameters::kMarkerMaxRange().
c_str());
1674 _ui->ArucoMarkerPriors->setObjectName(Parameters::kMarkerPriors().
c_str());
1675 _ui->ArucoPriorsVarianceLinear->setObjectName(Parameters::kMarkerPriorsVarianceLinear().
c_str());
1676 _ui->ArucoPriorsVarianceAngular->setObjectName(Parameters::kMarkerPriorsVarianceAngular().
c_str());
1677 _ui->ArucoCornerRefinementMethod->setObjectName(Parameters::kMarkerCornerRefinementMethod().
c_str());
1680 _ui->doubleSpinBox_imuFilterMadgwickGain->setObjectName(Parameters::kImuFilterMadgwickGain().
c_str());
1681 _ui->doubleSpinBox_imuFilterMadgwickZeta->setObjectName(Parameters::kImuFilterMadgwickZeta().
c_str());
1682 _ui->doubleSpinBox_imuFilterComplementaryGainAcc->setObjectName(Parameters::kImuFilterComplementaryGainAcc().
c_str());
1683 _ui->doubleSpinBox_imuFilterComplementaryBiasAlpha->setObjectName(Parameters::kImuFilterComplementaryBiasAlpha().
c_str());
1684 _ui->checkBox_imuFilterComplementaryDoAdaptiveGain->setObjectName(Parameters::kImuFilterComplementaryDoAdpativeGain().
c_str());
1685 _ui->checkBox_imuFilterComplementaryDoBiasEstimation->setObjectName(Parameters::kImuFilterComplementaryDoBiasEstimation().
c_str());
1697 connect(
_ui->doubleSpinBox_kp_roi0, SIGNAL(valueChanged(
double)),
this, SLOT(
updateKpROI()));
1698 connect(
_ui->doubleSpinBox_kp_roi1, SIGNAL(valueChanged(
double)),
this, SLOT(
updateKpROI()));
1699 connect(
_ui->doubleSpinBox_kp_roi2, SIGNAL(valueChanged(
double)),
this, SLOT(
updateKpROI()));
1700 connect(
_ui->doubleSpinBox_kp_roi3, SIGNAL(valueChanged(
double)),
this, SLOT(
updateKpROI()));
1701 connect(
_ui->checkBox_useOdomFeatures, SIGNAL(toggled(
bool)),
this, SLOT(
useOdomFeatures()));
1705 _ui->stackedWidget->setCurrentIndex(0);
1725 for(ParametersMap::const_iterator
iter=defaults.begin();
iter!=defaults.end(); ++
iter)
1740 for(
int i =0;
i<boxes.size();++
i)
1742 if(boxes[
i] ==
_ui->groupBox_source0)
1744 _ui->stackedWidget->setCurrentIndex(
i);
1760 _ui->treeView->setModel(0);
1766 if(
_ui->radioButton_basic->isChecked())
1768 boxes = boxes.mid(0,7);
1775 QStandardItem * parentItem =
_indexModel->invisibleRootItem();
1777 this->
parseModel(boxes, parentItem, 0, index);
1778 if(
_ui->radioButton_advanced->isChecked() && index !=
_ui->stackedWidget->count()-1)
1780 ULOGGER_ERROR(
"The tree model is not the same size of the stacked widgets...%d vs %d advanced stacks", index,
_ui->stackedWidget->count()-1);
1782 int currentIndex =
_ui->stackedWidget->currentIndex();
1783 if(
_ui->radioButton_basic->isChecked())
1785 if(currentIndex >= 6)
1787 _ui->stackedWidget->setCurrentIndex(6);
1793 if(currentIndex == 6)
1795 _ui->stackedWidget->setCurrentIndex(7);
1799 _ui->treeView->expandToDepth(1);
1802 connect(
_ui->treeView->selectionModel(), SIGNAL(currentChanged(
const QModelIndex &,
const QModelIndex &)),
this, SLOT(
clicked(
const QModelIndex &,
const QModelIndex &)));
1814 QStandardItem * currentItem = 0;
1815 while(absoluteIndex < boxes.size())
1817 QString objectName = boxes.at(absoluteIndex)->objectName();
1818 QString title = boxes.at(absoluteIndex)->title();
1820 int lvl = QString(objectName.at(objectName.size()-1)).toInt(&ok);
1823 ULOGGER_ERROR(
"Error while parsing the first number of the QGroupBox title (%s), the first character must be the number in the hierarchy", title.toStdString().c_str());
1828 if(lvl == currentLevel)
1830 QStandardItem * item =
new QStandardItem(title);
1831 item->setData(absoluteIndex);
1834 parentItem->appendRow(item);
1837 else if(lvl > currentLevel)
1839 if(lvl>currentLevel+1)
1841 ULOGGER_ERROR(
"Intermediary lvl doesn't exist, lvl %d to %d, indexes %d and %d", currentLevel, lvl, absoluteIndex-1, absoluteIndex);
1846 parseModel(boxes, currentItem, currentLevel+1, absoluteIndex);
1860 for(rtabmap::ParametersMap::const_iterator
iter=parameters.begin();
iter!=parameters.end(); ++
iter)
1862 QWidget * obj =
_ui->stackedWidget->findChild<QWidget*>((*iter).first.c_str());
1866 obj->setToolTip(tr(
"%1 (Default=\"%2\")").arg(
iter->first.c_str()).arg(
iter->second.c_str()));
1868 QSpinBox * spin = qobject_cast<QSpinBox *>(obj);
1869 QDoubleSpinBox * doubleSpin = qobject_cast<QDoubleSpinBox *>(obj);
1870 QComboBox * combo = qobject_cast<QComboBox *>(obj);
1871 QCheckBox *
check = qobject_cast<QCheckBox *>(obj);
1872 QRadioButton * radio = qobject_cast<QRadioButton *>(obj);
1873 QLineEdit * lineEdit = qobject_cast<QLineEdit *>(obj);
1874 QGroupBox * groupBox = qobject_cast<QGroupBox *>(obj);
1877 connect(spin, SIGNAL(valueChanged(
int)),
this, SLOT(
addParameter(
int)));
1881 connect(doubleSpin, SIGNAL(valueChanged(
double)),
this, SLOT(
addParameter(
double)));
1885 connect(combo, SIGNAL(currentIndexChanged(
int)),
this, SLOT(
addParameter(
int)));
1893 connect(radio, SIGNAL(toggled(
bool)),
this, SLOT(
addParameter(
bool)));
1897 connect(lineEdit, SIGNAL(textChanged(
const QString &)),
this, SLOT(
addParameter(
const QString &)));
1901 connect(groupBox, SIGNAL(toggled(
bool)),
this, SLOT(
addParameter(
bool)));
1905 ULOGGER_WARN(
"QWidget called %s can't be cast to a supported widget", (*iter).first.c_str());
1910 ULOGGER_WARN(
"Can't find the related QWidget for parameter %s", (*iter).first.c_str());
1917 QStandardItem * item =
_indexModel->itemFromIndex(current);
1918 if(item && item->isEnabled())
1920 int index = item->data().toInt();
1921 if(
_ui->radioButton_advanced->isChecked() && index >= 6)
1925 _ui->stackedWidget->setCurrentIndex(index);
1926 _ui->scrollArea->horizontalScrollBar()->setValue(0);
1927 _ui->scrollArea->verticalScrollBar()->setValue(0);
1945 QDialogButtonBox::ButtonRole role =
_ui->buttonBox_global->buttonRole(button);
1948 case QDialogButtonBox::RejectRole:
1956 case QDialogButtonBox::AcceptRole:
1979 QDialogButtonBox::ButtonRole role =
_ui->buttonBox_local->buttonRole(button);
1982 case QDialogButtonBox::ApplyRole:
1990 case QDialogButtonBox::ResetRole:
2001 if(groupBox->objectName() ==
_ui->groupBox_generalSettingsGui0->objectName())
2003 _ui->general_checkBox_imagesKept->setChecked(
true);
2004 _ui->general_checkBox_missing_cache_republished->setChecked(
true);
2005 _ui->general_checkBox_cloudsKept->setChecked(
true);
2006 _ui->checkBox_beep->setChecked(
false);
2007 _ui->checkBox_stamps->setChecked(
true);
2008 _ui->checkBox_cacheStatistics->setChecked(
true);
2009 _ui->checkBox_notifyWhenNewGlobalPathIsReceived->setChecked(
false);
2010 _ui->checkBox_verticalLayoutUsed->setChecked(
true);
2011 _ui->checkBox_imageRejectedShown->setChecked(
true);
2012 _ui->checkBox_imageHighestHypShown->setChecked(
false);
2013 _ui->spinBox_odomQualityWarnThr->setValue(50);
2014 _ui->checkBox_odom_onlyInliersShown->setChecked(
false);
2015 _ui->radioButton_posteriorGraphView->setChecked(
true);
2016 _ui->radioButton_wordsGraphView->setChecked(
false);
2017 _ui->radioButton_localizationsGraphView->setChecked(
false);
2018 _ui->radioButton_localizationsGraphViewOdomCache->setChecked(
false);
2019 _ui->radioButton_nochangeGraphView->setChecked(
false);
2020 _ui->checkbox_odomDisabled->setChecked(
false);
2021 _ui->checkbox_groundTruthAlign->setChecked(
true);
2023 else if(groupBox->objectName() ==
_ui->groupBox_cloudRendering1->objectName())
2025 for(
int i=0;
i<2; ++
i)
2050 _ui->doubleSpinBox_voxel->setValue(0);
2051 _ui->doubleSpinBox_noiseRadius->setValue(0);
2052 _ui->spinBox_noiseMinNeighbors->setValue(5);
2054 _ui->doubleSpinBox_ceilingFilterHeight->setValue(0);
2055 _ui->doubleSpinBox_floorFilterHeight->setValue(0);
2056 _ui->spinBox_normalKSearch->setValue(10);
2057 _ui->doubleSpinBox_normalRadiusSearch->setValue(0.0);
2059 _ui->doubleSpinBox_ceilingFilterHeight_scan->setValue(0);
2060 _ui->doubleSpinBox_floorFilterHeight_scan->setValue(0);
2061 _ui->spinBox_normalKSearch_scan->setValue(0);
2062 _ui->doubleSpinBox_normalRadiusSearch_scan->setValue(0.0);
2064 _ui->checkBox_showGraphs->setChecked(
true);
2065 _ui->checkBox_showLabels->setChecked(
false);
2066 _ui->checkBox_showFrames->setChecked(
false);
2067 _ui->checkBox_showLandmarks->setChecked(
true);
2068 _ui->doubleSpinBox_landmarkSize->setValue(0);
2069 _ui->checkBox_showIMUGravity->setChecked(
false);
2070 _ui->checkBox_showIMUAcc->setChecked(
false);
2072 _ui->doubleSpinBox_mesh_angleTolerance->setValue(15.0);
2073 _ui->groupBox_organized->setChecked(
false);
2074 #if PCL_VERSION_COMPARE(>=, 1, 7, 2)
2075 _ui->checkBox_mesh_quad->setChecked(
true);
2077 _ui->checkBox_mesh_quad->setChecked(
false);
2079 _ui->checkBox_mesh_texture->setChecked(
false);
2080 _ui->spinBox_mesh_triangleSize->setValue(2);
2082 else if(groupBox->objectName() ==
_ui->groupBox_filtering2->objectName())
2084 _ui->radioButton_noFiltering->setChecked(
true);
2085 _ui->radioButton_nodeFiltering->setChecked(
false);
2086 _ui->radioButton_subtractFiltering->setChecked(
false);
2087 _ui->doubleSpinBox_cloudFilterRadius->setValue(0.1);
2088 _ui->doubleSpinBox_cloudFilterAngle->setValue(30);
2089 _ui->spinBox_subtractFilteringMinPts->setValue(5);
2090 _ui->doubleSpinBox_subtractFilteringRadius->setValue(0.02);
2091 _ui->doubleSpinBox_subtractFilteringAngle->setValue(0);
2093 else if(groupBox->objectName() ==
_ui->groupBox_gridMap2->objectName())
2095 _ui->doubleSpinBox_map_resolution->setValue(0);
2096 _ui->checkBox_map_shown->setChecked(
false);
2097 _ui->doubleSpinBox_map_opacity->setValue(0.75);
2098 _ui->checkBox_elevation_shown->setCheckState(Qt::Unchecked);
2100 _ui->groupBox_octomap->setChecked(
false);
2101 _ui->spinBox_octomap_treeDepth->setValue(16);
2102 _ui->checkBox_octomap_2dgrid->setChecked(
true);
2103 _ui->checkBox_octomap_show3dMap->setChecked(
true);
2104 _ui->comboBox_octomap_renderingType->setCurrentIndex(0);
2105 _ui->spinBox_octomap_pointSize->setValue(5);
2107 else if(groupBox->objectName() ==
_ui->groupBox_logging1->objectName())
2109 _ui->comboBox_loggerLevel->setCurrentIndex(2);
2110 _ui->comboBox_loggerEventLevel->setCurrentIndex(3);
2111 _ui->comboBox_loggerPauseLevel->setCurrentIndex(3);
2112 _ui->checkBox_logger_printTime->setChecked(
true);
2113 _ui->checkBox_logger_printThreadId->setChecked(
false);
2114 _ui->comboBox_loggerType->setCurrentIndex(1);
2115 for(
int i=0;
i<
_ui->comboBox_loggerFilter->count(); ++
i)
2117 _ui->comboBox_loggerFilter->setItemChecked(
i,
false);
2120 else if(groupBox->objectName() ==
_ui->groupBox_source0->objectName())
2122 _ui->general_doubleSpinBox_imgRate->setValue(0.0);
2123 _ui->source_mirroring->setChecked(
false);
2124 _ui->lineEdit_calibrationFile->clear();
2125 _ui->comboBox_sourceType->setCurrentIndex(
kSrcRGBD);
2126 _ui->lineEdit_sourceDevice->setText(
"");
2127 _ui->lineEdit_sourceLocalTransform->setText(
"0 0 0 0 0 0");
2130 _ui->source_images_spinBox_startPos->setValue(0);
2131 _ui->source_images_spinBox_maxFrames->setValue(0);
2132 _ui->spinBox_usbcam_streamWidth->setValue(0);
2133 _ui->spinBox_usbcam_streamHeight->setValue(0);
2134 _ui->checkBox_rgb_rectify->setChecked(
false);
2135 _ui->comboBox_cameraImages_bayerMode->setCurrentIndex(0);
2137 _ui->source_checkBox_ignoreOdometry->setChecked(
false);
2138 _ui->source_checkBox_ignoreGoalDelay->setChecked(
true);
2139 _ui->source_checkBox_ignoreGoals->setChecked(
true);
2140 _ui->source_checkBox_ignoreLandmarks->setChecked(
true);
2141 _ui->source_checkBox_ignoreFeatures->setChecked(
true);
2142 _ui->source_checkBox_ignorePriors->setChecked(
false);
2143 _ui->source_spinBox_databaseStartId->setValue(0);
2144 _ui->source_spinBox_databaseStopId->setValue(0);
2145 _ui->source_lineEdit_databaseCameraIndex->setText(
"");
2146 _ui->source_checkBox_useDbStamps->setChecked(
true);
2177 _ui->checkbox_rgbd_colorOnly->setChecked(
false);
2178 _ui->spinBox_source_imageDecimation->setValue(1);
2179 _ui->comboBox_source_histogramMethod->setCurrentIndex(0);
2180 _ui->checkbox_source_feature_detection->setChecked(
false);
2181 _ui->checkbox_stereo_depthGenerated->setChecked(
false);
2182 _ui->checkBox_stereo_exposureCompensation->setChecked(
false);
2183 _ui->checkBox_stereo_rightGrayScale->setChecked(
true);
2184 _ui->openni2_autoWhiteBalance->setChecked(
true);
2185 _ui->openni2_autoExposure->setChecked(
true);
2186 _ui->openni2_exposure->setValue(0);
2187 _ui->openni2_gain->setValue(100);
2188 _ui->openni2_mirroring->setChecked(
false);
2189 _ui->openni2_stampsIdsUsed->setChecked(
false);
2190 _ui->openni2_hshift->setValue(0);
2191 _ui->openni2_vshift->setValue(0);
2192 _ui->openni2_depth_decimation->setValue(1);
2193 _ui->comboBox_freenect2Format->setCurrentIndex(1);
2194 _ui->doubleSpinBox_freenect2MinDepth->setValue(0.3);
2195 _ui->doubleSpinBox_freenect2MaxDepth->setValue(12.0);
2196 _ui->checkBox_freenect2BilateralFiltering->setChecked(
true);
2197 _ui->checkBox_freenect2EdgeAwareFiltering->setChecked(
true);
2198 _ui->checkBox_freenect2NoiseFiltering->setChecked(
true);
2199 _ui->lineEdit_freenect2Pipeline->setText(
"");
2200 _ui->comboBox_k4w2Format->setCurrentIndex(1);
2201 _ui->comboBox_realsensePresetRGB->setCurrentIndex(0);
2202 _ui->comboBox_realsensePresetDepth->setCurrentIndex(2);
2203 _ui->checkbox_realsenseOdom->setChecked(
false);
2204 _ui->checkbox_realsenseDepthScaledToRGBSize->setChecked(
false);
2205 _ui->comboBox_realsenseRGBSource->setCurrentIndex(0);
2206 _ui->checkbox_rs2_emitter->setChecked(
true);
2207 _ui->checkbox_rs2_irMode->setChecked(
false);
2208 _ui->checkbox_rs2_irDepth->setChecked(
true);
2209 _ui->spinBox_rs2_width->setValue(848);
2210 _ui->spinBox_rs2_height->setValue(480);
2211 _ui->spinBox_rs2_rate->setValue(60);
2212 _ui->spinBox_rs2_width_depth->setValue(640);
2213 _ui->spinBox_rs2_height_depth->setValue(480);
2214 _ui->spinBox_rs2_rate_depth->setValue(30);
2215 _ui->checkbox_rs2_globalTimeStync->setChecked(
true);
2216 _ui->lineEdit_rs2_jsonFile->clear();
2217 _ui->lineEdit_openniOniPath->clear();
2218 _ui->lineEdit_openni2OniPath->clear();
2219 _ui->comboBox_k4a_rgb_resolution->setCurrentIndex(0);
2220 _ui->comboBox_k4a_framerate->setCurrentIndex(2);
2221 _ui->comboBox_k4a_depth_resolution->setCurrentIndex(2);
2222 _ui->checkbox_k4a_irDepth->setChecked(
false);
2223 _ui->lineEdit_k4a_mkv->clear();
2224 _ui->source_checkBox_useMKVStamps->setChecked(
true);
2225 _ui->lineEdit_cameraRGBDImages_path_rgb->setText(
"");
2226 _ui->lineEdit_cameraRGBDImages_path_depth->setText(
"");
2227 _ui->doubleSpinBox_cameraRGBDImages_scale->setValue(1.0);
2228 _ui->spinBox_cameraRGBDImages_startIndex->setValue(0);
2229 _ui->spinBox_cameraRGBDImages_maxFrames->setValue(0);
2230 _ui->lineEdit_source_distortionModel->setText(
"");
2231 _ui->groupBox_bilateral->setChecked(
false);
2232 _ui->doubleSpinBox_bilateral_sigmaS->setValue(10.0);
2233 _ui->doubleSpinBox_bilateral_sigmaR->setValue(0.1);
2236 _ui->lineEdit_cameraStereoImages_path_left->setText(
"");
2237 _ui->lineEdit_cameraStereoImages_path_right->setText(
"");
2238 _ui->checkBox_stereo_rectify->setChecked(
false);
2239 _ui->spinBox_cameraStereoImages_startIndex->setValue(0);
2240 _ui->spinBox_cameraStereoImages_maxFrames->setValue(0);
2241 _ui->lineEdit_cameraStereoVideo_path->setText(
"");
2242 _ui->lineEdit_cameraStereoVideo_path_2->setText(
"");
2243 _ui->spinBox_stereo_right_device->setValue(-1);
2244 _ui->spinBox_stereousbcam_streamWidth->setValue(0);
2245 _ui->spinBox_stereousbcam_streamHeight->setValue(0);
2246 _ui->comboBox_stereoZed_resolution->setCurrentIndex(0);
2247 _ui->comboBox_stereoZed_quality->setCurrentIndex(1);
2248 _ui->checkbox_stereoZed_selfCalibration->setChecked(
true);
2249 _ui->comboBox_stereoZed_sensingMode->setCurrentIndex(0);
2250 _ui->spinBox_stereoZed_confidenceThr->setValue(100);
2251 _ui->spinBox_stereoZed_texturenessConfidenceThr->setValue(90);
2252 _ui->lineEdit_zedSvoPath->clear();
2253 _ui->comboBox_stereoZedOC_resolution->setCurrentIndex(3);
2254 _ui->checkbox_stereoMyntEye_rectify->setChecked(
false);
2255 _ui->checkbox_stereoMyntEye_depth->setChecked(
false);
2256 _ui->checkbox_stereoMyntEye_autoExposure->setChecked(
true);
2257 _ui->spinBox_stereoMyntEye_gain->setValue(24);
2258 _ui->spinBox_stereoMyntEye_brightness->setValue(120);
2259 _ui->spinBox_stereoMyntEye_contrast->setValue(116);
2260 _ui->spinBox_stereoMyntEye_irControl->setValue(0);
2261 _ui->comboBox_depthai_image_width->setCurrentIndex(1);
2262 _ui->comboBox_depthai_output_mode->setCurrentIndex(1);
2263 _ui->spinBox_depthai_conf_threshold->setValue(200);
2264 _ui->checkBox_depthai_extended_disparity->setChecked(
false);
2265 _ui->checkBox_depthai_disparity_companding->setChecked(
false);
2266 _ui->comboBox_depthai_subpixel_fractional_bits->setCurrentIndex(1);
2267 _ui->comboBox_depthai_disparity_width->setCurrentIndex(1);
2268 _ui->comboBox_depthai_median_filter->setCurrentIndex(2);
2269 _ui->spinBox_depthai_lrc_threshold->setValue(5);
2270 _ui->checkBox_depthai_use_spec_translation->setChecked(
false);
2271 _ui->doubleSpinBox_depthai_alpha_scaling->setValue(-1);
2272 _ui->checkBox_depthai_imu_published->setChecked(
true);
2273 _ui->doubleSpinBox_depthai_dot_intensity->setValue(0.0);
2274 _ui->doubleSpinBox_depthai_flood_intensity->setValue(0.0);
2275 _ui->comboBox_depthai_detect_features->setCurrentIndex(0);
2276 _ui->lineEdit_depthai_blob_path->clear();
2278 _ui->checkBox_cameraImages_configForEachFrame->setChecked(
false);
2279 _ui->checkBox_cameraImages_timestamps->setChecked(
false);
2280 _ui->checkBox_cameraImages_syncTimeStamps->setChecked(
true);
2281 _ui->lineEdit_cameraImages_timestamps->setText(
"");
2282 _ui->lineEdit_cameraImages_path_scans->setText(
"");
2283 _ui->lineEdit_cameraImages_laser_transform->setText(
"0 0 0 0 0 0");
2284 _ui->spinBox_cameraImages_max_scan_pts->setValue(0);
2285 _ui->lineEdit_cameraImages_odom->setText(
"");
2286 _ui->comboBox_cameraImages_odomFormat->setCurrentIndex(0);
2287 _ui->lineEdit_cameraImages_gt->setText(
"");
2288 _ui->comboBox_cameraImages_gtFormat->setCurrentIndex(0);
2289 _ui->doubleSpinBox_maxPoseTimeDiff->setValue(0.02);
2290 _ui->lineEdit_cameraImages_path_imu->setText(
"");
2291 _ui->lineEdit_cameraImages_imu_transform->setText(
"0 0 1 0 -1 0 1 0 0");
2292 _ui->spinBox_cameraImages_max_imu_rate->setValue(0);
2294 _ui->comboBox_odom_sensor->setCurrentIndex(0);
2295 _ui->lineEdit_odom_sensor_extrinsics->setText(
"-0.000622602 0.0303752 0.031389 -0.00272485 0.00749254 0.0");
2296 _ui->lineEdit_odom_sensor_path_calibration->setText(
"");
2297 _ui->lineEdit_odomSourceDevice->setText(
"");
2298 _ui->doubleSpinBox_odom_sensor_time_offset->setValue(0.0);
2299 _ui->doubleSpinBox_odom_sensor_scale_factor->setValue(1);
2300 _ui->doubleSpinBox_odom_sensor_wait_time->setValue(100);
2301 _ui->checkBox_odom_sensor_use_as_gt->setChecked(
false);
2303 _ui->comboBox_imuFilter_strategy->setCurrentIndex(2);
2304 _ui->doubleSpinBox_imuFilterMadgwickGain->setValue(Parameters::defaultImuFilterMadgwickGain());
2305 _ui->doubleSpinBox_imuFilterMadgwickZeta->setValue(Parameters::defaultImuFilterMadgwickZeta());
2306 _ui->doubleSpinBox_imuFilterComplementaryGainAcc->setValue(Parameters::defaultImuFilterComplementaryGainAcc());
2307 _ui->doubleSpinBox_imuFilterComplementaryBiasAlpha->setValue(Parameters::defaultImuFilterComplementaryBiasAlpha());
2308 _ui->checkBox_imuFilterComplementaryDoAdaptiveGain->setChecked(Parameters::defaultImuFilterComplementaryDoAdpativeGain());
2309 _ui->checkBox_imuFilterComplementaryDoBiasEstimation->setChecked(Parameters::defaultImuFilterComplementaryDoBiasEstimation());
2310 _ui->checkBox_imuFilter_baseFrameConversion->setChecked(
true);
2311 _ui->checkbox_publishInterIMU->setChecked(
false);
2313 _ui->comboBox_lidar_src->setCurrentIndex(0);
2314 _ui->checkBox_source_scanDeskewing->setChecked(
false);
2315 _ui->checkBox_source_scanFromDepth->setChecked(
false);
2316 _ui->spinBox_source_scanDownsampleStep->setValue(1);
2317 _ui->doubleSpinBox_source_scanRangeMin->setValue(0);
2318 _ui->doubleSpinBox_source_scanRangeMax->setValue(0);
2319 _ui->doubleSpinBox_source_scanVoxelSize->setValue(0.0
f);
2320 _ui->spinBox_source_scanNormalsK->setValue(0);
2321 _ui->doubleSpinBox_source_scanNormalsRadius->setValue(0.0);
2322 _ui->doubleSpinBox_source_scanNormalsForceGroundUp->setValue(0);
2324 _ui->lineEdit_lidar_local_transform->setText(
"0 0 0 0 0 0");
2325 _ui->lineEdit_vlp16_pcap_path->clear();
2326 _ui->spinBox_vlp16_ip1->setValue(192);
2327 _ui->spinBox_vlp16_ip2->setValue(168);
2328 _ui->spinBox_vlp16_ip3->setValue(1);
2329 _ui->spinBox_vlp16_ip4->setValue(201);
2330 _ui->spinBox_vlp16_port->setValue(2368);
2331 _ui->checkBox_vlp16_organized->setChecked(
false);
2332 _ui->checkBox_vlp16_hostTime->setChecked(
true);
2333 _ui->checkBox_vlp16_stamp_last->setChecked(
true);
2335 _ui->groupBox_depthFromScan->setChecked(
false);
2336 _ui->groupBox_depthFromScan_fillHoles->setChecked(
true);
2337 _ui->radioButton_depthFromScan_vertical->setChecked(
true);
2338 _ui->radioButton_depthFromScan_horizontal->setChecked(
false);
2339 _ui->checkBox_depthFromScan_fillBorders->setChecked(
false);
2341 else if(groupBox->objectName() ==
_ui->groupBox_rtabmap_basic0->objectName())
2343 _ui->general_doubleSpinBox_timeThr_2->setValue(Parameters::defaultRtabmapTimeThr());
2344 _ui->general_doubleSpinBox_hardThr_2->setValue(Parameters::defaultRtabmapLoopThr());
2345 _ui->doubleSpinBox_similarityThreshold_2->setValue(Parameters::defaultMemRehearsalSimilarity());
2346 _ui->general_spinBox_imagesBufferSize_2->setValue(Parameters::defaultRtabmapImageBufferSize());
2347 _ui->general_spinBox_maxStMemSize_2->setValue(Parameters::defaultMemSTMSize());
2348 _ui->general_checkBox_publishStats_2->setChecked(Parameters::defaultRtabmapPublishStats());
2349 _ui->general_checkBox_activateRGBD_2->setChecked(Parameters::defaultRGBDEnabled());
2350 _ui->general_checkBox_SLAM_mode_2->setChecked(Parameters::defaultMemIncrementalMemory());
2351 _ui->general_doubleSpinBox_detectionRate_2->setValue(Parameters::defaultRtabmapDetectionRate());
2353 _ui->general_doubleSpinBox_timeThr->setValue(Parameters::defaultRtabmapTimeThr());
2354 _ui->general_doubleSpinBox_hardThr->setValue(Parameters::defaultRtabmapLoopThr());
2355 _ui->doubleSpinBox_similarityThreshold->setValue(Parameters::defaultMemRehearsalSimilarity());
2356 _ui->general_spinBox_imagesBufferSize->setValue(Parameters::defaultRtabmapImageBufferSize());
2357 _ui->general_spinBox_maxStMemSize->setValue(Parameters::defaultMemSTMSize());
2358 _ui->general_doubleSpinBox_detectionRate->setValue(Parameters::defaultRtabmapDetectionRate());
2362 QObjectList children = groupBox->children();
2365 for(
int i=0;
i<children.size(); ++
i)
2367 key = children.at(
i)->objectName().toStdString();
2370 if(
key.compare(Parameters::kRtabmapWorkingDirectory().c_str()) == 0)
2378 if(qobject_cast<const QGroupBox*>(children.at(
i)))
2383 else if(qobject_cast<const QGroupBox*>(children.at(
i)))
2387 else if(qobject_cast<const QStackedWidget*>(children.at(
i)))
2389 QStackedWidget * stackedWidget = (QStackedWidget*)children.at(
i);
2390 for(
int j=0;
j<stackedWidget->count(); ++
j)
2392 const QObjectList & children2 = stackedWidget->widget(
j)->children();
2393 for(
int k=0; k<children2.size(); ++k)
2395 if(qobject_cast<QGroupBox *>(children2.at(k)))
2404 if(groupBox->findChild<QLineEdit*>(
_ui->lineEdit_kp_roi->objectName()))
2409 if(groupBox->objectName() ==
_ui->groupBox_odometry1->objectName())
2411 _ui->odom_registration->setCurrentIndex(3);
2412 _ui->odom_f2m_gravitySigma->setValue(-1);
2420 if(panelNumber >= 0 && panelNumber < boxes.size())
2424 else if(panelNumber == -1)
2426 for(QList<QGroupBox*>::iterator
iter = boxes.begin();
iter!=boxes.end(); ++
iter)
2433 ULOGGER_WARN(
"panel number and the number of stacked widget doesn't match");
2440 return _ui->lineEdit_workingDirectory->text();
2445 QString privatePath = QDir::homePath() +
"/.rtabmap";
2446 if(!QDir(privatePath).exists())
2448 QDir::home().mkdir(
".rtabmap");
2450 return privatePath +
"/rtabmap.ini";
2460 QString
path = QFileDialog::getOpenFileName(
this, tr(
"Load settings..."), this->
getWorkingDirectory(),
"*.ini");
2478 QStandardItem * parentItem =
_indexModel->invisibleRootItem();
2481 for(
int i=1;
i<parentItem->rowCount(); ++
i)
2483 parentItem->child(
i)->setEnabled(
false);
2486 _ui->radioButton_basic->setEnabled(
false);
2487 _ui->radioButton_advanced->setEnabled(
false);
2492 QStandardItem * parentItem =
_indexModel->invisibleRootItem();
2495 for(
int i=0;
i<parentItem->rowCount(); ++
i)
2497 parentItem->child(
i)->setEnabled(
true);
2500 _ui->radioButton_basic->setEnabled(
true);
2501 _ui->radioButton_advanced->setEnabled(
true);
2508 if(!filePath.isEmpty())
2512 QSettings settings(
path, QSettings::IniFormat);
2513 settings.beginGroup(
"Gui");
2514 settings.beginGroup(
"General");
2515 _ui->general_checkBox_imagesKept->setChecked(settings.value(
"imagesKept",
_ui->general_checkBox_imagesKept->isChecked()).toBool());
2516 _ui->general_checkBox_missing_cache_republished->setChecked(settings.value(
"missingRepublished",
_ui->general_checkBox_missing_cache_republished->isChecked()).toBool());
2517 _ui->general_checkBox_cloudsKept->setChecked(settings.value(
"cloudsKept",
_ui->general_checkBox_cloudsKept->isChecked()).toBool());
2518 _ui->comboBox_loggerLevel->setCurrentIndex(settings.value(
"loggerLevel",
_ui->comboBox_loggerLevel->currentIndex()).toInt());
2519 _ui->comboBox_loggerEventLevel->setCurrentIndex(settings.value(
"loggerEventLevel",
_ui->comboBox_loggerEventLevel->currentIndex()).toInt());
2520 _ui->comboBox_loggerPauseLevel->setCurrentIndex(settings.value(
"loggerPauseLevel",
_ui->comboBox_loggerPauseLevel->currentIndex()).toInt());
2521 _ui->comboBox_loggerType->setCurrentIndex(settings.value(
"loggerType",
_ui->comboBox_loggerType->currentIndex()).toInt());
2522 _ui->checkBox_logger_printTime->setChecked(settings.value(
"loggerPrintTime",
_ui->checkBox_logger_printTime->isChecked()).toBool());
2523 _ui->checkBox_logger_printThreadId->setChecked(settings.value(
"loggerPrintThreadId",
_ui->checkBox_logger_printThreadId->isChecked()).toBool());
2524 _ui->checkBox_verticalLayoutUsed->setChecked(settings.value(
"verticalLayoutUsed",
_ui->checkBox_verticalLayoutUsed->isChecked()).toBool());
2525 _ui->checkBox_imageRejectedShown->setChecked(settings.value(
"imageRejectedShown",
_ui->checkBox_imageRejectedShown->isChecked()).toBool());
2526 _ui->checkBox_imageHighestHypShown->setChecked(settings.value(
"imageHighestHypShown",
_ui->checkBox_imageHighestHypShown->isChecked()).toBool());
2527 _ui->checkBox_beep->setChecked(settings.value(
"beep",
_ui->checkBox_beep->isChecked()).toBool());
2528 _ui->checkBox_stamps->setChecked(settings.value(
"figure_time",
_ui->checkBox_stamps->isChecked()).toBool());
2529 _ui->checkBox_cacheStatistics->setChecked(settings.value(
"figure_cache",
_ui->checkBox_cacheStatistics->isChecked()).toBool());
2530 _ui->checkBox_notifyWhenNewGlobalPathIsReceived->setChecked(settings.value(
"notifyNewGlobalPath",
_ui->checkBox_notifyWhenNewGlobalPathIsReceived->isChecked()).toBool());
2531 _ui->spinBox_odomQualityWarnThr->setValue(settings.value(
"odomQualityThr",
_ui->spinBox_odomQualityWarnThr->value()).toInt());
2532 _ui->checkBox_odom_onlyInliersShown->setChecked(settings.value(
"odomOnlyInliersShown",
_ui->checkBox_odom_onlyInliersShown->isChecked()).toBool());
2533 _ui->radioButton_posteriorGraphView->setChecked(settings.value(
"posteriorGraphView",
_ui->radioButton_posteriorGraphView->isChecked()).toBool());
2534 _ui->radioButton_wordsGraphView->setChecked(settings.value(
"wordsGraphView",
_ui->radioButton_wordsGraphView->isChecked()).toBool());
2535 _ui->radioButton_localizationsGraphView->setChecked(settings.value(
"localizationsGraphView",
_ui->radioButton_localizationsGraphView->isChecked()).toBool());
2536 _ui->radioButton_localizationsGraphViewOdomCache->setChecked(settings.value(
"localizationsGraphViewOdomCache",
_ui->radioButton_localizationsGraphViewOdomCache->isChecked()).toBool());
2537 _ui->radioButton_nochangeGraphView->setChecked(settings.value(
"nochangeGraphView",
_ui->radioButton_nochangeGraphView->isChecked()).toBool());
2538 _ui->checkbox_odomDisabled->setChecked(settings.value(
"odomDisabled",
_ui->checkbox_odomDisabled->isChecked()).toBool());
2539 _ui->odom_registration->setCurrentIndex(settings.value(
"odomRegistration",
_ui->odom_registration->currentIndex()).toInt());
2540 _ui->odom_f2m_gravitySigma->setValue(settings.value(
"odomF2MGravitySigma",
_ui->odom_f2m_gravitySigma->value()).toDouble());
2541 _ui->checkbox_groundTruthAlign->setChecked(settings.value(
"gtAlign",
_ui->checkbox_groundTruthAlign->isChecked()).toBool());
2543 for(
int i=0;
i<2; ++
i)
2569 _ui->doubleSpinBox_voxel->setValue(settings.value(
"cloudVoxel",
_ui->doubleSpinBox_voxel->value()).toDouble());
2570 _ui->doubleSpinBox_noiseRadius->setValue(settings.value(
"cloudNoiseRadius",
_ui->doubleSpinBox_noiseRadius->value()).toDouble());
2571 _ui->spinBox_noiseMinNeighbors->setValue(settings.value(
"cloudNoiseMinNeighbors",
_ui->spinBox_noiseMinNeighbors->value()).toInt());
2572 _ui->doubleSpinBox_ceilingFilterHeight->setValue(settings.value(
"cloudCeilingHeight",
_ui->doubleSpinBox_ceilingFilterHeight->value()).toDouble());
2573 _ui->doubleSpinBox_floorFilterHeight->setValue(settings.value(
"cloudFloorHeight",
_ui->doubleSpinBox_floorFilterHeight->value()).toDouble());
2574 _ui->spinBox_normalKSearch->setValue(settings.value(
"normalKSearch",
_ui->spinBox_normalKSearch->value()).toInt());
2575 _ui->doubleSpinBox_normalRadiusSearch->setValue(settings.value(
"normalRadiusSearch",
_ui->doubleSpinBox_normalRadiusSearch->value()).toDouble());
2576 _ui->doubleSpinBox_ceilingFilterHeight_scan->setValue(settings.value(
"scanCeilingHeight",
_ui->doubleSpinBox_ceilingFilterHeight_scan->value()).toDouble());
2577 _ui->doubleSpinBox_floorFilterHeight_scan->setValue(settings.value(
"scanFloorHeight",
_ui->doubleSpinBox_floorFilterHeight_scan->value()).toDouble());
2578 _ui->spinBox_normalKSearch_scan->setValue(settings.value(
"scanNormalKSearch",
_ui->spinBox_normalKSearch_scan->value()).toInt());
2579 _ui->doubleSpinBox_normalRadiusSearch_scan->setValue(settings.value(
"scanNormalRadiusSearch",
_ui->doubleSpinBox_normalRadiusSearch_scan->value()).toDouble());
2581 _ui->checkBox_showGraphs->setChecked(settings.value(
"showGraphs",
_ui->checkBox_showGraphs->isChecked()).toBool());
2582 _ui->checkBox_showLabels->setChecked(settings.value(
"showLabels",
_ui->checkBox_showLabels->isChecked()).toBool());
2583 _ui->checkBox_showFrames->setChecked(settings.value(
"showFrames",
_ui->checkBox_showFrames->isChecked()).toBool());
2584 _ui->checkBox_showLandmarks->setChecked(settings.value(
"showLandmarks",
_ui->checkBox_showLandmarks->isChecked()).toBool());
2585 _ui->doubleSpinBox_landmarkSize->setValue(settings.value(
"landmarkSize",
_ui->doubleSpinBox_landmarkSize->value()).toDouble());
2586 _ui->checkBox_showIMUGravity->setChecked(settings.value(
"showIMUGravity",
_ui->checkBox_showIMUGravity->isChecked()).toBool());
2587 _ui->checkBox_showIMUAcc->setChecked(settings.value(
"showIMUAcc",
_ui->checkBox_showIMUAcc->isChecked()).toBool());
2589 _ui->radioButton_noFiltering->setChecked(settings.value(
"noFiltering",
_ui->radioButton_noFiltering->isChecked()).toBool());
2590 _ui->radioButton_nodeFiltering->setChecked(settings.value(
"cloudFiltering",
_ui->radioButton_nodeFiltering->isChecked()).toBool());
2591 _ui->doubleSpinBox_cloudFilterRadius->setValue(settings.value(
"cloudFilteringRadius",
_ui->doubleSpinBox_cloudFilterRadius->value()).toDouble());
2592 _ui->doubleSpinBox_cloudFilterAngle->setValue(settings.value(
"cloudFilteringAngle",
_ui->doubleSpinBox_cloudFilterAngle->value()).toDouble());
2593 _ui->radioButton_subtractFiltering->setChecked(settings.value(
"subtractFiltering",
_ui->radioButton_subtractFiltering->isChecked()).toBool());
2594 _ui->spinBox_subtractFilteringMinPts->setValue(settings.value(
"subtractFilteringMinPts",
_ui->spinBox_subtractFilteringMinPts->value()).toInt());
2595 _ui->doubleSpinBox_subtractFilteringRadius->setValue(settings.value(
"subtractFilteringRadius",
_ui->doubleSpinBox_subtractFilteringRadius->value()).toDouble());
2596 _ui->doubleSpinBox_subtractFilteringAngle->setValue(settings.value(
"subtractFilteringAngle",
_ui->doubleSpinBox_subtractFilteringAngle->value()).toDouble());
2598 _ui->doubleSpinBox_map_resolution->setValue(settings.value(
"gridUIResolution",
_ui->doubleSpinBox_map_resolution->value()).toDouble());
2599 _ui->checkBox_map_shown->setChecked(settings.value(
"gridMapShown",
_ui->checkBox_map_shown->isChecked()).toBool());
2600 _ui->doubleSpinBox_map_opacity->setValue(settings.value(
"gridMapOpacity",
_ui->doubleSpinBox_map_opacity->value()).toDouble());
2601 _ui->checkBox_elevation_shown->setCheckState((Qt::CheckState)settings.value(
"elevationMapShown",
_ui->checkBox_elevation_shown->checkState()).toInt());
2603 _ui->groupBox_octomap->setChecked(settings.value(
"octomap",
_ui->groupBox_octomap->isChecked()).toBool());
2604 _ui->spinBox_octomap_treeDepth->setValue(settings.value(
"octomap_depth",
_ui->spinBox_octomap_treeDepth->value()).toInt());
2605 _ui->checkBox_octomap_2dgrid->setChecked(settings.value(
"octomap_2dgrid",
_ui->checkBox_octomap_2dgrid->isChecked()).toBool());
2606 _ui->checkBox_octomap_show3dMap->setChecked(settings.value(
"octomap_3dmap",
_ui->checkBox_octomap_show3dMap->isChecked()).toBool());
2607 _ui->comboBox_octomap_renderingType->setCurrentIndex(settings.value(
"octomap_rendering_type",
_ui->comboBox_octomap_renderingType->currentIndex()).toInt());
2608 _ui->spinBox_octomap_pointSize->setValue(settings.value(
"octomap_point_size",
_ui->spinBox_octomap_pointSize->value()).toInt());
2610 _ui->groupBox_organized->setChecked(settings.value(
"meshing",
_ui->groupBox_organized->isChecked()).toBool());
2611 _ui->doubleSpinBox_mesh_angleTolerance->setValue(settings.value(
"meshing_angle",
_ui->doubleSpinBox_mesh_angleTolerance->value()).toDouble());
2612 _ui->checkBox_mesh_quad->setChecked(settings.value(
"meshing_quad",
_ui->checkBox_mesh_quad->isChecked()).toBool());
2613 _ui->checkBox_mesh_texture->setChecked(settings.value(
"meshing_texture",
_ui->checkBox_mesh_texture->isChecked()).toBool());
2614 _ui->spinBox_mesh_triangleSize->setValue(settings.value(
"meshing_triangle_size",
_ui->spinBox_mesh_triangleSize->value()).toInt());
2616 settings.endGroup();
2618 settings.endGroup();
2624 if(!filePath.isEmpty())
2628 QSettings settings(
path, QSettings::IniFormat);
2630 settings.beginGroup(
"Camera");
2631 _ui->general_doubleSpinBox_imgRate->setValue(settings.value(
"imgRate",
_ui->general_doubleSpinBox_imgRate->value()).toDouble());
2632 _ui->source_mirroring->setChecked(settings.value(
"mirroring",
_ui->source_mirroring->isChecked()).toBool());
2633 _ui->lineEdit_calibrationFile->setText(settings.value(
"calibrationName",
_ui->lineEdit_calibrationFile->text()).toString());
2634 _ui->comboBox_sourceType->setCurrentIndex(settings.value(
"type",
_ui->comboBox_sourceType->currentIndex()).toInt());
2635 _ui->lineEdit_sourceDevice->setText(settings.value(
"device",
_ui->lineEdit_sourceDevice->text()).toString());
2636 _ui->lineEdit_sourceLocalTransform->setText(settings.value(
"localTransform",
_ui->lineEdit_sourceLocalTransform->text()).toString());
2637 _ui->spinBox_source_imageDecimation->setValue(settings.value(
"imageDecimation",
_ui->spinBox_source_imageDecimation->value()).toInt());
2638 _ui->comboBox_source_histogramMethod->setCurrentIndex(settings.value(
"histogramMethod",
_ui->comboBox_source_histogramMethod->currentIndex()).toInt());
2639 _ui->checkbox_source_feature_detection->setChecked(settings.value(
"featureDetection",
_ui->checkbox_source_feature_detection->isChecked()).toBool());
2641 if(
_ui->lineEdit_sourceLocalTransform->text().compare(
"0 0 1 -1 0 0 0 -1 0") == 0)
2643 UWARN(
"From 0.20.11, the local transform of the camera should not contain optical rotation (read=\"%s\"). Resetting to default Identity for convenience.",
_ui->lineEdit_sourceLocalTransform->text().toStdString().c_str());
2644 _ui->lineEdit_sourceLocalTransform->setText(
"0 0 0 0 0 0");
2647 settings.beginGroup(
"rgbd");
2648 _ui->comboBox_cameraRGBD->setCurrentIndex(settings.value(
"driver",
_ui->comboBox_cameraRGBD->currentIndex()).toInt());
2649 _ui->checkbox_rgbd_colorOnly->setChecked(settings.value(
"rgbdColorOnly",
_ui->checkbox_rgbd_colorOnly->isChecked()).toBool());
2650 _ui->lineEdit_source_distortionModel->setText(settings.value(
"distortion_model",
_ui->lineEdit_source_distortionModel->text()).toString());
2651 _ui->groupBox_bilateral->setChecked(settings.value(
"bilateral",
_ui->groupBox_bilateral->isChecked()).toBool());
2652 _ui->doubleSpinBox_bilateral_sigmaS->setValue(settings.value(
"bilateral_sigma_s",
_ui->doubleSpinBox_bilateral_sigmaS->value()).toDouble());
2653 _ui->doubleSpinBox_bilateral_sigmaR->setValue(settings.value(
"bilateral_sigma_r",
_ui->doubleSpinBox_bilateral_sigmaR->value()).toDouble());
2654 settings.endGroup();
2656 settings.beginGroup(
"stereo");
2657 _ui->comboBox_cameraStereo->setCurrentIndex(settings.value(
"driver",
_ui->comboBox_cameraStereo->currentIndex()).toInt());
2658 _ui->checkbox_stereo_depthGenerated->setChecked(settings.value(
"depthGenerated",
_ui->checkbox_stereo_depthGenerated->isChecked()).toBool());
2659 _ui->checkBox_stereo_exposureCompensation->setChecked(settings.value(
"exposureCompensation",
_ui->checkBox_stereo_exposureCompensation->isChecked()).toBool());
2660 _ui->checkBox_stereo_rightGrayScale->setChecked(settings.value(
"rightGrayScale",
_ui->checkBox_stereo_rightGrayScale->isChecked()).toBool());
2661 settings.endGroup();
2663 settings.beginGroup(
"rgb");
2664 _ui->source_comboBox_image_type->setCurrentIndex(settings.value(
"driver",
_ui->source_comboBox_image_type->currentIndex()).toInt());
2665 _ui->checkBox_rgb_rectify->setChecked(settings.value(
"rectify",
_ui->checkBox_rgb_rectify->isChecked()).toBool());
2666 settings.endGroup();
2668 settings.beginGroup(
"Openni");
2669 _ui->lineEdit_openniOniPath->setText(settings.value(
"oniPath",
_ui->lineEdit_openniOniPath->text()).toString());
2670 settings.endGroup();
2672 settings.beginGroup(
"Openni2");
2673 _ui->openni2_autoWhiteBalance->setChecked(settings.value(
"autoWhiteBalance",
_ui->openni2_autoWhiteBalance->isChecked()).toBool());
2674 _ui->openni2_autoExposure->setChecked(settings.value(
"autoExposure",
_ui->openni2_autoExposure->isChecked()).toBool());
2675 _ui->openni2_exposure->setValue(settings.value(
"exposure",
_ui->openni2_exposure->value()).toInt());
2676 _ui->openni2_gain->setValue(settings.value(
"gain",
_ui->openni2_gain->value()).toInt());
2677 _ui->openni2_mirroring->setChecked(settings.value(
"mirroring",
_ui->openni2_mirroring->isChecked()).toBool());
2678 _ui->openni2_stampsIdsUsed->setChecked(settings.value(
"stampsIdsUsed",
_ui->openni2_stampsIdsUsed->isChecked()).toBool());
2679 _ui->lineEdit_openni2OniPath->setText(settings.value(
"oniPath",
_ui->lineEdit_openni2OniPath->text()).toString());
2680 _ui->openni2_hshift->setValue(settings.value(
"hshift",
_ui->openni2_hshift->value()).toInt());
2681 _ui->openni2_vshift->setValue(settings.value(
"vshift",
_ui->openni2_vshift->value()).toInt());
2682 _ui->openni2_depth_decimation->setValue(settings.value(
"depthDecimation",
_ui->openni2_depth_decimation->value()).toInt());
2683 settings.endGroup();
2685 settings.beginGroup(
"Freenect2");
2686 _ui->comboBox_freenect2Format->setCurrentIndex(settings.value(
"format",
_ui->comboBox_freenect2Format->currentIndex()).toInt());
2687 _ui->doubleSpinBox_freenect2MinDepth->setValue(settings.value(
"minDepth",
_ui->doubleSpinBox_freenect2MinDepth->value()).toDouble());
2688 _ui->doubleSpinBox_freenect2MaxDepth->setValue(settings.value(
"maxDepth",
_ui->doubleSpinBox_freenect2MaxDepth->value()).toDouble());
2689 _ui->checkBox_freenect2BilateralFiltering->setChecked(settings.value(
"bilateralFiltering",
_ui->checkBox_freenect2BilateralFiltering->isChecked()).toBool());
2690 _ui->checkBox_freenect2EdgeAwareFiltering->setChecked(settings.value(
"edgeAwareFiltering",
_ui->checkBox_freenect2EdgeAwareFiltering->isChecked()).toBool());
2691 _ui->checkBox_freenect2NoiseFiltering->setChecked(settings.value(
"noiseFiltering",
_ui->checkBox_freenect2NoiseFiltering->isChecked()).toBool());
2692 _ui->lineEdit_freenect2Pipeline->setText(settings.value(
"pipeline",
_ui->lineEdit_freenect2Pipeline->text()).toString());
2693 settings.endGroup();
2695 settings.beginGroup(
"K4W2");
2696 _ui->comboBox_k4w2Format->setCurrentIndex(settings.value(
"format",
_ui->comboBox_k4w2Format->currentIndex()).toInt());
2697 settings.endGroup();
2699 settings.beginGroup(
"K4A");
2700 _ui->comboBox_k4a_rgb_resolution->setCurrentIndex(settings.value(
"rgb_resolution",
_ui->comboBox_k4a_rgb_resolution->currentIndex()).toInt());
2701 _ui->comboBox_k4a_framerate->setCurrentIndex(settings.value(
"framerate",
_ui->comboBox_k4a_framerate->currentIndex()).toInt());
2702 _ui->comboBox_k4a_depth_resolution->setCurrentIndex(settings.value(
"depth_resolution",
_ui->comboBox_k4a_depth_resolution->currentIndex()).toInt());
2703 _ui->checkbox_k4a_irDepth->setChecked(settings.value(
"ir",
_ui->checkbox_k4a_irDepth->isChecked()).toBool());
2704 _ui->lineEdit_k4a_mkv->setText(settings.value(
"mkvPath",
_ui->lineEdit_k4a_mkv->text()).toString());
2705 _ui->source_checkBox_useMKVStamps->setChecked(settings.value(
"useMkvStamps",
_ui->source_checkBox_useMKVStamps->isChecked()).toBool());
2706 settings.endGroup();
2708 settings.beginGroup(
"RealSense");
2709 _ui->comboBox_realsensePresetRGB->setCurrentIndex(settings.value(
"presetRGB",
_ui->comboBox_realsensePresetRGB->currentIndex()).toInt());
2710 _ui->comboBox_realsensePresetDepth->setCurrentIndex(settings.value(
"presetDepth",
_ui->comboBox_realsensePresetDepth->currentIndex()).toInt());
2711 _ui->checkbox_realsenseOdom->setChecked(settings.value(
"odom",
_ui->checkbox_realsenseOdom->isChecked()).toBool());
2712 _ui->checkbox_realsenseDepthScaledToRGBSize->setChecked(settings.value(
"depthScaled",
_ui->checkbox_realsenseDepthScaledToRGBSize->isChecked()).toBool());
2713 _ui->comboBox_realsenseRGBSource->setCurrentIndex(settings.value(
"rgbSource",
_ui->comboBox_realsenseRGBSource->currentIndex()).toInt());
2714 settings.endGroup();
2716 settings.beginGroup(
"RealSense2");
2717 _ui->checkbox_rs2_emitter->setChecked(settings.value(
"emitter",
_ui->checkbox_rs2_emitter->isChecked()).toBool());
2718 _ui->checkbox_rs2_irMode->setChecked(settings.value(
"ir",
_ui->checkbox_rs2_irMode->isChecked()).toBool());
2719 _ui->checkbox_rs2_irDepth->setChecked(settings.value(
"irdepth",
_ui->checkbox_rs2_irDepth->isChecked()).toBool());
2720 _ui->spinBox_rs2_width->setValue(settings.value(
"width",
_ui->spinBox_rs2_width->value()).toInt());
2721 _ui->spinBox_rs2_height->setValue(settings.value(
"height",
_ui->spinBox_rs2_height->value()).toInt());
2722 _ui->spinBox_rs2_rate->setValue(settings.value(
"rate",
_ui->spinBox_rs2_rate->value()).toInt());
2723 _ui->spinBox_rs2_width_depth->setValue(settings.value(
"width_depth",
_ui->spinBox_rs2_width_depth->value()).toInt());
2724 _ui->spinBox_rs2_height_depth->setValue(settings.value(
"height_depth",
_ui->spinBox_rs2_height_depth->value()).toInt());
2725 _ui->spinBox_rs2_rate_depth->setValue(settings.value(
"rate_depth",
_ui->spinBox_rs2_rate_depth->value()).toInt());
2726 _ui->checkbox_rs2_globalTimeStync->setChecked(settings.value(
"global_time_sync",
_ui->checkbox_rs2_globalTimeStync->isChecked()).toBool());
2727 _ui->lineEdit_rs2_jsonFile->setText(settings.value(
"json_preset",
_ui->lineEdit_rs2_jsonFile->text()).toString());
2728 settings.endGroup();
2730 settings.beginGroup(
"RGBDImages");
2731 _ui->lineEdit_cameraRGBDImages_path_rgb->setText(settings.value(
"path_rgb",
_ui->lineEdit_cameraRGBDImages_path_rgb->text()).toString());
2732 _ui->lineEdit_cameraRGBDImages_path_depth->setText(settings.value(
"path_depth",
_ui->lineEdit_cameraRGBDImages_path_depth->text()).toString());
2733 _ui->doubleSpinBox_cameraRGBDImages_scale->setValue(settings.value(
"scale",
_ui->doubleSpinBox_cameraRGBDImages_scale->value()).toDouble());
2734 _ui->spinBox_cameraRGBDImages_startIndex->setValue(settings.value(
"start_index",
_ui->spinBox_cameraRGBDImages_startIndex->value()).toInt());
2735 _ui->spinBox_cameraRGBDImages_maxFrames->setValue(settings.value(
"max_frames",
_ui->spinBox_cameraRGBDImages_maxFrames->value()).toInt());
2736 settings.endGroup();
2738 settings.beginGroup(
"StereoImages");
2739 _ui->lineEdit_cameraStereoImages_path_left->setText(settings.value(
"path_left",
_ui->lineEdit_cameraStereoImages_path_left->text()).toString());
2740 _ui->lineEdit_cameraStereoImages_path_right->setText(settings.value(
"path_right",
_ui->lineEdit_cameraStereoImages_path_right->text()).toString());
2741 _ui->checkBox_stereo_rectify->setChecked(settings.value(
"rectify",
_ui->checkBox_stereo_rectify->isChecked()).toBool());
2742 _ui->spinBox_cameraStereoImages_startIndex->setValue(settings.value(
"start_index",
_ui->spinBox_cameraStereoImages_startIndex->value()).toInt());
2743 _ui->spinBox_cameraStereoImages_maxFrames->setValue(settings.value(
"max_frames",
_ui->spinBox_cameraStereoImages_maxFrames->value()).toInt());
2744 settings.endGroup();
2746 settings.beginGroup(
"StereoVideo");
2747 _ui->lineEdit_cameraStereoVideo_path->setText(settings.value(
"path",
_ui->lineEdit_cameraStereoVideo_path->text()).toString());
2748 _ui->lineEdit_cameraStereoVideo_path_2->setText(settings.value(
"path2",
_ui->lineEdit_cameraStereoVideo_path_2->text()).toString());
2749 _ui->spinBox_stereo_right_device->setValue(settings.value(
"device2",
_ui->spinBox_stereo_right_device->value()).toInt());
2750 _ui->spinBox_stereousbcam_streamWidth->setValue(settings.value(
"width",
_ui->spinBox_stereousbcam_streamWidth->value()).toInt());
2751 _ui->spinBox_stereousbcam_streamHeight->setValue(settings.value(
"height",
_ui->spinBox_stereousbcam_streamHeight->value()).toInt());
2752 _ui->lineEdit_stereousbcam_fourcc->setText(settings.value(
"fourcc",
_ui->lineEdit_stereousbcam_fourcc->text()).toString());
2753 settings.endGroup();
2755 settings.beginGroup(
"StereoZed");
2756 _ui->comboBox_stereoZed_resolution->setCurrentIndex(settings.value(
"resolution",
_ui->comboBox_stereoZed_resolution->currentIndex()).toInt());
2757 _ui->comboBox_stereoZed_quality->setCurrentIndex(settings.value(
"quality",
_ui->comboBox_stereoZed_quality->currentIndex()).toInt());
2758 _ui->checkbox_stereoZed_selfCalibration->setChecked(settings.value(
"self_calibration",
_ui->checkbox_stereoZed_selfCalibration->isChecked()).toBool());
2759 _ui->comboBox_stereoZed_sensingMode->setCurrentIndex(settings.value(
"sensing_mode",
_ui->comboBox_stereoZed_sensingMode->currentIndex()).toInt());
2760 _ui->spinBox_stereoZed_confidenceThr->setValue(settings.value(
"confidence_thr",
_ui->spinBox_stereoZed_confidenceThr->value()).toInt());
2761 _ui->spinBox_stereoZed_texturenessConfidenceThr->setValue(settings.value(
"textureness_confidence_thr",
_ui->spinBox_stereoZed_texturenessConfidenceThr->value()).toInt());
2762 _ui->lineEdit_zedSvoPath->setText(settings.value(
"svo_path",
_ui->lineEdit_zedSvoPath->text()).toString());
2763 settings.endGroup();
2765 settings.beginGroup(
"MyntEye");
2766 _ui->checkbox_stereoMyntEye_rectify->setChecked(settings.value(
"rectify",
_ui->checkbox_stereoMyntEye_rectify->isChecked()).toBool());
2767 _ui->checkbox_stereoMyntEye_depth->setChecked(settings.value(
"depth",
_ui->checkbox_stereoMyntEye_depth->isChecked()).toBool());
2768 _ui->checkbox_stereoMyntEye_autoExposure->setChecked(settings.value(
"auto_exposure",
_ui->checkbox_stereoMyntEye_autoExposure->isChecked()).toBool());
2769 _ui->spinBox_stereoMyntEye_gain->setValue(settings.value(
"gain",
_ui->spinBox_stereoMyntEye_gain->value()).toInt());
2770 _ui->spinBox_stereoMyntEye_brightness->setValue(settings.value(
"brightness",
_ui->spinBox_stereoMyntEye_brightness->value()).toInt());
2771 _ui->spinBox_stereoMyntEye_contrast->setValue(settings.value(
"contrast",
_ui->spinBox_stereoMyntEye_contrast->value()).toInt());
2772 _ui->spinBox_stereoMyntEye_irControl->setValue(settings.value(
"ir_control",
_ui->spinBox_stereoMyntEye_irControl->value()).toInt());
2773 settings.endGroup();
2775 settings.beginGroup(
"DepthAI");
2776 _ui->comboBox_depthai_image_width->setCurrentIndex(settings.value(
"image_width",
_ui->comboBox_depthai_image_width->currentIndex()).toInt());
2777 _ui->comboBox_depthai_output_mode->setCurrentIndex(settings.value(
"output_mode",
_ui->comboBox_depthai_output_mode->currentIndex()).toInt());
2778 _ui->spinBox_depthai_conf_threshold->setValue(settings.value(
"conf_threshold",
_ui->spinBox_depthai_conf_threshold->value()).toInt());
2779 _ui->spinBox_depthai_lrc_threshold->setValue(settings.value(
"lrc_threshold",
_ui->spinBox_depthai_lrc_threshold->value()).toInt());
2780 _ui->checkBox_depthai_extended_disparity->setChecked(settings.value(
"extended_disparity",
_ui->checkBox_depthai_extended_disparity->isChecked()).toBool());
2781 _ui->checkBox_depthai_disparity_companding->setChecked(settings.value(
"disparity_companding",
_ui->checkBox_depthai_disparity_companding->isChecked()).toBool());
2782 _ui->comboBox_depthai_subpixel_fractional_bits->setCurrentIndex(settings.value(
"subpixel_fractional_bits",
_ui->comboBox_depthai_subpixel_fractional_bits->currentIndex()).toInt());
2783 _ui->comboBox_depthai_disparity_width->setCurrentIndex(settings.value(
"disparity_width",
_ui->comboBox_depthai_disparity_width->currentIndex()).toInt());
2784 _ui->comboBox_depthai_median_filter->setCurrentIndex(settings.value(
"median_filter",
_ui->comboBox_depthai_median_filter->currentIndex()).toInt());
2785 _ui->checkBox_depthai_use_spec_translation->setChecked(settings.value(
"use_spec_translation",
_ui->checkBox_depthai_use_spec_translation->isChecked()).toBool());
2786 _ui->doubleSpinBox_depthai_alpha_scaling->setValue(settings.value(
"alpha_scaling",
_ui->doubleSpinBox_depthai_alpha_scaling->value()).toDouble());
2787 _ui->checkBox_depthai_imu_published->setChecked(settings.value(
"imu_published",
_ui->checkBox_depthai_imu_published->isChecked()).toBool());
2788 _ui->doubleSpinBox_depthai_dot_intensity->setValue(settings.value(
"dot_intensity",
_ui->doubleSpinBox_depthai_dot_intensity->value()).toDouble());
2789 _ui->doubleSpinBox_depthai_flood_intensity->setValue(settings.value(
"flood_intensity",
_ui->doubleSpinBox_depthai_flood_intensity->value()).toDouble());
2790 _ui->comboBox_depthai_detect_features->setCurrentIndex(settings.value(
"detect_features",
_ui->comboBox_depthai_detect_features->currentIndex()).toInt());
2791 _ui->lineEdit_depthai_blob_path->setText(settings.value(
"blob_path",
_ui->lineEdit_depthai_blob_path->text()).toString());
2792 settings.endGroup();
2794 settings.beginGroup(
"Images");
2795 _ui->source_images_lineEdit_path->setText(settings.value(
"path",
_ui->source_images_lineEdit_path->text()).toString());
2796 _ui->source_images_spinBox_startPos->setValue(settings.value(
"startPos",
_ui->source_images_spinBox_startPos->value()).toInt());
2797 _ui->source_images_spinBox_maxFrames->setValue(settings.value(
"maxFrames",
_ui->source_images_spinBox_maxFrames->value()).toInt());
2798 _ui->comboBox_cameraImages_bayerMode->setCurrentIndex(settings.value(
"bayerMode",
_ui->comboBox_cameraImages_bayerMode->currentIndex()).toInt());
2800 _ui->checkBox_cameraImages_configForEachFrame->setChecked(settings.value(
"config_each_frame",
_ui->checkBox_cameraImages_configForEachFrame->isChecked()).toBool());
2801 _ui->checkBox_cameraImages_timestamps->setChecked(settings.value(
"filenames_as_stamps",
_ui->checkBox_cameraImages_timestamps->isChecked()).toBool());
2802 _ui->checkBox_cameraImages_syncTimeStamps->setChecked(settings.value(
"sync_stamps",
_ui->checkBox_cameraImages_syncTimeStamps->isChecked()).toBool());
2803 _ui->lineEdit_cameraImages_timestamps->setText(settings.value(
"stamps",
_ui->lineEdit_cameraImages_timestamps->text()).toString());
2804 _ui->lineEdit_cameraImages_path_scans->setText(settings.value(
"path_scans",
_ui->lineEdit_cameraImages_path_scans->text()).toString());
2805 _ui->lineEdit_cameraImages_laser_transform->setText(settings.value(
"scan_transform",
_ui->lineEdit_cameraImages_laser_transform->text()).toString());
2806 _ui->spinBox_cameraImages_max_scan_pts->setValue(settings.value(
"scan_max_pts",
_ui->spinBox_cameraImages_max_scan_pts->value()).toInt());
2807 _ui->lineEdit_cameraImages_odom->setText(settings.value(
"odom_path",
_ui->lineEdit_cameraImages_odom->text()).toString());
2808 _ui->comboBox_cameraImages_odomFormat->setCurrentIndex(settings.value(
"odom_format",
_ui->comboBox_cameraImages_odomFormat->currentIndex()).toInt());
2809 _ui->lineEdit_cameraImages_gt->setText(settings.value(
"gt_path",
_ui->lineEdit_cameraImages_gt->text()).toString());
2810 _ui->comboBox_cameraImages_gtFormat->setCurrentIndex(settings.value(
"gt_format",
_ui->comboBox_cameraImages_gtFormat->currentIndex()).toInt());
2811 _ui->doubleSpinBox_maxPoseTimeDiff->setValue(settings.value(
"max_pose_time_diff",
_ui->doubleSpinBox_maxPoseTimeDiff->value()).toDouble());
2813 _ui->lineEdit_cameraImages_path_imu->setText(settings.value(
"imu_path",
_ui->lineEdit_cameraImages_path_imu->text()).toString());
2814 _ui->lineEdit_cameraImages_imu_transform->setText(settings.value(
"imu_local_transform",
_ui->lineEdit_cameraImages_imu_transform->text()).toString());
2815 _ui->spinBox_cameraImages_max_imu_rate->setValue(settings.value(
"imu_rate",
_ui->spinBox_cameraImages_max_imu_rate->value()).toInt());
2816 settings.endGroup();
2818 settings.beginGroup(
"OdomSensor");
2819 _ui->comboBox_odom_sensor->setCurrentIndex(settings.value(
"odom_sensor",
_ui->comboBox_odom_sensor->currentIndex()).toInt());
2820 _ui->lineEdit_odom_sensor_extrinsics->setText(settings.value(
"odom_sensor_extrinsics",
_ui->lineEdit_odom_sensor_extrinsics->text()).toString());
2821 _ui->lineEdit_odom_sensor_path_calibration->setText(settings.value(
"odom_sensor_calibration_path",
_ui->lineEdit_odom_sensor_path_calibration->text()).toString());
2822 _ui->lineEdit_odomSourceDevice->setText(settings.value(
"odom_sensor_device",
_ui->lineEdit_odomSourceDevice->text()).toString());
2823 _ui->doubleSpinBox_odom_sensor_time_offset->setValue(settings.value(
"odom_sensor_offset_time",
_ui->doubleSpinBox_odom_sensor_time_offset->value()).toDouble());
2824 _ui->doubleSpinBox_odom_sensor_scale_factor->setValue(settings.value(
"odom_sensor_scale_factor",
_ui->doubleSpinBox_odom_sensor_scale_factor->value()).toDouble());
2825 _ui->doubleSpinBox_odom_sensor_wait_time->setValue(settings.value(
"odom_sensor_wait_time",
_ui->doubleSpinBox_odom_sensor_wait_time->value()).toDouble());
2826 _ui->checkBox_odom_sensor_use_as_gt->setChecked(settings.value(
"odom_sensor_odom_as_gt",
_ui->checkBox_odom_sensor_use_as_gt->isChecked()).toBool());
2827 settings.endGroup();
2829 settings.beginGroup(
"UsbCam");
2830 _ui->spinBox_usbcam_streamWidth->setValue(settings.value(
"width",
_ui->spinBox_usbcam_streamWidth->value()).toInt());
2831 _ui->spinBox_usbcam_streamHeight->setValue(settings.value(
"height",
_ui->spinBox_usbcam_streamHeight->value()).toInt());
2832 _ui->lineEdit_usbcam_fourcc->setText(settings.value(
"fourcc",
_ui->lineEdit_usbcam_fourcc->text()).toString());
2833 settings.endGroup();
2835 settings.beginGroup(
"Video");
2836 _ui->source_video_lineEdit_path->setText(settings.value(
"path",
_ui->source_video_lineEdit_path->text()).toString());
2837 settings.endGroup();
2839 settings.beginGroup(
"IMU");
2840 _ui->comboBox_imuFilter_strategy->setCurrentIndex(settings.value(
"strategy",
_ui->comboBox_imuFilter_strategy->currentIndex()).toInt());
2841 _ui->doubleSpinBox_imuFilterMadgwickGain->setValue(settings.value(
"madgwick_gain",
_ui->doubleSpinBox_imuFilterMadgwickGain->value()).toDouble());
2842 _ui->doubleSpinBox_imuFilterMadgwickZeta->setValue(settings.value(
"madgwick_zeta",
_ui->doubleSpinBox_imuFilterMadgwickZeta->value()).toDouble());
2843 _ui->doubleSpinBox_imuFilterComplementaryGainAcc->setValue(settings.value(
"complementary_gain_acc",
_ui->doubleSpinBox_imuFilterComplementaryGainAcc->value()).toDouble());
2844 _ui->doubleSpinBox_imuFilterComplementaryBiasAlpha->setValue(settings.value(
"complementary_bias_alpha",
_ui->doubleSpinBox_imuFilterComplementaryBiasAlpha->value()).toDouble());
2845 _ui->checkBox_imuFilterComplementaryDoAdaptiveGain->setChecked(settings.value(
"complementary_adaptive_gain",
_ui->checkBox_imuFilterComplementaryDoAdaptiveGain->isChecked()).toBool());
2846 _ui->checkBox_imuFilterComplementaryDoBiasEstimation->setChecked(settings.value(
"complementary_biais_estimation",
_ui->checkBox_imuFilterComplementaryDoBiasEstimation->isChecked()).toBool());
2847 _ui->checkBox_imuFilter_baseFrameConversion->setChecked(settings.value(
"base_frame_conversion",
_ui->checkBox_imuFilter_baseFrameConversion->isChecked()).toBool());
2848 _ui->checkbox_publishInterIMU->setChecked(settings.value(
"publish_inter_imu",
_ui->checkbox_publishInterIMU->isChecked()).toBool());
2849 settings.endGroup();
2851 settings.beginGroup(
"Scan");
2852 _ui->comboBox_lidar_src->setCurrentIndex(settings.value(
"source",
_ui->comboBox_lidar_src->currentIndex()).toInt());
2853 _ui->checkBox_source_scanDeskewing->setChecked(settings.value(
"deskewing",
_ui->checkBox_source_scanDeskewing->isChecked()).toBool());
2854 _ui->checkBox_source_scanFromDepth->setChecked(settings.value(
"fromDepth",
_ui->checkBox_source_scanFromDepth->isChecked()).toBool());
2855 _ui->spinBox_source_scanDownsampleStep->setValue(settings.value(
"downsampleStep",
_ui->spinBox_source_scanDownsampleStep->value()).toInt());
2856 _ui->doubleSpinBox_source_scanRangeMin->setValue(settings.value(
"rangeMin",
_ui->doubleSpinBox_source_scanRangeMin->value()).toDouble());
2857 _ui->doubleSpinBox_source_scanRangeMax->setValue(settings.value(
"rangeMax",
_ui->doubleSpinBox_source_scanRangeMax->value()).toDouble());
2858 _ui->doubleSpinBox_source_scanVoxelSize->setValue(settings.value(
"voxelSize",
_ui->doubleSpinBox_source_scanVoxelSize->value()).toDouble());
2859 _ui->spinBox_source_scanNormalsK->setValue(settings.value(
"normalsK",
_ui->spinBox_source_scanNormalsK->value()).toInt());
2860 _ui->doubleSpinBox_source_scanNormalsRadius->setValue(settings.value(
"normalsRadius",
_ui->doubleSpinBox_source_scanNormalsRadius->value()).toDouble());
2861 _ui->doubleSpinBox_source_scanNormalsForceGroundUp->setValue(settings.value(
"normalsUpF",
_ui->doubleSpinBox_source_scanNormalsForceGroundUp->value()).toDouble());
2862 settings.endGroup();
2864 settings.beginGroup(
"DepthFromScan");
2865 _ui->groupBox_depthFromScan->setChecked(settings.value(
"depthFromScan",
_ui->groupBox_depthFromScan->isChecked()).toBool());
2866 _ui->groupBox_depthFromScan_fillHoles->setChecked(settings.value(
"depthFromScanFillHoles",
_ui->groupBox_depthFromScan_fillHoles->isChecked()).toBool());
2867 _ui->radioButton_depthFromScan_vertical->setChecked(settings.value(
"depthFromScanVertical",
_ui->radioButton_depthFromScan_vertical->isChecked()).toBool());
2868 _ui->radioButton_depthFromScan_horizontal->setChecked(settings.value(
"depthFromScanHorizontal",
_ui->radioButton_depthFromScan_horizontal->isChecked()).toBool());
2869 _ui->checkBox_depthFromScan_fillBorders->setChecked(settings.value(
"depthFromScanFillBorders",
_ui->checkBox_depthFromScan_fillBorders->isChecked()).toBool());
2870 settings.endGroup();
2872 settings.beginGroup(
"Database");
2873 _ui->source_database_lineEdit_path->setText(settings.value(
"path",
_ui->source_database_lineEdit_path->text()).toString());
2874 _ui->source_checkBox_ignoreOdometry->setChecked(settings.value(
"ignoreOdometry",
_ui->source_checkBox_ignoreOdometry->isChecked()).toBool());
2875 _ui->source_checkBox_ignoreGoalDelay->setChecked(settings.value(
"ignoreGoalDelay",
_ui->source_checkBox_ignoreGoalDelay->isChecked()).toBool());
2876 _ui->source_checkBox_ignoreGoals->setChecked(settings.value(
"ignoreGoals",
_ui->source_checkBox_ignoreGoals->isChecked()).toBool());
2877 _ui->source_checkBox_ignoreLandmarks->setChecked(settings.value(
"ignoreLandmarks",
_ui->source_checkBox_ignoreLandmarks->isChecked()).toBool());
2878 _ui->source_checkBox_ignoreFeatures->setChecked(settings.value(
"ignoreFeatures",
_ui->source_checkBox_ignoreFeatures->isChecked()).toBool());
2879 _ui->source_checkBox_ignorePriors->setChecked(settings.value(
"ignorePriors",
_ui->source_checkBox_ignorePriors->isChecked()).toBool());
2880 _ui->source_spinBox_databaseStartId->setValue(settings.value(
"startId",
_ui->source_spinBox_databaseStartId->value()).toInt());
2881 _ui->source_spinBox_databaseStopId->setValue(settings.value(
"stopId",
_ui->source_spinBox_databaseStopId->value()).toInt());
2882 _ui->source_lineEdit_databaseCameraIndex->setText(settings.value(
"cameraIndices",
_ui->source_lineEdit_databaseCameraIndex->text()).toString());
2883 _ui->source_checkBox_useDbStamps->setChecked(settings.value(
"useDatabaseStamps",
_ui->source_checkBox_useDbStamps->isChecked()).toBool());
2884 settings.endGroup();
2886 settings.endGroup();
2888 settings.beginGroup(
"Lidar");
2890 settings.beginGroup(
"VLP16");
2891 _ui->lineEdit_lidar_local_transform->setText(settings.value(
"localTransform",
_ui->lineEdit_lidar_local_transform->text()).toString());
2892 _ui->lineEdit_vlp16_pcap_path->setText(settings.value(
"pcapPath",
_ui->lineEdit_vlp16_pcap_path->text()).toString());
2893 _ui->spinBox_vlp16_ip1->setValue(settings.value(
"ip1",
_ui->spinBox_vlp16_ip1->value()).toInt());
2894 _ui->spinBox_vlp16_ip2->setValue(settings.value(
"ip2",
_ui->spinBox_vlp16_ip2->value()).toInt());
2895 _ui->spinBox_vlp16_ip3->setValue(settings.value(
"ip3",
_ui->spinBox_vlp16_ip3->value()).toInt());
2896 _ui->spinBox_vlp16_ip4->setValue(settings.value(
"ip4",
_ui->spinBox_vlp16_ip4->value()).toInt());
2897 _ui->spinBox_vlp16_port->setValue(settings.value(
"port",
_ui->spinBox_vlp16_port->value()).toInt());
2898 _ui->checkBox_vlp16_organized->setChecked(settings.value(
"organized",
_ui->checkBox_vlp16_organized->isChecked()).toBool());
2899 _ui->checkBox_vlp16_hostTime->setChecked(settings.value(
"hostTime",
_ui->checkBox_vlp16_hostTime->isChecked()).toBool());
2900 _ui->checkBox_vlp16_stamp_last->setChecked(settings.value(
"stampLast",
_ui->checkBox_vlp16_stamp_last->isChecked()).toBool());
2901 settings.endGroup();
2903 settings.endGroup();
2917 if(!filePath.isEmpty())
2924 if(!QFile::exists(
path))
2926 QMessageBox::information(
this, tr(
"INI file doesn't exist..."), tr(
"The configuration file \"%1\" does not exist, it will be created with default parameters.").
arg(
path));
2932 for(rtabmap::ParametersMap::const_iterator
iter = parameters.begin();
iter!=parameters.end(); ++
iter)
2935 if(
iter->first.compare(Parameters::kRtabmapWorkingDirectory()) == 0)
2939 UWARN(
"Reading config: Working directory is empty. Keeping old one (\"%s\").",
2949 UWARN(
"Reading config: Not existing working directory \"%s\". Keeping old one (\"%s\").",
2951 this->getWorkingDirectory().toStdString().c_str());
2957 UWARN(
"Reading config: Not existing working directory \"%s\". Using default one (\"%s\").",
2959 defaultWorkingDir.c_str());
2960 value = defaultWorkingDir;
2966 if(
iter->first.compare(Parameters::kIcpStrategy()) == 0)
2968 if(
value.compare(
"true") == 0)
2972 else if(
value.compare(
"false") == 0)
2982 if(parameters.find(Parameters::kRtabmapWorkingDirectory()) == parameters.end())
2986 QMessageBox::information(
this,
2987 tr(
"Working directory"),
2988 tr(
"RTAB-Map needs a working directory to put the database.\n\n"
2989 "By default, the directory \"%1\" is used.\n\n"
2990 "The working directory can be changed any time in the "
3002 QString
path = QFileDialog::getSaveFileName(
this, tr(
"Save settings..."), this->
getWorkingDirectory()+QDir::separator()+
"config.ini",
"*.ini");
3015 int button = QMessageBox::warning(
this,
3016 tr(
"Reset settings..."),
3017 tr(
"This will reset all settings. Restore all settings to default without saving them first?"),
3018 QMessageBox::Cancel | QMessageBox::Yes | QMessageBox::Save,
3019 QMessageBox::Cancel);
3020 if(button == QMessageBox::Yes ||
3032 if(!presetHexHeader.empty())
3040 parameters.erase(Parameters::kRtabmapWorkingDirectory());
3041 for(ParametersMap::iterator
iter=parameters.begin();
iter!=parameters.end(); ++
iter)
3049 if(sender() ==
_ui->pushButton_presets_camera_tof_icp)
3053 else if(sender() ==
_ui->pushButton_presets_lidar_3d_icp)
3059 UERROR(
"Unknown sender!");
3062 QMessageBox::information(
this,
3064 tr(
"Loaded \"%1\" preset!").
arg(((QPushButton*)sender())->
text()),
3090 bool different =
true;
3114 if(!filePath.isEmpty())
3118 QSettings settings(
path, QSettings::IniFormat);
3119 settings.beginGroup(
"Gui");
3121 settings.beginGroup(
"General");
3122 settings.remove(
"");
3123 settings.setValue(
"imagesKept",
_ui->general_checkBox_imagesKept->isChecked());
3124 settings.setValue(
"missingRepublished",
_ui->general_checkBox_missing_cache_republished->isChecked());
3125 settings.setValue(
"cloudsKept",
_ui->general_checkBox_cloudsKept->isChecked());
3126 settings.setValue(
"loggerLevel",
_ui->comboBox_loggerLevel->currentIndex());
3127 settings.setValue(
"loggerEventLevel",
_ui->comboBox_loggerEventLevel->currentIndex());
3128 settings.setValue(
"loggerPauseLevel",
_ui->comboBox_loggerPauseLevel->currentIndex());
3129 settings.setValue(
"loggerType",
_ui->comboBox_loggerType->currentIndex());
3130 settings.setValue(
"loggerPrintTime",
_ui->checkBox_logger_printTime->isChecked());
3131 settings.setValue(
"loggerPrintThreadId",
_ui->checkBox_logger_printThreadId->isChecked());
3132 settings.setValue(
"verticalLayoutUsed",
_ui->checkBox_verticalLayoutUsed->isChecked());
3133 settings.setValue(
"imageRejectedShown",
_ui->checkBox_imageRejectedShown->isChecked());
3134 settings.setValue(
"imageHighestHypShown",
_ui->checkBox_imageHighestHypShown->isChecked());
3135 settings.setValue(
"beep",
_ui->checkBox_beep->isChecked());
3136 settings.setValue(
"figure_time",
_ui->checkBox_stamps->isChecked());
3137 settings.setValue(
"figure_cache",
_ui->checkBox_cacheStatistics->isChecked());
3138 settings.setValue(
"notifyNewGlobalPath",
_ui->checkBox_notifyWhenNewGlobalPathIsReceived->isChecked());
3139 settings.setValue(
"odomQualityThr",
_ui->spinBox_odomQualityWarnThr->value());
3140 settings.setValue(
"odomOnlyInliersShown",
_ui->checkBox_odom_onlyInliersShown->isChecked());
3141 settings.setValue(
"posteriorGraphView",
_ui->radioButton_posteriorGraphView->isChecked());
3142 settings.setValue(
"wordsGraphView",
_ui->radioButton_wordsGraphView->isChecked());
3143 settings.setValue(
"localizationsGraphView",
_ui->radioButton_localizationsGraphView->isChecked());
3144 settings.setValue(
"localizationsGraphViewOdomCache",
_ui->radioButton_localizationsGraphViewOdomCache->isChecked());
3145 settings.setValue(
"nochangeGraphView",
_ui->radioButton_nochangeGraphView->isChecked());
3146 settings.setValue(
"odomDisabled",
_ui->checkbox_odomDisabled->isChecked());
3147 settings.setValue(
"odomRegistration",
_ui->odom_registration->currentIndex());
3148 settings.setValue(
"odomF2MGravitySigma",
_ui->odom_f2m_gravitySigma->value());
3149 settings.setValue(
"gtAlign",
_ui->checkbox_groundTruthAlign->isChecked());
3151 for(
int i=0;
i<2; ++
i)
3176 settings.setValue(
"cloudVoxel",
_ui->doubleSpinBox_voxel->value());
3177 settings.setValue(
"cloudNoiseRadius",
_ui->doubleSpinBox_noiseRadius->value());
3178 settings.setValue(
"cloudNoiseMinNeighbors",
_ui->spinBox_noiseMinNeighbors->value());
3179 settings.setValue(
"cloudCeilingHeight",
_ui->doubleSpinBox_ceilingFilterHeight->value());
3180 settings.setValue(
"cloudFloorHeight",
_ui->doubleSpinBox_floorFilterHeight->value());
3181 settings.setValue(
"normalKSearch",
_ui->spinBox_normalKSearch->value());
3182 settings.setValue(
"normalRadiusSearch",
_ui->doubleSpinBox_normalRadiusSearch->value());
3183 settings.setValue(
"scanCeilingHeight",
_ui->doubleSpinBox_ceilingFilterHeight_scan->value());
3184 settings.setValue(
"scanFloorHeight",
_ui->doubleSpinBox_floorFilterHeight_scan->value());
3185 settings.setValue(
"scanNormalKSearch",
_ui->spinBox_normalKSearch_scan->value());
3186 settings.setValue(
"scanNormalRadiusSearch",
_ui->doubleSpinBox_normalRadiusSearch_scan->value());
3188 settings.setValue(
"showGraphs",
_ui->checkBox_showGraphs->isChecked());
3189 settings.setValue(
"showLabels",
_ui->checkBox_showLabels->isChecked());
3190 settings.setValue(
"showFrames",
_ui->checkBox_showFrames->isChecked());
3191 settings.setValue(
"showLandmarks",
_ui->checkBox_showLandmarks->isChecked());
3192 settings.setValue(
"landmarkSize",
_ui->doubleSpinBox_landmarkSize->value());
3193 settings.setValue(
"showIMUGravity",
_ui->checkBox_showIMUGravity->isChecked());
3194 settings.setValue(
"showIMUAcc",
_ui->checkBox_showIMUAcc->isChecked());
3197 settings.setValue(
"noFiltering",
_ui->radioButton_noFiltering->isChecked());
3198 settings.setValue(
"cloudFiltering",
_ui->radioButton_nodeFiltering->isChecked());
3199 settings.setValue(
"cloudFilteringRadius",
_ui->doubleSpinBox_cloudFilterRadius->value());
3200 settings.setValue(
"cloudFilteringAngle",
_ui->doubleSpinBox_cloudFilterAngle->value());
3201 settings.setValue(
"subtractFiltering",
_ui->radioButton_subtractFiltering->isChecked());
3202 settings.setValue(
"subtractFilteringMinPts",
_ui->spinBox_subtractFilteringMinPts->value());
3203 settings.setValue(
"subtractFilteringRadius",
_ui->doubleSpinBox_subtractFilteringRadius->value());
3204 settings.setValue(
"subtractFilteringAngle",
_ui->doubleSpinBox_subtractFilteringAngle->value());
3206 settings.setValue(
"gridUIResolution",
_ui->doubleSpinBox_map_resolution->value());
3207 settings.setValue(
"gridMapShown",
_ui->checkBox_map_shown->isChecked());
3208 settings.setValue(
"gridMapOpacity",
_ui->doubleSpinBox_map_opacity->value());
3209 settings.setValue(
"elevationMapShown",
_ui->checkBox_elevation_shown->checkState());
3212 settings.setValue(
"octomap",
_ui->groupBox_octomap->isChecked());
3213 settings.setValue(
"octomap_depth",
_ui->spinBox_octomap_treeDepth->value());
3214 settings.setValue(
"octomap_2dgrid",
_ui->checkBox_octomap_2dgrid->isChecked());
3215 settings.setValue(
"octomap_3dmap",
_ui->checkBox_octomap_show3dMap->isChecked());
3216 settings.setValue(
"octomap_rendering_type",
_ui->comboBox_octomap_renderingType->currentIndex());
3217 settings.setValue(
"octomap_point_size",
_ui->spinBox_octomap_pointSize->value());
3220 settings.setValue(
"meshing",
_ui->groupBox_organized->isChecked());
3221 settings.setValue(
"meshing_angle",
_ui->doubleSpinBox_mesh_angleTolerance->value());
3222 settings.setValue(
"meshing_quad",
_ui->checkBox_mesh_quad->isChecked());
3223 settings.setValue(
"meshing_texture",
_ui->checkBox_mesh_texture->isChecked());
3224 settings.setValue(
"meshing_triangle_size",
_ui->spinBox_mesh_triangleSize->value());
3226 settings.endGroup();
3228 settings.endGroup();
3234 if(!filePath.isEmpty())
3238 QSettings settings(
path, QSettings::IniFormat);
3240 settings.beginGroup(
"Camera");
3241 settings.remove(
"");
3242 settings.setValue(
"imgRate",
_ui->general_doubleSpinBox_imgRate->value());
3243 settings.setValue(
"mirroring",
_ui->source_mirroring->isChecked());
3244 settings.setValue(
"calibrationName",
_ui->lineEdit_calibrationFile->text());
3245 settings.setValue(
"type",
_ui->comboBox_sourceType->currentIndex());
3246 settings.setValue(
"device",
_ui->lineEdit_sourceDevice->text());
3247 settings.setValue(
"localTransform",
_ui->lineEdit_sourceLocalTransform->text());
3248 settings.setValue(
"imageDecimation",
_ui->spinBox_source_imageDecimation->value());
3249 settings.setValue(
"histogramMethod",
_ui->comboBox_source_histogramMethod->currentIndex());
3250 settings.setValue(
"featureDetection",
_ui->checkbox_source_feature_detection->isChecked());
3252 settings.beginGroup(
"rgbd");
3253 settings.setValue(
"driver",
_ui->comboBox_cameraRGBD->currentIndex());
3254 settings.setValue(
"rgbdColorOnly",
_ui->checkbox_rgbd_colorOnly->isChecked());
3255 settings.setValue(
"distortion_model",
_ui->lineEdit_source_distortionModel->text());
3256 settings.setValue(
"bilateral",
_ui->groupBox_bilateral->isChecked());
3257 settings.setValue(
"bilateral_sigma_s",
_ui->doubleSpinBox_bilateral_sigmaS->value());
3258 settings.setValue(
"bilateral_sigma_r",
_ui->doubleSpinBox_bilateral_sigmaR->value());
3259 settings.endGroup();
3261 settings.beginGroup(
"stereo");
3262 settings.setValue(
"driver",
_ui->comboBox_cameraStereo->currentIndex());
3263 settings.setValue(
"depthGenerated",
_ui->checkbox_stereo_depthGenerated->isChecked());
3264 settings.setValue(
"exposureCompensation",
_ui->checkBox_stereo_exposureCompensation->isChecked());
3265 settings.setValue(
"rightGrayScale",
_ui->checkBox_stereo_rightGrayScale->isChecked());
3266 settings.endGroup();
3268 settings.beginGroup(
"rgb");
3269 settings.setValue(
"driver",
_ui->source_comboBox_image_type->currentIndex());
3270 settings.setValue(
"rectify",
_ui->checkBox_rgb_rectify->isChecked());
3271 settings.endGroup();
3273 settings.beginGroup(
"Openni");
3274 settings.setValue(
"oniPath",
_ui->lineEdit_openniOniPath->text());
3275 settings.endGroup();
3277 settings.beginGroup(
"Openni2");
3278 settings.setValue(
"autoWhiteBalance",
_ui->openni2_autoWhiteBalance->isChecked());
3279 settings.setValue(
"autoExposure",
_ui->openni2_autoExposure->isChecked());
3280 settings.setValue(
"exposure",
_ui->openni2_exposure->value());
3281 settings.setValue(
"gain",
_ui->openni2_gain->value());
3282 settings.setValue(
"mirroring",
_ui->openni2_mirroring->isChecked());
3283 settings.setValue(
"stampsIdsUsed",
_ui->openni2_stampsIdsUsed->isChecked());
3284 settings.setValue(
"oniPath",
_ui->lineEdit_openni2OniPath->text());
3285 settings.setValue(
"hshift",
_ui->openni2_hshift->value());
3286 settings.setValue(
"vshift",
_ui->openni2_vshift->value());
3287 settings.setValue(
"depthDecimation",
_ui->openni2_depth_decimation->value());
3288 settings.endGroup();
3290 settings.beginGroup(
"Freenect2");
3291 settings.setValue(
"format",
_ui->comboBox_freenect2Format->currentIndex());
3292 settings.setValue(
"minDepth",
_ui->doubleSpinBox_freenect2MinDepth->value());
3293 settings.setValue(
"maxDepth",
_ui->doubleSpinBox_freenect2MaxDepth->value());
3294 settings.setValue(
"bilateralFiltering",
_ui->checkBox_freenect2BilateralFiltering->isChecked());
3295 settings.setValue(
"edgeAwareFiltering",
_ui->checkBox_freenect2EdgeAwareFiltering->isChecked());
3296 settings.setValue(
"noiseFiltering",
_ui->checkBox_freenect2NoiseFiltering->isChecked());
3297 settings.setValue(
"pipeline",
_ui->lineEdit_freenect2Pipeline->text());
3298 settings.endGroup();
3300 settings.beginGroup(
"K4W2");
3301 settings.setValue(
"format",
_ui->comboBox_k4w2Format->currentIndex());
3302 settings.endGroup();
3304 settings.beginGroup(
"K4A");
3305 settings.setValue(
"rgb_resolution",
_ui->comboBox_k4a_rgb_resolution->currentIndex());
3306 settings.setValue(
"framerate",
_ui->comboBox_k4a_framerate->currentIndex());
3307 settings.setValue(
"depth_resolution",
_ui->comboBox_k4a_depth_resolution->currentIndex());
3308 settings.setValue(
"ir",
_ui->checkbox_k4a_irDepth->isChecked());
3309 settings.setValue(
"mkvPath",
_ui->lineEdit_k4a_mkv->text());
3310 settings.setValue(
"useMkvStamps",
_ui->source_checkBox_useMKVStamps->isChecked());
3311 settings.endGroup();
3313 settings.beginGroup(
"RealSense");
3314 settings.setValue(
"presetRGB",
_ui->comboBox_realsensePresetRGB->currentIndex());
3315 settings.setValue(
"presetDepth",
_ui->comboBox_realsensePresetDepth->currentIndex());
3316 settings.setValue(
"odom",
_ui->checkbox_realsenseOdom->isChecked());
3317 settings.setValue(
"depthScaled",
_ui->checkbox_realsenseDepthScaledToRGBSize->isChecked());
3318 settings.setValue(
"rgbSource",
_ui->comboBox_realsenseRGBSource->currentIndex());
3319 settings.endGroup();
3321 settings.beginGroup(
"RealSense2");
3322 settings.setValue(
"emitter",
_ui->checkbox_rs2_emitter->isChecked());
3323 settings.setValue(
"ir",
_ui->checkbox_rs2_irMode->isChecked());
3324 settings.setValue(
"irdepth",
_ui->checkbox_rs2_irDepth->isChecked());
3325 settings.setValue(
"width",
_ui->spinBox_rs2_width->value());
3326 settings.setValue(
"height",
_ui->spinBox_rs2_height->value());
3327 settings.setValue(
"rate",
_ui->spinBox_rs2_rate->value());
3328 settings.setValue(
"width_depth",
_ui->spinBox_rs2_width_depth->value());
3329 settings.setValue(
"height_depth",
_ui->spinBox_rs2_height_depth->value());
3330 settings.setValue(
"rate_depth",
_ui->spinBox_rs2_rate_depth->value());
3331 settings.setValue(
"global_time_sync",
_ui->checkbox_rs2_globalTimeStync->isChecked());
3332 settings.setValue(
"json_preset",
_ui->lineEdit_rs2_jsonFile->text());
3333 settings.endGroup();
3335 settings.beginGroup(
"RGBDImages");
3336 settings.setValue(
"path_rgb",
_ui->lineEdit_cameraRGBDImages_path_rgb->text());
3337 settings.setValue(
"path_depth",
_ui->lineEdit_cameraRGBDImages_path_depth->text());
3338 settings.setValue(
"scale",
_ui->doubleSpinBox_cameraRGBDImages_scale->value());
3339 settings.setValue(
"start_index",
_ui->spinBox_cameraRGBDImages_startIndex->value());
3340 settings.setValue(
"max_frames",
_ui->spinBox_cameraRGBDImages_maxFrames->value());
3341 settings.endGroup();
3343 settings.beginGroup(
"StereoImages");
3344 settings.setValue(
"path_left",
_ui->lineEdit_cameraStereoImages_path_left->text());
3345 settings.setValue(
"path_right",
_ui->lineEdit_cameraStereoImages_path_right->text());
3346 settings.setValue(
"rectify",
_ui->checkBox_stereo_rectify->isChecked());
3347 settings.setValue(
"start_index",
_ui->spinBox_cameraStereoImages_startIndex->value());
3348 settings.setValue(
"max_frames",
_ui->spinBox_cameraStereoImages_maxFrames->value());
3349 settings.endGroup();
3351 settings.beginGroup(
"StereoVideo");
3352 settings.setValue(
"path",
_ui->lineEdit_cameraStereoVideo_path->text());
3353 settings.setValue(
"path2",
_ui->lineEdit_cameraStereoVideo_path_2->text());
3354 settings.setValue(
"device2",
_ui->spinBox_stereo_right_device->value());
3355 settings.setValue(
"width",
_ui->spinBox_stereousbcam_streamWidth->value());
3356 settings.setValue(
"height",
_ui->spinBox_stereousbcam_streamHeight->value());
3357 settings.setValue(
"fourcc",
_ui->lineEdit_stereousbcam_fourcc->text());
3358 settings.endGroup();
3360 settings.beginGroup(
"StereoZed");
3361 settings.setValue(
"resolution",
_ui->comboBox_stereoZed_resolution->currentIndex());
3362 settings.setValue(
"quality",
_ui->comboBox_stereoZed_quality->currentIndex());
3363 settings.setValue(
"self_calibration",
_ui->checkbox_stereoZed_selfCalibration->isChecked());
3364 settings.setValue(
"sensing_mode",
_ui->comboBox_stereoZed_sensingMode->currentIndex());
3365 settings.setValue(
"confidence_thr",
_ui->spinBox_stereoZed_confidenceThr->value());
3366 settings.setValue(
"textureness_confidence_thr",
_ui->spinBox_stereoZed_texturenessConfidenceThr->value());
3367 settings.setValue(
"svo_path",
_ui->lineEdit_zedSvoPath->text());
3368 settings.endGroup();
3370 settings.beginGroup(
"MyntEye");
3371 settings.setValue(
"rectify",
_ui->checkbox_stereoMyntEye_rectify->isChecked());
3372 settings.setValue(
"depth",
_ui->checkbox_stereoMyntEye_depth->isChecked());
3373 settings.setValue(
"auto_exposure",
_ui->checkbox_stereoMyntEye_autoExposure->isChecked());
3374 settings.setValue(
"gain",
_ui->spinBox_stereoMyntEye_gain->value());
3375 settings.setValue(
"brightness",
_ui->spinBox_stereoMyntEye_brightness->value());
3376 settings.setValue(
"contrast",
_ui->spinBox_stereoMyntEye_contrast->value());
3377 settings.setValue(
"ir_control",
_ui->spinBox_stereoMyntEye_irControl->value());
3378 settings.endGroup();
3380 settings.beginGroup(
"DepthAI");
3381 settings.setValue(
"image_width",
_ui->comboBox_depthai_image_width->currentIndex());
3382 settings.setValue(
"output_mode",
_ui->comboBox_depthai_output_mode->currentIndex());
3383 settings.setValue(
"conf_threshold",
_ui->spinBox_depthai_conf_threshold->value());
3384 settings.setValue(
"lrc_threshold",
_ui->spinBox_depthai_lrc_threshold->value());
3385 settings.setValue(
"extended_disparity",
_ui->checkBox_depthai_extended_disparity->isChecked());
3386 settings.setValue(
"disparity_companding",
_ui->checkBox_depthai_disparity_companding->isChecked());
3387 settings.setValue(
"subpixel_fractional_bits",
_ui->comboBox_depthai_subpixel_fractional_bits->currentIndex());
3388 settings.setValue(
"disparity_width",
_ui->comboBox_depthai_disparity_width->currentIndex());
3389 settings.setValue(
"median_filter",
_ui->comboBox_depthai_median_filter->currentIndex());
3390 settings.setValue(
"use_spec_translation",
_ui->checkBox_depthai_use_spec_translation->isChecked());
3391 settings.setValue(
"alpha_scaling",
_ui->doubleSpinBox_depthai_alpha_scaling->value());
3392 settings.setValue(
"imu_published",
_ui->checkBox_depthai_imu_published->isChecked());
3393 settings.setValue(
"dot_intensity",
_ui->doubleSpinBox_depthai_dot_intensity->value());
3394 settings.setValue(
"flood_intensity",
_ui->doubleSpinBox_depthai_flood_intensity->value());
3395 settings.setValue(
"detect_features",
_ui->comboBox_depthai_detect_features->currentIndex());
3396 settings.setValue(
"blob_path",
_ui->lineEdit_depthai_blob_path->text());
3397 settings.endGroup();
3399 settings.beginGroup(
"Images");
3400 settings.setValue(
"path",
_ui->source_images_lineEdit_path->text());
3401 settings.setValue(
"startPos",
_ui->source_images_spinBox_startPos->value());
3402 settings.setValue(
"maxFrames",
_ui->source_images_spinBox_maxFrames->value());
3403 settings.setValue(
"bayerMode",
_ui->comboBox_cameraImages_bayerMode->currentIndex());
3404 settings.setValue(
"config_each_frame",
_ui->checkBox_cameraImages_configForEachFrame->isChecked());
3405 settings.setValue(
"filenames_as_stamps",
_ui->checkBox_cameraImages_timestamps->isChecked());
3406 settings.setValue(
"sync_stamps",
_ui->checkBox_cameraImages_syncTimeStamps->isChecked());
3407 settings.setValue(
"stamps",
_ui->lineEdit_cameraImages_timestamps->text());
3408 settings.setValue(
"path_scans",
_ui->lineEdit_cameraImages_path_scans->text());
3409 settings.setValue(
"scan_transform",
_ui->lineEdit_cameraImages_laser_transform->text());
3410 settings.setValue(
"scan_max_pts",
_ui->spinBox_cameraImages_max_scan_pts->value());
3411 settings.setValue(
"odom_path",
_ui->lineEdit_cameraImages_odom->text());
3412 settings.setValue(
"odom_format",
_ui->comboBox_cameraImages_odomFormat->currentIndex());
3413 settings.setValue(
"gt_path",
_ui->lineEdit_cameraImages_gt->text());
3414 settings.setValue(
"gt_format",
_ui->comboBox_cameraImages_gtFormat->currentIndex());
3415 settings.setValue(
"max_pose_time_diff",
_ui->doubleSpinBox_maxPoseTimeDiff->value());
3416 settings.setValue(
"imu_path",
_ui->lineEdit_cameraImages_path_imu->text());
3417 settings.setValue(
"imu_local_transform",
_ui->lineEdit_cameraImages_imu_transform->text());
3418 settings.setValue(
"imu_rate",
_ui->spinBox_cameraImages_max_imu_rate->value());
3419 settings.endGroup();
3421 settings.beginGroup(
"OdomSensor");
3422 settings.setValue(
"odom_sensor",
_ui->comboBox_odom_sensor->currentIndex());
3423 settings.setValue(
"odom_sensor_extrinsics",
_ui->lineEdit_odom_sensor_extrinsics->text());
3424 settings.setValue(
"odom_sensor_calibration_path",
_ui->lineEdit_odom_sensor_path_calibration->text());
3425 settings.setValue(
"odom_sensor_device",
_ui->lineEdit_odomSourceDevice->text());
3426 settings.setValue(
"odom_sensor_offset_time",
_ui->doubleSpinBox_odom_sensor_time_offset->value());
3427 settings.setValue(
"odom_sensor_scale_factor",
_ui->doubleSpinBox_odom_sensor_scale_factor->value());
3428 settings.setValue(
"odom_sensor_wait_time",
_ui->doubleSpinBox_odom_sensor_wait_time->value());
3429 settings.setValue(
"odom_sensor_odom_as_gt",
_ui->checkBox_odom_sensor_use_as_gt->isChecked());
3430 settings.endGroup();
3432 settings.beginGroup(
"UsbCam");
3433 settings.setValue(
"width",
_ui->spinBox_usbcam_streamWidth->value());
3434 settings.setValue(
"height",
_ui->spinBox_usbcam_streamHeight->value());
3435 settings.setValue(
"fourcc",
_ui->lineEdit_usbcam_fourcc->text());
3436 settings.endGroup();
3438 settings.beginGroup(
"Video");
3439 settings.setValue(
"path",
_ui->source_video_lineEdit_path->text());
3440 settings.endGroup();
3442 settings.beginGroup(
"IMU");
3443 settings.setValue(
"strategy",
_ui->comboBox_imuFilter_strategy->currentIndex());
3444 settings.setValue(
"madgwick_gain",
_ui->doubleSpinBox_imuFilterMadgwickGain->value());
3445 settings.setValue(
"madgwick_zeta",
_ui->doubleSpinBox_imuFilterMadgwickZeta->value());
3446 settings.setValue(
"complementary_gain_acc",
_ui->doubleSpinBox_imuFilterComplementaryGainAcc->value());
3447 settings.setValue(
"complementary_bias_alpha",
_ui->doubleSpinBox_imuFilterComplementaryBiasAlpha->value());
3448 settings.setValue(
"complementary_adaptive_gain",
_ui->checkBox_imuFilterComplementaryDoAdaptiveGain->isChecked());
3449 settings.setValue(
"complementary_biais_estimation",
_ui->checkBox_imuFilterComplementaryDoBiasEstimation->isChecked());
3450 settings.setValue(
"base_frame_conversion",
_ui->checkBox_imuFilter_baseFrameConversion->isChecked());
3451 settings.setValue(
"publish_inter_imu",
_ui->checkbox_publishInterIMU->isChecked());
3452 settings.endGroup();
3454 settings.beginGroup(
"Scan");
3455 settings.setValue(
"source",
_ui->comboBox_lidar_src->currentIndex());
3456 settings.setValue(
"deskewing",
_ui->checkBox_source_scanDeskewing->isChecked());
3457 settings.setValue(
"fromDepth",
_ui->checkBox_source_scanFromDepth->isChecked());
3458 settings.setValue(
"downsampleStep",
_ui->spinBox_source_scanDownsampleStep->value());
3459 settings.setValue(
"rangeMin",
_ui->doubleSpinBox_source_scanRangeMin->value());
3460 settings.setValue(
"rangeMax",
_ui->doubleSpinBox_source_scanRangeMax->value());
3461 settings.setValue(
"voxelSize",
_ui->doubleSpinBox_source_scanVoxelSize->value());
3462 settings.setValue(
"normalsK",
_ui->spinBox_source_scanNormalsK->value());
3463 settings.setValue(
"normalsRadius",
_ui->doubleSpinBox_source_scanNormalsRadius->value());
3464 settings.setValue(
"normalsUpF",
_ui->doubleSpinBox_source_scanNormalsForceGroundUp->value());
3465 settings.endGroup();
3467 settings.beginGroup(
"DepthFromScan");
3468 settings.setValue(
"depthFromScan",
_ui->groupBox_depthFromScan->isChecked());
3469 settings.setValue(
"depthFromScanFillHoles",
_ui->groupBox_depthFromScan_fillHoles->isChecked());
3470 settings.setValue(
"depthFromScanVertical",
_ui->radioButton_depthFromScan_vertical->isChecked());
3471 settings.setValue(
"depthFromScanHorizontal",
_ui->radioButton_depthFromScan_horizontal->isChecked());
3472 settings.setValue(
"depthFromScanFillBorders",
_ui->checkBox_depthFromScan_fillBorders->isChecked());
3473 settings.endGroup();
3475 settings.beginGroup(
"Database");
3476 settings.setValue(
"path",
_ui->source_database_lineEdit_path->text());
3477 settings.setValue(
"ignoreOdometry",
_ui->source_checkBox_ignoreOdometry->isChecked());
3478 settings.setValue(
"ignoreGoalDelay",
_ui->source_checkBox_ignoreGoalDelay->isChecked());
3479 settings.setValue(
"ignoreGoals",
_ui->source_checkBox_ignoreGoals->isChecked());
3480 settings.setValue(
"ignoreLandmarks",
_ui->source_checkBox_ignoreLandmarks->isChecked());
3481 settings.setValue(
"ignoreFeatures",
_ui->source_checkBox_ignoreFeatures->isChecked());
3482 settings.setValue(
"ignorePriors",
_ui->source_checkBox_ignorePriors->isChecked());
3483 settings.setValue(
"startId",
_ui->source_spinBox_databaseStartId->value());
3484 settings.setValue(
"stopId",
_ui->source_spinBox_databaseStopId->value());
3485 settings.setValue(
"cameraIndices",
_ui->source_lineEdit_databaseCameraIndex->text());
3486 settings.setValue(
"useDatabaseStamps",
_ui->source_checkBox_useDbStamps->isChecked());
3487 settings.endGroup();
3489 settings.endGroup();
3491 settings.beginGroup(
"Lidar");
3493 settings.beginGroup(
"VLP16");
3494 settings.setValue(
"localTransform",
_ui->lineEdit_lidar_local_transform->text());
3495 settings.setValue(
"pcapPath",
_ui->lineEdit_vlp16_pcap_path->text());
3496 settings.setValue(
"ip1",
_ui->spinBox_vlp16_ip1->value());
3497 settings.setValue(
"ip2",
_ui->spinBox_vlp16_ip2->value());
3498 settings.setValue(
"ip3",
_ui->spinBox_vlp16_ip3->value());
3499 settings.setValue(
"ip4",
_ui->spinBox_vlp16_ip4->value());
3500 settings.setValue(
"port",
_ui->spinBox_vlp16_port->value());
3501 settings.setValue(
"organized",
_ui->checkBox_vlp16_organized->isChecked());
3502 settings.setValue(
"hostTime",
_ui->checkBox_vlp16_hostTime->isChecked());
3503 settings.setValue(
"stampLast",
_ui->checkBox_vlp16_stamp_last->isChecked());
3504 settings.endGroup();
3506 settings.endGroup();
3514 if(!filePath.isEmpty())
3524 #if CV_MAJOR_VERSION < 3 || (CV_MAJOR_VERSION == 4 && CV_MINOR_VERSION <= 3) || (CV_MAJOR_VERSION == 3 && (CV_MINOR_VERSION < 4 || (CV_MINOR_VERSION==4 && CV_SUBMINOR_VERSION<11)))
3525 #ifndef RTABMAP_NONFREE
3528 if(
_ui->comboBox_detector_strategy->currentIndex() <= 1 ||
_ui->comboBox_detector_strategy->currentIndex() == 12)
3530 QMessageBox::warning(
this, tr(
"Parameter warning"),
3531 tr(
"Selected feature type (SURF/SIFT) is not available. RTAB-Map is not built "
3532 "with the nonfree module from OpenCV. ORB is set instead for the bag-of-words dictionary."));
3536 if(
_ui->vis_feature_detector->currentIndex() <= 1 ||
_ui->vis_feature_detector->currentIndex() == 12)
3538 QMessageBox::warning(
this, tr(
"Parameter warning"),
3539 tr(
"Selected feature type (SURF/SIFT) is not available. RTAB-Map is not built "
3540 "with the nonfree module from OpenCV. Fast/Brief is set instead for the re-extraction "
3541 "of features on loop closure."));
3545 #else //>= 4.4.0 >= 3.4.11
3546 #ifndef RTABMAP_NONFREE
3549 if(
_ui->comboBox_detector_strategy->currentIndex() < 1 ||
_ui->comboBox_detector_strategy->currentIndex() == 12)
3551 QMessageBox::warning(
this, tr(
"Parameter warning"),
3552 tr(
"Selected feature type (SURF) is not available. RTAB-Map is not built "
3553 "with the nonfree module from OpenCV. SIFT is set instead for the bag-of-words dictionary."));
3557 if(
_ui->vis_feature_detector->currentIndex() < 1 ||
_ui->vis_feature_detector->currentIndex() == 12)
3559 QMessageBox::warning(
this, tr(
"Parameter warning"),
3560 tr(
"Selected feature type (SURF) is not available. RTAB-Map is not built "
3561 "with the nonfree module from OpenCV. Fast/Brief is set instead for the re-extraction "
3562 "of features on loop closure."));
3568 #if CV_MAJOR_VERSION < 3
3571 #ifdef RTABMAP_NONFREE
3572 QMessageBox::warning(
this, tr(
"Parameter warning"),
3573 tr(
"Selected feature type (KAZE) is not available on OpenCV2. SURF is set instead "
3574 "for the bag-of-words dictionary."));
3577 QMessageBox::warning(
this, tr(
"Parameter warning"),
3578 tr(
"Selected feature type (KAZE) is not available on OpenCV2. ORB is set instead "
3579 "for the bag-of-words dictionary."));
3585 #ifdef RTABMAP_NONFREE
3586 QMessageBox::warning(
this, tr(
"Parameter warning"),
3587 tr(
"Selected feature type (KAZE) is not available on OpenCV2. SURF is set instead "
3588 "for the re-extraction of features on loop closure."));
3591 QMessageBox::warning(
this, tr(
"Parameter warning"),
3592 tr(
"Selected feature type (KAZE) is not available on OpenCV2. ORB is set instead "
3593 "for the re-extraction of features on loop closure."));
3599 #ifndef RTABMAP_ORB_OCTREE
3602 QMessageBox::warning(
this, tr(
"Parameter warning"),
3603 tr(
"Selected feature type (ORB Octree) is not available. ORB is set instead "
3604 "for the bag-of-words dictionary."));
3609 QMessageBox::warning(
this, tr(
"Parameter warning"),
3610 tr(
"Selected feature type (ORB Octree) is not available on OpenCV2. ORB is set instead "
3611 "for the re-extraction of features on loop closure."));
3621 QMessageBox::warning(
this, tr(
"Parameter warning"),
3622 tr(
"Selected graph optimization strategy (TORO) is not available. RTAB-Map is not built "
3623 "with TORO. GTSAM is set instead for graph optimization strategy."));
3626 #ifndef RTABMAP_ORB_SLAM
3629 QMessageBox::warning(
this, tr(
"Parameter warning"),
3630 tr(
"Selected graph optimization strategy (TORO) is not available. RTAB-Map is not built "
3631 "with TORO. g2o is set instead for graph optimization strategy."));
3636 #ifdef RTABMAP_ORB_SLAM
3637 if(
_ui->graphOptimization_type->currentIndex() == 1)
3644 QMessageBox::warning(
this, tr(
"Parameter warning"),
3645 tr(
"Selected graph optimization strategy (g2o) is not available. RTAB-Map is not built "
3646 "with g2o. GTSAM is set instead for graph optimization strategy."));
3651 QMessageBox::warning(
this, tr(
"Parameter warning"),
3652 tr(
"Selected graph optimization strategy (g2o) is not available. RTAB-Map is not built "
3653 "with g2o. TORO is set instead for graph optimization strategy."));
3659 #ifndef RTABMAP_ORB_SLAM
3662 QMessageBox::warning(
this, tr(
"Parameter warning"),
3663 tr(
"Selected graph optimization strategy (GTSAM) is not available. RTAB-Map is not built "
3664 "with GTSAM. g2o is set instead for graph optimization strategy."));
3671 QMessageBox::warning(
this, tr(
"Parameter warning"),
3672 tr(
"Selected graph optimization strategy (GTSAM) is not available. RTAB-Map is not built "
3673 "with GTSAM. TORO is set instead for graph optimization strategy."));
3681 QMessageBox::warning(
this, tr(
"Parameter warning"),
3682 tr(
"Selected visual registration bundle adjustment optimization strategy (g2o) is not available. RTAB-Map is not built "
3683 "with g2o. Bundle adjustment is disabled."));
3684 _ui->loopClosure_bundle->setCurrentIndex(0);
3688 QMessageBox::warning(
this, tr(
"Parameter warning"),
3689 tr(
"Selected visual registration bundle adjustment optimization strategy (cvsba) is not available. RTAB-Map is not built "
3690 "with cvsba. Bundle adjustment is disabled."));
3691 _ui->loopClosure_bundle->setCurrentIndex(0);
3695 QMessageBox::warning(
this, tr(
"Parameter warning"),
3696 tr(
"Selected visual registration bundle adjustment optimization strategy (Ceres) is not available. RTAB-Map is not built "
3697 "with cERES. Bundle adjustment is disabled."));
3698 _ui->loopClosure_bundle->setCurrentIndex(0);
3704 QMessageBox::warning(
this, tr(
"Parameter warning"),
3705 tr(
"Selected odometry local bundle adjustment optimization strategy (g2o) is not available. RTAB-Map is not built "
3706 "with g2o. Bundle adjustment is disabled."));
3707 _ui->odom_f2m_bundleStrategy->setCurrentIndex(0);
3711 QMessageBox::warning(
this, tr(
"Parameter warning"),
3712 tr(
"Selected odometry local bundle adjustment optimization strategy (cvsba) is not available. RTAB-Map is not built "
3713 "with cvsba. Bundle adjustment is disabled."));
3714 _ui->odom_f2m_bundleStrategy->setCurrentIndex(0);
3718 QMessageBox::warning(
this, tr(
"Parameter warning"),
3719 tr(
"Selected odometry local bundle adjustment optimization strategy (Ceres) is not available. RTAB-Map is not built "
3720 "with Ceres. Bundle adjustment is disabled."));
3721 _ui->odom_f2m_bundleStrategy->setCurrentIndex(0);
3725 if(
_ui->graphOptimization_robust->isChecked() &&
_ui->graphOptimization_maxError->value()>0.0)
3727 QMessageBox::warning(
this, tr(
"Parameter warning"),
3728 tr(
"Robust graph optimization and maximum optimization error threshold cannot be "
3729 "both used at the same time. Disabling robust optimization."));
3730 _ui->graphOptimization_robust->setChecked(
false);
3737 QMessageBox::warning(
this, tr(
"Parameter warning"),
3738 tr(
"With the selected feature type (SURF or SIFT), parameter \"Visual word->Nearest Neighbor\" "
3739 "cannot be LSH (used for binary descriptor). KD-tree is set instead for the bag-of-words dictionary."));
3746 QMessageBox::warning(
this, tr(
"Parameter warning"),
3747 tr(
"With the selected feature type (SURF or SIFT), parameter \"Visual word->Nearest Neighbor\" "
3748 "cannot be LSH (used for binary descriptor). KD-tree is set instead for the re-extraction "
3749 "of features on loop closure."));
3753 if(
_ui->doubleSpinBox_freenect2MinDepth->value() >=
_ui->doubleSpinBox_freenect2MaxDepth->value())
3755 QMessageBox::warning(
this, tr(
"Parameter warning"),
3756 tr(
"Freenect2 minimum depth (%1 m) should be lower than maximum depth (%2 m). Setting maximum depth to %3 m.")
3757 .
arg(
_ui->doubleSpinBox_freenect2MinDepth->value())
3758 .
arg(
_ui->doubleSpinBox_freenect2MaxDepth->value())
3759 .arg(
_ui->doubleSpinBox_freenect2MaxDepth->value()+1));
3760 _ui->doubleSpinBox_freenect2MaxDepth->setValue(
_ui->doubleSpinBox_freenect2MaxDepth->value()+1);
3763 if(
_ui->surf_doubleSpinBox_maxDepth->value() > 0.0 &&
3764 _ui->surf_doubleSpinBox_minDepth->value() >=
_ui->surf_doubleSpinBox_maxDepth->value())
3766 QMessageBox::warning(
this, tr(
"Parameter warning"),
3767 tr(
"Visual word minimum depth (%1 m) should be lower than maximum depth (%2 m). Setting maximum depth to %3 m.")
3768 .
arg(
_ui->surf_doubleSpinBox_minDepth->value())
3769 .
arg(
_ui->surf_doubleSpinBox_maxDepth->value())
3770 .arg(
_ui->surf_doubleSpinBox_maxDepth->value()+1));
3771 _ui->doubleSpinBox_freenect2MinDepth->setValue(0);
3774 if(
_ui->loopClosure_bowMaxDepth->value() > 0.0 &&
3775 _ui->loopClosure_bowMinDepth->value() >=
_ui->loopClosure_bowMaxDepth->value())
3777 QMessageBox::warning(
this, tr(
"Parameter warning"),
3778 tr(
"Visual registration word minimum depth (%1 m) should be lower than maximum depth (%2 m). Setting maximum depth to %3 m.")
3779 .
arg(
_ui->loopClosure_bowMinDepth->value())
3780 .
arg(
_ui->loopClosure_bowMaxDepth->value())
3781 .arg(
_ui->loopClosure_bowMaxDepth->value()+1));
3782 _ui->loopClosure_bowMinDepth->setValue(0);
3785 if(
_ui->fastThresholdMax->value() <
_ui->fastThresholdMin->value())
3787 QMessageBox::warning(
this, tr(
"Parameter warning"),
3788 tr(
"FAST minimum threshold cannot be lower than maximum threshold. Setting minimum to 1."));
3789 _ui->fastThresholdMin->setValue(1);
3791 if(
_ui->fastThreshold->value() >
_ui->fastThresholdMax->value())
3793 QMessageBox::warning(
this, tr(
"Parameter warning"),
3794 tr(
"FAST threshold cannot be higher than maximum threshold. Maximum value set to current threshold."));
3795 _ui->fastThresholdMax->setValue(
_ui->fastThreshold->value());
3797 if(
_ui->fastThreshold->value() <
_ui->fastThresholdMin->value())
3799 QMessageBox::warning(
this, tr(
"Parameter warning"),
3800 tr(
"FAST threshold cannot be lower than minimum threshold. Minimum value set to current threshold."));
3801 _ui->fastThresholdMin->setValue(
_ui->fastThreshold->value());
3804 if(
_ui->checkbox_odomDisabled->isChecked() &&
3805 _ui->general_checkBox_SLAM_mode->isChecked() &&
3806 _ui->general_checkBox_activateRGBD->isChecked())
3808 QMessageBox::warning(
this, tr(
"Parameter warning"),
3809 tr(
"Odometry is disabled but incremental RGB-D SLAM is activated! Re-enabling odometry."));
3810 _ui->checkbox_odomDisabled->setChecked(
false);
3813 #if CV_MAJOR_VERSION < 3 || (CV_MAJOR_VERSION == 3 && (CV_MINOR_VERSION <4 || (CV_MINOR_VERSION ==4 && CV_SUBMINOR_VERSION<2)))
3814 if(
_ui->ArucoDictionary->currentIndex()>=17)
3816 QMessageBox::warning(
this, tr(
"Parameter warning"),
3817 tr(
"ArUco dictionary: cannot select AprilTag dictionary, OpenCV version should be at least 3.4.2. Setting back to 0."));
3818 _ui->ArucoDictionary->setCurrentIndex(0);
3827 return tr(
"Reading parameters from the configuration file...");
3835 _ui->lineEdit_dictionaryPath->setEnabled(
false);
3836 _ui->toolButton_dictionaryPath->setEnabled(
false);
3837 _ui->label_dictionaryPath->setEnabled(
false);
3839 _ui->groupBox_source0->setEnabled(
false);
3840 _ui->groupBox_odometry1->setEnabled(
false);
3842 this->setWindowTitle(tr(
"Preferences [Monitoring mode]"));
3846 _ui->lineEdit_dictionaryPath->setEnabled(
true);
3847 _ui->toolButton_dictionaryPath->setEnabled(
true);
3848 _ui->label_dictionaryPath->setEnabled(
true);
3850 _ui->groupBox_source0->setEnabled(
true);
3851 _ui->groupBox_odometry1->setEnabled(
true);
3853 this->setWindowTitle(tr(
"Preferences"));
3859 std::set<std::string> threadsCheckedSet(threadsChecked.begin(), threadsChecked.end());
3860 _ui->comboBox_loggerFilter->clear();
3861 for(std::map<std::string, unsigned long>::iterator
iter=threads.begin();
iter!=threads.end(); ++
iter)
3863 if(threadsCheckedSet.find(
iter->first.c_str()) != threadsCheckedSet.end())
3865 _ui->comboBox_loggerFilter->addItem(QString(
iter->first.c_str()), QVariant(
true));
3869 _ui->comboBox_loggerFilter->addItem(QString(
iter->first.c_str()), QVariant(
false));
3887 QApplication::processEvents();
3892 if(this->isVisible())
3905 if(!window->objectName().isEmpty() && !window->isMaximized())
3908 settings.beginGroup(
"Gui");
3909 settings.beginGroup(window->objectName());
3910 settings.setValue(
"geometry", window->saveGeometry());
3911 settings.endGroup();
3912 settings.endGroup();
3915 settingsTmp.beginGroup(
"Gui");
3916 settingsTmp.beginGroup(window->objectName());
3917 settingsTmp.setValue(
"geometry", window->saveGeometry());
3918 settingsTmp.endGroup();
3919 settingsTmp.endGroup();
3925 if(!window->objectName().isEmpty())
3929 settings.beginGroup(
"Gui");
3930 settings.beginGroup(window->objectName());
3931 bytes = settings.value(
"geometry", QByteArray()).toByteArray();
3932 if(!
bytes.isEmpty())
3934 window->restoreGeometry(
bytes);
3936 settings.endGroup();
3937 settings.endGroup();
3940 settingsTmp.beginGroup(
"Gui");
3941 settingsTmp.beginGroup(window->objectName());
3942 settingsTmp.setValue(
"geometry", window->saveGeometry());
3943 settingsTmp.endGroup();
3944 settingsTmp.endGroup();
3950 if(!mainWindow->objectName().isEmpty())
3955 settings.beginGroup(
"Gui");
3956 settings.beginGroup(mainWindow->objectName());
3957 settings.setValue(
"state", mainWindow->saveState());
3958 settings.setValue(
"maximized", mainWindow->isMaximized());
3959 settings.setValue(
"status_bar", mainWindow->statusBar()->isVisible());
3960 settings.endGroup();
3961 settings.endGroup();
3964 settingsTmp.beginGroup(
"Gui");
3965 settingsTmp.beginGroup(mainWindow->objectName());
3966 settingsTmp.setValue(
"state", mainWindow->saveState());
3967 settingsTmp.setValue(
"maximized", mainWindow->isMaximized());
3968 settingsTmp.setValue(
"status_bar", mainWindow->statusBar()->isVisible());
3969 settingsTmp.endGroup();
3970 settingsTmp.endGroup();
3976 if(!mainWindow->objectName().isEmpty())
3982 settings.beginGroup(
"Gui");
3983 settings.beginGroup(mainWindow->objectName());
3984 bytes = settings.value(
"state", QByteArray()).toByteArray();
3985 if(!
bytes.isEmpty())
3987 mainWindow->restoreState(
bytes);
3989 maximized = settings.value(
"maximized",
false).toBool();
3990 statusBarShown = settings.value(
"status_bar",
false).toBool();
3991 mainWindow->statusBar()->setVisible(statusBarShown);
3992 settings.endGroup();
3993 settings.endGroup();
3996 settingsTmp.beginGroup(
"Gui");
3997 settingsTmp.beginGroup(mainWindow->objectName());
3998 settingsTmp.setValue(
"state", mainWindow->saveState());
3999 settingsTmp.setValue(
"maximized", maximized);
4000 settingsTmp.setValue(
"status_bar", statusBarShown);
4001 settingsTmp.endGroup();
4002 settingsTmp.endGroup();
4008 if(!widget->objectName().isEmpty())
4011 settings.beginGroup(
"Gui");
4012 settings.beginGroup(widget->objectName());
4015 settingsTmp.beginGroup(
"Gui");
4016 settingsTmp.beginGroup(widget->objectName());
4018 const CloudViewer * cloudViewer = qobject_cast<const CloudViewer*>(widget);
4019 const ImageView * imageView = qobject_cast<const ImageView*>(widget);
4020 const ExportCloudsDialog * exportCloudsDialog = qobject_cast<const ExportCloudsDialog*>(widget);
4021 const ExportBundlerDialog * exportBundlerDialog = qobject_cast<const ExportBundlerDialog*>(widget);
4022 const PostProcessingDialog * postProcessingDialog = qobject_cast<const PostProcessingDialog *>(widget);
4023 const GraphViewer * graphViewer = qobject_cast<const GraphViewer *>(widget);
4024 const CalibrationDialog * calibrationDialog = qobject_cast<const CalibrationDialog *>(widget);
4025 const DepthCalibrationDialog * depthCalibrationDialog = qobject_cast<const DepthCalibrationDialog *>(widget);
4037 else if(exportCloudsDialog)
4042 else if(exportBundlerDialog)
4047 else if(postProcessingDialog)
4052 else if(graphViewer)
4057 else if(calibrationDialog)
4062 else if(depthCalibrationDialog)
4069 UERROR(
"Widget \"%s\" cannot be exported in config file.", widget->objectName().toStdString().c_str());
4072 settings.endGroup();
4073 settings.endGroup();
4074 settingsTmp.endGroup();
4075 settingsTmp.endGroup();
4081 if(!widget->objectName().isEmpty())
4085 settings.beginGroup(
"Gui");
4086 settings.beginGroup(widget->objectName());
4089 settingsTmp.beginGroup(
"Gui");
4090 settingsTmp.beginGroup(widget->objectName());
4092 CloudViewer * cloudViewer = qobject_cast<CloudViewer*>(widget);
4093 ImageView * imageView = qobject_cast<ImageView*>(widget);
4097 GraphViewer * graphViewer = qobject_cast<GraphViewer *>(widget);
4098 CalibrationDialog * calibrationDialog = qobject_cast<CalibrationDialog *>(widget);
4111 else if(exportCloudsDialog)
4116 else if(exportBundlerDialog)
4121 else if(postProcessingDialog)
4126 else if(graphViewer)
4131 else if(calibrationDialog)
4136 else if(depthCalibrationDialog)
4143 UERROR(
"Widget \"%s\" cannot be loaded from config file.", widget->objectName().toStdString().c_str());
4146 settings.endGroup();
4147 settings.endGroup();
4148 settingsTmp.endGroup();
4149 settingsTmp.endGroup();
4157 settings.beginGroup(
"Gui");
4158 settings.beginGroup(section);
4160 settings.endGroup();
4161 settings.endGroup();
4164 settingsTmp.beginGroup(
"Gui");
4165 settingsTmp.beginGroup(section);
4167 settingsTmp.endGroup();
4168 settingsTmp.endGroup();
4175 settings.beginGroup(
"Gui");
4176 settings.beginGroup(section);
4177 value = settings.value(
key, QString()).toString();
4178 settings.endGroup();
4179 settings.endGroup();
4182 settingsTmp.beginGroup(
"Gui");
4183 settingsTmp.beginGroup(section);
4185 settingsTmp.endGroup();
4186 settingsTmp.endGroup();
4216 if(parameters.size())
4218 for(rtabmap::ParametersMap::const_iterator
iter = parameters.begin();
iter!=parameters.end(); ++
iter)
4222 if(setOtherParametersToDefault)
4228 if(parameters.find(
iter->first) == parameters.end() &&
4229 iter->first.compare(Parameters::kRtabmapWorkingDirectory())!=0)
4235 if(!this->isVisible())
4247 if(
_ui->comboBox_imuFilter_strategy->currentIndex()==0)
4249 _ui->comboBox_imuFilter_strategy->setCurrentIndex(2);
4256 _ui->comboBox_sourceType->setCurrentIndex(0);
4257 _ui->comboBox_cameraRGBD->setCurrentIndex(src -
kSrcRGBD);
4260 _ui->lineEdit_openniOniPath->clear();
4264 _ui->lineEdit_openni2OniPath->clear();
4268 _ui->lineEdit_k4a_mkv->clear();
4276 _ui->spinBox_rs2_width->setValue(1280);
4277 _ui->spinBox_rs2_height->setValue(720);
4278 _ui->spinBox_rs2_rate->setValue(30);
4279 _ui->checkbox_rs2_irMode->setChecked(
false);
4280 _ui->checkbox_rs2_emitter->setChecked(
true);
4284 _ui->spinBox_rs2_width->setValue(848);
4285 _ui->spinBox_rs2_height->setValue(480);
4286 _ui->spinBox_rs2_rate->setValue(60);
4287 _ui->checkbox_rs2_irMode->setChecked(
true);
4288 _ui->checkbox_rs2_emitter->setChecked(
false);
4294 _ui->comboBox_sourceType->setCurrentIndex(1);
4295 _ui->comboBox_cameraStereo->setCurrentIndex(src -
kSrcStereo);
4300 _ui->comboBox_imuFilter_strategy->setCurrentIndex(0);
4304 _ui->checkBox_depthai_imu_published->setChecked(variant >= 1);
4305 _ui->comboBox_depthai_image_width->setCurrentIndex(1);
4306 _ui->comboBox_depthai_output_mode->setCurrentIndex(variant==2?2:1);
4307 _ui->doubleSpinBox_depthai_dot_intensity->setValue(variant==2?1:0);
4312 _ui->comboBox_sourceType->setCurrentIndex(2);
4313 _ui->source_comboBox_image_type->setCurrentIndex(src -
kSrcRGB);
4317 _ui->comboBox_sourceType->setCurrentIndex(3);
4325 QMessageBox::question(
this, tr(
"Camera Source..."),
4326 tr(
"Do you want to use default camera settings?"),
4327 QMessageBox::Yes | QMessageBox::No, QMessageBox::Yes) == QMessageBox::Yes)
4330 _ui->comboBox_lidar_src->setCurrentIndex(0);
4331 _ui->comboBox_odom_sensor->setCurrentIndex(0);
4334 QMessageBox::question(
this, tr(
"LiDAR Source..."),
4335 tr(
"Do you want to use \"LiDAR 3D ICP\" preset?"),
4336 QMessageBox::Yes | QMessageBox::No, QMessageBox::Yes) == QMessageBox::Yes)
4339 _ui->comboBox_sourceType->setCurrentIndex(4);
4340 _ui->comboBox_odom_sensor->setCurrentIndex(0);
4363 QString dir =
_ui->source_database_lineEdit_path->text();
4368 QStringList paths = QFileDialog::getOpenFileNames(
this, tr(
"Select file"), dir, tr(
"RTAB-Map database files (*.db)"));
4371 int r = QMessageBox::question(
this, tr(
"Odometry in database..."), tr(
"Use odometry saved in database (if some saved)?"), QMessageBox::Yes | QMessageBox::No, QMessageBox::Yes);
4372 _ui->source_checkBox_ignoreOdometry->setChecked(r != QMessageBox::Yes);
4374 if (
_ui->general_doubleSpinBox_detectionRate->value() != 0 &&
_ui->general_spinBox_imagesBufferSize->value() != 0)
4376 r = QMessageBox::question(
this, tr(
"Detection rate..."),
4377 tr(
"Do you want to process all frames? \n\nClicking \"Yes\" will set "
4378 "RTAB-Map's detection rate (%1 Hz) and buffer size (%2) to 0 to make "
4379 "sure that all frames are processed.")
4380 .
arg(
_ui->general_doubleSpinBox_detectionRate->value())
4381 .
arg(
_ui->general_spinBox_imagesBufferSize->value()),
4382 QMessageBox::Yes | QMessageBox::No, QMessageBox::Yes);
4383 if (r == QMessageBox::Yes)
4385 _ui->general_doubleSpinBox_detectionRate->setValue(0.0);
4386 _ui->general_spinBox_imagesBufferSize->setValue(0);
4390 if(paths.size() > 1)
4392 std::vector<std::string> vFileNames(paths.size());
4393 for(
int i=0;
i<paths.size(); ++
i)
4395 vFileNames[
i] = paths[
i].toStdString();
4397 std::sort(vFileNames.begin(), vFileNames.end(),
sortCallback);
4398 for(
int i=0;
i<paths.size(); ++
i)
4400 paths[
i] = vFileNames[
i].c_str();
4404 _ui->source_database_lineEdit_path->setText(paths.size()==1?paths.front():paths.join(
";"));
4405 _ui->source_spinBox_databaseStartId->setValue(0);
4406 _ui->source_spinBox_databaseStopId->setValue(0);
4407 _ui->source_lineEdit_databaseCameraIndex->setText(
"");
4414 viewer->setWindowModality(Qt::WindowModal);
4415 viewer->setAttribute(Qt::WA_DeleteOnClose,
true);
4429 if(!
_ui->lineEdit_source_distortionModel->text().isEmpty() &&
4430 QFileInfo(
_ui->lineEdit_source_distortionModel->text()).exists())
4433 model.load(
_ui->lineEdit_source_distortionModel->text().toStdString());
4437 QString
name = QFileInfo(
_ui->lineEdit_source_distortionModel->text()).baseName()+
".png";
4438 cv::imwrite(
name.toStdString(),
img);
4439 QDesktopServices::openUrl(QUrl::fromLocalFile(
name));
4443 QMessageBox::warning(
this, tr(
"Distortion Model"), tr(
"Model loaded from \"%1\" is not valid!").
arg(
_ui->lineEdit_source_distortionModel->text()));
4448 QMessageBox::warning(
this, tr(
"Distortion Model"), tr(
"File \"%1\" doesn't exist!").
arg(
_ui->lineEdit_source_distortionModel->text()));
4454 QString dir =
_ui->lineEdit_calibrationFile->text();
4459 else if(!dir.contains(
'.'))
4463 QString
path = QFileDialog::getOpenFileName(
this, tr(
"Select file"), dir, tr(
"Calibration file (*.yaml)"));
4466 _ui->lineEdit_calibrationFile->setText(
path);
4472 QString dir =
_ui->lineEdit_odom_sensor_path_calibration->text();
4477 else if(!dir.contains(
'.'))
4481 QString
path = QFileDialog::getOpenFileName(
this, tr(
"Select file"), dir, tr(
"Calibration file (*.yaml)"));
4484 _ui->lineEdit_odom_sensor_path_calibration->setText(
path);
4490 QString dir =
_ui->lineEdit_cameraImages_timestamps->text();
4495 QString
path = QFileDialog::getOpenFileName(
this, tr(
"Select file"), dir, tr(
"Timestamps file (*.txt)"));
4498 _ui->lineEdit_cameraImages_timestamps->setText(
path);
4504 QString dir =
_ui->lineEdit_cameraRGBDImages_path_rgb->text();
4509 QString
path = QFileDialog::getExistingDirectory(
this, tr(
"Select RGB images directory"), dir);
4512 _ui->lineEdit_cameraRGBDImages_path_rgb->setText(
path);
4519 QString dir =
_ui->lineEdit_cameraImages_path_scans->text();
4524 QString
path = QFileDialog::getExistingDirectory(
this, tr(
"Select scans directory"), dir);
4527 _ui->lineEdit_cameraImages_path_scans->setText(
path);
4533 QString dir =
_ui->lineEdit_cameraImages_path_imu->text();
4538 QString
path = QFileDialog::getOpenFileName(
this, tr(
"Select file "), dir, tr(
"EuRoC IMU file (*.csv)"));
4541 _ui->lineEdit_cameraImages_path_imu->setText(
path);
4548 QString dir =
_ui->lineEdit_cameraRGBDImages_path_depth->text();
4553 QString
path = QFileDialog::getExistingDirectory(
this, tr(
"Select depth images directory"), dir);
4556 _ui->lineEdit_cameraRGBDImages_path_depth->setText(
path);
4562 QString dir =
_ui->lineEdit_cameraImages_odom->text();
4567 QString
path = QFileDialog::getOpenFileName(
this, tr(
"Select file"), dir, tr(
"Odometry (*.txt *.log *.toro *.g2o *.csv)"));
4571 for(
int i=0;
i<
_ui->comboBox_cameraImages_odomFormat->count(); ++
i)
4573 list.push_back(
_ui->comboBox_cameraImages_odomFormat->itemText(
i));
4575 QString item = QInputDialog::getItem(
this, tr(
"Odometry Format"), tr(
"Format:"),
list,
_ui->comboBox_cameraImages_odomFormat->currentIndex(),
false);
4578 _ui->lineEdit_cameraImages_odom->setText(
path);
4579 _ui->comboBox_cameraImages_odomFormat->setCurrentIndex(
_ui->comboBox_cameraImages_odomFormat->findText(item));
4586 QString dir =
_ui->lineEdit_cameraImages_gt->text();
4591 QString
path = QFileDialog::getOpenFileName(
this, tr(
"Select file"), dir, tr(
"Ground Truth (*.txt *.log *.toro *.g2o *.csv)"));
4595 for(
int i=0;
i<
_ui->comboBox_cameraImages_gtFormat->count(); ++
i)
4597 list.push_back(
_ui->comboBox_cameraImages_gtFormat->itemText(
i));
4599 QString item = QInputDialog::getItem(
this, tr(
"Ground Truth Format"), tr(
"Format:"),
list,
_ui->comboBox_cameraImages_gtFormat->currentIndex(),
false);
4602 _ui->lineEdit_cameraImages_gt->setText(
path);
4603 _ui->comboBox_cameraImages_gtFormat->setCurrentIndex(
_ui->comboBox_cameraImages_gtFormat->findText(item));
4610 QString dir =
_ui->lineEdit_cameraStereoImages_path_left->text();
4615 QString
path = QFileDialog::getExistingDirectory(
this, tr(
"Select left images directory"), dir);
4618 _ui->lineEdit_cameraStereoImages_path_left->setText(
path);
4624 QString dir =
_ui->lineEdit_cameraStereoImages_path_right->text();
4629 QString
path = QFileDialog::getExistingDirectory(
this, tr(
"Select right images directory"), dir);
4632 _ui->lineEdit_cameraStereoImages_path_right->setText(
path);
4638 QString dir =
_ui->source_images_lineEdit_path->text();
4643 QString
path = QFileDialog::getExistingDirectory(
this, tr(
"Select images directory"),
_ui->source_images_lineEdit_path->text());
4646 _ui->source_images_lineEdit_path->setText(
path);
4647 _ui->source_images_spinBox_startPos->setValue(0);
4648 _ui->source_images_spinBox_maxFrames->setValue(0);
4654 QString dir =
_ui->source_video_lineEdit_path->text();
4659 QString
path = QFileDialog::getOpenFileName(
this, tr(
"Select file"), dir, tr(
"Videos (*.avi *.mpg *.mp4 *.mov *.mkv)"));
4662 _ui->source_video_lineEdit_path->setText(
path);
4668 QString dir =
_ui->lineEdit_cameraStereoVideo_path->text();
4673 QString
path = QFileDialog::getOpenFileName(
this, tr(
"Select file"), dir, tr(
"Videos (*.avi *.mpg *.mp4 *.mov *.mkv)"));
4676 _ui->lineEdit_cameraStereoVideo_path->setText(
path);
4682 QString dir =
_ui->lineEdit_cameraStereoVideo_path_2->text();
4687 QString
path = QFileDialog::getOpenFileName(
this, tr(
"Select file"), dir, tr(
"Videos (*.avi *.mpg *.mp4 *.mov *.mkv)"));
4690 _ui->lineEdit_cameraStereoVideo_path_2->setText(
path);
4696 QString dir =
_ui->lineEdit_source_distortionModel->text();
4701 QString
path = QFileDialog::getOpenFileName(
this, tr(
"Select file"), dir, tr(
"Distortion model (*.bin *.txt)"));
4704 _ui->lineEdit_source_distortionModel->setText(
path);
4710 QString dir =
_ui->lineEdit_openniOniPath->text();
4715 QString
path = QFileDialog::getOpenFileName(
this, tr(
"Select file"), dir, tr(
"OpenNI (*.oni)"));
4718 _ui->lineEdit_openniOniPath->setText(
path);
4724 QString dir =
_ui->lineEdit_openni2OniPath->text();
4729 QString
path = QFileDialog::getOpenFileName(
this, tr(
"Select file"), dir, tr(
"OpenNI (*.oni)"));
4732 _ui->lineEdit_openni2OniPath->setText(
path);
4738 QString dir =
_ui->lineEdit_k4a_mkv->text();
4743 QString
path = QFileDialog::getOpenFileName(
this, tr(
"Select file"), dir, tr(
"K4A recording (*.mkv)"));
4744 if (!
path.isEmpty())
4746 _ui->lineEdit_k4a_mkv->setText(
path);
4752 QString dir =
_ui->lineEdit_zedSvoPath->text();
4757 QString
path = QFileDialog::getOpenFileName(
this, tr(
"Select file"), dir, tr(
"ZED (*.svo)"));
4760 _ui->lineEdit_zedSvoPath->setText(
path);
4766 QString dir =
_ui->lineEdit_rs2_jsonFile->text();
4771 QString
path = QFileDialog::getOpenFileName(
this, tr(
"Select RealSense2 preset"), dir, tr(
"JSON (*.json)"));
4774 _ui->lineEdit_rs2_jsonFile->setText(
path);
4780 QString dir =
_ui->lineEdit_depthai_blob_path->text();
4785 QString
path = QFileDialog::getOpenFileName(
this, tr(
"Select file"), dir, tr(
"MyriadX blob (*.blob)"));
4788 _ui->lineEdit_depthai_blob_path->setText(
path);
4794 QString dir =
_ui->lineEdit_vlp16_pcap_path->text();
4799 QString
path = QFileDialog::getOpenFileName(
this, tr(
"Select file"), dir, tr(
"Velodyne recording (*.pcap)"));
4800 if (!
path.isEmpty())
4802 _ui->lineEdit_vlp16_pcap_path->setText(
path);
4809 QWidget * obj =
_ui->stackedWidget->findChild<QWidget*>(
key.c_str());
4812 QSpinBox * spin = qobject_cast<QSpinBox *>(obj);
4813 QDoubleSpinBox * doubleSpin = qobject_cast<QDoubleSpinBox *>(obj);
4814 QComboBox * combo = qobject_cast<QComboBox *>(obj);
4815 QCheckBox *
check = qobject_cast<QCheckBox *>(obj);
4816 QRadioButton * radio = qobject_cast<QRadioButton *>(obj);
4817 QLineEdit * lineEdit = qobject_cast<QLineEdit *>(obj);
4818 QGroupBox * groupBox = qobject_cast<QGroupBox *>(obj);
4822 int v = QString(
value.c_str()).toInt(&ok);
4825 UERROR(
"Conversion failed from \"%s\" for parameter %s. Original value (%d) is kept.",
value.c_str(),
key.c_str(), spin->value());
4835 double v = QString(
value.c_str()).toDouble(&ok);
4838 UERROR(
"Conversion failed from \"%s\" for parameter %s. Original value (%f) is kept.",
value.c_str(),
key.c_str(), doubleSpin->value());
4842 doubleSpin->setValue(
v);
4849 std::string valueCpy =
value;
4850 if(
key.compare(Parameters::kIcpStrategy()) == 0 ||
4851 key.compare(Parameters::kGridSensor()) == 0)
4853 if(
value.compare(
"true") == 0)
4857 else if(
value.compare(
"false") == 0)
4863 int valueInt = QString(valueCpy.c_str()).toInt(&ok);
4866 UERROR(
"Conversion failed from \"%s\" for parameter %s. Original value (%d) is kept.", valueCpy.c_str(),
key.c_str(), combo->currentIndex());
4870 #ifndef RTABMAP_NONFREE
4872 (combo->objectName().toStdString().compare(Parameters::kKpDetectorStrategy()) == 0 ||
4873 combo->objectName().toStdString().compare(Parameters::kVisFeatureType()) == 0))
4875 UWARN(
"Trying to set \"%s\" to SURF but RTAB-Map isn't built "
4876 "with the nonfree module from OpenCV. Keeping default combo value: %s.",
4877 combo->objectName().toStdString().c_str(),
4878 combo->currentText().toStdString().c_str());
4881 #if CV_MAJOR_VERSION < 3 || (CV_MAJOR_VERSION == 4 && CV_MINOR_VERSION <= 3) || (CV_MAJOR_VERSION == 3 && (CV_MINOR_VERSION < 4 || (CV_MINOR_VERSION==4 && CV_SUBMINOR_VERSION<11)))
4883 (combo->objectName().toStdString().compare(Parameters::kKpDetectorStrategy()) == 0 ||
4884 combo->objectName().toStdString().compare(Parameters::kVisFeatureType()) == 0))
4886 UWARN(
"Trying to set \"%s\" to SIFT but RTAB-Map isn't built "
4887 "with the nonfree module from OpenCV. Keeping default combo value: %s.",
4888 combo->objectName().toStdString().c_str(),
4889 combo->currentText().toStdString().c_str());
4894 #ifndef RTABMAP_ORB_SLAM
4898 if(valueInt==1 && combo->objectName().toStdString().compare(Parameters::kOptimizerStrategy()) == 0)
4901 UWARN(
"Trying to set \"%s\" to g2o but RTAB-Map isn't built "
4902 "with g2o. Falling back to GTSAM.",
4903 combo->objectName().toStdString().c_str());
4908 UWARN(
"Trying to set \"%s\" to g2o but RTAB-Map isn't built "
4909 "with g2o. Keeping default combo value: %s.",
4910 combo->objectName().toStdString().c_str(),
4911 combo->currentText().toStdString().c_str());
4918 if(valueInt==2 && combo->objectName().toStdString().compare(Parameters::kOptimizerStrategy()) == 0)
4921 #ifndef RTABMAP_ORB_SLAM
4927 UWARN(
"Trying to set \"%s\" to GTSAM but RTAB-Map isn't built "
4928 "with GTSAM. Falling back to g2o.",
4929 combo->objectName().toStdString().c_str());
4934 UWARN(
"Trying to set \"%s\" to GTSAM but RTAB-Map isn't built "
4935 "with GTSAM. Keeping default combo value: %s.",
4936 combo->objectName().toStdString().c_str(),
4937 combo->currentText().toStdString().c_str());
4944 combo->setCurrentIndex(valueInt);
4952 _ui->checkBox_useOdomFeatures->blockSignals(
true);
4954 _ui->checkBox_useOdomFeatures->blockSignals(
false);
4964 lineEdit->setText(
value.c_str());
4974 ULOGGER_WARN(
"QObject called %s can't be cast to a supported widget",
key.c_str());
4979 ULOGGER_WARN(
"Can't find the related QObject for parameter %s",
key.c_str());
4991 ULOGGER_ERROR(
"This slot must be triggered by a signal, not a direct call...");
5003 ULOGGER_ERROR(
"This slot must be triggered by a signal, not a direct call...");
5015 ULOGGER_ERROR(
"This slot must be triggered by a signal, not a direct call...");
5027 ULOGGER_ERROR(
"This slot must be triggered by a signal, not a direct call...");
5035 const QComboBox * comboBox = qobject_cast<const QComboBox*>(
object);
5036 const QSpinBox * spinbox = qobject_cast<const QSpinBox*>(
object);
5037 if(comboBox || spinbox)
5045 UWARN(
"Undefined object \"%s\"",
object->objectName().toStdString().c_str());
5059 const QCheckBox * checkbox = qobject_cast<const QCheckBox*>(
object);
5060 const QRadioButton * radio = qobject_cast<const QRadioButton*>(
object);
5061 const QGroupBox * groupBox = qobject_cast<const QGroupBox*>(
object);
5062 if(checkbox || radio || groupBox)
5070 UWARN(
"Undefined object \"%s\"",
object->objectName().toStdString().c_str());
5084 UDEBUG(
"modify param %s=%f",
object->objectName().toStdString().c_str(),
value);
5097 UDEBUG(
"modify param %s=%s",
object->objectName().toStdString().c_str(),
value.toStdString().c_str());
5109 for(
int i=0;
i<children.size(); ++
i)
5111 const QSpinBox * spin = qobject_cast<const QSpinBox *>(children[
i]);
5112 const QDoubleSpinBox * doubleSpin = qobject_cast<const QDoubleSpinBox *>(children[
i]);
5113 const QComboBox * combo = qobject_cast<const QComboBox *>(children[
i]);
5114 const QCheckBox *
check = qobject_cast<const QCheckBox *>(children[
i]);
5115 const QRadioButton * radio = qobject_cast<const QRadioButton *>(children[
i]);
5116 const QLineEdit * lineEdit = qobject_cast<const QLineEdit *>(children[
i]);
5117 const QGroupBox * groupBox = qobject_cast<const QGroupBox *>(children[
i]);
5118 const QStackedWidget * stackedWidget = qobject_cast<const QStackedWidget *>(children[
i]);
5145 if(groupBox->isCheckable())
5154 else if(stackedWidget)
5167 for(
int i=0;
i<stackedWidget->count(); ++
i)
5169 const QObjectList & children = stackedWidget->widget(
i)->children();
5176 const QObjectList & children = stackedWidget->widget(panel)->children();
5186 const QObjectList & children =
box->children();
5198 if(sender() ==
_ui->general_doubleSpinBox_timeThr_2)
5200 _ui->general_doubleSpinBox_timeThr->setValue(
_ui->general_doubleSpinBox_timeThr_2->value());
5202 else if(sender() ==
_ui->general_doubleSpinBox_hardThr_2)
5204 _ui->general_doubleSpinBox_hardThr->setValue(
_ui->general_doubleSpinBox_hardThr_2->value());
5206 else if(sender() ==
_ui->general_doubleSpinBox_detectionRate_2)
5208 _ui->general_doubleSpinBox_detectionRate->setValue(
_ui->general_doubleSpinBox_detectionRate_2->value());
5210 else if(sender() ==
_ui->general_spinBox_imagesBufferSize_2)
5212 _ui->general_spinBox_imagesBufferSize->setValue(
_ui->general_spinBox_imagesBufferSize_2->value());
5214 else if(sender() ==
_ui->general_spinBox_maxStMemSize_2)
5216 _ui->general_spinBox_maxStMemSize->setValue(
_ui->general_spinBox_maxStMemSize_2->value());
5218 else if(sender() ==
_ui->groupBox_publishing)
5220 _ui->general_checkBox_publishStats_2->setChecked(
_ui->groupBox_publishing->isChecked());
5222 else if(sender() ==
_ui->general_checkBox_publishStats_2)
5224 _ui->groupBox_publishing->setChecked(
_ui->general_checkBox_publishStats_2->isChecked());
5226 else if(sender() ==
_ui->doubleSpinBox_similarityThreshold_2)
5228 _ui->doubleSpinBox_similarityThreshold->setValue(
_ui->doubleSpinBox_similarityThreshold_2->value());
5230 else if(sender() ==
_ui->general_checkBox_activateRGBD)
5232 _ui->general_checkBox_activateRGBD_2->blockSignals(
true);
5233 _ui->general_checkBox_activateRGBD_2->setChecked(
_ui->general_checkBox_activateRGBD->isChecked());
5234 _ui->general_checkBox_activateRGBD_2->blockSignals(
false);
5236 else if(sender() ==
_ui->general_checkBox_activateRGBD_2)
5238 _ui->general_checkBox_activateRGBD->blockSignals(
true);
5239 _ui->general_checkBox_activateRGBD->setChecked(
_ui->general_checkBox_activateRGBD_2->isChecked());
5240 addParameter(
_ui->general_checkBox_activateRGBD,
_ui->general_checkBox_activateRGBD->isChecked());
5241 _ui->general_checkBox_activateRGBD->blockSignals(
false);
5243 else if(sender() ==
_ui->general_checkBox_SLAM_mode)
5245 _ui->general_checkBox_SLAM_mode_2->blockSignals(
true);
5246 _ui->general_checkBox_SLAM_mode_2->setChecked(
_ui->general_checkBox_SLAM_mode->isChecked());
5247 _ui->general_checkBox_SLAM_mode_2->blockSignals(
false);
5249 else if(sender() ==
_ui->general_checkBox_SLAM_mode_2)
5251 _ui->general_checkBox_SLAM_mode->blockSignals(
true);
5252 _ui->general_checkBox_SLAM_mode->setChecked(
_ui->general_checkBox_SLAM_mode_2->isChecked());
5253 addParameter(
_ui->general_checkBox_SLAM_mode,
_ui->general_checkBox_SLAM_mode->isChecked());
5254 _ui->general_checkBox_SLAM_mode->blockSignals(
false);
5259 _ui->general_doubleSpinBox_timeThr->setValue(
_ui->general_doubleSpinBox_timeThr_2->value());
5260 _ui->general_doubleSpinBox_hardThr->setValue(
_ui->general_doubleSpinBox_hardThr_2->value());
5261 _ui->general_doubleSpinBox_detectionRate->setValue(
_ui->general_doubleSpinBox_detectionRate_2->value());
5262 _ui->general_spinBox_imagesBufferSize->setValue(
_ui->general_spinBox_imagesBufferSize_2->value());
5263 _ui->general_spinBox_maxStMemSize->setValue(
_ui->general_spinBox_maxStMemSize_2->value());
5264 _ui->doubleSpinBox_similarityThreshold->setValue(
_ui->doubleSpinBox_similarityThreshold_2->value());
5300 QList<QGroupBox*> boxes;
5301 for(
int i=0;
i<
_ui->stackedWidget->count(); ++
i)
5304 const QObjectList & children =
_ui->stackedWidget->widget(
i)->children();
5305 for(
int j=0;
j<children.size(); ++
j)
5307 if((gb = qobject_cast<QGroupBox *>(children.at(
j))))
5319 ULOGGER_ERROR(
"A QGroupBox must be included in the first level of children in stacked widget, index=%d",
i);
5327 QStringList
values =
_ui->lineEdit_bayes_predictionLC->text().simplified().split(
' ');
5330 UERROR(
"Error parsing prediction (must have at least 2 items) : %s",
5331 _ui->lineEdit_bayes_predictionLC->text().toStdString().c_str());
5334 QVector<qreal> dataX((
values.
size()-2)*2 + 1);
5335 QVector<qreal> dataY((
values.
size()-2)*2 + 1);
5341 int loopClosureIndex = (dataX.size()-1)/2;
5347 UERROR(
"Error parsing prediction : \"%s\"",
values.
at(
i).toStdString().c_str());
5357 dataY[loopClosureIndex] =
value;
5358 dataX[loopClosureIndex] = 0;
5362 dataY[loopClosureIndex-lvl] =
value;
5363 dataX[loopClosureIndex-lvl] = -lvl;
5364 dataY[loopClosureIndex+lvl] =
value;
5365 dataX[loopClosureIndex+lvl] = lvl;
5370 _ui->label_prediction_sum->setNum(sum);
5373 _ui->label_prediction_sum->setText(QString(
"<font color=#FF0000>") +
_ui->label_prediction_sum->text() +
"</font>");
5377 _ui->label_prediction_sum->setText(QString(
"<font color=#00FF00>") +
_ui->label_prediction_sum->text() +
"</font>");
5381 _ui->label_prediction_sum->setText(QString(
"<font color=#FFa500>") +
_ui->label_prediction_sum->text() +
"</font>");
5385 _ui->label_prediction_sum->setText(QString(
"<font color=#000000>") +
_ui->label_prediction_sum->text() +
"</font>");
5388 _ui->predictionPlot->removeCurves();
5389 _ui->predictionPlot->addCurve(
new UPlotCurve(
"Prediction", dataX, dataY,
_ui->predictionPlot));
5394 QStringList strings =
_ui->lineEdit_kp_roi->text().split(
' ');
5395 if(strings.size()!=4)
5397 UERROR(
"ROI must have 4 values (%s)",
_ui->lineEdit_kp_roi->text().toStdString().c_str());
5400 _ui->doubleSpinBox_kp_roi0->setValue(strings[0].toDouble()*100.0);
5401 _ui->doubleSpinBox_kp_roi1->setValue(strings[1].toDouble()*100.0);
5402 _ui->doubleSpinBox_kp_roi2->setValue(strings[2].toDouble()*100.0);
5403 _ui->doubleSpinBox_kp_roi3->setValue(strings[3].toDouble()*100.0);
5408 QStringList strings;
5409 strings.append(QString::number(
_ui->doubleSpinBox_kp_roi0->value()/100.0));
5410 strings.append(QString::number(
_ui->doubleSpinBox_kp_roi1->value()/100.0));
5411 strings.append(QString::number(
_ui->doubleSpinBox_kp_roi2->value()/100.0));
5412 strings.append(QString::number(
_ui->doubleSpinBox_kp_roi3->value()/100.0));
5413 _ui->lineEdit_kp_roi->setText(strings.join(
" "));
5419 _ui->checkbox_stereo_depthGenerated->setVisible(
5421 _ui->comboBox_stereoZed_quality->currentIndex() == 0);
5422 _ui->label_stereo_depthGenerated->setVisible(
5424 _ui->comboBox_stereoZed_quality->currentIndex() == 0);
5426 _ui->checkBox_stereo_rectify->setEnabled(
5433 _ui->checkBox_stereo_rectify->setVisible(
_ui->checkBox_stereo_rectify->isEnabled());
5434 _ui->label_stereo_rectify->setVisible(
_ui->checkBox_stereo_rectify->isEnabled());
5439 _ui->groupBox_pymatcher->setVisible(
_ui->reextract_nn->currentIndex() == 6);
5440 _ui->groupBox_gms->setVisible(
_ui->reextract_nn->currentIndex() == 7);
5445 _ui->groupBox_pydescriptor->setVisible(
_ui->comboBox_globalDescriptorExtractor->currentIndex() == 1);
5452 _ui->stackedWidget_odometryType->setCurrentIndex(7);
5456 _ui->stackedWidget_odometryType->setCurrentIndex(index);
5458 _ui->groupBox_odomF2M->setVisible(index==0);
5459 _ui->groupBox_odomF2F->setVisible(index==1);
5460 _ui->groupBox_odomFovis->setVisible(index==2);
5461 _ui->groupBox_odomViso2->setVisible(index==3);
5462 _ui->groupBox_odomDVO->setVisible(index==4);
5463 _ui->groupBox_odomORBSLAM->setVisible(index==5);
5464 _ui->groupBox_odomOKVIS->setVisible(index==6);
5465 _ui->groupBox_odomLOAM->setVisible(index==7);
5466 _ui->groupBox_odomMSCKF->setVisible(index==8);
5467 _ui->groupBox_odomVINS->setVisible(index==9);
5468 _ui->groupBox_odomOpenVINS->setVisible(index==10);
5469 _ui->groupBox_odomOpen3D->setVisible(index==12);
5474 if(this->isVisible() &&
_ui->checkBox_useOdomFeatures->isChecked())
5476 int r = QMessageBox::question(
this, tr(
"Using odometry features for vocabulary..."),
5477 tr(
"Do you want to match vocabulary feature parameters "
5478 "with corresponding ones used for odometry?"), QMessageBox::Yes | QMessageBox::No, QMessageBox::Yes);
5480 if(r == QMessageBox::Yes)
5482 _ui->comboBox_detector_strategy->setCurrentIndex(
_ui->vis_feature_detector->currentIndex());
5483 _ui->surf_doubleSpinBox_maxDepth->setValue(
_ui->loopClosure_bowMaxDepth->value());
5484 _ui->surf_doubleSpinBox_minDepth->setValue(
_ui->loopClosure_bowMinDepth->value());
5485 _ui->surf_spinBox_wordsPerImageTarget->setValue(
_ui->reextract_maxFeatures->value());
5486 _ui->checkBox_kp_ssc->setChecked(
_ui->checkBox_visSSC->isChecked());
5487 _ui->spinBox_KPGridRows->setValue(
_ui->reextract_gridrows->value());
5488 _ui->spinBox_KPGridCols->setValue(
_ui->reextract_gridcols->value());
5489 _ui->lineEdit_kp_roi->setText(
_ui->loopClosure_roi->text());
5490 _ui->subpix_winSize_kp->setValue(
_ui->subpix_winSize->value());
5491 _ui->subpix_iterations_kp->setValue(
_ui->subpix_iterations->value());
5492 _ui->subpix_eps_kp->setValue(
_ui->subpix_eps->value());
5499 QString directory = QFileDialog::getExistingDirectory(
this, tr(
"Working directory"),
_ui->lineEdit_workingDirectory->text());
5500 if(!directory.isEmpty())
5502 ULOGGER_DEBUG(
"New working directory = %s", directory.toStdString().c_str());
5503 _ui->lineEdit_workingDirectory->setText(directory);
5510 if(
_ui->lineEdit_dictionaryPath->text().isEmpty())
5512 path = QFileDialog::getOpenFileName(
this, tr(
"Dictionary"), this->
getWorkingDirectory(), tr(
"Dictionary (*.txt *.db)"));
5516 path = QFileDialog::getOpenFileName(
this, tr(
"Dictionary"),
_ui->lineEdit_dictionaryPath->text(), tr(
"Dictionary (*.txt *.db)"));
5520 _ui->lineEdit_dictionaryPath->setText(
path);
5527 if(
_ui->lineEdit_OdomORBSLAMVocPath->text().isEmpty())
5529 path = QFileDialog::getOpenFileName(
this, tr(
"ORBSLAM Vocabulary"), this->
getWorkingDirectory(), tr(
"Vocabulary (*.txt)"));
5533 path = QFileDialog::getOpenFileName(
this, tr(
"ORBSLAM Vocabulary"),
_ui->lineEdit_OdomORBSLAMVocPath->text(), tr(
"Vocabulary (*.txt)"));
5537 _ui->lineEdit_OdomORBSLAMVocPath->setText(
path);
5544 if(
_ui->lineEdit_OdomOkvisPath->text().isEmpty())
5546 path = QFileDialog::getOpenFileName(
this, tr(
"OKVIS Config"), this->
getWorkingDirectory(), tr(
"OKVIS config (*.yaml)"));
5550 path = QFileDialog::getOpenFileName(
this, tr(
"OKVIS Config"),
_ui->lineEdit_OdomOkvisPath->text(), tr(
"OKVIS config (*.yaml)"));
5554 _ui->lineEdit_OdomOkvisPath->setText(
path);
5561 if(
_ui->lineEdit_OdomVinsPath->text().isEmpty())
5563 path = QFileDialog::getOpenFileName(
this, tr(
"VINS-Fusion Config"), this->
getWorkingDirectory(), tr(
"VINS-Fusion config (*.yaml)"));
5567 path = QFileDialog::getOpenFileName(
this, tr(
"VINS-Fusion Config"),
_ui->lineEdit_OdomVinsPath->text(), tr(
"VINS-Fusion config (*.yaml)"));
5571 _ui->lineEdit_OdomVinsPath->setText(
path);
5578 if(
_ui->lineEdit_OdomOpenVINSLeftMaskPath->text().isEmpty())
5580 path = QFileDialog::getOpenFileName(
this, tr(
"Select Left Mask"), this->
getWorkingDirectory(), tr(
"Image mask (*.jpg *.png)"));
5584 path = QFileDialog::getOpenFileName(
this, tr(
"Select Left Mask"),
_ui->lineEdit_OdomOpenVINSLeftMaskPath->text(), tr(
"Image mask (*.jpg *.png)"));
5588 _ui->lineEdit_OdomOpenVINSLeftMaskPath->setText(
path);
5595 if(
_ui->lineEdit_OdomOpenVINSRightMaskPath->text().isEmpty())
5597 path = QFileDialog::getOpenFileName(
this, tr(
"Select Right Mask"), this->
getWorkingDirectory(), tr(
"Image mask (*.jpg *.png)"));
5601 path = QFileDialog::getOpenFileName(
this, tr(
"Select Right Mask"),
_ui->lineEdit_OdomOpenVINSRightMaskPath->text(), tr(
"Image mask (*.jpg *.png)"));
5605 _ui->lineEdit_OdomOpenVINSRightMaskPath->setText(
path);
5612 if(
_ui->lineEdit_IcpPMConfigPath->text().isEmpty())
5614 path = QFileDialog::getOpenFileName(
this, tr(
"Select file"), this->
getWorkingDirectory(), tr(
"libpointmatcher (*.yaml)"));
5618 path = QFileDialog::getOpenFileName(
this, tr(
"Select file"),
_ui->lineEdit_IcpPMConfigPath->text(), tr(
"libpointmatcher (*.yaml)"));
5622 _ui->lineEdit_IcpPMConfigPath->setText(
path);
5629 if(
_ui->lineEdit_sptorch_path->text().isEmpty())
5631 path = QFileDialog::getOpenFileName(
this, tr(
"Select file"), this->
getWorkingDirectory(), tr(
"SuperPoint weights (*.pt)"));
5635 path = QFileDialog::getOpenFileName(
this, tr(
"Select file"),
_ui->lineEdit_sptorch_path->text(), tr(
"SuperPoint weights (*.pt)"));
5639 _ui->lineEdit_sptorch_path->setText(
path);
5646 if(
_ui->lineEdit_pymatcher_path->text().isEmpty())
5648 path = QFileDialog::getOpenFileName(
this, tr(
"Select file"), this->
getWorkingDirectory(), tr(
"Python wrapper (*.py)"));
5652 path = QFileDialog::getOpenFileName(
this, tr(
"Select file"),
_ui->lineEdit_pymatcher_path->text(), tr(
"Python wrapper (*.py)"));
5656 _ui->lineEdit_pymatcher_path->setText(
path);
5663 if(
_ui->lineEdit_pymatcher_model->text().isEmpty())
5665 path = QFileDialog::getOpenFileName(
this, tr(
"Select file"), this->
getWorkingDirectory(), tr(
"PyTorch model (*.pth *.pt)"));
5669 path = QFileDialog::getOpenFileName(
this, tr(
"Select file"),
_ui->lineEdit_pymatcher_model->text(), tr(
"PyTorch model (*.pth *.pt)"));
5673 _ui->lineEdit_pymatcher_model->setText(
path);
5680 if(
_ui->lineEdit_pydescriptor_path->text().isEmpty())
5682 path = QFileDialog::getOpenFileName(
this, tr(
"Select file"), this->
getWorkingDirectory(), tr(
"Python wrapper (*.py)"));
5686 path = QFileDialog::getOpenFileName(
this, tr(
"Select file"),
_ui->lineEdit_pydescriptor_path->text(), tr(
"Python wrapper (*.py)"));
5690 _ui->lineEdit_pydescriptor_path->setText(
path);
5696 if(
_ui->lineEdit_pydetector_path->text().isEmpty())
5698 path = QFileDialog::getOpenFileName(
this, tr(
"Select file"), this->
getWorkingDirectory(), tr(
"Python wrapper (*.py)"));
5702 path = QFileDialog::getOpenFileName(
this, tr(
"Select file"),
_ui->lineEdit_pydetector_path->text(), tr(
"Python wrapper (*.py)"));
5706 _ui->lineEdit_pydetector_path->setText(
path);
5712 _ui->stackedWidget_src->setVisible(
_ui->comboBox_sourceType->currentIndex() != 4);
5713 _ui->frame_camera_sensor->setVisible(
_ui->comboBox_sourceType->currentIndex() != 4);
5715 _ui->groupBox_sourceRGBD->setVisible(
_ui->comboBox_sourceType->currentIndex() == 0);
5716 _ui->groupBox_sourceStereo->setVisible(
_ui->comboBox_sourceType->currentIndex() == 1);
5717 _ui->groupBox_sourceRGB->setVisible(
_ui->comboBox_sourceType->currentIndex() == 2);
5718 _ui->groupBox_sourceDatabase->setVisible(
_ui->comboBox_sourceType->currentIndex() == 3);
5720 _ui->stackedWidget_rgbd->setVisible(
_ui->comboBox_sourceType->currentIndex() == 0 &&
5730 _ui->groupBox_openni2->setVisible(
_ui->comboBox_sourceType->currentIndex() == 0 &&
_ui->comboBox_cameraRGBD->currentIndex() ==
kSrcOpenNI2-
kSrcRGBD);
5731 _ui->groupBox_freenect2->setVisible(
_ui->comboBox_sourceType->currentIndex() == 0 &&
_ui->comboBox_cameraRGBD->currentIndex() ==
kSrcFreenect2-
kSrcRGBD);
5732 _ui->groupBox_k4w2->setVisible(
_ui->comboBox_sourceType->currentIndex() == 0 &&
_ui->comboBox_cameraRGBD->currentIndex() ==
kSrcK4W2 -
kSrcRGBD);
5733 _ui->groupBox_k4a->setVisible(
_ui->comboBox_sourceType->currentIndex() == 0 &&
_ui->comboBox_cameraRGBD->currentIndex() ==
kSrcK4A -
kSrcRGBD);
5734 _ui->groupBox_realsense->setVisible(
_ui->comboBox_sourceType->currentIndex() == 0 &&
_ui->comboBox_cameraRGBD->currentIndex() ==
kSrcRealSense -
kSrcRGBD);
5735 _ui->groupBox_realsense2->setVisible(
_ui->comboBox_sourceType->currentIndex() == 0 &&
_ui->comboBox_cameraRGBD->currentIndex() ==
kSrcRealSense2 -
kSrcRGBD);
5736 _ui->groupBox_cameraRGBDImages->setVisible(
_ui->comboBox_sourceType->currentIndex() == 0 &&
_ui->comboBox_cameraRGBD->currentIndex() ==
kSrcRGBDImages-
kSrcRGBD);
5737 _ui->groupBox_openni->setVisible(
_ui->comboBox_sourceType->currentIndex() == 0 &&
_ui->comboBox_cameraRGBD->currentIndex() ==
kSrcOpenNI_PCL -
kSrcRGBD);
5739 _ui->stackedWidget_stereo->setVisible(
_ui->comboBox_sourceType->currentIndex() == 1 &&
5748 _ui->groupBox_cameraStereoVideo->setVisible(
_ui->comboBox_sourceType->currentIndex() == 1 &&
_ui->comboBox_cameraStereo->currentIndex() ==
kSrcStereoVideo -
kSrcStereo);
5749 _ui->groupBox_cameraStereoUsb->setVisible(
_ui->comboBox_sourceType->currentIndex() == 1 &&
_ui->comboBox_cameraStereo->currentIndex() ==
kSrcStereoUsb -
kSrcStereo);
5750 _ui->groupBox_cameraStereoZed->setVisible(
_ui->comboBox_sourceType->currentIndex() == 1 &&
_ui->comboBox_cameraStereo->currentIndex() ==
kSrcStereoZed -
kSrcStereo);
5752 _ui->groupBox_cameraStereoZedOC->setVisible(
_ui->comboBox_sourceType->currentIndex() == 1 &&
_ui->comboBox_cameraStereo->currentIndex() ==
kSrcStereoZedOC -
kSrcStereo);
5755 _ui->stackedWidget_image->setVisible(
_ui->comboBox_sourceType->currentIndex() == 2 &&
5759 _ui->source_groupBox_images->setVisible(
_ui->comboBox_sourceType->currentIndex() == 2 &&
_ui->source_comboBox_image_type->currentIndex() ==
kSrcImages-
kSrcRGB);
5760 _ui->source_groupBox_video->setVisible(
_ui->comboBox_sourceType->currentIndex() == 2 &&
_ui->source_comboBox_image_type->currentIndex() ==
kSrcVideo-
kSrcRGB);
5761 _ui->source_groupBox_usbcam->setVisible(
_ui->comboBox_sourceType->currentIndex() == 2 &&
_ui->source_comboBox_image_type->currentIndex() ==
kSrcUsbDevice-
kSrcRGB);
5763 _ui->groupBox_sourceImages_optional->setVisible(
5766 (
_ui->comboBox_sourceType->currentIndex() == 2 &&
_ui->source_comboBox_image_type->currentIndex() ==
kSrcImages-
kSrcRGB));
5768 _ui->groupBox_depthImageFiltering->setEnabled(
5769 _ui->comboBox_sourceType->currentIndex() == 0 ||
5770 _ui->comboBox_sourceType->currentIndex() == 3);
5771 _ui->groupBox_depthImageFiltering->setVisible(
_ui->groupBox_depthImageFiltering->isEnabled());
5773 _ui->groupBox_depthFromScan->setVisible(
_ui->comboBox_sourceType->currentIndex() == 2 &&
_ui->source_comboBox_image_type->currentIndex() ==
kSrcImages-
kSrcRGB);
5777 _ui->groupBox_odom_sensor->setVisible(
_ui->comboBox_sourceType->currentIndex() != 3);
5780 _ui->comboBox_lidar_src->setEnabled(
_ui->comboBox_sourceType->currentIndex() != 3);
5781 if(!
_ui->comboBox_lidar_src->isEnabled() &&
_ui->comboBox_lidar_src->currentIndex() != 0)
5783 _ui->comboBox_lidar_src->setCurrentIndex(0);
5785 _ui->checkBox_source_scanFromDepth->setEnabled(
_ui->comboBox_sourceType->currentIndex() <= 1 ||
_ui->comboBox_sourceType->currentIndex() == 3);
5786 _ui->label_source_scanFromDepth->setEnabled(
_ui->checkBox_source_scanFromDepth->isEnabled());
5787 if(!
_ui->checkBox_source_scanFromDepth->isEnabled())
5789 _ui->checkBox_source_scanFromDepth->setChecked(
false);
5791 _ui->stackedWidget_lidar_src->setVisible(
_ui->comboBox_lidar_src->currentIndex() > 0);
5793 _ui->frame_lidar_sensor->setVisible(
_ui->comboBox_lidar_src->currentIndex() > 0 ||
_ui->checkBox_source_scanFromDepth->isChecked());
5794 _ui->pushButton_test_lidar->setEnabled(
_ui->comboBox_lidar_src->currentIndex() > 0);
5797 _ui->groupBox_imuFiltering->setEnabled(
5800 (
_ui->comboBox_sourceType->currentIndex() == 2 &&
_ui->source_comboBox_image_type->currentIndex() ==
kSrcImages-
kSrcRGB) ||
5802 (
_ui->comboBox_sourceType->currentIndex() == 0 &&
_ui->comboBox_cameraRGBD->currentIndex() ==
kSrcK4A -
kSrcRGBD) ||
5811 _ui->stackedWidget_imuFilter->setVisible(
_ui->comboBox_imuFilter_strategy->currentIndex() > 0);
5812 _ui->groupBox_madgwickfilter->setVisible(
_ui->comboBox_imuFilter_strategy->currentIndex() == 1);
5813 _ui->groupBox_complementaryfilter->setVisible(
_ui->comboBox_imuFilter_strategy->currentIndex() == 2);
5814 _ui->groupBox_imuFiltering->setVisible(
_ui->groupBox_imuFiltering->isEnabled());
5821 return _ui->comboBox_loggerLevel->currentIndex();
5825 return _ui->comboBox_loggerEventLevel->currentIndex();
5829 return _ui->comboBox_loggerPauseLevel->currentIndex();
5833 return _ui->comboBox_loggerType->currentIndex();
5837 return _ui->checkBox_logger_printTime->isChecked();
5841 return _ui->checkBox_logger_printThreadId->isChecked();
5845 std::vector<std::string> threads;
5846 for(
int i=0;
i<
_ui->comboBox_loggerFilter->count(); ++
i)
5848 if(
_ui->comboBox_loggerFilter->itemData(
i).toBool())
5850 threads.push_back(
_ui->comboBox_loggerFilter->itemText(
i).toStdString());
5857 return _ui->checkBox_verticalLayoutUsed->isChecked();
5861 return _ui->checkBox_imageRejectedShown->isChecked();
5865 return _ui->checkBox_imageHighestHypShown->isChecked();
5869 return _ui->checkBox_beep->isChecked();
5873 return _ui->checkBox_stamps->isChecked();
5877 return _ui->checkBox_cacheStatistics->isChecked();
5881 return _ui->checkBox_notifyWhenNewGlobalPathIsReceived->isChecked();
5885 return _ui->spinBox_odomQualityWarnThr->value();
5889 return _ui->checkBox_odom_onlyInliersShown->isChecked();
5893 return _ui->radioButton_posteriorGraphView->isChecked();
5897 return _ui->radioButton_wordsGraphView->isChecked();
5901 return _ui->radioButton_localizationsGraphView->isChecked();
5905 return _ui->radioButton_localizationsGraphViewOdomCache->isChecked();
5909 return _ui->checkbox_odomDisabled->isChecked();
5913 return _ui->checkBox_odom_sensor_use_as_gt->isChecked();
5917 return _ui->odom_registration->currentIndex();
5921 return _ui->odom_f2m_gravitySigma->value();
5925 return _ui->checkbox_groundTruthAlign->isChecked();
5930 UASSERT(index >= 0 && index <= 1);
5935 #ifdef RTABMAP_OCTOMAP
5936 return _ui->groupBox_octomap->isChecked();
5942 #ifdef RTABMAP_OCTOMAP
5943 return _ui->groupBox_octomap->isChecked() &&
_ui->checkBox_octomap_show3dMap->isChecked();
5949 return _ui->comboBox_octomap_renderingType->currentIndex();
5953 #ifdef RTABMAP_OCTOMAP
5954 return _ui->groupBox_octomap->isChecked() &&
_ui->checkBox_octomap_2dgrid->isChecked();
5960 return _ui->spinBox_octomap_treeDepth->value();
5964 return _ui->spinBox_octomap_pointSize->value();
5969 return _ui->doubleSpinBox_voxel->value();
5973 return _ui->doubleSpinBox_noiseRadius->value();
5977 return _ui->spinBox_noiseMinNeighbors->value();
5981 return _ui->doubleSpinBox_ceilingFilterHeight->value();
5985 return _ui->doubleSpinBox_floorFilterHeight->value();
5989 return _ui->spinBox_normalKSearch->value();
5993 return _ui->doubleSpinBox_normalRadiusSearch->value();
5997 return _ui->doubleSpinBox_ceilingFilterHeight_scan->value();
6001 return _ui->doubleSpinBox_floorFilterHeight_scan->value();
6005 return _ui->spinBox_normalKSearch_scan->value();
6009 return _ui->doubleSpinBox_normalRadiusSearch_scan->value();
6014 return _ui->checkBox_showGraphs->isChecked();
6018 return _ui->checkBox_showLabels->isChecked();
6022 return _ui->checkBox_showFrames->isChecked();
6026 return _ui->checkBox_showLandmarks->isChecked();
6030 return _ui->doubleSpinBox_landmarkSize->value();
6034 UASSERT(index >= 0 && index <= 1);
6039 UASSERT(index >= 0 && index <= 1);
6044 return _ui->checkBox_showIMUAcc->isChecked();
6048 return _ui->RGBDMarkerDetection->isChecked();
6052 return _ui->ArucoMarkerLength->value();
6056 return _ui->groupBox_organized->isChecked();
6060 return _ui->doubleSpinBox_mesh_angleTolerance->value()*
M_PI/180.0;
6064 return _ui->checkBox_mesh_quad->isChecked();
6068 return _ui->checkBox_mesh_texture->isChecked();
6072 return _ui->spinBox_mesh_triangleSize->value();
6076 UASSERT(index >= 0 && index <= 1);
6081 UASSERT(index >= 0 && index <= 1);
6086 UASSERT(index >= 0 && index <= 1);
6091 UASSERT(index >= 0 && index <= 1);
6092 std::vector<float> roiRatios;
6098 roiRatios.resize(4);
6109 UASSERT(index >= 0 && index <= 1);
6114 UASSERT(index >= 0 && index <= 1);
6119 UASSERT(index >= 0 && index <= 1);
6125 UASSERT(index >= 0 && index <= 1);
6130 UASSERT(index >= 0 && index <= 1);
6135 UASSERT(index >= 0 && index <= 1);
6140 UASSERT(index >= 0 && index <= 1);
6145 UASSERT(index >= 0 && index <= 1);
6150 UASSERT(index >= 0 && index <= 1);
6155 UASSERT(index >= 0 && index <= 1);
6160 UASSERT(index >= 0 && index <= 1);
6166 UASSERT(index >= 0 && index <= 1);
6171 UASSERT(index >= 0 && index <= 1);
6176 UASSERT(index >= 0 && index <= 1);
6182 return _ui->radioButton_nodeFiltering->isChecked();
6186 return _ui->radioButton_subtractFiltering->isChecked();
6190 return _ui->doubleSpinBox_cloudFilterRadius->value();
6194 return _ui->doubleSpinBox_cloudFilterAngle->value();
6198 return _ui->spinBox_subtractFilteringMinPts->value();
6202 return _ui->doubleSpinBox_subtractFilteringRadius->value();
6206 return _ui->doubleSpinBox_subtractFilteringAngle->value()*
M_PI/180.0;
6210 return _ui->doubleSpinBox_map_resolution->value();
6214 return _ui->checkBox_map_shown->isChecked();
6218 return _ui->checkBox_elevation_shown->checkState();
6222 return _ui->comboBox_grid_sensor->currentIndex();
6226 return _ui->checkBox_grid_projMapFrame->isChecked();
6230 return _ui->doubleSpinBox_grid_maxGroundAngle->value()*
M_PI/180.0;
6234 return _ui->doubleSpinBox_grid_maxGroundHeight->value();
6238 return _ui->spinBox_grid_minClusterSize->value();
6242 return _ui->doubleSpinBox_grid_maxObstacleHeight->value();
6246 return _ui->checkBox_grid_flatObstaclesDetected->isChecked();
6250 return _ui->doubleSpinBox_map_opacity->value();
6257 return _ui->general_doubleSpinBox_imgRate->value();
6261 return _ui->source_mirroring->isChecked();
6265 int index =
_ui->comboBox_sourceType->currentIndex();
6310 return _ui->comboBox_cameraRGBD->currentText();
6314 return _ui->comboBox_cameraStereo->currentText();
6318 return _ui->source_comboBox_image_type->currentText();
6329 return _ui->lineEdit_sourceDevice->text();
6334 if(
_ui->comboBox_odom_sensor->currentIndex() == 1)
6339 else if(
_ui->comboBox_odom_sensor->currentIndex() == 2)
6344 else if(
_ui->comboBox_odom_sensor->currentIndex() == 3)
6349 else if(
_ui->comboBox_odom_sensor->currentIndex() != 0)
6351 UERROR(
"Not implemented!");
6358 if(
_ui->comboBox_lidar_src->currentIndex() == 0)
6387 return _ui->lineEdit_cameraImages_path_imu->text();
6400 return _ui->spinBox_cameraImages_max_imu_rate->value();
6405 return _ui->source_checkBox_useDbStamps->isChecked();
6409 return _ui->checkbox_rgbd_colorOnly->isChecked();
6413 return _ui->comboBox_imuFilter_strategy->currentIndex();
6417 return _ui->checkBox_imuFilter_baseFrameConversion->isChecked();
6421 return _ui->groupBox_depthImageFiltering->isEnabled();
6425 return _ui->lineEdit_source_distortionModel->text();
6429 return _ui->groupBox_bilateral->isChecked();
6433 return _ui->doubleSpinBox_bilateral_sigmaS->value();
6437 return _ui->doubleSpinBox_bilateral_sigmaR->value();
6441 return _ui->spinBox_source_imageDecimation->value();
6445 return _ui->comboBox_source_histogramMethod->currentIndex();
6449 return _ui->checkbox_source_feature_detection->isChecked();
6453 return _ui->checkbox_stereo_depthGenerated->isChecked();
6457 return _ui->checkBox_stereo_exposureCompensation->isChecked();
6461 return _ui->checkBox_stereo_rightGrayScale->isChecked();
6465 return _ui->checkBox_source_scanFromDepth->isChecked();
6469 return _ui->checkBox_source_scanDeskewing->isChecked();
6473 return _ui->spinBox_source_scanDownsampleStep->value();
6477 return _ui->doubleSpinBox_source_scanRangeMin->value();
6481 return _ui->doubleSpinBox_source_scanRangeMax->value();
6485 return _ui->doubleSpinBox_source_scanVoxelSize->value();
6489 return _ui->spinBox_source_scanNormalsK->value();
6493 return _ui->doubleSpinBox_source_scanNormalsRadius->value();
6497 return _ui->doubleSpinBox_source_scanNormalsForceGroundUp->value();
6504 _ui->lineEdit_sourceDevice->text(),
6505 _ui->lineEdit_calibrationFile->text(),
6515 const QString & calibrationPath,
6519 bool odomSensorExtrinsicsCalib)
6523 QMessageBox::warning(
this, tr(
"Odometry Sensor"),
6524 tr(
"Driver %1 cannot support odometry only mode.").
arg(driver), QMessageBox::Ok);
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);
6542 _ui->lineEdit_openniOniPath->text().isEmpty()?
device.toStdString():
_ui->lineEdit_openniOniPath->text().toStdString(),
6543 this->getGeneralInputRate(),
6544 this->getSourceLocalTransform());
6550 _ui->lineEdit_openni2OniPath->text().isEmpty()?
device.toStdString():
_ui->lineEdit_openni2OniPath->text().toStdString(),
6552 this->getGeneralInputRate(),
6553 this->getSourceLocalTransform());
6560 this->getGeneralInputRate(),
6561 this->getSourceLocalTransform());
6568 QMessageBox::warning(
this, tr(
"Calibration"),
6569 tr(
"Using raw images for \"OpenNI\" driver is not yet supported. "
6570 "Factory calibration loaded from OpenNI is used."), QMessageBox::Ok);
6586 this->getGeneralInputRate(),
6587 this->getSourceLocalTransform(),
6588 _ui->doubleSpinBox_freenect2MinDepth->value(),
6589 _ui->doubleSpinBox_freenect2MaxDepth->value(),
6590 _ui->checkBox_freenect2BilateralFiltering->isChecked(),
6591 _ui->checkBox_freenect2EdgeAwareFiltering->isChecked(),
6592 _ui->checkBox_freenect2NoiseFiltering->isChecked(),
6593 _ui->lineEdit_freenect2Pipeline->text().toStdString());
6598 device.isEmpty() ? 0 : atoi(
device.toStdString().c_str()),
6600 this->getGeneralInputRate(),
6601 this->getSourceLocalTransform());
6605 if (!
_ui->lineEdit_k4a_mkv->text().isEmpty())
6609 _ui->lineEdit_k4a_mkv->text().toStdString().c_str(),
6610 _ui->source_checkBox_useMKVStamps->isChecked() ? -1 :
this->getGeneralInputRate(),
6611 this->getSourceLocalTransform());
6616 device.isEmpty() ? 0 : atoi(
device.toStdString().c_str()),
6617 this->getGeneralInputRate(),
6618 this->getSourceLocalTransform());
6622 ((
CameraK4A*)
camera)->setPreferences(
_ui->comboBox_k4a_rgb_resolution->currentIndex(),
6623 _ui->comboBox_k4a_framerate->currentIndex(),
6624 _ui->comboBox_k4a_depth_resolution->currentIndex());
6628 if(useRawImages &&
_ui->comboBox_realsenseRGBSource->currentIndex()!=2)
6630 QMessageBox::warning(
this, tr(
"Calibration"),
6631 tr(
"Using raw images for \"RealSense\" driver is not yet supported for color and infrared streams. "
6632 "Factory calibration loaded from RealSense is used."), QMessageBox::Ok);
6638 device.isEmpty() ? 0 : atoi(
device.toStdString().c_str()),
6639 _ui->comboBox_realsensePresetRGB->currentIndex(),
6640 _ui->comboBox_realsensePresetDepth->currentIndex(),
6641 _ui->checkbox_realsenseOdom->isChecked(),
6642 this->getGeneralInputRate(),
6643 this->getSourceLocalTransform());
6652 QMessageBox::warning(
this, tr(
"Calibration"),
6653 tr(
"Using raw images for \"RealSense\" driver is not yet supported. "
6654 "Factory calibration loaded from RealSense2 is used."), QMessageBox::Ok);
6661 this->getGeneralInputRate(),
6662 this->getSourceLocalTransform());
6664 _ui->checkbox_publishInterIMU->isChecked(),
6669 ((
CameraRealSense2*)
camera)->setImagesRectified((
_ui->checkBox_stereo_rectify->isEnabled() &&
_ui->checkBox_stereo_rectify->isChecked()) && !useRawImages);
6677 ((
CameraRealSense2*)
camera)->setDepthResolution(
_ui->spinBox_rs2_width_depth->value(),
_ui->spinBox_rs2_height_depth->value(),
_ui->spinBox_rs2_rate_depth->value());
6688 QMessageBox::warning(
this, tr(
"Calibration"),
6689 tr(
"Using raw images for \"MyntEye\" driver is not yet supported. "
6690 "Factory calibration loaded from MyntEye is used."), QMessageBox::Ok);
6697 _ui->checkbox_stereoMyntEye_rectify->isChecked(),
6698 _ui->checkbox_stereoMyntEye_depth->isChecked(),
6699 this->getGeneralInputRate(),
6700 this->getSourceLocalTransform());
6702 if(
_ui->checkbox_stereoMyntEye_autoExposure->isChecked())
6709 _ui->spinBox_stereoMyntEye_gain->value(),
6710 _ui->spinBox_stereoMyntEye_brightness->value(),
6711 _ui->spinBox_stereoMyntEye_contrast->value());
6714 _ui->spinBox_stereoMyntEye_irControl->value());
6720 _ui->lineEdit_cameraRGBDImages_path_rgb->text().append(QDir::separator()).toStdString(),
6721 _ui->lineEdit_cameraRGBDImages_path_depth->text().append(QDir::separator()).toStdString(),
6722 _ui->doubleSpinBox_cameraRGBDImages_scale->value(),
6723 this->getGeneralInputRate(),
6724 this->getSourceLocalTransform());
6728 ((
CameraRGBDImages*)
camera)->setOdometryPath(
_ui->lineEdit_cameraImages_odom->text().toStdString(),
_ui->comboBox_cameraImages_odomFormat->currentIndex());
6729 ((
CameraRGBDImages*)
camera)->setGroundTruthPath(
_ui->lineEdit_cameraImages_gt->text().toStdString(),
_ui->comboBox_cameraImages_gtFormat->currentIndex());
6732 _ui->lineEdit_cameraImages_path_scans->text().isEmpty()?
"":
_ui->lineEdit_cameraImages_path_scans->text().append(QDir::separator()).toStdString(),
6733 _ui->spinBox_cameraImages_max_scan_pts->value(),
6736 _ui->checkBox_cameraImages_timestamps->isChecked(),
6737 _ui->lineEdit_cameraImages_timestamps->text().toStdString(),
6738 _ui->checkBox_cameraImages_syncTimeStamps->isChecked());
6751 QMessageBox::warning(
this, tr(
"Calibration"),
6752 tr(
"Using raw images for \"FlyCapture2\" driver is not yet supported. "
6753 "Factory calibration loaded from FlyCapture2 is used."), QMessageBox::Ok);
6766 _ui->lineEdit_cameraStereoImages_path_left->text().append(QDir::separator()).toStdString(),
6767 _ui->lineEdit_cameraStereoImages_path_right->text().append(QDir::separator()).toStdString(),
6768 (
_ui->checkBox_stereo_rectify->isEnabled() &&
_ui->checkBox_stereo_rectify->isChecked()) && !useRawImages,
6769 this->getGeneralInputRate(),
6770 this->getSourceLocalTransform());
6774 ((
CameraStereoImages*)
camera)->setOdometryPath(
_ui->lineEdit_cameraImages_odom->text().toStdString(),
_ui->comboBox_cameraImages_odomFormat->currentIndex());
6775 ((
CameraStereoImages*)
camera)->setGroundTruthPath(
_ui->lineEdit_cameraImages_gt->text().toStdString(),
_ui->comboBox_cameraImages_gtFormat->currentIndex());
6778 _ui->lineEdit_cameraImages_path_scans->text().isEmpty()?
"":
_ui->lineEdit_cameraImages_path_scans->text().append(QDir::separator()).toStdString(),
6779 _ui->spinBox_cameraImages_max_scan_pts->value(),
6782 _ui->checkBox_cameraImages_timestamps->isChecked(),
6783 _ui->lineEdit_cameraImages_timestamps->text().toStdString(),
6784 _ui->checkBox_cameraImages_syncTimeStamps->isChecked());
6790 if(
_ui->spinBox_stereo_right_device->value()>=0)
6793 device.isEmpty() ? 0 : atoi(
device.toStdString().c_str()),
6794 _ui->spinBox_stereo_right_device->value(),
6795 (
_ui->checkBox_stereo_rectify->isEnabled() &&
_ui->checkBox_stereo_rectify->isChecked()) && !useRawImages,
6796 this->getGeneralInputRate(),
6797 this->getSourceLocalTransform());
6802 device.isEmpty() ? 0 : atoi(
device.toStdString().c_str()),
6803 (
_ui->checkBox_stereo_rectify->isEnabled() &&
_ui->checkBox_stereo_rectify->isChecked()) && !useRawImages,
6804 this->getGeneralInputRate(),
6805 this->getSourceLocalTransform());
6807 ((
CameraStereoVideo*)
camera)->setResolution(
_ui->spinBox_stereousbcam_streamWidth->value(),
_ui->spinBox_stereousbcam_streamHeight->value());
6808 if(!
_ui->lineEdit_stereousbcam_fourcc->text().isEmpty())
6816 if(!
_ui->lineEdit_cameraStereoVideo_path_2->text().isEmpty())
6820 _ui->lineEdit_cameraStereoVideo_path->text().toStdString(),
6821 _ui->lineEdit_cameraStereoVideo_path_2->text().toStdString(),
6822 (
_ui->checkBox_stereo_rectify->isEnabled() &&
_ui->checkBox_stereo_rectify->isChecked()) && !useRawImages,
6823 this->getGeneralInputRate(),
6824 this->getSourceLocalTransform());
6830 _ui->lineEdit_cameraStereoVideo_path->text().toStdString(),
6831 (
_ui->checkBox_stereo_rectify->isEnabled() &&
_ui->checkBox_stereo_rectify->isChecked()) && !useRawImages,
6832 this->getGeneralInputRate(),
6833 this->getSourceLocalTransform());
6843 (
_ui->checkBox_stereo_rectify->isEnabled() &&
_ui->checkBox_stereo_rectify->isChecked()) && !useRawImages,
6844 this->getGeneralInputRate(),
6845 this->getSourceLocalTransform());
6851 if(!
_ui->lineEdit_zedSvoPath->text().isEmpty())
6854 _ui->lineEdit_zedSvoPath->text().toStdString(),
6855 _ui->comboBox_stereoZed_quality->currentIndex(),
6856 _ui->comboBox_stereoZed_sensingMode->currentIndex(),
6857 _ui->spinBox_stereoZed_confidenceThr->value(),
6861 _ui->checkbox_stereoZed_selfCalibration->isChecked(),
6862 _ui->loopClosure_bowForce2D->isChecked(),
6863 _ui->spinBox_stereoZed_texturenessConfidenceThr->value());
6869 _ui->comboBox_stereoZed_resolution->currentIndex()-1,
6871 _ui->comboBox_stereoZed_quality->currentIndex()==0&&odomOnly?1:
_ui->comboBox_stereoZed_quality->currentIndex(),
6872 _ui->comboBox_stereoZed_sensingMode->currentIndex(),
6873 _ui->spinBox_stereoZed_confidenceThr->value(),
6877 _ui->checkbox_stereoZed_selfCalibration->isChecked(),
6878 _ui->loopClosure_bowForce2D->isChecked(),
6879 _ui->spinBox_stereoZed_texturenessConfidenceThr->value());
6882 _ui->checkbox_publishInterIMU->isChecked(),
6891 device.isEmpty()?-1:atoi(
device.toStdString().c_str()),
6892 _ui->comboBox_stereoZedOC_resolution->currentIndex(),
6893 this->getGeneralInputRate(),
6894 this->getSourceLocalTransform());
6901 device.toStdString().c_str(),
6902 _ui->comboBox_depthai_image_width->currentIndex()?1280:640,
6903 this->getGeneralInputRate(),
6904 this->getSourceLocalTransform());
6906 ((
CameraDepthAI*)
camera)->setDepthProfile(
_ui->spinBox_depthai_conf_threshold->value(),
_ui->spinBox_depthai_lrc_threshold->value());
6907 ((
CameraDepthAI*)
camera)->setExtendedDisparity(
_ui->checkBox_depthai_extended_disparity->isChecked(),
_ui->checkBox_depthai_disparity_companding->isChecked());
6908 ((
CameraDepthAI*)
camera)->setSubpixelMode(
_ui->comboBox_depthai_subpixel_fractional_bits->currentIndex()!=0,
_ui->comboBox_depthai_subpixel_fractional_bits->currentIndex()==2?4:
_ui->comboBox_depthai_subpixel_fractional_bits->currentIndex()==3?5:3);
6909 ((
CameraDepthAI*)
camera)->setDisparityWidthAndFilter(
_ui->comboBox_depthai_disparity_width->currentIndex()==0?64:96,
_ui->comboBox_depthai_median_filter->currentIndex()==2?5:
_ui->comboBox_depthai_median_filter->currentIndex()==3?7:3);
6910 ((
CameraDepthAI*)
camera)->setRectification(
_ui->checkBox_depthai_use_spec_translation->isChecked(),
_ui->doubleSpinBox_depthai_alpha_scaling->value(), !useRawImages);
6911 ((
CameraDepthAI*)
camera)->setIMU(
_ui->checkBox_depthai_imu_published->isChecked(),
_ui->checkbox_publishInterIMU->isChecked());
6912 ((
CameraDepthAI*)
camera)->setIrIntensity(
_ui->doubleSpinBox_depthai_dot_intensity->value(),
_ui->doubleSpinBox_depthai_flood_intensity->value());
6913 ((
CameraDepthAI*)
camera)->setDetectFeatures(
_ui->comboBox_depthai_detect_features->currentIndex(),
_ui->lineEdit_depthai_blob_path->text().toStdString());
6914 if(
_ui->comboBox_depthai_detect_features->currentIndex() == 1)
6916 ((
CameraDepthAI*)
camera)->setGFTTDetector(
_ui->checkBox_GFTT_useHarrisDetector->isChecked(),
_ui->doubleSpinBox_GFTT_minDistance->value(),
_ui->reextract_maxFeatures->value());
6918 else if(
_ui->comboBox_depthai_detect_features->currentIndex() >= 2)
6920 ((
CameraDepthAI*)
camera)->setSuperPointDetector(
_ui->doubleSpinBox_sptorch_threshold->value(),
_ui->checkBox_sptorch_nms->isChecked(),
_ui->spinBox_sptorch_minDistance->value());
6931 _ui->checkbox_publishInterIMU->isChecked(),
6939 (
_ui->checkBox_rgb_rectify->isEnabled() &&
_ui->checkBox_rgb_rectify->isChecked()) && !useRawImages,
6940 this->getGeneralInputRate(),
6941 this->getSourceLocalTransform());
6942 ((
CameraVideo*)
camera)->setResolution(
_ui->spinBox_usbcam_streamWidth->value(),
_ui->spinBox_usbcam_streamHeight->value());
6943 if(!
_ui->lineEdit_usbcam_fourcc->text().isEmpty())
6951 _ui->source_video_lineEdit_path->text().toStdString(),
6952 (
_ui->checkBox_rgb_rectify->isEnabled() &&
_ui->checkBox_rgb_rectify->isChecked()) && !useRawImages,
6953 this->getGeneralInputRate(),
6954 this->getSourceLocalTransform());
6959 _ui->source_images_lineEdit_path->text().toStdString(),
6960 this->getGeneralInputRate(),
6961 this->getSourceLocalTransform());
6965 ((
CameraImages*)
camera)->setImagesRectified((
_ui->checkBox_rgb_rectify->isEnabled() &&
_ui->checkBox_rgb_rectify->isChecked()) && !useRawImages);
6969 _ui->lineEdit_cameraImages_odom->text().toStdString(),
6970 _ui->comboBox_cameraImages_odomFormat->currentIndex());
6972 _ui->lineEdit_cameraImages_gt->text().toStdString(),
6973 _ui->comboBox_cameraImages_gtFormat->currentIndex());
6976 _ui->lineEdit_cameraImages_path_scans->text().isEmpty()?
"":
_ui->lineEdit_cameraImages_path_scans->text().append(QDir::separator()).toStdString(),
6977 _ui->spinBox_cameraImages_max_scan_pts->value(),
6980 _ui->groupBox_depthFromScan->isChecked(),
6981 !
_ui->groupBox_depthFromScan_fillHoles->isChecked()?0:
_ui->radioButton_depthFromScan_vertical->isChecked()?1:-1,
6982 _ui->checkBox_depthFromScan_fillBorders->isChecked());
6984 _ui->checkBox_cameraImages_timestamps->isChecked(),
6985 _ui->lineEdit_cameraImages_timestamps->text().toStdString(),
6986 _ui->checkBox_cameraImages_syncTimeStamps->isChecked());
6991 std::vector<unsigned int> cameraIndices;
6992 if(!
_ui->source_lineEdit_databaseCameraIndex->text().isEmpty())
6995 std::shared_ptr<DBReader>
reader(
6997 _ui->source_database_lineEdit_path->text().toStdString(),
7002 _ui->source_spinBox_databaseStartId->value()));
7006 unsigned int numCamerasInDb =
data.cameraModels().size()>0?
data.cameraModels().size():
data.stereoCameraModels().size();
7007 if(numCamerasInDb>1)
7009 QStringList indicesStr =
_ui->source_lineEdit_databaseCameraIndex->text().split(
' ');
7010 for(QStringList::iterator
iter=indicesStr.begin();
iter!=indicesStr.end(); ++
iter)
7012 cameraIndices.push_back(
iter->toInt());
7013 if(cameraIndices.back() > numCamerasInDb)
7015 QMessageBox::warning(
this,
7016 tr(
"Creating Database Reader"),
7017 tr(
"Camera index %1 is not valid, it should be between 0 and %2. Remove or update camera indices under Source->Database panel (currently set to \"%3\").")
7018 .
arg(cameraIndices.back()).
arg(numCamerasInDb).arg(
_ui->source_lineEdit_databaseCameraIndex->text()),
7020 cameraIndices.clear();
7029 _ui->source_checkBox_useDbStamps->isChecked()?-1:
this->getGeneralInputRate(),
7030 _ui->source_checkBox_ignoreOdometry->isChecked(),
7031 _ui->source_checkBox_ignoreGoalDelay->isChecked(),
7032 _ui->source_checkBox_ignoreGoals->isChecked(),
7033 _ui->source_spinBox_databaseStartId->value(),
7035 _ui->source_spinBox_databaseStopId->value(),
7036 !
_ui->general_checkBox_createIntermediateNodes->isChecked(),
7037 _ui->source_checkBox_ignoreLandmarks->isChecked(),
7038 _ui->source_checkBox_ignoreFeatures->isChecked(),
7041 _ui->source_checkBox_ignorePriors->isChecked());
7045 UFATAL(
"Source driver undefined (%d)!", driver);
7052 QString calibrationFile = calibrationPath;
7055 calibrationFile.remove(
"_left.yaml").remove(
"_right.yaml").remove(
"_pose.yaml").remove(
"_rgb.yaml").remove(
"_depth.yaml");
7057 QString
name = QFileInfo(calibrationFile.remove(
".yaml")).fileName();
7058 if(!calibrationPath.isEmpty())
7060 QDir
d = QFileInfo(calibrationPath).dir();
7061 QString tmp = calibrationPath;
7062 if(!tmp.remove(QFileInfo(calibrationPath).baseName()).isEmpty())
7064 dir =
d.absolutePath();
7068 UDEBUG(
"useRawImages=%d dir=%s", useRawImages?1:0, dir.toStdString().c_str());
7070 if(!
camera->
init(useRawImages?
"":dir.toStdString(),
name.toStdString()))
7072 UWARN(
"init camera failed... ");
7073 QMessageBox::warning(
this,
7075 tr(
"Camera initialization failed..."));
7110 _ui->lineEdit_odomSourceDevice->text().compare(
_ui->lineEdit_sourceDevice->text()) == 0)
7112 QMessageBox::warning(
this, tr(
"Odometry Sensor"),
7113 tr(
"Cannot create an odometry sensor with same driver than camera AND with same "
7114 "device. Change device ID of the odometry or camera sensor. To use odometry option "
7115 "from a single camera, look at the parameters of that driver to enable it, "
7116 "then disable odometry sensor. "), QMessageBox::Ok);
7120 extrinsics =
Transform::fromString(
_ui->lineEdit_odom_sensor_extrinsics->text().replace(
"PI_2", QString::number(3.141592/2.0)).toStdString());
7121 timeOffset =
_ui->doubleSpinBox_odom_sensor_time_offset->value()/1000.0;
7122 scaleFactor = (
float)
_ui->doubleSpinBox_odom_sensor_scale_factor->value();
7123 waitTime =
_ui->doubleSpinBox_odom_sensor_wait_time->value()/1000.0;
7125 return createCamera(driver,
_ui->lineEdit_odomSourceDevice->text(),
_ui->lineEdit_odom_sensor_path_calibration->text(),
false,
true,
true,
false);
7136 #if PCL_VERSION_COMPARE(>=, 1, 8, 0)
7138 if(localTransform.
isNull())
7140 UWARN(
"Failed to parse lidar local transfor string \"%s\"!",
7141 _ui->lineEdit_lidar_local_transform->text().toStdString().c_str());
7144 if(!
_ui->lineEdit_vlp16_pcap_path->text().isEmpty())
7148 _ui->lineEdit_vlp16_pcap_path->text().toStdString(),
7149 _ui->checkBox_vlp16_organized->isChecked(),
7150 _ui->checkBox_vlp16_stamp_last->isChecked(),
7151 this->getGeneralInputRate(),
7159 #
if BOOST_VERSION >= 108700
7160 boost::asio::ip::make_address(
uFormat(
"%ld.%ld.%ld.%ld",
7162 boost::asio::ip::address_v4::from_string(
uFormat(
"%ld.%ld.%ld.%ld",
7164 (
size_t)
_ui->spinBox_vlp16_ip1->value(),
7165 (
size_t)
_ui->spinBox_vlp16_ip2->value(),
7166 (
size_t)
_ui->spinBox_vlp16_ip3->value(),
7167 (
size_t)
_ui->spinBox_vlp16_ip4->value())),
7168 _ui->spinBox_vlp16_port->value(),
7169 _ui->checkBox_vlp16_organized->isChecked(),
7170 _ui->checkBox_vlp16_hostTime->isChecked(),
7171 _ui->checkBox_vlp16_stamp_last->isChecked(),
7172 this->getGeneralInputRate(),
7178 UWARN(
"init lidar failed... ");
7179 QMessageBox::warning(this,
7181 tr(
"Lidar initialization failed..."));
7186 UWARN(
"Lidar cannot be used with rtabmap built with PCL < 1.8... ");
7187 QMessageBox::warning(
this,
7189 tr(
"Lidar initialization failed..."));
7197 return _ui->groupBox_publishing->isChecked();
7201 return _ui->general_doubleSpinBox_hardThr->value();
7205 return _ui->general_doubleSpinBox_vp->value();
7209 return _ui->doubleSpinBox_similarityThreshold->value();
7213 return _ui->odom_strategy->currentIndex();
7217 return _ui->odom_dataBufferSize->value();
7227 return _ui->general_checkBox_imagesKept->isChecked();
7231 return _ui->general_checkBox_missing_cache_republished->isChecked();
7235 return _ui->general_checkBox_cloudsKept->isChecked();
7239 return _ui->general_doubleSpinBox_timeThr->value();
7243 return _ui->general_doubleSpinBox_detectionRate->value();
7247 return _ui->general_checkBox_SLAM_mode->isChecked();
7251 return _ui->general_checkBox_activateRGBD->isChecked();
7255 return _ui->surf_spinBox_wordsPerImageTarget->value();
7259 return _ui->graphOptimization_priorsIgnored->isChecked();
7266 if(
_ui->general_doubleSpinBox_imgRate->value() !=
value)
7268 _ui->general_doubleSpinBox_imgRate->setValue(
value);
7283 if(
_ui->general_doubleSpinBox_detectionRate->value() !=
value)
7285 _ui->general_doubleSpinBox_detectionRate->setValue(
value);
7300 if(
_ui->general_doubleSpinBox_timeThr->value() !=
value)
7302 _ui->general_doubleSpinBox_timeThr->setValue(
value);
7317 if(
_ui->general_checkBox_SLAM_mode->isChecked() != enabled)
7319 _ui->general_checkBox_SLAM_mode->setChecked(enabled);
7344 !
_ui->lineEdit_cameraImages_path_imu->text().isEmpty())
7346 imuThread =
new IMUThread(
_ui->spinBox_cameraImages_max_imu_rate->value(),
this->getIMULocalTransform());
7351 if(!imuThread->
init(
_ui->lineEdit_cameraImages_path_imu->text().toStdString()))
7353 QMessageBox::warning(
this, tr(
"Source IMU Path"),
7354 tr(
"Initialization of IMU data has failed! Path=%1.").
arg(
_ui->lineEdit_cameraImages_path_imu->text()), QMessageBox::Ok);
7366 int odomStrategy = Parameters::defaultOdomStrategy();
7368 if(odomStrategy != 1)
7371 parameters.erase(Parameters::kVisCorType());
7378 _ui->odom_dataBufferSize->value());
7382 _ui->spinBox_decimation_odom->value(),
7384 _ui->doubleSpinBox_maxDepth_odom->value(),
7385 this->getOdomQualityWarnThr(),
7387 this->getAllParameters());
7388 odomViewer->setWindowTitle(tr(
"Odometry viewer"));
7389 odomViewer->resize(1280, 480+QPushButton().minimumHeight());
7397 if(
_ui->checkbox_source_feature_detection->isChecked())
7404 _ui->checkBox_source_scanFromDepth->isChecked(),
7405 _ui->spinBox_source_scanDownsampleStep->value(),
7406 _ui->doubleSpinBox_source_scanRangeMin->value(),
7407 _ui->doubleSpinBox_source_scanRangeMax->value(),
7408 _ui->doubleSpinBox_source_scanVoxelSize->value(),
7409 _ui->spinBox_source_scanNormalsK->value(),
7410 _ui->doubleSpinBox_source_scanNormalsRadius->value(),
7411 (
float)
_ui->doubleSpinBox_source_scanNormalsForceGroundUp->value(),
7412 _ui->checkBox_source_scanDeskewing->isChecked());
7413 if(
_ui->comboBox_imuFilter_strategy->currentIndex()>0 &&
dynamic_cast<DBReader*
>(
camera) == 0)
7415 cameraThread.
enableIMUFiltering(
_ui->comboBox_imuFilter_strategy->currentIndex()-1,
this->getAllParameters(),
_ui->checkBox_imuFilter_baseFrameConversion->isChecked());
7419 if(
_ui->groupBox_bilateral->isChecked())
7422 _ui->doubleSpinBox_bilateral_sigmaS->value(),
7423 _ui->doubleSpinBox_bilateral_sigmaR->value());
7425 if(!
_ui->lineEdit_source_distortionModel->text().isEmpty())
7440 cameraThread.
start();
7452 imuThread->
join(
true);
7455 cameraThread.
join(
true);
7456 odomThread.
join(
true);
7462 window->setWindowTitle(tr(
"Camera viewer"));
7463 window->resize(1280, 480+QPushButton().minimumHeight());
7474 if(
_ui->checkbox_source_feature_detection->isChecked())
7481 _ui->checkBox_source_scanFromDepth->isChecked(),
7482 _ui->spinBox_source_scanDownsampleStep->value(),
7483 _ui->doubleSpinBox_source_scanRangeMin->value(),
7484 _ui->doubleSpinBox_source_scanRangeMax->value(),
7485 _ui->doubleSpinBox_source_scanVoxelSize->value(),
7486 _ui->spinBox_source_scanNormalsK->value(),
7487 _ui->doubleSpinBox_source_scanNormalsRadius->value(),
7488 (
float)
_ui->doubleSpinBox_source_scanNormalsForceGroundUp->value(),
7489 _ui->checkBox_source_scanDeskewing->isChecked());
7490 if(
_ui->comboBox_imuFilter_strategy->currentIndex()>0 &&
dynamic_cast<DBReader*
>(
camera) == 0)
7492 cameraThread.
enableIMUFiltering(
_ui->comboBox_imuFilter_strategy->currentIndex()-1,
this->getAllParameters(),
_ui->checkBox_imuFilter_baseFrameConversion->isChecked());
7496 if(
_ui->groupBox_bilateral->isChecked())
7499 _ui->doubleSpinBox_bilateral_sigmaS->value(),
7500 _ui->doubleSpinBox_bilateral_sigmaR->value());
7502 if(!
_ui->lineEdit_source_distortionModel->text().isEmpty())
7509 cameraThread.
start();
7512 cameraThread.
join(
true);
7524 QMessageBox::warning(
this,
7526 tr(
"Cannot calibrate database source!"));
7536 if(!dir.mkpath(
this->getCameraInfoDir()))
7547 QMessageBox::StandardButton button = QMessageBox::question(
this, tr(
"Calibration"),
7548 tr(
"With \"%1\" driver, Color and IR cameras cannot be streamed at the "
7549 "same time. A 3-steps calibration is required (Color -> IR -> extrinsics). We will "
7550 "start with the Color camera calibration. Do you want to continue?").
arg(this->
getSourceDriverStr()),
7551 QMessageBox::Yes | QMessageBox::No | QMessageBox::Ignore, QMessageBox::Yes);
7553 if(button == QMessageBox::Yes || button == QMessageBox::Ignore)
7560 if(button != QMessageBox::Ignore)
7573 cameraThread.
start();
7576 cameraThread.
join(
true);
7580 button = QMessageBox::question(
this, tr(
"Calibration"),
7581 tr(
"We will now calibrate the IR camera. Hide the IR projector with a Post-It and "
7582 "make sure you have enough ambient IR light (e.g., external IR source or sunlight!) to see the "
7583 "checkerboard with the IR camera. Do you want to continue?"),
7584 QMessageBox::Yes | QMessageBox::No | QMessageBox::Ignore, QMessageBox::Yes);
7585 if(button == QMessageBox::Yes || button == QMessageBox::Ignore)
7588 if(button != QMessageBox::Ignore)
7601 cameraThread.
start();
7604 cameraThread.
join(
true);
7608 button = QMessageBox::question(
this, tr(
"Calibration"),
7609 tr(
"We will now calibrate the extrinsics. Important: Make sure "
7610 "the cameras and the checkerboard don't move and that both "
7611 "cameras can see the checkerboard. We will repeat this "
7612 "multiple times. Each time, you will have to move the camera (or "
7613 "checkerboard) for a different point of view. Do you want to "
7615 QMessageBox::Yes | QMessageBox::No, QMessageBox::Yes);
7618 int totalSamples = 0;
7619 if(button == QMessageBox::Yes)
7621 totalSamples = QInputDialog::getInt(
this, tr(
"Calibration"), tr(
"Samples: "), 1, 1, 99, 1, &ok);
7635 for(;
count < totalSamples && button == QMessageBox::Yes; )
7666 if(
count < totalSamples)
7668 button = QMessageBox::question(
this, tr(
"Calibration"),
7669 tr(
"A stereo pair has been taken (total=%1/%2). Move the checkerboard or "
7670 "camera to another position. Press \"Yes\" when you are ready "
7671 "for the next capture.").
arg(
count).
arg(totalSamples),
7672 QMessageBox::Yes | QMessageBox::Abort, QMessageBox::Yes);
7677 button = QMessageBox::question(
this, tr(
"Calibration"),
7678 tr(
"Could not detect the checkerboard on both images or "
7679 "the point of view didn't change enough. Try again?"),
7680 QMessageBox::Yes | QMessageBox::No, QMessageBox::Yes);
7685 button = QMessageBox::question(
this, tr(
"Calibration"),
7686 tr(
"Failed to start the camera. Try again?"), QMessageBox::Yes | QMessageBox::No, QMessageBox::Yes);
7689 if(
count == totalSamples && button == QMessageBox::Yes)
7692 stereoModel.
setName(stereoModel.
name(),
"depth",
"rgb");
7695 QMessageBox::warning(
this, tr(
"Calibration"),
7696 tr(
"Extrinsic calibration has failed! Look on the terminal "
7697 "for possible error messages. Make sure corresponding calibration files exist "
7698 "in \"%1\" folder for camera \"%2\" or calibration name set. If not, re-do "
7699 "step 1 and 2 and make sure to export the calibration files.").
arg(this->
getCameraInfoDir()).
arg(serial.c_str()), QMessageBox::Ok);
7703 QMessageBox::information(
this, tr(
"Calibration"),
7704 tr(
"Calibration is completed! Extrinsics have been saved to \"%1/%2_pose.yaml\"").
arg(this->
getCameraInfoDir()).
arg(stereoModel.
name().c_str()), QMessageBox::Ok);
7720 bool rgbDepth = freenect2 || (driver==
kSrcStereoDepthAI &&
_ui->comboBox_depthai_output_mode->currentIndex() == 2);
7734 cameraThread.
start();
7739 cameraThread.
join(
true);
7757 QMessageBox::warning(
this,
7759 tr(
"Cannot calibrate database source!"));
7769 if(!dir.mkpath(
this->getCameraInfoDir()))
7779 QMessageBox::warning(
this,
7781 tr(
"No odometry sensor selected!"));
7787 QMessageBox::StandardButton button = QMessageBox::question(
this, tr(
"Calibration"),
7788 tr(
"We will calibrate the extrinsics. Important: Make sure "
7789 "the cameras and the checkerboard don't move and that both "
7790 "cameras can see the checkerboard. We will repeat this "
7791 "multiple times. Each time, you will have to move the camera (or "
7792 "checkerboard) for a different point of view. Do you want to "
7794 QMessageBox::Yes | QMessageBox::No, QMessageBox::Yes);
7796 if(button == QMessageBox::Yes)
7801 int totalSamples = 0;
7802 if(button == QMessageBox::Yes)
7804 QDialog dialog(
this);
7805 QFormLayout form(&dialog);
7808 QSpinBox *
samples =
new QSpinBox(&dialog);
7812 QSpinBox * boardWidth =
new QSpinBox(&dialog);
7813 boardWidth->setMinimum(2);
7814 boardWidth->setMaximum(99);
7816 QSpinBox * boardHeight =
new QSpinBox(&dialog);
7817 boardHeight->setMinimum(2);
7818 boardHeight->setMaximum(99);
7820 QDoubleSpinBox * squareSize =
new QDoubleSpinBox(&dialog);
7821 squareSize->setDecimals(4);
7822 squareSize->setMinimum(0.0001);
7823 squareSize->setMaximum(9);
7825 squareSize->setSuffix(
" m");
7826 form.addRow(
"Samples: ",
samples);
7827 form.addRow(
"Checkerboard Width: ", boardWidth);
7828 form.addRow(
"Checkerboard Height: ", boardHeight);
7829 form.addRow(
"Checkerboard Square Size: ", squareSize);
7832 QDialogButtonBox buttonBox(QDialogButtonBox::Ok | QDialogButtonBox::Cancel,
7834 form.addRow(&buttonBox);
7835 QObject::connect(&buttonBox, SIGNAL(accepted()), &dialog, SLOT(accept()));
7836 QObject::connect(&buttonBox, SIGNAL(rejected()), &dialog, SLOT(reject()));
7839 if (dialog.exec() == QDialog::Accepted) {
7843 totalSamples =
samples->value();
7860 for(;
count < totalSamples && button == QMessageBox::Yes; )
7865 _ui->lineEdit_odomSourceDevice->text(),
7866 _ui->lineEdit_odom_sensor_path_calibration->text(),
7867 false,
true,
false,
true);
7875 tr(
"Odom sensor is not calibrated. Camera and odometry sensor should be individually calibrated (intrinsics) before calibrating the extrinsics between them. Aborting..."), QMessageBox::Ok);
7888 int currentIndex =
_ui->comboBox_odom_sensor->currentIndex();
7889 _ui->comboBox_odom_sensor->setCurrentIndex(0);
7891 _ui->comboBox_odom_sensor->setCurrentIndex(currentIndex);
7899 tr(
"Odom sensor is not calibrated. Camera and odometry sensor should be individually calibrated (intrinsics) before calibrating the extrinsics between them. Aborting..."), QMessageBox::Ok);
7920 if(
count < totalSamples)
7923 tr(
"A stereo pair has been taken (total=%1/%2). Move the checkerboard or "
7924 "camera to another position. Press \"Yes\" when you are ready "
7925 "for the next capture.").
arg(
count).
arg(totalSamples),
7926 QMessageBox::Yes | QMessageBox::Abort, QMessageBox::Yes);
7932 tr(
"Could not detect the checkerboard on both images or "
7933 "the point of view didn't change enough. Try again?"),
7934 QMessageBox::Yes | QMessageBox::No, QMessageBox::Yes);
7940 tr(
"Failed to start the camera. Try again?"), QMessageBox::Yes | QMessageBox::No, QMessageBox::Yes);
7943 if(
count == totalSamples && button == QMessageBox::Yes)
7947 odomSensorModel =
CameraModel(
"odom_sensor", odomSensorModel.
imageSize(), odomSensorModel.
K(), cv::Mat::zeros(1,5,CV_64FC1), cv::Mat(), cv::Mat(), odomSensorModel.
localTransform());
7950 stereoModel.
setName(stereoModel.
name(),
"camera",
"odom_sensor");
7954 tr(
"Extrinsic calibration has failed! Look on the terminal "
7955 "for possible error messages."), QMessageBox::Ok);
7956 std::cout <<
"stereoModel: " << stereoModel << std::endl;
7964 UINFO(
"Odom sensor frame to camera frame: %s",
t.prettyPrint().c_str());
7968 _ui->lineEdit_odom_sensor_extrinsics->setText(QString(
"%1 %2 %3 %4 %5 %6")
7972 tr(
"Calibration is completed! Extrinsics have been computed: %1. "
7973 "You can close the calibration dialog.").
arg(
t.prettyPrint().c_str()), QMessageBox::Ok);
7983 window->setWindowTitle(tr(
"Lidar viewer"));
7984 window->setWindowFlags(Qt::Window);
7985 window->resize(1280, 480+QPushButton().minimumHeight());
7994 _ui->checkBox_source_scanFromDepth->isChecked(),
7995 _ui->spinBox_source_scanDownsampleStep->value(),
7996 _ui->doubleSpinBox_source_scanRangeMin->value(),
7997 _ui->doubleSpinBox_source_scanRangeMax->value(),
7998 _ui->doubleSpinBox_source_scanVoxelSize->value(),
7999 _ui->spinBox_source_scanNormalsK->value(),
8000 _ui->doubleSpinBox_source_scanNormalsRadius->value(),
8001 (
float)
_ui->doubleSpinBox_source_scanNormalsForceGroundUp->value(),
8002 _ui->checkBox_source_scanDeskewing->isChecked());
8006 lidarThread.
start();
8009 lidarThread.
join(
true);