33 #include <QtCore/QSettings> 34 #include <QtCore/QDir> 35 #include <QtCore/QTimer> 38 #include <QButtonGroup> 39 #include <QFileDialog> 40 #include <QInputDialog> 41 #include <QMessageBox> 42 #include <QtGui/QStandardItemModel> 43 #include <QMainWindow> 44 #include <QProgressDialog> 47 #include <QFormLayout> 48 #include <QDesktopServices> 49 #include <QtGui/QCloseEvent> 51 #include "ui_preferencesDialog.h" 53 #include "rtabmap/core/Version.h" 86 #include <opencv2/opencv_modules.hpp> 87 #if CV_MAJOR_VERSION < 3 88 #ifdef HAVE_OPENCV_GPU 89 #include <opencv2/gpu/gpu.hpp> 92 #ifdef HAVE_OPENCV_CUDAFEATURES2D 93 #include <opencv2/core/cuda.hpp> 103 _obsoletePanels(kPanelDummy),
107 _progressDialog(new QProgressDialog(this)),
119 _ui =
new Ui_preferencesDialog();
122 bool haveCuda =
false;
123 #if CV_MAJOR_VERSION < 3 124 #ifdef HAVE_OPENCV_GPU 125 haveCuda = cv::gpu::getCudaEnabledDeviceCount() != 0;
128 #ifdef HAVE_OPENCV_CUDAFEATURES2D 129 haveCuda = cv::cuda::getCudaEnabledDeviceCount() != 0;
134 _ui->surf_checkBox_gpuVersion->setChecked(
false);
135 _ui->surf_checkBox_gpuVersion->setEnabled(
false);
136 _ui->label_surf_checkBox_gpuVersion->setEnabled(
false);
137 _ui->surf_doubleSpinBox_gpuKeypointsRatio->setEnabled(
false);
138 _ui->label_surf_checkBox_gpuKeypointsRatio->setEnabled(
false);
140 _ui->fastGpu->setChecked(
false);
141 _ui->fastGpu->setEnabled(
false);
142 _ui->label_fastGPU->setEnabled(
false);
143 _ui->fastKeypointRatio->setEnabled(
false);
144 _ui->label_fastGPUKptRatio->setEnabled(
false);
146 _ui->checkBox_ORBGpu->setChecked(
false);
147 _ui->checkBox_ORBGpu->setEnabled(
false);
148 _ui->label_orbGpu->setEnabled(
false);
151 _ui->comboBox_dictionary_strategy->setItemData(4, 0, Qt::UserRole - 1);
152 _ui->reextract_nn->setItemData(4, 0, Qt::UserRole - 1);
155 #ifndef RTABMAP_OCTOMAP 156 _ui->groupBox_octomap->setChecked(
false);
157 _ui->groupBox_octomap->setEnabled(
false);
160 #ifndef RTABMAP_REALSENSE_SLAM 161 _ui->checkbox_realsenseOdom->setChecked(
false);
162 _ui->checkbox_realsenseOdom->setEnabled(
false);
163 _ui->label_realsenseOdom->setEnabled(
false);
166 #ifndef RTABMAP_FOVIS 167 _ui->odom_strategy->setItemData(2, 0, Qt::UserRole - 1);
169 #ifndef RTABMAP_VISO2 170 _ui->odom_strategy->setItemData(3, 0, Qt::UserRole - 1);
173 _ui->odom_strategy->setItemData(4, 0, Qt::UserRole - 1);
175 #ifndef RTABMAP_ORB_SLAM 176 _ui->odom_strategy->setItemData(5, 0, Qt::UserRole - 1);
177 #elif RTABMAP_ORB_SLAM == 3 178 _ui->odom_strategy->setItemText(5,
"ORB SLAM 3");
179 _ui->groupBox_odomORBSLAM->setTitle(
"ORB SLAM 3");
181 _ui->odom_strategy->setItemText(5,
"ORB SLAM 2");
182 _ui->groupBox_odomORBSLAM->setTitle(
"ORB SLAM 2");
184 #ifndef RTABMAP_OKVIS 185 _ui->odom_strategy->setItemData(6, 0, Qt::UserRole - 1);
188 _ui->odom_strategy->setItemData(7, 0, Qt::UserRole - 1);
190 #ifndef RTABMAP_MSCKF_VIO 191 _ui->odom_strategy->setItemData(8, 0, Qt::UserRole - 1);
194 _ui->odom_strategy->setItemData(9, 0, Qt::UserRole - 1);
196 #ifndef RTABMAP_OPENVINS 197 _ui->odom_strategy->setItemData(10, 0, Qt::UserRole - 1);
199 #ifndef RTABMAP_FLOAM 200 _ui->odom_strategy->setItemData(11, 0, Qt::UserRole - 1);
202 #ifndef RTABMAP_OPEN3D 203 _ui->odom_strategy->setItemData(12, 0, Qt::UserRole - 1);
206 #if CV_MAJOR_VERSION < 3 207 _ui->stereosgbm_mode->setItemData(2, 0, Qt::UserRole - 1);
211 #ifndef RTABMAP_NONFREE 212 _ui->comboBox_detector_strategy->setItemData(0, 0, Qt::UserRole - 1);
213 _ui->comboBox_detector_strategy->setItemData(12, 0, Qt::UserRole - 1);
214 _ui->comboBox_detector_strategy->setItemData(14, 0, Qt::UserRole - 1);
215 _ui->vis_feature_detector->setItemData(0, 0, Qt::UserRole - 1);
216 _ui->vis_feature_detector->setItemData(12, 0, Qt::UserRole - 1);
217 _ui->vis_feature_detector->setItemData(14, 0, Qt::UserRole - 1);
221 #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))) 222 #ifndef RTABMAP_NONFREE 223 _ui->comboBox_detector_strategy->setItemData(1, 0, Qt::UserRole - 1);
224 _ui->vis_feature_detector->setItemData(1, 0, Qt::UserRole - 1);
228 #if CV_MAJOR_VERSION >= 3 && !defined(HAVE_OPENCV_XFEATURES2D) 229 _ui->comboBox_detector_strategy->setItemData(3, 0, Qt::UserRole - 1);
230 _ui->comboBox_detector_strategy->setItemData(4, 0, Qt::UserRole - 1);
231 _ui->comboBox_detector_strategy->setItemData(5, 0, Qt::UserRole - 1);
232 _ui->comboBox_detector_strategy->setItemData(6, 0, Qt::UserRole - 1);
233 _ui->comboBox_detector_strategy->setItemData(12, 0, Qt::UserRole - 1);
234 _ui->comboBox_detector_strategy->setItemData(13, 0, Qt::UserRole - 1);
235 _ui->comboBox_detector_strategy->setItemData(14, 0, Qt::UserRole - 1);
236 _ui->vis_feature_detector->setItemData(3, 0, Qt::UserRole - 1);
237 _ui->vis_feature_detector->setItemData(4, 0, Qt::UserRole - 1);
238 _ui->vis_feature_detector->setItemData(5, 0, Qt::UserRole - 1);
239 _ui->vis_feature_detector->setItemData(6, 0, Qt::UserRole - 1);
240 _ui->vis_feature_detector->setItemData(12, 0, Qt::UserRole - 1);
241 _ui->vis_feature_detector->setItemData(13, 0, Qt::UserRole - 1);
242 _ui->vis_feature_detector->setItemData(14, 0, Qt::UserRole - 1);
245 #ifndef RTABMAP_ORB_OCTREE 246 _ui->comboBox_detector_strategy->setItemData(10, 0, Qt::UserRole - 1);
247 _ui->vis_feature_detector->setItemData(10, 0, Qt::UserRole - 1);
250 #ifndef RTABMAP_TORCH 251 _ui->comboBox_detector_strategy->setItemData(11, 0, Qt::UserRole - 1);
252 _ui->vis_feature_detector->setItemData(11, 0, Qt::UserRole - 1);
255 #ifndef RTABMAP_PYTHON 256 _ui->comboBox_detector_strategy->setItemData(15, 0, Qt::UserRole - 1);
257 _ui->vis_feature_detector->setItemData(15, 0, Qt::UserRole - 1);
258 _ui->reextract_nn->setItemData(6, 0, Qt::UserRole - 1);
261 #if !defined(HAVE_OPENCV_XFEATURES2D) || (CV_MAJOR_VERSION == 3 && (CV_MINOR_VERSION<4 || CV_MINOR_VERSION==4 && CV_SUBMINOR_VERSION<1)) 262 _ui->reextract_nn->setItemData(7, 0, Qt::UserRole - 1);
265 #if CV_MAJOR_VERSION >= 3 266 _ui->groupBox_fast_opencv2->setEnabled(
false);
268 _ui->comboBox_detector_strategy->setItemData(9, 0, Qt::UserRole - 1);
269 _ui->comboBox_detector_strategy->setItemData(13, 0, Qt::UserRole - 1);
270 _ui->comboBox_detector_strategy->setItemData(14, 0, Qt::UserRole - 1);
271 _ui->vis_feature_detector->setItemData(9, 0, Qt::UserRole - 1);
272 _ui->vis_feature_detector->setItemData(13, 0, Qt::UserRole - 1);
273 _ui->vis_feature_detector->setItemData(14, 0, Qt::UserRole - 1);
276 _ui->comboBox_cameraImages_odomFormat->setItemData(4, 0, Qt::UserRole - 1);
277 _ui->comboBox_cameraImages_gtFormat->setItemData(4, 0, Qt::UserRole - 1);
280 _ui->graphOptimization_type->setItemData(1, 0, Qt::UserRole - 1);
281 _ui->odom_f2m_bundleStrategy->setItemData(1, 0, Qt::UserRole - 1);
282 _ui->loopClosure_bundle->setItemData(1, 0, Qt::UserRole - 1);
283 _ui->groupBoxx_g2o->setEnabled(
false);
285 #ifdef RTABMAP_ORB_SLAM 289 _ui->graphOptimization_type->setItemData(1, 0, Qt::UserRole - 1);
294 _ui->comboBox_g2o_solver->setItemData(0, 0, Qt::UserRole - 1);
298 _ui->comboBox_g2o_solver->setItemData(2, 0, Qt::UserRole - 1);
302 _ui->graphOptimization_type->setItemData(0, 0, Qt::UserRole - 1);
306 _ui->graphOptimization_type->setItemData(2, 0, Qt::UserRole - 1);
310 _ui->odom_f2m_bundleStrategy->setItemData(2, 0, Qt::UserRole - 1);
311 _ui->loopClosure_bundle->setItemData(2, 0, Qt::UserRole - 1);
315 _ui->graphOptimization_type->setItemData(3, 0, Qt::UserRole - 1);
316 _ui->odom_f2m_bundleStrategy->setItemData(3, 0, Qt::UserRole - 1);
317 _ui->loopClosure_bundle->setItemData(3, 0, Qt::UserRole - 1);
319 #ifdef RTABMAP_VERTIGO 323 _ui->graphOptimization_robust->setEnabled(
false);
325 #ifndef RTABMAP_POINTMATCHER 326 _ui->comboBox_icpStrategy->setItemData(1, 0, Qt::UserRole - 1);
328 #ifndef RTABMAP_CCCORELIB 329 _ui->comboBox_icpStrategy->setItemData(2, 0, Qt::UserRole - 1);
368 _ui->comboBox_odom_sensor->setItemData(1, 0, Qt::UserRole - 1);
381 _ui->comboBox_odom_sensor->setItemData(2, 0, Qt::UserRole - 1);
402 #if PCL_VERSION_COMPARE(<, 1, 7, 2) 403 _ui->checkBox_showFrustums->setEnabled(
false);
404 _ui->checkBox_showFrustums->setChecked(
false);
405 _ui->checkBox_showOdomFrustums->setEnabled(
false);
406 _ui->checkBox_showOdomFrustums->setChecked(
false);
410 #if CV_MAJOR_VERSION < 3 || (CV_MAJOR_VERSION == 3 && (CV_MINOR_VERSION <4 || (CV_MINOR_VERSION ==4 && CV_SUBMINOR_VERSION<2))) 411 _ui->ArucoDictionary->setItemData(17, 0, Qt::UserRole - 1);
412 _ui->ArucoDictionary->setItemData(18, 0, Qt::UserRole - 1);
413 _ui->ArucoDictionary->setItemData(19, 0, Qt::UserRole - 1);
414 _ui->ArucoDictionary->setItemData(20, 0, Qt::UserRole - 1);
416 #ifndef HAVE_OPENCV_ARUCO 417 _ui->label_markerDetection->setText(
_ui->label_markerDetection->text()+
" This option works only if OpenCV has been built with \"aruco\" module.");
420 #ifndef RTABMAP_MADGWICK 421 _ui->comboBox_imuFilter_strategy->setItemData(1, 0, Qt::UserRole - 1);
425 UASSERT(
_ui->odom_registration->count() == 4);
435 _ui->predictionPlot->showLegend(
false);
437 QButtonGroup * buttonGroup =
new QButtonGroup(
this);
438 buttonGroup->addButton(
_ui->radioButton_basic);
439 buttonGroup->addButton(
_ui->radioButton_advanced);
442 connect(
_ui->buttonBox_global, SIGNAL(
clicked(QAbstractButton *)),
this, SLOT(
closeDialog(QAbstractButton *)));
443 connect(
_ui->buttonBox_local, SIGNAL(
clicked(QAbstractButton *)),
this, SLOT(
resetApply(QAbstractButton *)));
447 connect(
_ui->radioButton_basic, SIGNAL(toggled(
bool)),
this, SLOT(
setupTreeView()));
559 for(
int i=0; i<2; ++i)
637 _ui->comboBox_loggerFilter->SetDisplayText(
"Select:");
642 connect(
_ui->general_doubleSpinBox_imgRate, SIGNAL(valueChanged(
double)),
_ui->doubleSpinBox_OdomORBSLAMFps, SLOT(setValue(
double)));
646 _ui->stackedWidget_src->setCurrentIndex(
_ui->comboBox_sourceType->currentIndex());
647 connect(
_ui->comboBox_sourceType, SIGNAL(currentIndexChanged(
int)),
_ui->stackedWidget_src, SLOT(setCurrentIndex(
int)));
653 _ui->stackedWidget_image->setCurrentIndex(
_ui->source_comboBox_image_type->currentIndex());
654 connect(
_ui->source_comboBox_image_type, SIGNAL(currentIndexChanged(
int)),
_ui->stackedWidget_image, SLOT(setCurrentIndex(
int)));
683 connect(
_ui->source_checkBox_stereoToDepthDB, SIGNAL(toggled(
bool)),
_ui->checkbox_stereo_depthGenerated, SLOT(setChecked(
bool)));
684 connect(
_ui->checkbox_stereo_depthGenerated, SIGNAL(toggled(
bool)),
_ui->source_checkBox_stereoToDepthDB, SLOT(setChecked(
bool)));
687 _ui->stackedWidget_rgbd->setCurrentIndex(
_ui->comboBox_cameraRGBD->currentIndex());
688 connect(
_ui->comboBox_cameraRGBD, SIGNAL(currentIndexChanged(
int)),
_ui->stackedWidget_rgbd, SLOT(setCurrentIndex(
int)));
690 _ui->stackedWidget_stereo->setCurrentIndex(
_ui->comboBox_cameraStereo->currentIndex());
691 connect(
_ui->comboBox_cameraStereo, SIGNAL(currentIndexChanged(
int)),
_ui->stackedWidget_stereo, SLOT(setCurrentIndex(
int)));
736 connect(
_ui->lineEdit_cameraRGBDImages_path_rgb, SIGNAL(textChanged(
const QString &)),
this, SLOT(
makeObsoleteSourcePanel()));
737 connect(
_ui->lineEdit_cameraRGBDImages_path_depth, SIGNAL(textChanged(
const QString &)),
this, SLOT(
makeObsoleteSourcePanel()));
745 connect(
_ui->lineEdit_cameraImages_laser_transform, SIGNAL(textChanged(
const QString &)),
this, SLOT(
makeObsoleteSourcePanel()));
753 connect(
_ui->lineEdit_cameraImages_imu_transform, SIGNAL(textChanged(
const QString &)),
this, SLOT(
makeObsoleteSourcePanel()));
763 connect(
_ui->lineEdit_cameraStereoImages_path_left, SIGNAL(textChanged(
const QString &)),
this, SLOT(
makeObsoleteSourcePanel()));
764 connect(
_ui->lineEdit_cameraStereoImages_path_right, SIGNAL(textChanged(
const QString &)),
this, SLOT(
makeObsoleteSourcePanel()));
831 connect(
_ui->lineEdit_odom_sensor_path_calibration, SIGNAL(textChanged(
const QString &)),
this, SLOT(
makeObsoleteSourcePanel()));
838 connect(
_ui->comboBox_imuFilter_strategy, SIGNAL(currentIndexChanged(
int)),
_ui->stackedWidget_imuFilter, SLOT(setCurrentIndex(
int)));
839 _ui->stackedWidget_imuFilter->setCurrentIndex(
_ui->comboBox_imuFilter_strategy->currentIndex());
850 connect(
_ui->doubleSpinBox_source_scanNormalsForceGroundUp, SIGNAL(valueChanged(
double)),
this, SLOT(
makeObsoleteSourcePanel()));
854 connect(
_ui->general_doubleSpinBox_timeThr, SIGNAL(valueChanged(
double)),
_ui->general_doubleSpinBox_timeThr_2, SLOT(setValue(
double)));
855 connect(
_ui->general_doubleSpinBox_hardThr, SIGNAL(valueChanged(
double)),
_ui->general_doubleSpinBox_hardThr_2, SLOT(setValue(
double)));
856 connect(
_ui->doubleSpinBox_similarityThreshold, SIGNAL(valueChanged(
double)),
_ui->doubleSpinBox_similarityThreshold_2, SLOT(setValue(
double)));
857 connect(
_ui->general_doubleSpinBox_detectionRate, SIGNAL(valueChanged(
double)),
_ui->general_doubleSpinBox_detectionRate_2, SLOT(setValue(
double)));
858 connect(
_ui->general_spinBox_imagesBufferSize, SIGNAL(valueChanged(
int)),
_ui->general_spinBox_imagesBufferSize_2, SLOT(setValue(
int)));
859 connect(
_ui->general_spinBox_maxStMemSize, SIGNAL(valueChanged(
int)),
_ui->general_spinBox_maxStMemSize_2, SLOT(setValue(
int)));
863 connect(
_ui->doubleSpinBox_similarityThreshold_2, SIGNAL(editingFinished()),
this, SLOT(
updateBasicParameter()));
864 connect(
_ui->general_doubleSpinBox_detectionRate_2, SIGNAL(editingFinished()),
this, SLOT(
updateBasicParameter()));
865 connect(
_ui->general_spinBox_imagesBufferSize_2, SIGNAL(editingFinished()),
this, SLOT(
updateBasicParameter()));
876 _ui->groupBox_publishing->setObjectName(Parameters::kRtabmapPublishStats().c_str());
877 _ui->general_checkBox_publishRawData->setObjectName(Parameters::kRtabmapPublishLastSignature().c_str());
878 _ui->general_checkBox_publishPdf->setObjectName(Parameters::kRtabmapPublishPdf().c_str());
879 _ui->general_checkBox_publishLikelihood->setObjectName(Parameters::kRtabmapPublishLikelihood().c_str());
880 _ui->general_checkBox_publishRMSE->setObjectName(Parameters::kRtabmapComputeRMSE().c_str());
881 _ui->general_checkBox_saveWMState->setObjectName(Parameters::kRtabmapSaveWMState().c_str());
882 _ui->general_checkBox_publishRAM->setObjectName(Parameters::kRtabmapPublishRAMUsage().c_str());
883 _ui->general_checkBox_statisticLogsBufferedInRAM->setObjectName(Parameters::kRtabmapStatisticLogsBufferedInRAM().c_str());
884 _ui->groupBox_statistics->setObjectName(Parameters::kRtabmapStatisticLogged().c_str());
885 _ui->general_checkBox_statisticLoggedHeaders->setObjectName(Parameters::kRtabmapStatisticLoggedHeaders().c_str());
886 _ui->general_doubleSpinBox_timeThr->setObjectName(Parameters::kRtabmapTimeThr().c_str());
887 _ui->general_spinBox_memoryThr->setObjectName(Parameters::kRtabmapMemoryThr().c_str());
888 _ui->general_doubleSpinBox_detectionRate->setObjectName(Parameters::kRtabmapDetectionRate().c_str());
889 _ui->general_spinBox_imagesBufferSize->setObjectName(Parameters::kRtabmapImageBufferSize().c_str());
890 _ui->general_checkBox_createIntermediateNodes->setObjectName(Parameters::kRtabmapCreateIntermediateNodes().c_str());
891 _ui->general_spinBox_maxRetrieved->setObjectName(Parameters::kRtabmapMaxRetrieved().c_str());
892 _ui->general_spinBox_max_republished->setObjectName(Parameters::kRtabmapMaxRepublished().c_str());
893 _ui->general_checkBox_startNewMapOnLoopClosure->setObjectName(Parameters::kRtabmapStartNewMapOnLoopClosure().c_str());
894 _ui->general_checkBox_startNewMapOnGoodSignature->setObjectName(Parameters::kRtabmapStartNewMapOnGoodSignature().c_str());
895 _ui->general_checkBox_imagesAlreadyRectified->setObjectName(Parameters::kRtabmapImagesAlreadyRectified().c_str());
896 _ui->general_checkBox_rectifyOnlyFeatures->setObjectName(Parameters::kRtabmapRectifyOnlyFeatures().c_str());
897 _ui->checkBox_rtabmap_loopGPS->setObjectName(Parameters::kRtabmapLoopGPS().c_str());
898 _ui->lineEdit_workingDirectory->setObjectName(Parameters::kRtabmapWorkingDirectory().c_str());
902 _ui->general_checkBox_keepRawData->setObjectName(Parameters::kMemImageKept().c_str());
903 _ui->general_checkBox_keepBinaryData->setObjectName(Parameters::kMemBinDataKept().c_str());
904 _ui->general_checkBox_saveIntermediateNodeData->setObjectName(Parameters::kMemIntermediateNodeDataKept().c_str());
905 _ui->lineEdit_rgbCompressionFormat->setObjectName(Parameters::kMemImageCompressionFormat().c_str());
906 _ui->general_checkBox_keepDescriptors->setObjectName(Parameters::kMemRawDescriptorsKept().c_str());
907 _ui->general_checkBox_saveDepth16bits->setObjectName(Parameters::kMemSaveDepth16Format().c_str());
908 _ui->general_checkBox_compressionParallelized->setObjectName(Parameters::kMemCompressionParallelized().c_str());
909 _ui->general_checkBox_reduceGraph->setObjectName(Parameters::kMemReduceGraph().c_str());
910 _ui->general_checkBox_keepNotLinkedNodes->setObjectName(Parameters::kMemNotLinkedNodesKept().c_str());
911 _ui->general_spinBox_maxStMemSize->setObjectName(Parameters::kMemSTMSize().c_str());
912 _ui->doubleSpinBox_similarityThreshold->setObjectName(Parameters::kMemRehearsalSimilarity().c_str());
913 _ui->general_checkBox_SLAM_mode->setObjectName(Parameters::kMemIncrementalMemory().c_str());
914 _ui->general_checkBox_saveLocalizationData->setObjectName(Parameters::kMemLocalizationDataSaved().c_str());
915 _ui->general_doubleSpinBox_recentWmRatio->setObjectName(Parameters::kMemRecentWmRatio().c_str());
916 _ui->general_checkBox_transferSortingByWeightId->setObjectName(Parameters::kMemTransferSortingByWeightId().c_str());
917 _ui->general_checkBox_RehearsalIdUpdatedToNewOne->setObjectName(Parameters::kMemRehearsalIdUpdatedToNewOne().c_str());
918 _ui->general_checkBox_generateIds->setObjectName(Parameters::kMemGenerateIds().c_str());
919 _ui->general_checkBox_badSignaturesIgnored->setObjectName(Parameters::kMemBadSignaturesIgnored().c_str());
920 _ui->general_checkBox_createMapLabels->setObjectName(Parameters::kMemMapLabelsAdded().c_str());
921 _ui->general_checkBox_initWMWithAllNodes->setObjectName(Parameters::kMemInitWMWithAllNodes().c_str());
922 _ui->checkBox_localSpaceScanMatchingIDsSaved->setObjectName(Parameters::kRGBDScanMatchingIdsSavedInLinks().c_str());
923 _ui->checkBox_localSpaceCreateGlobalScanMap->setObjectName(Parameters::kRGBDProximityGlobalScanMap().c_str());
924 _ui->spinBox_imagePreDecimation->setObjectName(Parameters::kMemImagePreDecimation().c_str());
925 _ui->spinBox_imagePostDecimation->setObjectName(Parameters::kMemImagePostDecimation().c_str());
926 _ui->general_spinBox_laserScanDownsample->setObjectName(Parameters::kMemLaserScanDownsampleStepSize().c_str());
927 _ui->general_doubleSpinBox_laserScanVoxelSize->setObjectName(Parameters::kMemLaserScanVoxelSize().c_str());
928 _ui->general_spinBox_laserScanNormalK->setObjectName(Parameters::kMemLaserScanNormalK().c_str());
929 _ui->general_doubleSpinBox_laserScanNormalRadius->setObjectName(Parameters::kMemLaserScanNormalRadius().c_str());
930 _ui->checkBox_useOdomFeatures->setObjectName(Parameters::kMemUseOdomFeatures().c_str());
931 _ui->memCovOffDiagIgnored->setObjectName(Parameters::kMemCovOffDiagIgnored().c_str());
934 _ui->checkBox_dbInMemory->setObjectName(Parameters::kDbSqlite3InMemory().c_str());
935 _ui->spinBox_dbCacheSize->setObjectName(Parameters::kDbSqlite3CacheSize().c_str());
936 _ui->comboBox_dbJournalMode->setObjectName(Parameters::kDbSqlite3JournalMode().c_str());
937 _ui->comboBox_dbSynchronous->setObjectName(Parameters::kDbSqlite3Synchronous().c_str());
938 _ui->comboBox_dbTempStore->setObjectName(Parameters::kDbSqlite3TempStore().c_str());
939 _ui->lineEdit_targetDatabaseVersion->setObjectName(Parameters::kDbTargetVersion().c_str());
943 _ui->general_doubleSpinBox_hardThr->setObjectName(Parameters::kRtabmapLoopThr().c_str());
944 _ui->general_doubleSpinBox_loopRatio->setObjectName(Parameters::kRtabmapLoopRatio().c_str());
947 _ui->general_doubleSpinBox_vp->setObjectName(Parameters::kBayesVirtualPlacePriorThr().c_str());
948 _ui->lineEdit_bayes_predictionLC->setObjectName(Parameters::kBayesPredictionLC().c_str());
949 _ui->checkBox_bayes_fullPredictionUpdate->setObjectName(Parameters::kBayesFullPredictionUpdate().c_str());
950 connect(
_ui->lineEdit_bayes_predictionLC, SIGNAL(textChanged(
const QString &)),
this, SLOT(
updatePredictionPlot()));
953 _ui->comboBox_dictionary_strategy->setObjectName(Parameters::kKpNNStrategy().c_str());
954 _ui->checkBox_dictionary_incremental->setObjectName(Parameters::kKpIncrementalDictionary().c_str());
955 _ui->checkBox_kp_incrementalFlann->setObjectName(Parameters::kKpIncrementalFlann().c_str());
956 _ui->checkBox_kp_byteToFloat->setObjectName(Parameters::kKpByteToFloat().c_str());
957 _ui->surf_doubleSpinBox_rebalancingFactor->setObjectName(Parameters::kKpFlannRebalancingFactor().c_str());
958 _ui->comboBox_detector_strategy->setObjectName(Parameters::kKpDetectorStrategy().c_str());
959 _ui->surf_doubleSpinBox_nndrRatio->setObjectName(Parameters::kKpNndrRatio().c_str());
960 _ui->surf_doubleSpinBox_maxDepth->setObjectName(Parameters::kKpMaxDepth().c_str());
961 _ui->surf_doubleSpinBox_minDepth->setObjectName(Parameters::kKpMinDepth().c_str());
962 _ui->checkBox_memDepthAsMask->setObjectName(Parameters::kMemDepthAsMask().c_str());
963 _ui->checkBox_memStereoFromMotion->setObjectName(Parameters::kMemStereoFromMotion().c_str());
964 _ui->surf_spinBox_wordsPerImageTarget->setObjectName(Parameters::kKpMaxFeatures().c_str());
965 _ui->spinBox_KPGridRows->setObjectName(Parameters::kKpGridRows().c_str());
966 _ui->spinBox_KPGridCols->setObjectName(Parameters::kKpGridCols().c_str());
967 _ui->surf_doubleSpinBox_ratioBadSign->setObjectName(Parameters::kKpBadSignRatio().c_str());
968 _ui->checkBox_kp_tfIdfLikelihoodUsed->setObjectName(Parameters::kKpTfIdfLikelihoodUsed().c_str());
969 _ui->checkBox_kp_parallelized->setObjectName(Parameters::kKpParallelized().c_str());
970 _ui->lineEdit_kp_roi->setObjectName(Parameters::kKpRoiRatios().c_str());
971 _ui->lineEdit_dictionaryPath->setObjectName(Parameters::kKpDictionaryPath().c_str());
973 _ui->checkBox_kp_newWordsComparedTogether->setObjectName(Parameters::kKpNewWordsComparedTogether().c_str());
974 _ui->subpix_winSize_kp->setObjectName(Parameters::kKpSubPixWinSize().c_str());
975 _ui->subpix_iterations_kp->setObjectName(Parameters::kKpSubPixIterations().c_str());
976 _ui->subpix_eps_kp->setObjectName(Parameters::kKpSubPixEps().c_str());
978 _ui->subpix_winSize->setObjectName(Parameters::kKpSubPixWinSize().c_str());
979 _ui->subpix_iterations->setObjectName(Parameters::kKpSubPixIterations().c_str());
980 _ui->subpix_eps->setObjectName(Parameters::kKpSubPixEps().c_str());
983 _ui->surf_doubleSpinBox_hessianThr->setObjectName(Parameters::kSURFHessianThreshold().c_str());
984 _ui->surf_spinBox_octaves->setObjectName(Parameters::kSURFOctaves().c_str());
985 _ui->surf_spinBox_octaveLayers->setObjectName(Parameters::kSURFOctaveLayers().c_str());
986 _ui->checkBox_surfExtended->setObjectName(Parameters::kSURFExtended().c_str());
987 _ui->surf_checkBox_upright->setObjectName(Parameters::kSURFUpright().c_str());
988 _ui->surf_checkBox_gpuVersion->setObjectName(Parameters::kSURFGpuVersion().c_str());
989 _ui->surf_doubleSpinBox_gpuKeypointsRatio->setObjectName(Parameters::kSURFGpuKeypointsRatio().c_str());
992 _ui->sift_spinBox_nFeatures->setObjectName(Parameters::kSIFTNFeatures().c_str());
993 _ui->sift_spinBox_nOctaveLayers->setObjectName(Parameters::kSIFTNOctaveLayers().c_str());
994 _ui->sift_doubleSpinBox_contrastThr->setObjectName(Parameters::kSIFTContrastThreshold().c_str());
995 _ui->sift_doubleSpinBox_edgeThr->setObjectName(Parameters::kSIFTEdgeThreshold().c_str());
996 _ui->sift_doubleSpinBox_sigma->setObjectName(Parameters::kSIFTSigma().c_str());
997 _ui->sift_checkBox_rootsift->setObjectName(Parameters::kSIFTRootSIFT().c_str());
1000 _ui->briefBytes->setObjectName(Parameters::kBRIEFBytes().c_str());
1003 _ui->fastSuppressNonMax->setObjectName(Parameters::kFASTNonmaxSuppression().c_str());
1004 _ui->fastThreshold->setObjectName(Parameters::kFASTThreshold().c_str());
1005 _ui->fastThresholdMin->setObjectName(Parameters::kFASTMinThreshold().c_str());
1006 _ui->fastThresholdMax->setObjectName(Parameters::kFASTMaxThreshold().c_str());
1007 _ui->fastGridRows->setObjectName(Parameters::kFASTGridRows().c_str());
1008 _ui->fastGridCols->setObjectName(Parameters::kFASTGridCols().c_str());
1009 _ui->fastGpu->setObjectName(Parameters::kFASTGpu().c_str());
1010 _ui->fastKeypointRatio->setObjectName(Parameters::kFASTGpuKeypointsRatio().c_str());
1011 _ui->fastCV->setObjectName(Parameters::kFASTCV().c_str());
1014 _ui->doubleSpinBox_ORBScaleFactor->setObjectName(Parameters::kORBScaleFactor().c_str());
1015 _ui->spinBox_ORBNLevels->setObjectName(Parameters::kORBNLevels().c_str());
1016 _ui->spinBox_ORBEdgeThreshold->setObjectName(Parameters::kORBEdgeThreshold().c_str());
1017 _ui->spinBox_ORBFirstLevel->setObjectName(Parameters::kORBFirstLevel().c_str());
1018 _ui->spinBox_ORBWTA_K->setObjectName(Parameters::kORBWTA_K().c_str());
1019 _ui->spinBox_ORBScoreType->setObjectName(Parameters::kORBScoreType().c_str());
1020 _ui->spinBox_ORBPatchSize->setObjectName(Parameters::kORBPatchSize().c_str());
1021 _ui->checkBox_ORBGpu->setObjectName(Parameters::kORBGpu().c_str());
1024 _ui->checkBox_FREAKOrientationNormalized->setObjectName(Parameters::kFREAKOrientationNormalized().c_str());
1025 _ui->checkBox_FREAKScaleNormalized->setObjectName(Parameters::kFREAKScaleNormalized().c_str());
1026 _ui->doubleSpinBox_FREAKPatternScale->setObjectName(Parameters::kFREAKPatternScale().c_str());
1027 _ui->spinBox_FREAKNOctaves->setObjectName(Parameters::kFREAKNOctaves().c_str());
1030 _ui->doubleSpinBox_GFTT_qualityLevel->setObjectName(Parameters::kGFTTQualityLevel().c_str());
1031 _ui->doubleSpinBox_GFTT_minDistance->setObjectName(Parameters::kGFTTMinDistance().c_str());
1032 _ui->spinBox_GFTT_blockSize->setObjectName(Parameters::kGFTTBlockSize().c_str());
1033 _ui->checkBox_GFTT_useHarrisDetector->setObjectName(Parameters::kGFTTUseHarrisDetector().c_str());
1034 _ui->doubleSpinBox_GFTT_k->setObjectName(Parameters::kGFTTK().c_str());
1037 _ui->spinBox_BRISK_thresh->setObjectName(Parameters::kBRISKThresh().c_str());
1038 _ui->spinBox_BRISK_octaves->setObjectName(Parameters::kBRISKOctaves().c_str());
1039 _ui->doubleSpinBox_BRISK_patterScale->setObjectName(Parameters::kBRISKPatternScale().c_str());
1042 _ui->checkBox_kaze_extended->setObjectName(Parameters::kKAZEExtended().c_str());
1043 _ui->checkBox_kaze_upright->setObjectName(Parameters::kKAZEUpright().c_str());
1044 _ui->doubleSpinBox_kaze_threshold->setObjectName(Parameters::kKAZEThreshold().c_str());
1045 _ui->spinBox_kaze_octaves->setObjectName(Parameters::kKAZENOctaves().c_str());
1046 _ui->spinBox_kaze_octavelayers->setObjectName(Parameters::kKAZENOctaveLayers().c_str());
1047 _ui->spinBox_kaze_diffusivity->setObjectName(Parameters::kKAZEDiffusivity().c_str());
1050 _ui->lineEdit_sptorch_path->setObjectName(Parameters::kSuperPointModelPath().c_str());
1052 _ui->doubleSpinBox_sptorch_threshold->setObjectName(Parameters::kSuperPointThreshold().c_str());
1053 _ui->checkBox_sptorch_nms->setObjectName(Parameters::kSuperPointNMS().c_str());
1054 _ui->spinBox_sptorch_minDistance->setObjectName(Parameters::kSuperPointNMSRadius().c_str());
1055 _ui->checkBox_sptorch_cuda->setObjectName(Parameters::kSuperPointCuda().c_str());
1058 _ui->lineEdit_pymatcher_path->setObjectName(Parameters::kPyMatcherPath().c_str());
1060 _ui->pymatcher_matchThreshold->setObjectName(Parameters::kPyMatcherThreshold().c_str());
1061 _ui->pymatcher_iterations->setObjectName(Parameters::kPyMatcherIterations().c_str());
1062 _ui->checkBox_pymatcher_cuda->setObjectName(Parameters::kPyMatcherCuda().c_str());
1063 _ui->lineEdit_pymatcher_model->setObjectName(Parameters::kPyMatcherModel().c_str());
1067 _ui->lineEdit_pydetector_path->setObjectName(Parameters::kPyDetectorPath().c_str());
1069 _ui->checkBox_pydetector_cuda->setObjectName(Parameters::kPyDetectorCuda().c_str());
1072 _ui->checkBox_gms_withRotation->setObjectName(Parameters::kGMSWithRotation().c_str());
1073 _ui->checkBox_gms_withScale->setObjectName(Parameters::kGMSWithScale().c_str());
1074 _ui->gms_thresholdFactor->setObjectName(Parameters::kGMSThresholdFactor().c_str());
1077 _ui->groupBox_vh_epipolar2->setObjectName(Parameters::kVhEpEnabled().c_str());
1078 _ui->surf_spinBox_matchCountMinAccepted->setObjectName(Parameters::kVhEpMatchCountMin().c_str());
1079 _ui->surf_doubleSpinBox_ransacParam1->setObjectName(Parameters::kVhEpRansacParam1().c_str());
1080 _ui->surf_doubleSpinBox_ransacParam2->setObjectName(Parameters::kVhEpRansacParam2().c_str());
1083 _ui->general_checkBox_activateRGBD->setObjectName(Parameters::kRGBDEnabled().c_str());
1084 _ui->rgdb_linearUpdate->setObjectName(Parameters::kRGBDLinearUpdate().c_str());
1085 _ui->rgdb_angularUpdate->setObjectName(Parameters::kRGBDAngularUpdate().c_str());
1086 _ui->rgdb_linearSpeedUpdate->setObjectName(Parameters::kRGBDLinearSpeedUpdate().c_str());
1087 _ui->rgdb_angularSpeedUpdate->setObjectName(Parameters::kRGBDAngularSpeedUpdate().c_str());
1088 _ui->rgbd_savedLocalizationIgnored->setObjectName(Parameters::kRGBDStartAtOrigin().c_str());
1089 _ui->rgdb_rehearsalWeightIgnoredWhileMoving->setObjectName(Parameters::kMemRehearsalWeightIgnoredWhileMoving().c_str());
1090 _ui->rgdb_newMapOdomChange->setObjectName(Parameters::kRGBDNewMapOdomChangeDistance().c_str());
1091 _ui->odomScanHistory->setObjectName(Parameters::kRGBDNeighborLinkRefining().c_str());
1092 _ui->odomGravity->setObjectName(Parameters::kMemUseOdomGravity().c_str());
1093 _ui->spinBox_maxLocalLocationsRetrieved->setObjectName(Parameters::kRGBDMaxLocalRetrieved().c_str());
1094 _ui->rgbd_loopCovLimited->setObjectName(Parameters::kRGBDLoopCovLimited().c_str());
1096 _ui->graphOptimization_type->setObjectName(Parameters::kOptimizerStrategy().c_str());
1097 _ui->graphOptimization_iterations->setObjectName(Parameters::kOptimizerIterations().c_str());
1098 _ui->graphOptimization_covarianceIgnored->setObjectName(Parameters::kOptimizerVarianceIgnored().c_str());
1099 _ui->graphOptimization_fromGraphEnd->setObjectName(Parameters::kRGBDOptimizeFromGraphEnd().c_str());
1100 _ui->graphOptimization_maxError->setObjectName(Parameters::kRGBDOptimizeMaxError().c_str());
1101 _ui->graphOptimization_gravitySigma->setObjectName(Parameters::kOptimizerGravitySigma().c_str());
1102 _ui->graphOptimization_stopEpsilon->setObjectName(Parameters::kOptimizerEpsilon().c_str());
1103 _ui->graphOptimization_robust->setObjectName(Parameters::kOptimizerRobust().c_str());
1104 _ui->graphOptimization_priorsIgnored->setObjectName(Parameters::kOptimizerPriorsIgnored().c_str());
1105 _ui->graphOptimization_landmarksIgnored->setObjectName(Parameters::kOptimizerLandmarksIgnored().c_str());
1107 _ui->comboBox_g2o_solver->setObjectName(Parameters::kg2oSolver().c_str());
1108 _ui->comboBox_g2o_optimizer->setObjectName(Parameters::kg2oOptimizer().c_str());
1109 _ui->doubleSpinBox_g2o_pixelVariance->setObjectName(Parameters::kg2oPixelVariance().c_str());
1110 _ui->doubleSpinBox_g2o_robustKernelDelta->setObjectName(Parameters::kg2oRobustKernelDelta().c_str());
1111 _ui->doubleSpinBox_g2o_baseline->setObjectName(Parameters::kg2oBaseline().c_str());
1113 _ui->comboBox_gtsam_optimizer->setObjectName(Parameters::kGTSAMOptimizer().c_str());
1115 _ui->graphPlan_goalReachedRadius->setObjectName(Parameters::kRGBDGoalReachedRadius().c_str());
1116 _ui->graphPlan_goalsSavedInUserData->setObjectName(Parameters::kRGBDGoalsSavedInUserData().c_str());
1117 _ui->graphPlan_stuckIterations->setObjectName(Parameters::kRGBDPlanStuckIterations().c_str());
1118 _ui->graphPlan_linearVelocity->setObjectName(Parameters::kRGBDPlanLinearVelocity().c_str());
1119 _ui->graphPlan_angularVelocity->setObjectName(Parameters::kRGBDPlanAngularVelocity().c_str());
1121 _ui->groupBox_localDetection_time->setObjectName(Parameters::kRGBDProximityByTime().c_str());
1122 _ui->groupBox_localDetection_space->setObjectName(Parameters::kRGBDProximityBySpace().c_str());
1123 _ui->localDetection_radius->setObjectName(Parameters::kRGBDLocalRadius().c_str());
1124 _ui->maxLocalizationDistance->setObjectName(Parameters::kRGBDMaxLoopClosureDistance().c_str());
1125 _ui->localDetection_maxDiffID->setObjectName(Parameters::kRGBDProximityMaxGraphDepth().c_str());
1126 _ui->localDetection_maxNeighbors->setObjectName(Parameters::kRGBDProximityPathMaxNeighbors().c_str());
1127 _ui->localDetection_maxPaths->setObjectName(Parameters::kRGBDProximityMaxPaths().c_str());
1128 _ui->localDetection_pathFilteringRadius->setObjectName(Parameters::kRGBDProximityPathFilteringRadius().c_str());
1129 _ui->localDetection_angle->setObjectName(Parameters::kRGBDProximityAngle().c_str());
1130 _ui->localDetection_mergedScanCovFactor->setObjectName(Parameters::kRGBDProximityMergedScanCovFactor().c_str());
1131 _ui->checkBox_localSpaceOdomGuess->setObjectName(Parameters::kRGBDProximityOdomGuess().c_str());
1132 _ui->checkBox_localSpacePathOdomPosesUsed->setObjectName(Parameters::kRGBDProximityPathRawPosesUsed().c_str());
1133 _ui->rgdb_localImmunizationRatio->setObjectName(Parameters::kRGBDLocalImmunizationRatio().c_str());
1134 _ui->loopClosure_identityGuess->setObjectName(Parameters::kRGBDLoopClosureIdentityGuess().c_str());
1135 _ui->loopClosure_reextract->setObjectName(Parameters::kRGBDLoopClosureReextractFeatures().c_str());
1136 _ui->loopClosure_bunlde->setObjectName(Parameters::kRGBDLocalBundleOnLoopClosure().c_str());
1137 _ui->loopClosure_invertedReg->setObjectName(Parameters::kRGBDInvertedReg().c_str());
1138 _ui->checkbox_rgbd_createOccupancyGrid->setObjectName(Parameters::kRGBDCreateOccupancyGrid().c_str());
1139 _ui->RGBDMarkerDetection->setObjectName(Parameters::kRGBDMarkerDetection().c_str());
1140 _ui->spinBox_maxOdomCacheSize->setObjectName(Parameters::kRGBDMaxOdomCacheSize().c_str());
1143 _ui->reg_repeatOnce->setObjectName(Parameters::kRegRepeatOnce().c_str());
1144 _ui->comboBox_registrationStrategy->setObjectName(Parameters::kRegStrategy().c_str());
1145 _ui->loopClosure_bowForce2D->setObjectName(Parameters::kRegForce3DoF().c_str());
1148 _ui->loopClosure_bowMinInliers->setObjectName(Parameters::kVisMinInliers().c_str());
1149 _ui->loopClosure_bowInlierDistance->setObjectName(Parameters::kVisInlierDistance().c_str());
1150 _ui->loopClosure_bowIterations->setObjectName(Parameters::kVisIterations().c_str());
1151 _ui->loopClosure_bowRefineIterations->setObjectName(Parameters::kVisRefineIterations().c_str());
1152 _ui->visMeanDistance->setObjectName(Parameters::kVisMeanInliersDistance().c_str());
1153 _ui->visMinDistribution->setObjectName(Parameters::kVisMinInliersDistribution().c_str());
1154 _ui->loopClosure_estimationType->setObjectName(Parameters::kVisEstimationType().c_str());
1155 connect(
_ui->loopClosure_estimationType, SIGNAL(currentIndexChanged(
int)),
_ui->stackedWidget_loopClosureEstimation, SLOT(setCurrentIndex(
int)));
1156 _ui->stackedWidget_loopClosureEstimation->setCurrentIndex(Parameters::defaultVisEstimationType());
1157 _ui->loopClosure_forwardEst->setObjectName(Parameters::kVisForwardEstOnly().c_str());
1158 _ui->loopClosure_bowEpipolarGeometryVar->setObjectName(Parameters::kVisEpipolarGeometryVar().c_str());
1159 _ui->loopClosure_pnpReprojError->setObjectName(Parameters::kVisPnPReprojError().c_str());
1160 _ui->loopClosure_pnpFlags->setObjectName(Parameters::kVisPnPFlags().c_str());
1161 _ui->loopClosure_pnpRefineIterations->setObjectName(Parameters::kVisPnPRefineIterations().c_str());
1162 _ui->loopClosure_pnpMaxVariance->setObjectName(Parameters::kVisPnPMaxVariance().c_str());
1163 _ui->reextract_nn->setObjectName(Parameters::kVisCorNNType().c_str());
1165 _ui->reextract_nndrRatio->setObjectName(Parameters::kVisCorNNDR().c_str());
1166 _ui->spinBox_visCorGuessWinSize->setObjectName(Parameters::kVisCorGuessWinSize().c_str());
1167 _ui->checkBox__visCorGuessMatchToProjection->setObjectName(Parameters::kVisCorGuessMatchToProjection().c_str());
1168 _ui->vis_feature_detector->setObjectName(Parameters::kVisFeatureType().c_str());
1169 _ui->reextract_maxFeatures->setObjectName(Parameters::kVisMaxFeatures().c_str());
1170 _ui->reextract_gridrows->setObjectName(Parameters::kVisGridRows().c_str());
1171 _ui->reextract_gridcols->setObjectName(Parameters::kVisGridCols().c_str());
1172 _ui->loopClosure_bowMaxDepth->setObjectName(Parameters::kVisMaxDepth().c_str());
1173 _ui->loopClosure_bowMinDepth->setObjectName(Parameters::kVisMinDepth().c_str());
1174 _ui->checkBox_visDepthAsMask->setObjectName(Parameters::kVisDepthAsMask().c_str());
1175 _ui->loopClosure_roi->setObjectName(Parameters::kVisRoiRatios().c_str());
1176 _ui->subpix_winSize->setObjectName(Parameters::kVisSubPixWinSize().c_str());
1177 _ui->subpix_iterations->setObjectName(Parameters::kVisSubPixIterations().c_str());
1178 _ui->subpix_eps->setObjectName(Parameters::kVisSubPixEps().c_str());
1179 _ui->odom_flow_winSize_2->setObjectName(Parameters::kVisCorFlowWinSize().c_str());
1180 _ui->odom_flow_maxLevel_2->setObjectName(Parameters::kVisCorFlowMaxLevel().c_str());
1181 _ui->odom_flow_iterations_2->setObjectName(Parameters::kVisCorFlowIterations().c_str());
1182 _ui->odom_flow_eps_2->setObjectName(Parameters::kVisCorFlowEps().c_str());
1183 _ui->loopClosure_bundle->setObjectName(Parameters::kVisBundleAdjustment().c_str());
1186 _ui->comboBox_icpStrategy->setObjectName(Parameters::kIcpStrategy().c_str());
1187 connect(
_ui->comboBox_icpStrategy, SIGNAL(currentIndexChanged(
int)),
_ui->stackedWidget_icpStrategy, SLOT(setCurrentIndex(
int)));
1188 _ui->comboBox_icpStrategy->setCurrentIndex(Parameters::defaultIcpStrategy());
1189 _ui->globalDetection_icpMaxTranslation->setObjectName(Parameters::kIcpMaxTranslation().c_str());
1190 _ui->globalDetection_icpMaxRotation->setObjectName(Parameters::kIcpMaxRotation().c_str());
1191 _ui->loopClosure_icpVoxelSize->setObjectName(Parameters::kIcpVoxelSize().c_str());
1192 _ui->loopClosure_icpDownsamplingStep->setObjectName(Parameters::kIcpDownsamplingStep().c_str());
1193 _ui->loopClosure_icpRangeMin->setObjectName(Parameters::kIcpRangeMin().c_str());
1194 _ui->loopClosure_icpRangeMax->setObjectName(Parameters::kIcpRangeMax().c_str());
1195 _ui->loopClosure_icpMaxCorrespondenceDistance->setObjectName(Parameters::kIcpMaxCorrespondenceDistance().c_str());
1196 _ui->loopClosure_icpIterations->setObjectName(Parameters::kIcpIterations().c_str());
1197 _ui->loopClosure_icpEpsilon->setObjectName(Parameters::kIcpEpsilon().c_str());
1198 _ui->loopClosure_icpRatio->setObjectName(Parameters::kIcpCorrespondenceRatio().c_str());
1199 _ui->doubleSpinBox_icpOutlierRatio->setObjectName(Parameters::kIcpOutlierRatio().c_str());
1200 _ui->loopClosure_icpPointToPlane->setObjectName(Parameters::kIcpPointToPlane().c_str());
1201 _ui->loopClosure_icpPointToPlaneNormals->setObjectName(Parameters::kIcpPointToPlaneK().c_str());
1202 _ui->loopClosure_icpPointToPlaneNormalsRadius->setObjectName(Parameters::kIcpPointToPlaneRadius().c_str());
1203 _ui->loopClosure_icpPointToPlaneGroundNormalsUp->setObjectName(Parameters::kIcpPointToPlaneGroundNormalsUp().c_str());
1204 _ui->loopClosure_icpPointToPlaneNormalsMinComplexity->setObjectName(Parameters::kIcpPointToPlaneMinComplexity().c_str());
1205 _ui->loopClosure_icpPointToPlaneLowComplexityStrategy->setObjectName(Parameters::kIcpPointToPlaneLowComplexityStrategy().c_str());
1206 _ui->loopClosure_icpDebugExportFormat->setObjectName(Parameters::kIcpDebugExportFormat().c_str());
1208 _ui->lineEdit_IcpPMConfigPath->setObjectName(Parameters::kIcpPMConfig().c_str());
1210 _ui->spinBox_icpPMMatcherKnn->setObjectName(Parameters::kIcpPMMatcherKnn().c_str());
1211 _ui->doubleSpinBox_icpPMMatcherEpsilon->setObjectName(Parameters::kIcpPMMatcherEpsilon().c_str());
1212 _ui->loopClosure_icpPMMatcherIntensity->setObjectName(Parameters::kIcpPMMatcherIntensity().c_str());
1213 _ui->loopClosure_icpForce4DoF->setObjectName(Parameters::kIcpForce4DoF().c_str());
1215 _ui->spinBox_icpCCSamplingLimit->setObjectName(Parameters::kIcpCCSamplingLimit().c_str());
1216 _ui->checkBox_icpCCFilterOutFarthestPoints->setObjectName(Parameters::kIcpCCFilterOutFarthestPoints().c_str());
1217 _ui->doubleSpinBox_icpCCMaxFinalRMS->setObjectName(Parameters::kIcpCCMaxFinalRMS().c_str());
1221 _ui->groupBox_grid_3d->setObjectName(Parameters::kGrid3D().c_str());
1222 _ui->checkBox_grid_groundObstacle->setObjectName(Parameters::kGridGroundIsObstacle().c_str());
1223 _ui->doubleSpinBox_grid_resolution->setObjectName(Parameters::kGridCellSize().c_str());
1224 _ui->checkBox_grid_preVoxelFiltering->setObjectName(Parameters::kGridPreVoxelFiltering().c_str());
1225 _ui->spinBox_grid_decimation->setObjectName(Parameters::kGridDepthDecimation().c_str());
1226 _ui->doubleSpinBox_grid_maxDepth->setObjectName(Parameters::kGridRangeMax().c_str());
1227 _ui->doubleSpinBox_grid_minDepth->setObjectName(Parameters::kGridRangeMin().c_str());
1228 _ui->lineEdit_grid_roi->setObjectName(Parameters::kGridDepthRoiRatios().c_str());
1229 _ui->checkBox_grid_projRayTracing->setObjectName(Parameters::kGridRayTracing().c_str());
1230 _ui->doubleSpinBox_grid_footprintLength->setObjectName(Parameters::kGridFootprintLength().c_str());
1231 _ui->doubleSpinBox_grid_footprintWidth->setObjectName(Parameters::kGridFootprintWidth().c_str());
1232 _ui->doubleSpinBox_grid_footprintHeight->setObjectName(Parameters::kGridFootprintHeight().c_str());
1233 _ui->checkBox_grid_flatObstaclesDetected->setObjectName(Parameters::kGridFlatObstacleDetected().c_str());
1234 _ui->comboBox_grid_sensor->setObjectName(Parameters::kGridSensor().c_str());
1235 _ui->checkBox_grid_projMapFrame->setObjectName(Parameters::kGridMapFrameProjection().c_str());
1236 _ui->doubleSpinBox_grid_maxGroundAngle->setObjectName(Parameters::kGridMaxGroundAngle().c_str());
1237 _ui->spinBox_grid_normalK->setObjectName(Parameters::kGridNormalK().c_str());
1238 _ui->doubleSpinBox_grid_maxGroundHeight->setObjectName(Parameters::kGridMaxGroundHeight().c_str());
1239 _ui->doubleSpinBox_grid_maxObstacleHeight->setObjectName(Parameters::kGridMaxObstacleHeight().c_str());
1240 _ui->doubleSpinBox_grid_clusterRadius->setObjectName(Parameters::kGridClusterRadius().c_str());
1241 _ui->spinBox_grid_minClusterSize->setObjectName(Parameters::kGridMinClusterSize().c_str());
1242 _ui->doubleSpinBox_grid_minGroundHeight->setObjectName(Parameters::kGridMinGroundHeight().c_str());
1243 _ui->spinBox_grid_noiseMinNeighbors->setObjectName(Parameters::kGridNoiseFilteringMinNeighbors().c_str());
1244 _ui->doubleSpinBox_grid_noiseRadius->setObjectName(Parameters::kGridNoiseFilteringRadius().c_str());
1245 _ui->groupBox_grid_normalsSegmentation->setObjectName(Parameters::kGridNormalsSegmentation().c_str());
1246 _ui->checkBox_grid_unknownSpaceFilled->setObjectName(Parameters::kGridScan2dUnknownSpaceFilled().c_str());
1247 _ui->spinBox_grid_scanDecimation->setObjectName(Parameters::kGridScanDecimation().c_str());
1249 _ui->checkBox_grid_fullUpdate->setObjectName(Parameters::kGridGlobalFullUpdate().c_str());
1250 _ui->doubleSpinBox_grid_updateError->setObjectName(Parameters::kGridGlobalUpdateError().c_str());
1251 _ui->doubleSpinBox_grid_minMapSize->setObjectName(Parameters::kGridGlobalMinSize().c_str());
1252 _ui->spinBox_grid_maxNodes->setObjectName(Parameters::kGridGlobalMaxNodes().c_str());
1253 _ui->doubleSpinBox_grid_altitudeDelta->setObjectName(Parameters::kGridGlobalAltitudeDelta().c_str());
1254 _ui->doubleSpinBox_grid_footprintRadius->setObjectName(Parameters::kGridGlobalFootprintRadius().c_str());
1255 _ui->doubleSpinBox_grid_occThr->setObjectName(Parameters::kGridGlobalOccupancyThr().c_str());
1256 _ui->doubleSpinBox_grid_probHit->setObjectName(Parameters::kGridGlobalProbHit().c_str());
1257 _ui->doubleSpinBox_grid_probMiss->setObjectName(Parameters::kGridGlobalProbMiss().c_str());
1258 _ui->doubleSpinBox_grid_clampingMin->setObjectName(Parameters::kGridGlobalProbClampingMin().c_str());
1259 _ui->doubleSpinBox_grid_clampingMax->setObjectName(Parameters::kGridGlobalProbClampingMax().c_str());
1260 _ui->checkBox_grid_erode->setObjectName(Parameters::kGridGlobalEroded().c_str());
1261 _ui->spinBox_grid_floodfilldepth->setObjectName(Parameters::kGridGlobalFloodFillDepth().c_str());
1264 _ui->odom_strategy->setObjectName(Parameters::kOdomStrategy().c_str());
1266 _ui->odom_strategy->setCurrentIndex(Parameters::defaultOdomStrategy());
1268 _ui->odom_countdown->setObjectName(Parameters::kOdomResetCountdown().c_str());
1269 _ui->odom_holonomic->setObjectName(Parameters::kOdomHolonomic().c_str());
1270 _ui->odom_fillInfoData->setObjectName(Parameters::kOdomFillInfoData().c_str());
1271 _ui->odom_dataBufferSize->setObjectName(Parameters::kOdomImageBufferSize().c_str());
1272 _ui->odom_flow_keyframeThr->setObjectName(Parameters::kOdomKeyFrameThr().c_str());
1273 _ui->odom_VisKeyFrameThr->setObjectName(Parameters::kOdomVisKeyFrameThr().c_str());
1274 _ui->odom_flow_scanKeyframeThr->setObjectName(Parameters::kOdomScanKeyFrameThr().c_str());
1275 _ui->odom_flow_guessMotion->setObjectName(Parameters::kOdomGuessMotion().c_str());
1276 _ui->odom_guess_smoothing_delay->setObjectName(Parameters::kOdomGuessSmoothingDelay().c_str());
1277 _ui->odom_imageDecimation->setObjectName(Parameters::kOdomImageDecimation().c_str());
1278 _ui->odom_alignWithGround->setObjectName(Parameters::kOdomAlignWithGround().c_str());
1281 _ui->odom_localHistory->setObjectName(Parameters::kOdomF2MMaxSize().c_str());
1282 _ui->spinBox_odom_f2m_maxNewFeatures->setObjectName(Parameters::kOdomF2MMaxNewFeatures().c_str());
1283 _ui->spinBox_odom_f2m_scanMaxSize->setObjectName(Parameters::kOdomF2MScanMaxSize().c_str());
1284 _ui->doubleSpinBox_odom_f2m_scanRadius->setObjectName(Parameters::kOdomF2MScanSubtractRadius().c_str());
1285 _ui->doubleSpinBox_odom_f2m_scanAngle->setObjectName(Parameters::kOdomF2MScanSubtractAngle().c_str());
1286 _ui->doubleSpinBox_odom_f2m_scanRange->setObjectName(Parameters::kOdomF2MScanRange().c_str());
1287 _ui->odom_f2m_validDepthRatio->setObjectName(Parameters::kOdomF2MValidDepthRatio().c_str());
1288 _ui->odom_f2m_bundleStrategy->setObjectName(Parameters::kOdomF2MBundleAdjustment().c_str());
1289 _ui->odom_f2m_bundleMaxFrames->setObjectName(Parameters::kOdomF2MBundleAdjustmentMaxFrames().c_str());
1292 _ui->comboBox_odomf2f_corType->setObjectName(Parameters::kVisCorType().c_str());
1295 _ui->doubleSpinBox_minFlow->setObjectName(Parameters::kOdomMonoInitMinFlow().c_str());
1296 _ui->doubleSpinBox_minInitTranslation->setObjectName(Parameters::kOdomMonoInitMinTranslation().c_str());
1297 _ui->doubleSpinBox_minTranslation->setObjectName(Parameters::kOdomMonoMinTranslation().c_str());
1298 _ui->doubleSpinBox_maxVariance->setObjectName(Parameters::kOdomMonoMaxVariance().c_str());
1301 _ui->odom_filteringStrategy->setObjectName(Parameters::kOdomFilteringStrategy().c_str());
1302 _ui->stackedWidget_odometryFiltering->setCurrentIndex(
_ui->odom_filteringStrategy->currentIndex());
1303 connect(
_ui->odom_filteringStrategy, SIGNAL(currentIndexChanged(
int)),
_ui->stackedWidget_odometryFiltering, SLOT(setCurrentIndex(
int)));
1304 _ui->spinBox_particleSize->setObjectName(Parameters::kOdomParticleSize().c_str());
1305 _ui->doubleSpinBox_particleNoiseT->setObjectName(Parameters::kOdomParticleNoiseT().c_str());
1306 _ui->doubleSpinBox_particleLambdaT->setObjectName(Parameters::kOdomParticleLambdaT().c_str());
1307 _ui->doubleSpinBox_particleNoiseR->setObjectName(Parameters::kOdomParticleNoiseR().c_str());
1308 _ui->doubleSpinBox_particleLambdaR->setObjectName(Parameters::kOdomParticleLambdaR().c_str());
1311 _ui->doubleSpinBox_kalmanProcessNoise->setObjectName(Parameters::kOdomKalmanProcessNoise().c_str());
1312 _ui->doubleSpinBox_kalmanMeasurementNoise->setObjectName(Parameters::kOdomKalmanMeasurementNoise().c_str());
1315 _ui->spinBox_OdomFovisFeatureWindowSize->setObjectName(Parameters::kOdomFovisFeatureWindowSize().c_str());
1316 _ui->spinBox_OdomFovisMaxPyramidLevel->setObjectName(Parameters::kOdomFovisMaxPyramidLevel().c_str());
1317 _ui->spinBox_OdomFovisMinPyramidLevel->setObjectName(Parameters::kOdomFovisMinPyramidLevel().c_str());
1318 _ui->spinBox_OdomFovisTargetPixelsPerFeature->setObjectName(Parameters::kOdomFovisTargetPixelsPerFeature().c_str());
1319 _ui->spinBox_OdomFovisFastThreshold->setObjectName(Parameters::kOdomFovisFastThreshold().c_str());
1320 _ui->checkBox_OdomFovisUseAdaptiveThreshold->setObjectName(Parameters::kOdomFovisUseAdaptiveThreshold().c_str());
1321 _ui->doubleSpinBox_OdomFovisFastThresholdAdaptiveGain->setObjectName(Parameters::kOdomFovisFastThresholdAdaptiveGain().c_str());
1322 _ui->checkBox_OdomFovisUseHomographyInitialization->setObjectName(Parameters::kOdomFovisUseHomographyInitialization().c_str());
1324 _ui->checkBox_OdomFovisUseBucketing->setObjectName(Parameters::kOdomFovisUseBucketing().c_str());
1325 _ui->spinBox_OdomFovisBucketWidth->setObjectName(Parameters::kOdomFovisBucketWidth().c_str());
1326 _ui->spinBox_OdomFovisBucketHeight->setObjectName(Parameters::kOdomFovisBucketHeight().c_str());
1327 _ui->spinBox_OdomFovisMaxKeypointsPerBucket->setObjectName(Parameters::kOdomFovisMaxKeypointsPerBucket().c_str());
1328 _ui->checkBox_OdomFovisUseImageNormalization->setObjectName(Parameters::kOdomFovisUseImageNormalization().c_str());
1330 _ui->doubleSpinBox_OdomFovisInlierMaxReprojectionError->setObjectName(Parameters::kOdomFovisInlierMaxReprojectionError().c_str());
1331 _ui->doubleSpinBox_OdomFovisCliqueInlierThreshold->setObjectName(Parameters::kOdomFovisCliqueInlierThreshold().c_str());
1332 _ui->spinBox_OdomFovisMinFeaturesForEstimate->setObjectName(Parameters::kOdomFovisMinFeaturesForEstimate().c_str());
1333 _ui->doubleSpinBox_OdomFovisMaxMeanReprojectionError->setObjectName(Parameters::kOdomFovisMaxMeanReprojectionError().c_str());
1334 _ui->checkBox_OdomFovisUseSubpixelRefinement->setObjectName(Parameters::kOdomFovisUseSubpixelRefinement().c_str());
1335 _ui->spinBox_OdomFovisFeatureSearchWindow->setObjectName(Parameters::kOdomFovisFeatureSearchWindow().c_str());
1336 _ui->checkBox_OdomFovisUpdateTargetFeaturesWithRefined->setObjectName(Parameters::kOdomFovisUpdateTargetFeaturesWithRefined().c_str());
1338 _ui->checkBox_OdomFovisStereoRequireMutualMatch->setObjectName(Parameters::kOdomFovisStereoRequireMutualMatch().c_str());
1339 _ui->doubleSpinBox_OdomFovisStereoMaxDistEpipolarLine->setObjectName(Parameters::kOdomFovisStereoMaxDistEpipolarLine().c_str());
1340 _ui->doubleSpinBox_OdomFovisStereoMaxRefinementDisplacement->setObjectName(Parameters::kOdomFovisStereoMaxRefinementDisplacement().c_str());
1341 _ui->spinBox_OdomFovisStereoMaxDisparity->setObjectName(Parameters::kOdomFovisStereoMaxDisparity().c_str());
1344 _ui->spinBox_OdomViso2RansacIters->setObjectName(Parameters::kOdomViso2RansacIters().c_str());
1345 _ui->doubleSpinBox_OdomViso2InlierThreshold->setObjectName(Parameters::kOdomViso2InlierThreshold().c_str());
1346 _ui->checkBox_OdomViso2Reweighting->setObjectName(Parameters::kOdomViso2Reweighting().c_str());
1348 _ui->spinBox_OdomViso2MatchNmsN->setObjectName(Parameters::kOdomViso2MatchNmsN().c_str());
1349 _ui->spinBox_OdomViso2MatchNmsTau->setObjectName(Parameters::kOdomViso2MatchNmsTau().c_str());
1350 _ui->spinBox_OdomViso2MatchBinsize->setObjectName(Parameters::kOdomViso2MatchBinsize().c_str());
1351 _ui->spinBox_OdomViso2MatchRadius->setObjectName(Parameters::kOdomViso2MatchRadius().c_str());
1352 _ui->spinBox_OdomViso2MatchDispTolerance->setObjectName(Parameters::kOdomViso2MatchDispTolerance().c_str());
1353 _ui->spinBox_OdomViso2MatchOutlierDispTolerance->setObjectName(Parameters::kOdomViso2MatchOutlierDispTolerance().c_str());
1354 _ui->spinBox_OdomViso2MatchOutlierFlowTolerance->setObjectName(Parameters::kOdomViso2MatchOutlierFlowTolerance().c_str());
1355 _ui->checkBox_OdomViso2MatchMultiStage->setObjectName(Parameters::kOdomViso2MatchMultiStage().c_str());
1356 _ui->checkBox_OdomViso2MatchHalfResolution->setObjectName(Parameters::kOdomViso2MatchHalfResolution().c_str());
1357 _ui->spinBox_OdomViso2MatchRefinement->setObjectName(Parameters::kOdomViso2MatchRefinement().c_str());
1359 _ui->spinBox_OdomViso2BucketMaxFeatures->setObjectName(Parameters::kOdomViso2BucketMaxFeatures().c_str());
1360 _ui->doubleSpinBox_OdomViso2BucketWidth->setObjectName(Parameters::kOdomViso2BucketWidth().c_str());
1361 _ui->doubleSpinBox_OdomViso2BucketHeight->setObjectName(Parameters::kOdomViso2BucketHeight().c_str());
1364 _ui->lineEdit_OdomORBSLAMVocPath->setObjectName(Parameters::kOdomORBSLAMVocPath().c_str());
1366 _ui->doubleSpinBox_OdomORBSLAMBf->setObjectName(Parameters::kOdomORBSLAMBf().c_str());
1367 _ui->doubleSpinBox_OdomORBSLAMThDepth->setObjectName(Parameters::kOdomORBSLAMThDepth().c_str());
1368 _ui->doubleSpinBox_OdomORBSLAMFps->setObjectName(Parameters::kOdomORBSLAMFps().c_str());
1369 _ui->spinBox_OdomORBSLAMMaxFeatures->setObjectName(Parameters::kOdomORBSLAMMaxFeatures().c_str());
1370 _ui->spinBox_OdomORBSLAMMapSize->setObjectName(Parameters::kOdomORBSLAMMapSize().c_str());
1373 _ui->lineEdit_OdomOkvisPath->setObjectName(Parameters::kOdomOKVISConfigPath().c_str());
1377 _ui->odom_loam_sensor->setObjectName(Parameters::kOdomLOAMSensor().c_str());
1378 _ui->odom_loam_scan_period->setObjectName(Parameters::kOdomLOAMScanPeriod().c_str());
1379 _ui->odom_loam_resolution->setObjectName(Parameters::kOdomLOAMResolution().c_str());
1380 _ui->odom_loam_linvar->setObjectName(Parameters::kOdomLOAMLinVar().c_str());
1381 _ui->odom_loam_angvar->setObjectName(Parameters::kOdomLOAMAngVar().c_str());
1382 _ui->odom_loam_localMapping->setObjectName(Parameters::kOdomLOAMLocalMapping().c_str());
1385 _ui->OdomMSCKFGridRow->setObjectName(Parameters::kOdomMSCKFGridRow().c_str());
1386 _ui->OdomMSCKFGridCol->setObjectName(Parameters::kOdomMSCKFGridCol().c_str());
1387 _ui->OdomMSCKFGridMinFeatureNum->setObjectName(Parameters::kOdomMSCKFGridMinFeatureNum().c_str());
1388 _ui->OdomMSCKFGridMaxFeatureNum->setObjectName(Parameters::kOdomMSCKFGridMaxFeatureNum().c_str());
1389 _ui->OdomMSCKFPyramidLevels->setObjectName(Parameters::kOdomMSCKFPyramidLevels().c_str());
1390 _ui->OdomMSCKFPatchSize->setObjectName(Parameters::kOdomMSCKFPatchSize().c_str());
1391 _ui->OdomMSCKFFastThreshold->setObjectName(Parameters::kOdomMSCKFFastThreshold().c_str());
1392 _ui->OdomMSCKFMaxIteration->setObjectName(Parameters::kOdomMSCKFMaxIteration().c_str());
1393 _ui->OdomMSCKFMaxCamStateSize->setObjectName(Parameters::kOdomMSCKFMaxCamStateSize().c_str());
1394 _ui->OdomMSCKFTrackPrecision->setObjectName(Parameters::kOdomMSCKFTrackPrecision().c_str());
1395 _ui->OdomMSCKFRansacThreshold->setObjectName(Parameters::kOdomMSCKFRansacThreshold().c_str());
1396 _ui->OdomMSCKFStereoThreshold->setObjectName(Parameters::kOdomMSCKFStereoThreshold().c_str());
1397 _ui->OdomMSCKFPositionStdThreshold->setObjectName(Parameters::kOdomMSCKFPositionStdThreshold().c_str());
1398 _ui->OdomMSCKFRotationThreshold->setObjectName(Parameters::kOdomMSCKFRotationThreshold().c_str());
1399 _ui->OdomMSCKFTranslationThreshold->setObjectName(Parameters::kOdomMSCKFTranslationThreshold().c_str());
1400 _ui->OdomMSCKFTrackingRateThreshold->setObjectName(Parameters::kOdomMSCKFTrackingRateThreshold().c_str());
1401 _ui->OdomMSCKFOptTranslationThreshold->setObjectName(Parameters::kOdomMSCKFOptTranslationThreshold().c_str());
1402 _ui->OdomMSCKFNoiseGyro->setObjectName(Parameters::kOdomMSCKFNoiseGyro().c_str());
1403 _ui->OdomMSCKFNoiseAcc->setObjectName(Parameters::kOdomMSCKFNoiseAcc().c_str());
1404 _ui->OdomMSCKFNoiseGyroBias->setObjectName(Parameters::kOdomMSCKFNoiseGyroBias().c_str());
1405 _ui->OdomMSCKFNoiseAccBias->setObjectName(Parameters::kOdomMSCKFNoiseAccBias().c_str());
1406 _ui->OdomMSCKFNoiseFeature->setObjectName(Parameters::kOdomMSCKFNoiseFeature().c_str());
1407 _ui->OdomMSCKFInitCovVel->setObjectName(Parameters::kOdomMSCKFInitCovVel().c_str());
1408 _ui->OdomMSCKFInitCovGyroBias->setObjectName(Parameters::kOdomMSCKFInitCovGyroBias().c_str());
1409 _ui->OdomMSCKFInitCovAccBias->setObjectName(Parameters::kOdomMSCKFInitCovAccBias().c_str());
1410 _ui->OdomMSCKFInitCovExRot->setObjectName(Parameters::kOdomMSCKFInitCovExRot().c_str());
1411 _ui->OdomMSCKFInitCovExTrans->setObjectName(Parameters::kOdomMSCKFInitCovExTrans().c_str());
1414 _ui->lineEdit_OdomVinsPath->setObjectName(Parameters::kOdomVINSConfigPath().c_str());
1418 _ui->stereo_winWidth->setObjectName(Parameters::kStereoWinWidth().c_str());
1419 _ui->stereo_winHeight->setObjectName(Parameters::kStereoWinHeight().c_str());
1420 _ui->stereo_maxLevel->setObjectName(Parameters::kStereoMaxLevel().c_str());
1421 _ui->stereo_iterations->setObjectName(Parameters::kStereoIterations().c_str());
1422 _ui->stereo_minDisparity->setObjectName(Parameters::kStereoMinDisparity().c_str());
1423 _ui->stereo_maxDisparity->setObjectName(Parameters::kStereoMaxDisparity().c_str());
1424 _ui->stereo_ssd->setObjectName(Parameters::kStereoSSD().c_str());
1425 _ui->stereo_flow_eps->setObjectName(Parameters::kStereoEps().c_str());
1426 _ui->stereo_opticalFlow->setObjectName(Parameters::kStereoOpticalFlow().c_str());
1429 _ui->odom_open3d_method->setObjectName(Parameters::kOdomOpen3DMethod().c_str());
1430 _ui->odom_open3d_max_depth->setObjectName(Parameters::kOdomOpen3DMaxDepth().c_str());
1433 _ui->comboBox_stereoDense_strategy->setObjectName(Parameters::kStereoDenseStrategy().c_str());
1434 connect(
_ui->comboBox_stereoDense_strategy, SIGNAL(currentIndexChanged(
int)),
_ui->stackedWidget_stereoDense, SLOT(setCurrentIndex(
int)));
1435 _ui->comboBox_stereoDense_strategy->setCurrentIndex(Parameters::defaultStereoDenseStrategy());
1436 _ui->stackedWidget_stereoDense->setCurrentIndex(Parameters::defaultStereoDenseStrategy());
1439 _ui->stereobm_blockSize->setObjectName(Parameters::kStereoBMBlockSize().c_str());
1440 _ui->stereobm_minDisparity->setObjectName(Parameters::kStereoBMMinDisparity().c_str());
1441 _ui->stereobm_numDisparities->setObjectName(Parameters::kStereoBMNumDisparities().c_str());
1442 _ui->stereobm_preFilterCap->setObjectName(Parameters::kStereoBMPreFilterCap().c_str());
1443 _ui->stereobm_preFilterSize->setObjectName(Parameters::kStereoBMPreFilterSize().c_str());
1444 _ui->stereobm_speckleRange->setObjectName(Parameters::kStereoBMSpeckleRange().c_str());
1445 _ui->stereobm_speckleWinSize->setObjectName(Parameters::kStereoBMSpeckleWindowSize().c_str());
1446 _ui->stereobm_tetureThreshold->setObjectName(Parameters::kStereoBMTextureThreshold().c_str());
1447 _ui->stereobm_uniquessRatio->setObjectName(Parameters::kStereoBMUniquenessRatio().c_str());
1448 _ui->stereobm_disp12MaxDiff->setObjectName(Parameters::kStereoBMDisp12MaxDiff().c_str());
1451 _ui->stereosgbm_blockSize->setObjectName(Parameters::kStereoSGBMBlockSize().c_str());
1452 _ui->stereosgbm_minDisparity->setObjectName(Parameters::kStereoSGBMMinDisparity().c_str());
1453 _ui->stereosgbm_numDisparities->setObjectName(Parameters::kStereoSGBMNumDisparities().c_str());
1454 _ui->stereosgbm_preFilterCap->setObjectName(Parameters::kStereoSGBMPreFilterCap().c_str());
1455 _ui->stereosgbm_speckleRange->setObjectName(Parameters::kStereoSGBMSpeckleRange().c_str());
1456 _ui->stereosgbm_speckleWinSize->setObjectName(Parameters::kStereoSGBMSpeckleWindowSize().c_str());
1457 _ui->stereosgbm_uniquessRatio->setObjectName(Parameters::kStereoSGBMUniquenessRatio().c_str());
1458 _ui->stereosgbm_disp12MaxDiff->setObjectName(Parameters::kStereoSGBMDisp12MaxDiff().c_str());
1459 _ui->stereosgbm_p1->setObjectName(Parameters::kStereoSGBMP1().c_str());
1460 _ui->stereosgbm_p2->setObjectName(Parameters::kStereoSGBMP2().c_str());
1461 _ui->stereosgbm_mode->setObjectName(Parameters::kStereoSGBMMode().c_str());
1464 _ui->ArucoDictionary->setObjectName(Parameters::kMarkerDictionary().c_str());
1465 _ui->ArucoMarkerLength->setObjectName(Parameters::kMarkerLength().c_str());
1466 _ui->ArucoMaxDepthError->setObjectName(Parameters::kMarkerMaxDepthError().c_str());
1467 _ui->ArucoVarianceLinear->setObjectName(Parameters::kMarkerVarianceLinear().c_str());
1468 _ui->ArucoVarianceAngular->setObjectName(Parameters::kMarkerVarianceAngular().c_str());
1469 _ui->ArucoMarkerRangeMin->setObjectName(Parameters::kMarkerMinRange().c_str());
1470 _ui->ArucoMarkerRangeMax->setObjectName(Parameters::kMarkerMaxRange().c_str());
1471 _ui->ArucoMarkerPriors->setObjectName(Parameters::kMarkerPriors().c_str());
1472 _ui->ArucoPriorsVarianceLinear->setObjectName(Parameters::kMarkerPriorsVarianceLinear().c_str());
1473 _ui->ArucoPriorsVarianceAngular->setObjectName(Parameters::kMarkerPriorsVarianceAngular().c_str());
1474 _ui->ArucoCornerRefinementMethod->setObjectName(Parameters::kMarkerCornerRefinementMethod().c_str());
1477 _ui->doubleSpinBox_imuFilterMadgwickGain->setObjectName(Parameters::kImuFilterMadgwickGain().c_str());
1478 _ui->doubleSpinBox_imuFilterMadgwickZeta->setObjectName(Parameters::kImuFilterMadgwickZeta().c_str());
1479 _ui->doubleSpinBox_imuFilterComplementaryGainAcc->setObjectName(Parameters::kImuFilterComplementaryGainAcc().c_str());
1480 _ui->doubleSpinBox_imuFilterComplementaryBiasAlpha->setObjectName(Parameters::kImuFilterComplementaryBiasAlpha().c_str());
1481 _ui->checkBox_imuFilterComplementaryDoAdaptiveGain->setObjectName(Parameters::kImuFilterComplementaryDoAdpativeGain().c_str());
1482 _ui->checkBox_imuFilterComplementaryDoBiasEstimation->setObjectName(Parameters::kImuFilterComplementaryDoBiasEstimation().c_str());
1494 connect(
_ui->doubleSpinBox_kp_roi0, SIGNAL(valueChanged(
double)),
this, SLOT(
updateKpROI()));
1495 connect(
_ui->doubleSpinBox_kp_roi1, SIGNAL(valueChanged(
double)),
this, SLOT(
updateKpROI()));
1496 connect(
_ui->doubleSpinBox_kp_roi2, SIGNAL(valueChanged(
double)),
this, SLOT(
updateKpROI()));
1497 connect(
_ui->doubleSpinBox_kp_roi3, SIGNAL(valueChanged(
double)),
this, SLOT(
updateKpROI()));
1498 connect(
_ui->checkBox_useOdomFeatures, SIGNAL(toggled(
bool)),
this, SLOT(
useOdomFeatures()));
1502 _ui->stackedWidget->setCurrentIndex(0);
1519 for(ParametersMap::const_iterator iter=defaults.begin(); iter!=defaults.end(); ++iter)
1533 for(
int i =0;i<boxes.size();++i)
1535 if(boxes[i] ==
_ui->groupBox_source0)
1537 _ui->stackedWidget->setCurrentIndex(i);
1553 _ui->treeView->setModel(0);
1559 if(
_ui->radioButton_basic->isChecked())
1561 boxes = boxes.mid(0,7);
1568 QStandardItem * parentItem =
_indexModel->invisibleRootItem();
1570 this->
parseModel(boxes, parentItem, 0, index);
1571 if(
_ui->radioButton_advanced->isChecked() && index !=
_ui->stackedWidget->count()-1)
1573 ULOGGER_ERROR(
"The tree model is not the same size of the stacked widgets...%d vs %d advanced stacks", index,
_ui->stackedWidget->count()-1);
1575 int currentIndex =
_ui->stackedWidget->currentIndex();
1576 if(
_ui->radioButton_basic->isChecked())
1578 if(currentIndex >= 6)
1580 _ui->stackedWidget->setCurrentIndex(6);
1586 if(currentIndex == 6)
1588 _ui->stackedWidget->setCurrentIndex(7);
1592 _ui->treeView->expandToDepth(1);
1595 connect(
_ui->treeView->selectionModel(), SIGNAL(currentChanged(
const QModelIndex &,
const QModelIndex &)),
this, SLOT(
clicked(
const QModelIndex &,
const QModelIndex &)));
1607 QStandardItem * currentItem = 0;
1608 while(absoluteIndex < boxes.size())
1610 QString objectName = boxes.at(absoluteIndex)->objectName();
1611 QString title = boxes.at(absoluteIndex)->title();
1613 int lvl = QString(objectName.at(objectName.size()-1)).toInt(&ok);
1616 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());
1621 if(lvl == currentLevel)
1623 QStandardItem * item =
new QStandardItem(title);
1624 item->setData(absoluteIndex);
1627 parentItem->appendRow(item);
1630 else if(lvl > currentLevel)
1632 if(lvl>currentLevel+1)
1634 ULOGGER_ERROR(
"Intermediary lvl doesn't exist, lvl %d to %d, indexes %d and %d", currentLevel, lvl, absoluteIndex-1, absoluteIndex);
1639 parseModel(boxes, currentItem, currentLevel+1, absoluteIndex);
1653 for(rtabmap::ParametersMap::const_iterator iter=parameters.begin(); iter!=parameters.end(); ++iter)
1655 QWidget * obj =
_ui->stackedWidget->findChild<QWidget*>((*iter).first.c_str());
1659 obj->setToolTip(tr(
"%1 (Default=\"%2\")").arg(iter->first.c_str()).arg(iter->second.c_str()));
1661 QSpinBox * spin = qobject_cast<QSpinBox *>(obj);
1662 QDoubleSpinBox * doubleSpin = qobject_cast<QDoubleSpinBox *>(obj);
1663 QComboBox * combo = qobject_cast<QComboBox *>(obj);
1664 QCheckBox * check = qobject_cast<QCheckBox *>(obj);
1665 QRadioButton * radio = qobject_cast<QRadioButton *>(obj);
1666 QLineEdit * lineEdit = qobject_cast<QLineEdit *>(obj);
1667 QGroupBox * groupBox = qobject_cast<QGroupBox *>(obj);
1670 connect(spin, SIGNAL(valueChanged(
int)),
this, SLOT(
addParameter(
int)));
1674 connect(doubleSpin, SIGNAL(valueChanged(
double)),
this, SLOT(
addParameter(
double)));
1678 connect(combo, SIGNAL(currentIndexChanged(
int)),
this, SLOT(
addParameter(
int)));
1682 connect(check, SIGNAL(toggled(
bool)),
this, SLOT(
addParameter(
bool)));
1686 connect(radio, SIGNAL(toggled(
bool)),
this, SLOT(
addParameter(
bool)));
1690 connect(lineEdit, SIGNAL(textChanged(
const QString &)),
this, SLOT(
addParameter(
const QString &)));
1694 connect(groupBox, SIGNAL(toggled(
bool)),
this, SLOT(
addParameter(
bool)));
1698 ULOGGER_WARN(
"QWidget called %s can't be cast to a supported widget", (*iter).first.c_str());
1703 ULOGGER_WARN(
"Can't find the related QWidget for parameter %s", (*iter).first.c_str());
1710 QStandardItem * item =
_indexModel->itemFromIndex(current);
1711 if(item && item->isEnabled())
1713 int index = item->data().toInt();
1714 if(
_ui->radioButton_advanced->isChecked() && index >= 6)
1718 _ui->stackedWidget->setCurrentIndex(index);
1719 _ui->scrollArea->horizontalScrollBar()->setValue(0);
1720 _ui->scrollArea->verticalScrollBar()->setValue(0);
1738 QDialogButtonBox::ButtonRole role =
_ui->buttonBox_global->buttonRole(button);
1741 case QDialogButtonBox::RejectRole:
1749 case QDialogButtonBox::AcceptRole:
1772 QDialogButtonBox::ButtonRole role =
_ui->buttonBox_local->buttonRole(button);
1775 case QDialogButtonBox::ApplyRole:
1783 case QDialogButtonBox::ResetRole:
1794 if(groupBox->objectName() ==
_ui->groupBox_generalSettingsGui0->objectName())
1796 _ui->general_checkBox_imagesKept->setChecked(
true);
1797 _ui->general_checkBox_missing_cache_republished->setChecked(
true);
1798 _ui->general_checkBox_cloudsKept->setChecked(
true);
1799 _ui->checkBox_beep->setChecked(
false);
1800 _ui->checkBox_stamps->setChecked(
true);
1801 _ui->checkBox_cacheStatistics->setChecked(
true);
1802 _ui->checkBox_notifyWhenNewGlobalPathIsReceived->setChecked(
false);
1803 _ui->checkBox_verticalLayoutUsed->setChecked(
true);
1804 _ui->checkBox_imageRejectedShown->setChecked(
true);
1805 _ui->checkBox_imageHighestHypShown->setChecked(
false);
1806 _ui->spinBox_odomQualityWarnThr->setValue(50);
1807 _ui->checkBox_odom_onlyInliersShown->setChecked(
false);
1808 _ui->radioButton_posteriorGraphView->setChecked(
true);
1809 _ui->radioButton_wordsGraphView->setChecked(
false);
1810 _ui->radioButton_localizationsGraphView->setChecked(
false);
1811 _ui->radioButton_localizationsGraphViewOdomCache->setChecked(
false);
1812 _ui->radioButton_nochangeGraphView->setChecked(
false);
1813 _ui->checkbox_odomDisabled->setChecked(
false);
1814 _ui->checkbox_groundTruthAlign->setChecked(
true);
1816 else if(groupBox->objectName() ==
_ui->groupBox_cloudRendering1->objectName())
1818 for(
int i=0; i<2; ++i)
1843 _ui->doubleSpinBox_voxel->setValue(0);
1844 _ui->doubleSpinBox_noiseRadius->setValue(0);
1845 _ui->spinBox_noiseMinNeighbors->setValue(5);
1847 _ui->doubleSpinBox_ceilingFilterHeight->setValue(0);
1848 _ui->doubleSpinBox_floorFilterHeight->setValue(0);
1849 _ui->spinBox_normalKSearch->setValue(10);
1850 _ui->doubleSpinBox_normalRadiusSearch->setValue(0.0);
1852 _ui->doubleSpinBox_ceilingFilterHeight_scan->setValue(0);
1853 _ui->doubleSpinBox_floorFilterHeight_scan->setValue(0);
1854 _ui->spinBox_normalKSearch_scan->setValue(0);
1855 _ui->doubleSpinBox_normalRadiusSearch_scan->setValue(0.0);
1857 _ui->checkBox_showGraphs->setChecked(
true);
1858 _ui->checkBox_showLabels->setChecked(
false);
1859 _ui->checkBox_showFrames->setChecked(
false);
1860 _ui->checkBox_showLandmarks->setChecked(
true);
1861 _ui->doubleSpinBox_landmarkSize->setValue(0);
1862 _ui->checkBox_showIMUGravity->setChecked(
false);
1863 _ui->checkBox_showIMUAcc->setChecked(
false);
1865 _ui->doubleSpinBox_mesh_angleTolerance->setValue(15.0);
1866 _ui->groupBox_organized->setChecked(
false);
1867 #if PCL_VERSION_COMPARE(>=, 1, 7, 2) 1868 _ui->checkBox_mesh_quad->setChecked(
true);
1870 _ui->checkBox_mesh_quad->setChecked(
false);
1872 _ui->checkBox_mesh_texture->setChecked(
false);
1873 _ui->spinBox_mesh_triangleSize->setValue(2);
1875 else if(groupBox->objectName() ==
_ui->groupBox_filtering2->objectName())
1877 _ui->radioButton_noFiltering->setChecked(
true);
1878 _ui->radioButton_nodeFiltering->setChecked(
false);
1879 _ui->radioButton_subtractFiltering->setChecked(
false);
1880 _ui->doubleSpinBox_cloudFilterRadius->setValue(0.1);
1881 _ui->doubleSpinBox_cloudFilterAngle->setValue(30);
1882 _ui->spinBox_subtractFilteringMinPts->setValue(5);
1883 _ui->doubleSpinBox_subtractFilteringRadius->setValue(0.02);
1884 _ui->doubleSpinBox_subtractFilteringAngle->setValue(0);
1886 else if(groupBox->objectName() ==
_ui->groupBox_gridMap2->objectName())
1888 _ui->checkBox_map_shown->setChecked(
false);
1889 _ui->doubleSpinBox_map_opacity->setValue(0.75);
1891 _ui->groupBox_octomap->setChecked(
false);
1892 _ui->spinBox_octomap_treeDepth->setValue(16);
1893 _ui->checkBox_octomap_2dgrid->setChecked(
true);
1894 _ui->checkBox_octomap_show3dMap->setChecked(
true);
1895 _ui->comboBox_octomap_renderingType->setCurrentIndex(0);
1896 _ui->spinBox_octomap_pointSize->setValue(5);
1898 else if(groupBox->objectName() ==
_ui->groupBox_logging1->objectName())
1900 _ui->comboBox_loggerLevel->setCurrentIndex(2);
1901 _ui->comboBox_loggerEventLevel->setCurrentIndex(3);
1902 _ui->comboBox_loggerPauseLevel->setCurrentIndex(3);
1903 _ui->checkBox_logger_printTime->setChecked(
true);
1904 _ui->checkBox_logger_printThreadId->setChecked(
false);
1905 _ui->comboBox_loggerType->setCurrentIndex(1);
1906 for(
int i=0; i<
_ui->comboBox_loggerFilter->count(); ++i)
1908 _ui->comboBox_loggerFilter->setItemChecked(i,
false);
1911 else if(groupBox->objectName() ==
_ui->groupBox_source0->objectName())
1913 _ui->general_doubleSpinBox_imgRate->setValue(0.0);
1914 _ui->source_mirroring->setChecked(
false);
1915 _ui->lineEdit_calibrationFile->clear();
1916 _ui->comboBox_sourceType->setCurrentIndex(
kSrcRGBD);
1917 _ui->lineEdit_sourceDevice->setText(
"");
1918 _ui->lineEdit_sourceLocalTransform->setText(
"0 0 0 0 0 0");
1921 _ui->source_images_spinBox_startPos->setValue(0);
1922 _ui->source_images_spinBox_maxFrames->setValue(0);
1923 _ui->spinBox_usbcam_streamWidth->setValue(0);
1924 _ui->spinBox_usbcam_streamHeight->setValue(0);
1925 _ui->checkBox_rgb_rectify->setChecked(
false);
1926 _ui->comboBox_cameraImages_bayerMode->setCurrentIndex(0);
1928 _ui->source_checkBox_ignoreOdometry->setChecked(
false);
1929 _ui->source_checkBox_ignoreGoalDelay->setChecked(
true);
1930 _ui->source_checkBox_ignoreGoals->setChecked(
true);
1931 _ui->source_checkBox_ignoreLandmarks->setChecked(
true);
1932 _ui->source_checkBox_ignoreFeatures->setChecked(
true);
1933 _ui->source_spinBox_databaseStartId->setValue(0);
1934 _ui->source_spinBox_databaseStopId->setValue(0);
1935 _ui->source_spinBox_database_cameraIndex->setValue(-1);
1936 _ui->source_checkBox_useDbStamps->setChecked(
true);
1967 _ui->checkbox_rgbd_colorOnly->setChecked(
false);
1968 _ui->spinBox_source_imageDecimation->setValue(1);
1969 _ui->checkbox_stereo_depthGenerated->setChecked(
false);
1970 _ui->checkBox_stereo_exposureCompensation->setChecked(
false);
1971 _ui->openni2_autoWhiteBalance->setChecked(
true);
1972 _ui->openni2_autoExposure->setChecked(
true);
1973 _ui->openni2_exposure->setValue(0);
1974 _ui->openni2_gain->setValue(100);
1975 _ui->openni2_mirroring->setChecked(
false);
1976 _ui->openni2_stampsIdsUsed->setChecked(
false);
1977 _ui->openni2_hshift->setValue(0);
1978 _ui->openni2_vshift->setValue(0);
1979 _ui->openni2_depth_decimation->setValue(1);
1980 _ui->comboBox_freenect2Format->setCurrentIndex(1);
1981 _ui->doubleSpinBox_freenect2MinDepth->setValue(0.3);
1982 _ui->doubleSpinBox_freenect2MaxDepth->setValue(12.0);
1983 _ui->checkBox_freenect2BilateralFiltering->setChecked(
true);
1984 _ui->checkBox_freenect2EdgeAwareFiltering->setChecked(
true);
1985 _ui->checkBox_freenect2NoiseFiltering->setChecked(
true);
1986 _ui->lineEdit_freenect2Pipeline->setText(
"");
1987 _ui->comboBox_k4w2Format->setCurrentIndex(1);
1988 _ui->comboBox_realsensePresetRGB->setCurrentIndex(0);
1989 _ui->comboBox_realsensePresetDepth->setCurrentIndex(2);
1990 _ui->checkbox_realsenseOdom->setChecked(
false);
1991 _ui->checkbox_realsenseDepthScaledToRGBSize->setChecked(
false);
1992 _ui->comboBox_realsenseRGBSource->setCurrentIndex(0);
1993 _ui->checkbox_rs2_emitter->setChecked(
true);
1994 _ui->checkbox_rs2_irMode->setChecked(
false);
1995 _ui->checkbox_rs2_irDepth->setChecked(
true);
1996 _ui->spinBox_rs2_width->setValue(848);
1997 _ui->spinBox_rs2_height->setValue(480);
1998 _ui->spinBox_rs2_rate->setValue(60);
1999 _ui->spinBox_rs2_width_depth->setValue(640);
2000 _ui->spinBox_rs2_height_depth->setValue(480);
2001 _ui->spinBox_rs2_rate_depth->setValue(30);
2002 _ui->checkbox_rs2_globalTimeStync->setChecked(
true);
2003 _ui->lineEdit_rs2_jsonFile->clear();
2004 _ui->lineEdit_openniOniPath->clear();
2005 _ui->lineEdit_openni2OniPath->clear();
2006 _ui->comboBox_k4a_rgb_resolution->setCurrentIndex(0);
2007 _ui->comboBox_k4a_framerate->setCurrentIndex(2);
2008 _ui->comboBox_k4a_depth_resolution->setCurrentIndex(2);
2009 _ui->checkbox_k4a_irDepth->setChecked(
false);
2010 _ui->lineEdit_k4a_mkv->clear();
2011 _ui->source_checkBox_useMKVStamps->setChecked(
true);
2012 _ui->lineEdit_cameraRGBDImages_path_rgb->setText(
"");
2013 _ui->lineEdit_cameraRGBDImages_path_depth->setText(
"");
2014 _ui->doubleSpinBox_cameraRGBDImages_scale->setValue(1.0);
2015 _ui->spinBox_cameraRGBDImages_startIndex->setValue(0);
2016 _ui->spinBox_cameraRGBDImages_maxFrames->setValue(0);
2017 _ui->lineEdit_source_distortionModel->setText(
"");
2018 _ui->groupBox_bilateral->setChecked(
false);
2019 _ui->doubleSpinBox_bilateral_sigmaS->setValue(10.0);
2020 _ui->doubleSpinBox_bilateral_sigmaR->setValue(0.1);
2023 _ui->lineEdit_cameraStereoImages_path_left->setText(
"");
2024 _ui->lineEdit_cameraStereoImages_path_right->setText(
"");
2025 _ui->checkBox_stereo_rectify->setChecked(
false);
2026 _ui->spinBox_cameraStereoImages_startIndex->setValue(0);
2027 _ui->spinBox_cameraStereoImages_maxFrames->setValue(0);
2028 _ui->lineEdit_cameraStereoVideo_path->setText(
"");
2029 _ui->lineEdit_cameraStereoVideo_path_2->setText(
"");
2030 _ui->spinBox_stereo_right_device->setValue(-1);
2031 _ui->spinBox_stereousbcam_streamWidth->setValue(0);
2032 _ui->spinBox_stereousbcam_streamHeight->setValue(0);
2033 _ui->comboBox_stereoZed_resolution->setCurrentIndex(2);
2034 _ui->comboBox_stereoZed_quality->setCurrentIndex(1);
2035 _ui->checkbox_stereoZed_selfCalibration->setChecked(
true);
2036 _ui->comboBox_stereoZed_sensingMode->setCurrentIndex(0);
2037 _ui->spinBox_stereoZed_confidenceThr->setValue(100);
2038 _ui->spinBox_stereoZed_texturenessConfidenceThr->setValue(90);
2039 _ui->lineEdit_zedSvoPath->clear();
2040 _ui->comboBox_stereoZedOC_resolution->setCurrentIndex(3);
2041 _ui->checkbox_stereoMyntEye_rectify->setChecked(
false);
2042 _ui->checkbox_stereoMyntEye_depth->setChecked(
false);
2043 _ui->checkbox_stereoMyntEye_autoExposure->setChecked(
true);
2044 _ui->spinBox_stereoMyntEye_gain->setValue(24);
2045 _ui->spinBox_stereoMyntEye_brightness->setValue(120);
2046 _ui->spinBox_stereoMyntEye_contrast->setValue(116);
2047 _ui->spinBox_stereoMyntEye_irControl->setValue(0);
2048 _ui->comboBox_depthai_resolution->setCurrentIndex(1);
2049 _ui->checkBox_depthai_depth->setChecked(
false);
2050 _ui->spinBox_depthai_confidence->setValue(200);
2051 _ui->checkBox_depthai_imu_published->setChecked(
true);
2052 _ui->checkBox_depthai_imu_firmware_update->setChecked(
false);
2054 _ui->checkBox_cameraImages_configForEachFrame->setChecked(
false);
2055 _ui->checkBox_cameraImages_timestamps->setChecked(
false);
2056 _ui->checkBox_cameraImages_syncTimeStamps->setChecked(
true);
2057 _ui->lineEdit_cameraImages_timestamps->setText(
"");
2058 _ui->lineEdit_cameraImages_path_scans->setText(
"");
2059 _ui->lineEdit_cameraImages_laser_transform->setText(
"0 0 0 0 0 0");
2060 _ui->spinBox_cameraImages_max_scan_pts->setValue(0);
2061 _ui->lineEdit_cameraImages_odom->setText(
"");
2062 _ui->comboBox_cameraImages_odomFormat->setCurrentIndex(0);
2063 _ui->lineEdit_cameraImages_gt->setText(
"");
2064 _ui->comboBox_cameraImages_gtFormat->setCurrentIndex(0);
2065 _ui->doubleSpinBox_maxPoseTimeDiff->setValue(0.02);
2066 _ui->lineEdit_cameraImages_path_imu->setText(
"");
2067 _ui->lineEdit_cameraImages_imu_transform->setText(
"0 0 1 0 -1 0 1 0 0");
2068 _ui->spinBox_cameraImages_max_imu_rate->setValue(0);
2070 _ui->comboBox_odom_sensor->setCurrentIndex(0);
2071 _ui->lineEdit_odom_sensor_extrinsics->setText(
"-0.000622602 0.0303752 0.031389 -0.00272485 0.00749254 0.0");
2072 _ui->lineEdit_odom_sensor_path_calibration->setText(
"");
2073 _ui->lineEdit_odomSourceDevice->setText(
"");
2074 _ui->doubleSpinBox_odom_sensor_time_offset->setValue(0.0);
2075 _ui->doubleSpinBox_odom_sensor_scale_factor->setValue(1);
2076 _ui->checkBox_odom_sensor_use_as_gt->setChecked(
false);
2078 _ui->comboBox_imuFilter_strategy->setCurrentIndex(2);
2079 _ui->doubleSpinBox_imuFilterMadgwickGain->setValue(Parameters::defaultImuFilterMadgwickGain());
2080 _ui->doubleSpinBox_imuFilterMadgwickZeta->setValue(Parameters::defaultImuFilterMadgwickZeta());
2081 _ui->doubleSpinBox_imuFilterComplementaryGainAcc->setValue(Parameters::defaultImuFilterComplementaryGainAcc());
2082 _ui->doubleSpinBox_imuFilterComplementaryBiasAlpha->setValue(Parameters::defaultImuFilterComplementaryBiasAlpha());
2083 _ui->checkBox_imuFilterComplementaryDoAdaptiveGain->setChecked(Parameters::defaultImuFilterComplementaryDoAdpativeGain());
2084 _ui->checkBox_imuFilterComplementaryDoBiasEstimation->setChecked(Parameters::defaultImuFilterComplementaryDoBiasEstimation());
2085 _ui->checkBox_imuFilter_baseFrameConversion->setChecked(
true);
2086 _ui->checkbox_publishInterIMU->setChecked(
false);
2088 _ui->checkBox_source_scanFromDepth->setChecked(
false);
2089 _ui->spinBox_source_scanDownsampleStep->setValue(1);
2090 _ui->doubleSpinBox_source_scanRangeMin->setValue(0);
2091 _ui->doubleSpinBox_source_scanRangeMax->setValue(0);
2092 _ui->doubleSpinBox_source_scanVoxelSize->setValue(0.0
f);
2093 _ui->spinBox_source_scanNormalsK->setValue(0);
2094 _ui->doubleSpinBox_source_scanNormalsRadius->setValue(0.0);
2095 _ui->doubleSpinBox_source_scanNormalsForceGroundUp->setValue(0);
2097 _ui->groupBox_depthFromScan->setChecked(
false);
2098 _ui->groupBox_depthFromScan_fillHoles->setChecked(
true);
2099 _ui->radioButton_depthFromScan_vertical->setChecked(
true);
2100 _ui->radioButton_depthFromScan_horizontal->setChecked(
false);
2101 _ui->checkBox_depthFromScan_fillBorders->setChecked(
false);
2103 else if(groupBox->objectName() ==
_ui->groupBox_rtabmap_basic0->objectName())
2105 _ui->general_doubleSpinBox_timeThr_2->setValue(Parameters::defaultRtabmapTimeThr());
2106 _ui->general_doubleSpinBox_hardThr_2->setValue(Parameters::defaultRtabmapLoopThr());
2107 _ui->doubleSpinBox_similarityThreshold_2->setValue(Parameters::defaultMemRehearsalSimilarity());
2108 _ui->general_spinBox_imagesBufferSize_2->setValue(Parameters::defaultRtabmapImageBufferSize());
2109 _ui->general_spinBox_maxStMemSize_2->setValue(Parameters::defaultMemSTMSize());
2110 _ui->general_checkBox_publishStats_2->setChecked(Parameters::defaultRtabmapPublishStats());
2111 _ui->general_checkBox_activateRGBD_2->setChecked(Parameters::defaultRGBDEnabled());
2112 _ui->general_checkBox_SLAM_mode_2->setChecked(Parameters::defaultMemIncrementalMemory());
2113 _ui->general_doubleSpinBox_detectionRate_2->setValue(Parameters::defaultRtabmapDetectionRate());
2115 _ui->general_doubleSpinBox_timeThr->setValue(Parameters::defaultRtabmapTimeThr());
2116 _ui->general_doubleSpinBox_hardThr->setValue(Parameters::defaultRtabmapLoopThr());
2117 _ui->doubleSpinBox_similarityThreshold->setValue(Parameters::defaultMemRehearsalSimilarity());
2118 _ui->general_spinBox_imagesBufferSize->setValue(Parameters::defaultRtabmapImageBufferSize());
2119 _ui->general_spinBox_maxStMemSize->setValue(Parameters::defaultMemSTMSize());
2120 _ui->general_doubleSpinBox_detectionRate->setValue(Parameters::defaultRtabmapDetectionRate());
2124 QObjectList children = groupBox->children();
2127 for(
int i=0; i<children.size(); ++i)
2129 key = children.at(i)->objectName().toStdString();
2132 if(key.compare(Parameters::kRtabmapWorkingDirectory().c_str()) == 0)
2140 if(qobject_cast<const QGroupBox*>(children.at(i)))
2145 else if(qobject_cast<const QGroupBox*>(children.at(i)))
2149 else if(qobject_cast<const QStackedWidget*>(children.at(i)))
2151 QStackedWidget * stackedWidget = (QStackedWidget*)children.at(i);
2152 for(
int j=0; j<stackedWidget->count(); ++j)
2154 const QObjectList & children2 = stackedWidget->widget(j)->children();
2155 for(
int k=0; k<children2.size(); ++k)
2157 if(qobject_cast<QGroupBox *>(children2.at(k)))
2166 if(groupBox->findChild<QLineEdit*>(
_ui->lineEdit_kp_roi->objectName()))
2171 if(groupBox->objectName() ==
_ui->groupBox_odometry1->objectName())
2173 _ui->odom_registration->setCurrentIndex(3);
2174 _ui->odom_f2m_gravitySigma->setValue(-1);
2182 if(panelNumber >= 0 && panelNumber < boxes.size())
2186 else if(panelNumber == -1)
2188 for(QList<QGroupBox*>::iterator iter = boxes.begin(); iter!=boxes.end(); ++iter)
2195 ULOGGER_WARN(
"panel number and the number of stacked widget doesn't match");
2202 return _ui->lineEdit_workingDirectory->text();
2207 QString privatePath = QDir::homePath() +
"/.rtabmap";
2208 if(!QDir(privatePath).exists())
2210 QDir::home().mkdir(
".rtabmap");
2212 return privatePath +
"/rtabmap.ini";
2222 QString path = QFileDialog::getOpenFileName(
this, tr(
"Load settings..."), this->
getWorkingDirectory(),
"*.ini");
2240 QStandardItem * parentItem =
_indexModel->invisibleRootItem();
2243 for(
int i=1; i<parentItem->rowCount(); ++i)
2245 parentItem->child(i)->setEnabled(
false);
2248 _ui->radioButton_basic->setEnabled(
false);
2249 _ui->radioButton_advanced->setEnabled(
false);
2254 QStandardItem * parentItem =
_indexModel->invisibleRootItem();
2257 for(
int i=0; i<parentItem->rowCount(); ++i)
2259 parentItem->child(i)->setEnabled(
true);
2262 _ui->radioButton_basic->setEnabled(
true);
2263 _ui->radioButton_advanced->setEnabled(
true);
2270 if(!filePath.isEmpty())
2274 QSettings settings(path, QSettings::IniFormat);
2275 settings.beginGroup(
"Gui");
2276 settings.beginGroup(
"General");
2277 _ui->general_checkBox_imagesKept->setChecked(settings.value(
"imagesKept",
_ui->general_checkBox_imagesKept->isChecked()).toBool());
2278 _ui->general_checkBox_missing_cache_republished->setChecked(settings.value(
"missingRepublished",
_ui->general_checkBox_missing_cache_republished->isChecked()).toBool());
2279 _ui->general_checkBox_cloudsKept->setChecked(settings.value(
"cloudsKept",
_ui->general_checkBox_cloudsKept->isChecked()).toBool());
2280 _ui->comboBox_loggerLevel->setCurrentIndex(settings.value(
"loggerLevel",
_ui->comboBox_loggerLevel->currentIndex()).toInt());
2281 _ui->comboBox_loggerEventLevel->setCurrentIndex(settings.value(
"loggerEventLevel",
_ui->comboBox_loggerEventLevel->currentIndex()).toInt());
2282 _ui->comboBox_loggerPauseLevel->setCurrentIndex(settings.value(
"loggerPauseLevel",
_ui->comboBox_loggerPauseLevel->currentIndex()).toInt());
2283 _ui->comboBox_loggerType->setCurrentIndex(settings.value(
"loggerType",
_ui->comboBox_loggerType->currentIndex()).toInt());
2284 _ui->checkBox_logger_printTime->setChecked(settings.value(
"loggerPrintTime",
_ui->checkBox_logger_printTime->isChecked()).toBool());
2285 _ui->checkBox_logger_printThreadId->setChecked(settings.value(
"loggerPrintThreadId",
_ui->checkBox_logger_printThreadId->isChecked()).toBool());
2286 _ui->checkBox_verticalLayoutUsed->setChecked(settings.value(
"verticalLayoutUsed",
_ui->checkBox_verticalLayoutUsed->isChecked()).toBool());
2287 _ui->checkBox_imageRejectedShown->setChecked(settings.value(
"imageRejectedShown",
_ui->checkBox_imageRejectedShown->isChecked()).toBool());
2288 _ui->checkBox_imageHighestHypShown->setChecked(settings.value(
"imageHighestHypShown",
_ui->checkBox_imageHighestHypShown->isChecked()).toBool());
2289 _ui->checkBox_beep->setChecked(settings.value(
"beep",
_ui->checkBox_beep->isChecked()).toBool());
2290 _ui->checkBox_stamps->setChecked(settings.value(
"figure_time",
_ui->checkBox_stamps->isChecked()).toBool());
2291 _ui->checkBox_cacheStatistics->setChecked(settings.value(
"figure_cache",
_ui->checkBox_cacheStatistics->isChecked()).toBool());
2292 _ui->checkBox_notifyWhenNewGlobalPathIsReceived->setChecked(settings.value(
"notifyNewGlobalPath",
_ui->checkBox_notifyWhenNewGlobalPathIsReceived->isChecked()).toBool());
2293 _ui->spinBox_odomQualityWarnThr->setValue(settings.value(
"odomQualityThr",
_ui->spinBox_odomQualityWarnThr->value()).toInt());
2294 _ui->checkBox_odom_onlyInliersShown->setChecked(settings.value(
"odomOnlyInliersShown",
_ui->checkBox_odom_onlyInliersShown->isChecked()).toBool());
2295 _ui->radioButton_posteriorGraphView->setChecked(settings.value(
"posteriorGraphView",
_ui->radioButton_posteriorGraphView->isChecked()).toBool());
2296 _ui->radioButton_wordsGraphView->setChecked(settings.value(
"wordsGraphView",
_ui->radioButton_wordsGraphView->isChecked()).toBool());
2297 _ui->radioButton_localizationsGraphView->setChecked(settings.value(
"localizationsGraphView",
_ui->radioButton_localizationsGraphView->isChecked()).toBool());
2298 _ui->radioButton_localizationsGraphViewOdomCache->setChecked(settings.value(
"localizationsGraphViewOdomCache",
_ui->radioButton_localizationsGraphViewOdomCache->isChecked()).toBool());
2299 _ui->radioButton_nochangeGraphView->setChecked(settings.value(
"nochangeGraphView",
_ui->radioButton_nochangeGraphView->isChecked()).toBool());
2300 _ui->checkbox_odomDisabled->setChecked(settings.value(
"odomDisabled",
_ui->checkbox_odomDisabled->isChecked()).toBool());
2301 _ui->odom_registration->setCurrentIndex(settings.value(
"odomRegistration",
_ui->odom_registration->currentIndex()).toInt());
2302 _ui->odom_f2m_gravitySigma->setValue(settings.value(
"odomF2MGravitySigma",
_ui->odom_f2m_gravitySigma->value()).toDouble());
2303 _ui->checkbox_groundTruthAlign->setChecked(settings.value(
"gtAlign",
_ui->checkbox_groundTruthAlign->isChecked()).toBool());
2305 for(
int i=0; i<2; ++i)
2331 _ui->doubleSpinBox_voxel->setValue(settings.value(
"cloudVoxel",
_ui->doubleSpinBox_voxel->value()).toDouble());
2332 _ui->doubleSpinBox_noiseRadius->setValue(settings.value(
"cloudNoiseRadius",
_ui->doubleSpinBox_noiseRadius->value()).toDouble());
2333 _ui->spinBox_noiseMinNeighbors->setValue(settings.value(
"cloudNoiseMinNeighbors",
_ui->spinBox_noiseMinNeighbors->value()).toInt());
2334 _ui->doubleSpinBox_ceilingFilterHeight->setValue(settings.value(
"cloudCeilingHeight",
_ui->doubleSpinBox_ceilingFilterHeight->value()).toDouble());
2335 _ui->doubleSpinBox_floorFilterHeight->setValue(settings.value(
"cloudFloorHeight",
_ui->doubleSpinBox_floorFilterHeight->value()).toDouble());
2336 _ui->spinBox_normalKSearch->setValue(settings.value(
"normalKSearch",
_ui->spinBox_normalKSearch->value()).toInt());
2337 _ui->doubleSpinBox_normalRadiusSearch->setValue(settings.value(
"normalRadiusSearch",
_ui->doubleSpinBox_normalRadiusSearch->value()).toDouble());
2338 _ui->doubleSpinBox_ceilingFilterHeight_scan->setValue(settings.value(
"scanCeilingHeight",
_ui->doubleSpinBox_ceilingFilterHeight_scan->value()).toDouble());
2339 _ui->doubleSpinBox_floorFilterHeight_scan->setValue(settings.value(
"scanFloorHeight",
_ui->doubleSpinBox_floorFilterHeight_scan->value()).toDouble());
2340 _ui->spinBox_normalKSearch_scan->setValue(settings.value(
"scanNormalKSearch",
_ui->spinBox_normalKSearch_scan->value()).toInt());
2341 _ui->doubleSpinBox_normalRadiusSearch_scan->setValue(settings.value(
"scanNormalRadiusSearch",
_ui->doubleSpinBox_normalRadiusSearch_scan->value()).toDouble());
2343 _ui->checkBox_showGraphs->setChecked(settings.value(
"showGraphs",
_ui->checkBox_showGraphs->isChecked()).toBool());
2344 _ui->checkBox_showLabels->setChecked(settings.value(
"showLabels",
_ui->checkBox_showLabels->isChecked()).toBool());
2345 _ui->checkBox_showFrames->setChecked(settings.value(
"showFrames",
_ui->checkBox_showFrames->isChecked()).toBool());
2346 _ui->checkBox_showLandmarks->setChecked(settings.value(
"showLandmarks",
_ui->checkBox_showLandmarks->isChecked()).toBool());
2347 _ui->doubleSpinBox_landmarkSize->setValue(settings.value(
"landmarkSize",
_ui->doubleSpinBox_landmarkSize->value()).toDouble());
2348 _ui->checkBox_showIMUGravity->setChecked(settings.value(
"showIMUGravity",
_ui->checkBox_showIMUGravity->isChecked()).toBool());
2349 _ui->checkBox_showIMUAcc->setChecked(settings.value(
"showIMUAcc",
_ui->checkBox_showIMUAcc->isChecked()).toBool());
2351 _ui->radioButton_noFiltering->setChecked(settings.value(
"noFiltering",
_ui->radioButton_noFiltering->isChecked()).toBool());
2352 _ui->radioButton_nodeFiltering->setChecked(settings.value(
"cloudFiltering",
_ui->radioButton_nodeFiltering->isChecked()).toBool());
2353 _ui->doubleSpinBox_cloudFilterRadius->setValue(settings.value(
"cloudFilteringRadius",
_ui->doubleSpinBox_cloudFilterRadius->value()).toDouble());
2354 _ui->doubleSpinBox_cloudFilterAngle->setValue(settings.value(
"cloudFilteringAngle",
_ui->doubleSpinBox_cloudFilterAngle->value()).toDouble());
2355 _ui->radioButton_subtractFiltering->setChecked(settings.value(
"subtractFiltering",
_ui->radioButton_subtractFiltering->isChecked()).toBool());
2356 _ui->spinBox_subtractFilteringMinPts->setValue(settings.value(
"subtractFilteringMinPts",
_ui->spinBox_subtractFilteringMinPts->value()).toInt());
2357 _ui->doubleSpinBox_subtractFilteringRadius->setValue(settings.value(
"subtractFilteringRadius",
_ui->doubleSpinBox_subtractFilteringRadius->value()).toDouble());
2358 _ui->doubleSpinBox_subtractFilteringAngle->setValue(settings.value(
"subtractFilteringAngle",
_ui->doubleSpinBox_subtractFilteringAngle->value()).toDouble());
2360 _ui->checkBox_map_shown->setChecked(settings.value(
"gridMapShown",
_ui->checkBox_map_shown->isChecked()).toBool());
2361 _ui->doubleSpinBox_map_opacity->setValue(settings.value(
"gridMapOpacity",
_ui->doubleSpinBox_map_opacity->value()).toDouble());
2363 _ui->groupBox_octomap->setChecked(settings.value(
"octomap",
_ui->groupBox_octomap->isChecked()).toBool());
2364 _ui->spinBox_octomap_treeDepth->setValue(settings.value(
"octomap_depth",
_ui->spinBox_octomap_treeDepth->value()).toInt());
2365 _ui->checkBox_octomap_2dgrid->setChecked(settings.value(
"octomap_2dgrid",
_ui->checkBox_octomap_2dgrid->isChecked()).toBool());
2366 _ui->checkBox_octomap_show3dMap->setChecked(settings.value(
"octomap_3dmap",
_ui->checkBox_octomap_show3dMap->isChecked()).toBool());
2367 _ui->comboBox_octomap_renderingType->setCurrentIndex(settings.value(
"octomap_rendering_type",
_ui->comboBox_octomap_renderingType->currentIndex()).toInt());
2368 _ui->spinBox_octomap_pointSize->setValue(settings.value(
"octomap_point_size",
_ui->spinBox_octomap_pointSize->value()).toInt());
2370 _ui->groupBox_organized->setChecked(settings.value(
"meshing",
_ui->groupBox_organized->isChecked()).toBool());
2371 _ui->doubleSpinBox_mesh_angleTolerance->setValue(settings.value(
"meshing_angle",
_ui->doubleSpinBox_mesh_angleTolerance->value()).toDouble());
2372 _ui->checkBox_mesh_quad->setChecked(settings.value(
"meshing_quad",
_ui->checkBox_mesh_quad->isChecked()).toBool());
2373 _ui->checkBox_mesh_texture->setChecked(settings.value(
"meshing_texture",
_ui->checkBox_mesh_texture->isChecked()).toBool());
2374 _ui->spinBox_mesh_triangleSize->setValue(settings.value(
"meshing_triangle_size",
_ui->spinBox_mesh_triangleSize->value()).toInt());
2376 settings.endGroup();
2378 settings.endGroup();
2384 if(!filePath.isEmpty())
2388 QSettings settings(path, QSettings::IniFormat);
2390 settings.beginGroup(
"Camera");
2391 _ui->general_doubleSpinBox_imgRate->setValue(settings.value(
"imgRate",
_ui->general_doubleSpinBox_imgRate->value()).toDouble());
2392 _ui->source_mirroring->setChecked(settings.value(
"mirroring",
_ui->source_mirroring->isChecked()).toBool());
2393 _ui->lineEdit_calibrationFile->setText(settings.value(
"calibrationName",
_ui->lineEdit_calibrationFile->text()).toString());
2394 _ui->comboBox_sourceType->setCurrentIndex(settings.value(
"type",
_ui->comboBox_sourceType->currentIndex()).toInt());
2395 _ui->lineEdit_sourceDevice->setText(settings.value(
"device",
_ui->lineEdit_sourceDevice->text()).toString());
2396 _ui->lineEdit_sourceLocalTransform->setText(settings.value(
"localTransform",
_ui->lineEdit_sourceLocalTransform->text()).toString());
2397 _ui->spinBox_source_imageDecimation->setValue(settings.value(
"imageDecimation",
_ui->spinBox_source_imageDecimation->value()).toInt());
2399 if(
_ui->lineEdit_sourceLocalTransform->text().compare(
"0 0 1 -1 0 0 0 -1 0") == 0)
2401 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());
2402 _ui->lineEdit_sourceLocalTransform->setText(
"0 0 0 0 0 0");
2405 settings.beginGroup(
"rgbd");
2406 _ui->comboBox_cameraRGBD->setCurrentIndex(settings.value(
"driver",
_ui->comboBox_cameraRGBD->currentIndex()).toInt());
2407 _ui->checkbox_rgbd_colorOnly->setChecked(settings.value(
"rgbdColorOnly",
_ui->checkbox_rgbd_colorOnly->isChecked()).toBool());
2408 _ui->lineEdit_source_distortionModel->setText(settings.value(
"distortion_model",
_ui->lineEdit_source_distortionModel->text()).toString());
2409 _ui->groupBox_bilateral->setChecked(settings.value(
"bilateral",
_ui->groupBox_bilateral->isChecked()).toBool());
2410 _ui->doubleSpinBox_bilateral_sigmaS->setValue(settings.value(
"bilateral_sigma_s",
_ui->doubleSpinBox_bilateral_sigmaS->value()).toDouble());
2411 _ui->doubleSpinBox_bilateral_sigmaR->setValue(settings.value(
"bilateral_sigma_r",
_ui->doubleSpinBox_bilateral_sigmaR->value()).toDouble());
2412 settings.endGroup();
2414 settings.beginGroup(
"stereo");
2415 _ui->comboBox_cameraStereo->setCurrentIndex(settings.value(
"driver",
_ui->comboBox_cameraStereo->currentIndex()).toInt());
2416 _ui->checkbox_stereo_depthGenerated->setChecked(settings.value(
"depthGenerated",
_ui->checkbox_stereo_depthGenerated->isChecked()).toBool());
2417 _ui->checkBox_stereo_exposureCompensation->setChecked(settings.value(
"exposureCompensation",
_ui->checkBox_stereo_exposureCompensation->isChecked()).toBool());
2418 settings.endGroup();
2420 settings.beginGroup(
"rgb");
2421 _ui->source_comboBox_image_type->setCurrentIndex(settings.value(
"driver",
_ui->source_comboBox_image_type->currentIndex()).toInt());
2422 _ui->checkBox_rgb_rectify->setChecked(settings.value(
"rectify",
_ui->checkBox_rgb_rectify->isChecked()).toBool());
2423 settings.endGroup();
2425 settings.beginGroup(
"Openni");
2426 _ui->lineEdit_openniOniPath->setText(settings.value(
"oniPath",
_ui->lineEdit_openniOniPath->text()).toString());
2427 settings.endGroup();
2429 settings.beginGroup(
"Openni2");
2430 _ui->openni2_autoWhiteBalance->setChecked(settings.value(
"autoWhiteBalance",
_ui->openni2_autoWhiteBalance->isChecked()).toBool());
2431 _ui->openni2_autoExposure->setChecked(settings.value(
"autoExposure",
_ui->openni2_autoExposure->isChecked()).toBool());
2432 _ui->openni2_exposure->setValue(settings.value(
"exposure",
_ui->openni2_exposure->value()).toInt());
2433 _ui->openni2_gain->setValue(settings.value(
"gain",
_ui->openni2_gain->value()).toInt());
2434 _ui->openni2_mirroring->setChecked(settings.value(
"mirroring",
_ui->openni2_mirroring->isChecked()).toBool());
2435 _ui->openni2_stampsIdsUsed->setChecked(settings.value(
"stampsIdsUsed",
_ui->openni2_stampsIdsUsed->isChecked()).toBool());
2436 _ui->lineEdit_openni2OniPath->setText(settings.value(
"oniPath",
_ui->lineEdit_openni2OniPath->text()).toString());
2437 _ui->openni2_hshift->setValue(settings.value(
"hshift",
_ui->openni2_hshift->value()).toInt());
2438 _ui->openni2_vshift->setValue(settings.value(
"vshift",
_ui->openni2_vshift->value()).toInt());
2439 _ui->openni2_depth_decimation->setValue(settings.value(
"depthDecimation",
_ui->openni2_depth_decimation->value()).toInt());
2440 settings.endGroup();
2442 settings.beginGroup(
"Freenect2");
2443 _ui->comboBox_freenect2Format->setCurrentIndex(settings.value(
"format",
_ui->comboBox_freenect2Format->currentIndex()).toInt());
2444 _ui->doubleSpinBox_freenect2MinDepth->setValue(settings.value(
"minDepth",
_ui->doubleSpinBox_freenect2MinDepth->value()).toDouble());
2445 _ui->doubleSpinBox_freenect2MaxDepth->setValue(settings.value(
"maxDepth",
_ui->doubleSpinBox_freenect2MaxDepth->value()).toDouble());
2446 _ui->checkBox_freenect2BilateralFiltering->setChecked(settings.value(
"bilateralFiltering",
_ui->checkBox_freenect2BilateralFiltering->isChecked()).toBool());
2447 _ui->checkBox_freenect2EdgeAwareFiltering->setChecked(settings.value(
"edgeAwareFiltering",
_ui->checkBox_freenect2EdgeAwareFiltering->isChecked()).toBool());
2448 _ui->checkBox_freenect2NoiseFiltering->setChecked(settings.value(
"noiseFiltering",
_ui->checkBox_freenect2NoiseFiltering->isChecked()).toBool());
2449 _ui->lineEdit_freenect2Pipeline->setText(settings.value(
"pipeline",
_ui->lineEdit_freenect2Pipeline->text()).toString());
2450 settings.endGroup();
2452 settings.beginGroup(
"K4W2");
2453 _ui->comboBox_k4w2Format->setCurrentIndex(settings.value(
"format",
_ui->comboBox_k4w2Format->currentIndex()).toInt());
2454 settings.endGroup();
2456 settings.beginGroup(
"K4A");
2457 _ui->comboBox_k4a_rgb_resolution->setCurrentIndex(settings.value(
"rgb_resolution",
_ui->comboBox_k4a_rgb_resolution->currentIndex()).toInt());
2458 _ui->comboBox_k4a_framerate->setCurrentIndex(settings.value(
"framerate",
_ui->comboBox_k4a_framerate->currentIndex()).toInt());
2459 _ui->comboBox_k4a_depth_resolution->setCurrentIndex(settings.value(
"depth_resolution",
_ui->comboBox_k4a_depth_resolution->currentIndex()).toInt());
2460 _ui->checkbox_k4a_irDepth->setChecked(settings.value(
"ir",
_ui->checkbox_k4a_irDepth->isChecked()).toBool());
2461 _ui->lineEdit_k4a_mkv->setText(settings.value(
"mkvPath",
_ui->lineEdit_k4a_mkv->text()).toString());
2462 _ui->source_checkBox_useMKVStamps->setChecked(settings.value(
"useMkvStamps",
_ui->source_checkBox_useMKVStamps->isChecked()).toBool());
2463 settings.endGroup();
2465 settings.beginGroup(
"RealSense");
2466 _ui->comboBox_realsensePresetRGB->setCurrentIndex(settings.value(
"presetRGB",
_ui->comboBox_realsensePresetRGB->currentIndex()).toInt());
2467 _ui->comboBox_realsensePresetDepth->setCurrentIndex(settings.value(
"presetDepth",
_ui->comboBox_realsensePresetDepth->currentIndex()).toInt());
2468 _ui->checkbox_realsenseOdom->setChecked(settings.value(
"odom",
_ui->checkbox_realsenseOdom->isChecked()).toBool());
2469 _ui->checkbox_realsenseDepthScaledToRGBSize->setChecked(settings.value(
"depthScaled",
_ui->checkbox_realsenseDepthScaledToRGBSize->isChecked()).toBool());
2470 _ui->comboBox_realsenseRGBSource->setCurrentIndex(settings.value(
"rgbSource",
_ui->comboBox_realsenseRGBSource->currentIndex()).toInt());
2471 settings.endGroup();
2473 settings.beginGroup(
"RealSense2");
2474 _ui->checkbox_rs2_emitter->setChecked(settings.value(
"emitter",
_ui->checkbox_rs2_emitter->isChecked()).toBool());
2475 _ui->checkbox_rs2_irMode->setChecked(settings.value(
"ir",
_ui->checkbox_rs2_irMode->isChecked()).toBool());
2476 _ui->checkbox_rs2_irDepth->setChecked(settings.value(
"irdepth",
_ui->checkbox_rs2_irDepth->isChecked()).toBool());
2477 _ui->spinBox_rs2_width->setValue(settings.value(
"width",
_ui->spinBox_rs2_width->value()).toInt());
2478 _ui->spinBox_rs2_height->setValue(settings.value(
"height",
_ui->spinBox_rs2_height->value()).toInt());
2479 _ui->spinBox_rs2_rate->setValue(settings.value(
"rate",
_ui->spinBox_rs2_rate->value()).toInt());
2480 _ui->spinBox_rs2_width_depth->setValue(settings.value(
"width_depth",
_ui->spinBox_rs2_width_depth->value()).toInt());
2481 _ui->spinBox_rs2_height_depth->setValue(settings.value(
"height_depth",
_ui->spinBox_rs2_height_depth->value()).toInt());
2482 _ui->spinBox_rs2_rate_depth->setValue(settings.value(
"rate_depth",
_ui->spinBox_rs2_rate_depth->value()).toInt());
2483 _ui->checkbox_rs2_globalTimeStync->setChecked(settings.value(
"global_time_sync",
_ui->checkbox_rs2_globalTimeStync->isChecked()).toBool());
2484 _ui->lineEdit_rs2_jsonFile->setText(settings.value(
"json_preset",
_ui->lineEdit_rs2_jsonFile->text()).toString());
2485 settings.endGroup();
2487 settings.beginGroup(
"RGBDImages");
2488 _ui->lineEdit_cameraRGBDImages_path_rgb->setText(settings.value(
"path_rgb",
_ui->lineEdit_cameraRGBDImages_path_rgb->text()).toString());
2489 _ui->lineEdit_cameraRGBDImages_path_depth->setText(settings.value(
"path_depth",
_ui->lineEdit_cameraRGBDImages_path_depth->text()).toString());
2490 _ui->doubleSpinBox_cameraRGBDImages_scale->setValue(settings.value(
"scale",
_ui->doubleSpinBox_cameraRGBDImages_scale->value()).toDouble());
2491 _ui->spinBox_cameraRGBDImages_startIndex->setValue(settings.value(
"start_index",
_ui->spinBox_cameraRGBDImages_startIndex->value()).toInt());
2492 _ui->spinBox_cameraRGBDImages_maxFrames->setValue(settings.value(
"max_frames",
_ui->spinBox_cameraRGBDImages_maxFrames->value()).toInt());
2493 settings.endGroup();
2495 settings.beginGroup(
"StereoImages");
2496 _ui->lineEdit_cameraStereoImages_path_left->setText(settings.value(
"path_left",
_ui->lineEdit_cameraStereoImages_path_left->text()).toString());
2497 _ui->lineEdit_cameraStereoImages_path_right->setText(settings.value(
"path_right",
_ui->lineEdit_cameraStereoImages_path_right->text()).toString());
2498 _ui->checkBox_stereo_rectify->setChecked(settings.value(
"rectify",
_ui->checkBox_stereo_rectify->isChecked()).toBool());
2499 _ui->spinBox_cameraStereoImages_startIndex->setValue(settings.value(
"start_index",
_ui->spinBox_cameraStereoImages_startIndex->value()).toInt());
2500 _ui->spinBox_cameraStereoImages_maxFrames->setValue(settings.value(
"max_frames",
_ui->spinBox_cameraStereoImages_maxFrames->value()).toInt());
2501 settings.endGroup();
2503 settings.beginGroup(
"StereoVideo");
2504 _ui->lineEdit_cameraStereoVideo_path->setText(settings.value(
"path",
_ui->lineEdit_cameraStereoVideo_path->text()).toString());
2505 _ui->lineEdit_cameraStereoVideo_path_2->setText(settings.value(
"path2",
_ui->lineEdit_cameraStereoVideo_path_2->text()).toString());
2506 _ui->spinBox_stereo_right_device->setValue(settings.value(
"device2",
_ui->spinBox_stereo_right_device->value()).toInt());
2507 _ui->spinBox_stereousbcam_streamWidth->setValue(settings.value(
"width",
_ui->spinBox_stereousbcam_streamWidth->value()).toInt());
2508 _ui->spinBox_stereousbcam_streamHeight->setValue(settings.value(
"height",
_ui->spinBox_stereousbcam_streamHeight->value()).toInt());
2509 settings.endGroup();
2511 settings.beginGroup(
"StereoZed");
2512 _ui->comboBox_stereoZed_resolution->setCurrentIndex(settings.value(
"resolution",
_ui->comboBox_stereoZed_resolution->currentIndex()).toInt());
2513 _ui->comboBox_stereoZed_quality->setCurrentIndex(settings.value(
"quality",
_ui->comboBox_stereoZed_quality->currentIndex()).toInt());
2514 _ui->checkbox_stereoZed_selfCalibration->setChecked(settings.value(
"self_calibration",
_ui->checkbox_stereoZed_selfCalibration->isChecked()).toBool());
2515 _ui->comboBox_stereoZed_sensingMode->setCurrentIndex(settings.value(
"sensing_mode",
_ui->comboBox_stereoZed_sensingMode->currentIndex()).toInt());
2516 _ui->spinBox_stereoZed_confidenceThr->setValue(settings.value(
"confidence_thr",
_ui->spinBox_stereoZed_confidenceThr->value()).toInt());
2517 _ui->spinBox_stereoZed_texturenessConfidenceThr->setValue(settings.value(
"textureness_confidence_thr",
_ui->spinBox_stereoZed_texturenessConfidenceThr->value()).toInt());
2518 _ui->lineEdit_zedSvoPath->setText(settings.value(
"svo_path",
_ui->lineEdit_zedSvoPath->text()).toString());
2519 settings.endGroup();
2521 settings.beginGroup(
"MyntEye");
2522 _ui->checkbox_stereoMyntEye_rectify->setChecked(settings.value(
"rectify",
_ui->checkbox_stereoMyntEye_rectify->isChecked()).toBool());
2523 _ui->checkbox_stereoMyntEye_depth->setChecked(settings.value(
"depth",
_ui->checkbox_stereoMyntEye_depth->isChecked()).toBool());
2524 _ui->checkbox_stereoMyntEye_autoExposure->setChecked(settings.value(
"auto_exposure",
_ui->checkbox_stereoMyntEye_autoExposure->isChecked()).toBool());
2525 _ui->spinBox_stereoMyntEye_gain->setValue(settings.value(
"gain",
_ui->spinBox_stereoMyntEye_gain->value()).toInt());
2526 _ui->spinBox_stereoMyntEye_brightness->setValue(settings.value(
"brightness",
_ui->spinBox_stereoMyntEye_brightness->value()).toInt());
2527 _ui->spinBox_stereoMyntEye_contrast->setValue(settings.value(
"contrast",
_ui->spinBox_stereoMyntEye_contrast->value()).toInt());
2528 _ui->spinBox_stereoMyntEye_irControl->setValue(settings.value(
"ir_control",
_ui->spinBox_stereoMyntEye_irControl->value()).toInt());
2529 settings.endGroup();
2531 settings.beginGroup(
"DepthAI");
2532 _ui->comboBox_depthai_resolution->setCurrentIndex(settings.value(
"resolution",
_ui->comboBox_depthai_resolution->currentIndex()).toInt());
2533 _ui->checkBox_depthai_depth->setChecked(settings.value(
"depth",
_ui->checkBox_depthai_depth->isChecked()).toBool());
2534 _ui->spinBox_depthai_confidence->setValue(settings.value(
"confidence",
_ui->spinBox_depthai_confidence->value()).toInt());
2535 _ui->checkBox_depthai_imu_published->setChecked(settings.value(
"imu_published",
_ui->checkBox_depthai_imu_published->isChecked()).toBool());
2536 _ui->checkBox_depthai_imu_firmware_update->setChecked(settings.value(
"imu_firmware_update",
_ui->checkBox_depthai_imu_firmware_update->isChecked()).toBool());
2537 settings.endGroup();
2539 settings.beginGroup(
"Images");
2540 _ui->source_images_lineEdit_path->setText(settings.value(
"path",
_ui->source_images_lineEdit_path->text()).toString());
2541 _ui->source_images_spinBox_startPos->setValue(settings.value(
"startPos",
_ui->source_images_spinBox_startPos->value()).toInt());
2542 _ui->source_images_spinBox_maxFrames->setValue(settings.value(
"maxFrames",
_ui->source_images_spinBox_maxFrames->value()).toInt());
2543 _ui->comboBox_cameraImages_bayerMode->setCurrentIndex(settings.value(
"bayerMode",
_ui->comboBox_cameraImages_bayerMode->currentIndex()).toInt());
2545 _ui->checkBox_cameraImages_configForEachFrame->setChecked(settings.value(
"config_each_frame",
_ui->checkBox_cameraImages_configForEachFrame->isChecked()).toBool());
2546 _ui->checkBox_cameraImages_timestamps->setChecked(settings.value(
"filenames_as_stamps",
_ui->checkBox_cameraImages_timestamps->isChecked()).toBool());
2547 _ui->checkBox_cameraImages_syncTimeStamps->setChecked(settings.value(
"sync_stamps",
_ui->checkBox_cameraImages_syncTimeStamps->isChecked()).toBool());
2548 _ui->lineEdit_cameraImages_timestamps->setText(settings.value(
"stamps",
_ui->lineEdit_cameraImages_timestamps->text()).toString());
2549 _ui->lineEdit_cameraImages_path_scans->setText(settings.value(
"path_scans",
_ui->lineEdit_cameraImages_path_scans->text()).toString());
2550 _ui->lineEdit_cameraImages_laser_transform->setText(settings.value(
"scan_transform",
_ui->lineEdit_cameraImages_laser_transform->text()).toString());
2551 _ui->spinBox_cameraImages_max_scan_pts->setValue(settings.value(
"scan_max_pts",
_ui->spinBox_cameraImages_max_scan_pts->value()).toInt());
2552 _ui->lineEdit_cameraImages_odom->setText(settings.value(
"odom_path",
_ui->lineEdit_cameraImages_odom->text()).toString());
2553 _ui->comboBox_cameraImages_odomFormat->setCurrentIndex(settings.value(
"odom_format",
_ui->comboBox_cameraImages_odomFormat->currentIndex()).toInt());
2554 _ui->lineEdit_cameraImages_gt->setText(settings.value(
"gt_path",
_ui->lineEdit_cameraImages_gt->text()).toString());
2555 _ui->comboBox_cameraImages_gtFormat->setCurrentIndex(settings.value(
"gt_format",
_ui->comboBox_cameraImages_gtFormat->currentIndex()).toInt());
2556 _ui->doubleSpinBox_maxPoseTimeDiff->setValue(settings.value(
"max_pose_time_diff",
_ui->doubleSpinBox_maxPoseTimeDiff->value()).toDouble());
2558 _ui->lineEdit_cameraImages_path_imu->setText(settings.value(
"imu_path",
_ui->lineEdit_cameraImages_path_imu->text()).toString());
2559 _ui->lineEdit_cameraImages_imu_transform->setText(settings.value(
"imu_local_transform",
_ui->lineEdit_cameraImages_imu_transform->text()).toString());
2560 _ui->spinBox_cameraImages_max_imu_rate->setValue(settings.value(
"imu_rate",
_ui->spinBox_cameraImages_max_imu_rate->value()).toInt());
2561 settings.endGroup();
2563 settings.beginGroup(
"OdomSensor");
2564 _ui->comboBox_odom_sensor->setCurrentIndex(settings.value(
"odom_sensor",
_ui->comboBox_odom_sensor->currentIndex()).toInt());
2565 _ui->lineEdit_odom_sensor_extrinsics->setText(settings.value(
"odom_sensor_extrinsics",
_ui->lineEdit_odom_sensor_extrinsics->text()).toString());
2566 _ui->lineEdit_odom_sensor_path_calibration->setText(settings.value(
"odom_sensor_calibration_path",
_ui->lineEdit_odom_sensor_path_calibration->text()).toString());
2567 _ui->lineEdit_odomSourceDevice->setText(settings.value(
"odom_sensor_device",
_ui->lineEdit_odomSourceDevice->text()).toString());
2568 _ui->doubleSpinBox_odom_sensor_time_offset->setValue(settings.value(
"odom_sensor_offset_time",
_ui->doubleSpinBox_odom_sensor_time_offset->value()).toDouble());
2569 _ui->doubleSpinBox_odom_sensor_scale_factor->setValue(settings.value(
"odom_sensor_scale_factor",
_ui->doubleSpinBox_odom_sensor_scale_factor->value()).toDouble());
2570 _ui->checkBox_odom_sensor_use_as_gt->setChecked(settings.value(
"odom_sensor_odom_as_gt",
_ui->checkBox_odom_sensor_use_as_gt->isChecked()).toBool());
2571 settings.endGroup();
2573 settings.beginGroup(
"UsbCam");
2574 _ui->spinBox_usbcam_streamWidth->setValue(settings.value(
"width",
_ui->spinBox_usbcam_streamWidth->value()).toInt());
2575 _ui->spinBox_usbcam_streamHeight->setValue(settings.value(
"height",
_ui->spinBox_usbcam_streamHeight->value()).toInt());
2576 settings.endGroup();
2578 settings.beginGroup(
"Video");
2579 _ui->source_video_lineEdit_path->setText(settings.value(
"path",
_ui->source_video_lineEdit_path->text()).toString());
2580 settings.endGroup();
2582 settings.beginGroup(
"IMU");
2583 _ui->comboBox_imuFilter_strategy->setCurrentIndex(settings.value(
"strategy",
_ui->comboBox_imuFilter_strategy->currentIndex()).toInt());
2584 _ui->doubleSpinBox_imuFilterMadgwickGain->setValue(settings.value(
"madgwick_gain",
_ui->doubleSpinBox_imuFilterMadgwickGain->value()).toDouble());
2585 _ui->doubleSpinBox_imuFilterMadgwickZeta->setValue(settings.value(
"madgwick_zeta",
_ui->doubleSpinBox_imuFilterMadgwickZeta->value()).toDouble());
2586 _ui->doubleSpinBox_imuFilterComplementaryGainAcc->setValue(settings.value(
"complementary_gain_acc",
_ui->doubleSpinBox_imuFilterComplementaryGainAcc->value()).toDouble());
2587 _ui->doubleSpinBox_imuFilterComplementaryBiasAlpha->setValue(settings.value(
"complementary_bias_alpha",
_ui->doubleSpinBox_imuFilterComplementaryBiasAlpha->value()).toDouble());
2588 _ui->checkBox_imuFilterComplementaryDoAdaptiveGain->setChecked(settings.value(
"complementary_adaptive_gain",
_ui->checkBox_imuFilterComplementaryDoAdaptiveGain->isChecked()).toBool());
2589 _ui->checkBox_imuFilterComplementaryDoBiasEstimation->setChecked(settings.value(
"complementary_biais_estimation",
_ui->checkBox_imuFilterComplementaryDoBiasEstimation->isChecked()).toBool());
2590 _ui->checkBox_imuFilter_baseFrameConversion->setChecked(settings.value(
"base_frame_conversion",
_ui->checkBox_imuFilter_baseFrameConversion->isChecked()).toBool());
2591 _ui->checkbox_publishInterIMU->setChecked(settings.value(
"publish_inter_imu",
_ui->checkbox_publishInterIMU->isChecked()).toBool());
2592 settings.endGroup();
2594 settings.beginGroup(
"Scan");
2595 _ui->checkBox_source_scanFromDepth->setChecked(settings.value(
"fromDepth",
_ui->checkBox_source_scanFromDepth->isChecked()).toBool());
2596 _ui->spinBox_source_scanDownsampleStep->setValue(settings.value(
"downsampleStep",
_ui->spinBox_source_scanDownsampleStep->value()).toInt());
2597 _ui->doubleSpinBox_source_scanRangeMin->setValue(settings.value(
"rangeMin",
_ui->doubleSpinBox_source_scanRangeMin->value()).toDouble());
2598 _ui->doubleSpinBox_source_scanRangeMax->setValue(settings.value(
"rangeMax",
_ui->doubleSpinBox_source_scanRangeMax->value()).toDouble());
2599 _ui->doubleSpinBox_source_scanVoxelSize->setValue(settings.value(
"voxelSize",
_ui->doubleSpinBox_source_scanVoxelSize->value()).toDouble());
2600 _ui->spinBox_source_scanNormalsK->setValue(settings.value(
"normalsK",
_ui->spinBox_source_scanNormalsK->value()).toInt());
2601 _ui->doubleSpinBox_source_scanNormalsRadius->setValue(settings.value(
"normalsRadius",
_ui->doubleSpinBox_source_scanNormalsRadius->value()).toDouble());
2602 _ui->doubleSpinBox_source_scanNormalsForceGroundUp->setValue(settings.value(
"normalsUpF",
_ui->doubleSpinBox_source_scanNormalsForceGroundUp->value()).toDouble());
2603 settings.endGroup();
2605 settings.beginGroup(
"DepthFromScan");
2606 _ui->groupBox_depthFromScan->setChecked(settings.value(
"depthFromScan",
_ui->groupBox_depthFromScan->isChecked()).toBool());
2607 _ui->groupBox_depthFromScan_fillHoles->setChecked(settings.value(
"depthFromScanFillHoles",
_ui->groupBox_depthFromScan_fillHoles->isChecked()).toBool());
2608 _ui->radioButton_depthFromScan_vertical->setChecked(settings.value(
"depthFromScanVertical",
_ui->radioButton_depthFromScan_vertical->isChecked()).toBool());
2609 _ui->radioButton_depthFromScan_horizontal->setChecked(settings.value(
"depthFromScanHorizontal",
_ui->radioButton_depthFromScan_horizontal->isChecked()).toBool());
2610 _ui->checkBox_depthFromScan_fillBorders->setChecked(settings.value(
"depthFromScanFillBorders",
_ui->checkBox_depthFromScan_fillBorders->isChecked()).toBool());
2611 settings.endGroup();
2613 settings.beginGroup(
"Database");
2614 _ui->source_database_lineEdit_path->setText(settings.value(
"path",
_ui->source_database_lineEdit_path->text()).toString());
2615 _ui->source_checkBox_ignoreOdometry->setChecked(settings.value(
"ignoreOdometry",
_ui->source_checkBox_ignoreOdometry->isChecked()).toBool());
2616 _ui->source_checkBox_ignoreGoalDelay->setChecked(settings.value(
"ignoreGoalDelay",
_ui->source_checkBox_ignoreGoalDelay->isChecked()).toBool());
2617 _ui->source_checkBox_ignoreGoals->setChecked(settings.value(
"ignoreGoals",
_ui->source_checkBox_ignoreGoals->isChecked()).toBool());
2618 _ui->source_checkBox_ignoreLandmarks->setChecked(settings.value(
"ignoreLandmarks",
_ui->source_checkBox_ignoreLandmarks->isChecked()).toBool());
2619 _ui->source_checkBox_ignoreFeatures->setChecked(settings.value(
"ignoreFeatures",
_ui->source_checkBox_ignoreFeatures->isChecked()).toBool());
2620 _ui->source_spinBox_databaseStartId->setValue(settings.value(
"startId",
_ui->source_spinBox_databaseStartId->value()).toInt());
2621 _ui->source_spinBox_databaseStopId->setValue(settings.value(
"stopId",
_ui->source_spinBox_databaseStopId->value()).toInt());
2622 _ui->source_spinBox_database_cameraIndex->setValue(settings.value(
"cameraIndex",
_ui->source_spinBox_database_cameraIndex->value()).toInt());
2623 _ui->source_checkBox_useDbStamps->setChecked(settings.value(
"useDatabaseStamps",
_ui->source_checkBox_useDbStamps->isChecked()).toBool());
2624 settings.endGroup();
2626 settings.endGroup();
2640 if(!filePath.isEmpty())
2645 UDEBUG(
"%s", path.toStdString().c_str());
2647 if(!QFile::exists(path))
2649 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));
2655 for(rtabmap::ParametersMap::const_iterator iter = parameters.begin(); iter!=parameters.end(); ++iter)
2657 std::string value = iter->second;
2658 if(iter->first.compare(Parameters::kRtabmapWorkingDirectory()) == 0)
2662 UWARN(
"Reading config: Working directory is empty. Keeping old one (\"%s\").",
2672 UWARN(
"Reading config: Not existing working directory \"%s\". Keeping old one (\"%s\").",
2680 UWARN(
"Reading config: Not existing working directory \"%s\". Using default one (\"%s\").",
2682 defaultWorkingDir.c_str());
2683 value = defaultWorkingDir;
2689 if(iter->first.compare(Parameters::kIcpStrategy()) == 0)
2691 if(value.compare(
"true") == 0)
2695 else if(value.compare(
"false") == 0)
2705 if(parameters.find(Parameters::kRtabmapWorkingDirectory()) == parameters.end())
2709 QMessageBox::information(
this,
2710 tr(
"Working directory"),
2711 tr(
"RTAB-Map needs a working directory to put the database.\n\n" 2712 "By default, the directory \"%1\" is used.\n\n" 2713 "The working directory can be changed any time in the " 2725 QString path = QFileDialog::getSaveFileName(
this, tr(
"Save settings..."), this->
getWorkingDirectory()+QDir::separator()+
"config.ini",
"*.ini");
2738 int button = QMessageBox::warning(
this,
2739 tr(
"Reset settings..."),
2740 tr(
"This will reset all settings. Restore all settings to default without saving them first?"),
2741 QMessageBox::Cancel | QMessageBox::Yes | QMessageBox::Save,
2742 QMessageBox::Cancel);
2743 if(button == QMessageBox::Yes ||
2772 if (
_parameters.at(iter->first).compare(iter->second) != 0)
2774 bool different =
true;
2785 UINFO(
"modified %s = %s->%s", iter->first.c_str(),
_parameters.at(iter->first).c_str(), iter->second.c_str());
2798 if(!filePath.isEmpty())
2802 QSettings settings(path, QSettings::IniFormat);
2803 settings.beginGroup(
"Gui");
2805 settings.beginGroup(
"General");
2806 settings.remove(
"");
2807 settings.setValue(
"imagesKept",
_ui->general_checkBox_imagesKept->isChecked());
2808 settings.setValue(
"missingRepublished",
_ui->general_checkBox_missing_cache_republished->isChecked());
2809 settings.setValue(
"cloudsKept",
_ui->general_checkBox_cloudsKept->isChecked());
2810 settings.setValue(
"loggerLevel",
_ui->comboBox_loggerLevel->currentIndex());
2811 settings.setValue(
"loggerEventLevel",
_ui->comboBox_loggerEventLevel->currentIndex());
2812 settings.setValue(
"loggerPauseLevel",
_ui->comboBox_loggerPauseLevel->currentIndex());
2813 settings.setValue(
"loggerType",
_ui->comboBox_loggerType->currentIndex());
2814 settings.setValue(
"loggerPrintTime",
_ui->checkBox_logger_printTime->isChecked());
2815 settings.setValue(
"loggerPrintThreadId",
_ui->checkBox_logger_printThreadId->isChecked());
2816 settings.setValue(
"verticalLayoutUsed",
_ui->checkBox_verticalLayoutUsed->isChecked());
2817 settings.setValue(
"imageRejectedShown",
_ui->checkBox_imageRejectedShown->isChecked());
2818 settings.setValue(
"imageHighestHypShown",
_ui->checkBox_imageHighestHypShown->isChecked());
2819 settings.setValue(
"beep",
_ui->checkBox_beep->isChecked());
2820 settings.setValue(
"figure_time",
_ui->checkBox_stamps->isChecked());
2821 settings.setValue(
"figure_cache",
_ui->checkBox_cacheStatistics->isChecked());
2822 settings.setValue(
"notifyNewGlobalPath",
_ui->checkBox_notifyWhenNewGlobalPathIsReceived->isChecked());
2823 settings.setValue(
"odomQualityThr",
_ui->spinBox_odomQualityWarnThr->value());
2824 settings.setValue(
"odomOnlyInliersShown",
_ui->checkBox_odom_onlyInliersShown->isChecked());
2825 settings.setValue(
"posteriorGraphView",
_ui->radioButton_posteriorGraphView->isChecked());
2826 settings.setValue(
"wordsGraphView",
_ui->radioButton_wordsGraphView->isChecked());
2827 settings.setValue(
"localizationsGraphView",
_ui->radioButton_localizationsGraphView->isChecked());
2828 settings.setValue(
"localizationsGraphViewOdomCache",
_ui->radioButton_localizationsGraphViewOdomCache->isChecked());
2829 settings.setValue(
"nochangeGraphView",
_ui->radioButton_nochangeGraphView->isChecked());
2830 settings.setValue(
"odomDisabled",
_ui->checkbox_odomDisabled->isChecked());
2831 settings.setValue(
"odomRegistration",
_ui->odom_registration->currentIndex());
2832 settings.setValue(
"odomF2MGravitySigma",
_ui->odom_f2m_gravitySigma->value());
2833 settings.setValue(
"gtAlign",
_ui->checkbox_groundTruthAlign->isChecked());
2835 for(
int i=0; i<2; ++i)
2860 settings.setValue(
"cloudVoxel",
_ui->doubleSpinBox_voxel->value());
2861 settings.setValue(
"cloudNoiseRadius",
_ui->doubleSpinBox_noiseRadius->value());
2862 settings.setValue(
"cloudNoiseMinNeighbors",
_ui->spinBox_noiseMinNeighbors->value());
2863 settings.setValue(
"cloudCeilingHeight",
_ui->doubleSpinBox_ceilingFilterHeight->value());
2864 settings.setValue(
"cloudFloorHeight",
_ui->doubleSpinBox_floorFilterHeight->value());
2865 settings.setValue(
"normalKSearch",
_ui->spinBox_normalKSearch->value());
2866 settings.setValue(
"normalRadiusSearch",
_ui->doubleSpinBox_normalRadiusSearch->value());
2867 settings.setValue(
"scanCeilingHeight",
_ui->doubleSpinBox_ceilingFilterHeight_scan->value());
2868 settings.setValue(
"scanFloorHeight",
_ui->doubleSpinBox_floorFilterHeight_scan->value());
2869 settings.setValue(
"scanNormalKSearch",
_ui->spinBox_normalKSearch_scan->value());
2870 settings.setValue(
"scanNormalRadiusSearch",
_ui->doubleSpinBox_normalRadiusSearch_scan->value());
2872 settings.setValue(
"showGraphs",
_ui->checkBox_showGraphs->isChecked());
2873 settings.setValue(
"showLabels",
_ui->checkBox_showLabels->isChecked());
2874 settings.setValue(
"showFrames",
_ui->checkBox_showFrames->isChecked());
2875 settings.setValue(
"showLandmarks",
_ui->checkBox_showLandmarks->isChecked());
2876 settings.setValue(
"landmarkSize",
_ui->doubleSpinBox_landmarkSize->value());
2877 settings.setValue(
"showIMUGravity",
_ui->checkBox_showIMUGravity->isChecked());
2878 settings.setValue(
"showIMUAcc",
_ui->checkBox_showIMUAcc->isChecked());
2881 settings.setValue(
"noFiltering",
_ui->radioButton_noFiltering->isChecked());
2882 settings.setValue(
"cloudFiltering",
_ui->radioButton_nodeFiltering->isChecked());
2883 settings.setValue(
"cloudFilteringRadius",
_ui->doubleSpinBox_cloudFilterRadius->value());
2884 settings.setValue(
"cloudFilteringAngle",
_ui->doubleSpinBox_cloudFilterAngle->value());
2885 settings.setValue(
"subtractFiltering",
_ui->radioButton_subtractFiltering->isChecked());
2886 settings.setValue(
"subtractFilteringMinPts",
_ui->spinBox_subtractFilteringMinPts->value());
2887 settings.setValue(
"subtractFilteringRadius",
_ui->doubleSpinBox_subtractFilteringRadius->value());
2888 settings.setValue(
"subtractFilteringAngle",
_ui->doubleSpinBox_subtractFilteringAngle->value());
2890 settings.setValue(
"gridMapShown",
_ui->checkBox_map_shown->isChecked());
2891 settings.setValue(
"gridMapOpacity",
_ui->doubleSpinBox_map_opacity->value());
2893 settings.setValue(
"octomap",
_ui->groupBox_octomap->isChecked());
2894 settings.setValue(
"octomap_depth",
_ui->spinBox_octomap_treeDepth->value());
2895 settings.setValue(
"octomap_2dgrid",
_ui->checkBox_octomap_2dgrid->isChecked());
2896 settings.setValue(
"octomap_3dmap",
_ui->checkBox_octomap_show3dMap->isChecked());
2897 settings.setValue(
"octomap_rendering_type",
_ui->comboBox_octomap_renderingType->currentIndex());
2898 settings.setValue(
"octomap_point_size",
_ui->spinBox_octomap_pointSize->value());
2901 settings.setValue(
"meshing",
_ui->groupBox_organized->isChecked());
2902 settings.setValue(
"meshing_angle",
_ui->doubleSpinBox_mesh_angleTolerance->value());
2903 settings.setValue(
"meshing_quad",
_ui->checkBox_mesh_quad->isChecked());
2904 settings.setValue(
"meshing_texture",
_ui->checkBox_mesh_texture->isChecked());
2905 settings.setValue(
"meshing_triangle_size",
_ui->spinBox_mesh_triangleSize->value());
2907 settings.endGroup();
2909 settings.endGroup();
2915 if(!filePath.isEmpty())
2919 QSettings settings(path, QSettings::IniFormat);
2921 settings.beginGroup(
"Camera");
2922 settings.remove(
"");
2923 settings.setValue(
"imgRate",
_ui->general_doubleSpinBox_imgRate->value());
2924 settings.setValue(
"mirroring",
_ui->source_mirroring->isChecked());
2925 settings.setValue(
"calibrationName",
_ui->lineEdit_calibrationFile->text());
2926 settings.setValue(
"type",
_ui->comboBox_sourceType->currentIndex());
2927 settings.setValue(
"device",
_ui->lineEdit_sourceDevice->text());
2928 settings.setValue(
"localTransform",
_ui->lineEdit_sourceLocalTransform->text());
2929 settings.setValue(
"imageDecimation",
_ui->spinBox_source_imageDecimation->value());
2931 settings.beginGroup(
"rgbd");
2932 settings.setValue(
"driver",
_ui->comboBox_cameraRGBD->currentIndex());
2933 settings.setValue(
"rgbdColorOnly",
_ui->checkbox_rgbd_colorOnly->isChecked());
2934 settings.setValue(
"distortion_model",
_ui->lineEdit_source_distortionModel->text());
2935 settings.setValue(
"bilateral",
_ui->groupBox_bilateral->isChecked());
2936 settings.setValue(
"bilateral_sigma_s",
_ui->doubleSpinBox_bilateral_sigmaS->value());
2937 settings.setValue(
"bilateral_sigma_r",
_ui->doubleSpinBox_bilateral_sigmaR->value());
2938 settings.endGroup();
2940 settings.beginGroup(
"stereo");
2941 settings.setValue(
"driver",
_ui->comboBox_cameraStereo->currentIndex());
2942 settings.setValue(
"depthGenerated",
_ui->checkbox_stereo_depthGenerated->isChecked());
2943 settings.setValue(
"exposureCompensation",
_ui->checkBox_stereo_exposureCompensation->isChecked());
2944 settings.endGroup();
2946 settings.beginGroup(
"rgb");
2947 settings.setValue(
"driver",
_ui->source_comboBox_image_type->currentIndex());
2948 settings.setValue(
"rectify",
_ui->checkBox_rgb_rectify->isChecked());
2949 settings.endGroup();
2951 settings.beginGroup(
"Openni");
2952 settings.setValue(
"oniPath",
_ui->lineEdit_openniOniPath->text());
2953 settings.endGroup();
2955 settings.beginGroup(
"Openni2");
2956 settings.setValue(
"autoWhiteBalance",
_ui->openni2_autoWhiteBalance->isChecked());
2957 settings.setValue(
"autoExposure",
_ui->openni2_autoExposure->isChecked());
2958 settings.setValue(
"exposure",
_ui->openni2_exposure->value());
2959 settings.setValue(
"gain",
_ui->openni2_gain->value());
2960 settings.setValue(
"mirroring",
_ui->openni2_mirroring->isChecked());
2961 settings.setValue(
"stampsIdsUsed",
_ui->openni2_stampsIdsUsed->isChecked());
2962 settings.setValue(
"oniPath",
_ui->lineEdit_openni2OniPath->text());
2963 settings.setValue(
"hshift",
_ui->openni2_hshift->value());
2964 settings.setValue(
"vshift",
_ui->openni2_vshift->value());
2965 settings.setValue(
"depthDecimation",
_ui->openni2_depth_decimation->value());
2966 settings.endGroup();
2968 settings.beginGroup(
"Freenect2");
2969 settings.setValue(
"format",
_ui->comboBox_freenect2Format->currentIndex());
2970 settings.setValue(
"minDepth",
_ui->doubleSpinBox_freenect2MinDepth->value());
2971 settings.setValue(
"maxDepth",
_ui->doubleSpinBox_freenect2MaxDepth->value());
2972 settings.setValue(
"bilateralFiltering",
_ui->checkBox_freenect2BilateralFiltering->isChecked());
2973 settings.setValue(
"edgeAwareFiltering",
_ui->checkBox_freenect2EdgeAwareFiltering->isChecked());
2974 settings.setValue(
"noiseFiltering",
_ui->checkBox_freenect2NoiseFiltering->isChecked());
2975 settings.setValue(
"pipeline",
_ui->lineEdit_freenect2Pipeline->text());
2976 settings.endGroup();
2978 settings.beginGroup(
"K4W2");
2979 settings.setValue(
"format",
_ui->comboBox_k4w2Format->currentIndex());
2980 settings.endGroup();
2982 settings.beginGroup(
"K4A");
2983 settings.setValue(
"rgb_resolution",
_ui->comboBox_k4a_rgb_resolution->currentIndex());
2984 settings.setValue(
"framerate",
_ui->comboBox_k4a_framerate->currentIndex());
2985 settings.setValue(
"depth_resolution",
_ui->comboBox_k4a_depth_resolution->currentIndex());
2986 settings.setValue(
"ir",
_ui->checkbox_k4a_irDepth->isChecked());
2987 settings.setValue(
"mkvPath",
_ui->lineEdit_k4a_mkv->text());
2988 settings.setValue(
"useMkvStamps",
_ui->source_checkBox_useMKVStamps->isChecked());
2989 settings.endGroup();
2991 settings.beginGroup(
"RealSense");
2992 settings.setValue(
"presetRGB",
_ui->comboBox_realsensePresetRGB->currentIndex());
2993 settings.setValue(
"presetDepth",
_ui->comboBox_realsensePresetDepth->currentIndex());
2994 settings.setValue(
"odom",
_ui->checkbox_realsenseOdom->isChecked());
2995 settings.setValue(
"depthScaled",
_ui->checkbox_realsenseDepthScaledToRGBSize->isChecked());
2996 settings.setValue(
"rgbSource",
_ui->comboBox_realsenseRGBSource->currentIndex());
2997 settings.endGroup();
2999 settings.beginGroup(
"RealSense2");
3000 settings.setValue(
"emitter",
_ui->checkbox_rs2_emitter->isChecked());
3001 settings.setValue(
"ir",
_ui->checkbox_rs2_irMode->isChecked());
3002 settings.setValue(
"irdepth",
_ui->checkbox_rs2_irDepth->isChecked());
3003 settings.setValue(
"width",
_ui->spinBox_rs2_width->value());
3004 settings.setValue(
"height",
_ui->spinBox_rs2_height->value());
3005 settings.setValue(
"rate",
_ui->spinBox_rs2_rate->value());
3006 settings.setValue(
"width_depth",
_ui->spinBox_rs2_width_depth->value());
3007 settings.setValue(
"height_depth",
_ui->spinBox_rs2_height_depth->value());
3008 settings.setValue(
"rate_depth",
_ui->spinBox_rs2_rate_depth->value());
3009 settings.setValue(
"global_time_sync",
_ui->checkbox_rs2_globalTimeStync->isChecked());
3010 settings.setValue(
"json_preset",
_ui->lineEdit_rs2_jsonFile->text());
3011 settings.endGroup();
3013 settings.beginGroup(
"RGBDImages");
3014 settings.setValue(
"path_rgb",
_ui->lineEdit_cameraRGBDImages_path_rgb->text());
3015 settings.setValue(
"path_depth",
_ui->lineEdit_cameraRGBDImages_path_depth->text());
3016 settings.setValue(
"scale",
_ui->doubleSpinBox_cameraRGBDImages_scale->value());
3017 settings.setValue(
"start_index",
_ui->spinBox_cameraRGBDImages_startIndex->value());
3018 settings.setValue(
"max_frames",
_ui->spinBox_cameraRGBDImages_maxFrames->value());
3019 settings.endGroup();
3021 settings.beginGroup(
"StereoImages");
3022 settings.setValue(
"path_left",
_ui->lineEdit_cameraStereoImages_path_left->text());
3023 settings.setValue(
"path_right",
_ui->lineEdit_cameraStereoImages_path_right->text());
3024 settings.setValue(
"rectify",
_ui->checkBox_stereo_rectify->isChecked());
3025 settings.setValue(
"start_index",
_ui->spinBox_cameraStereoImages_startIndex->value());
3026 settings.setValue(
"max_frames",
_ui->spinBox_cameraStereoImages_maxFrames->value());
3027 settings.endGroup();
3029 settings.beginGroup(
"StereoVideo");
3030 settings.setValue(
"path",
_ui->lineEdit_cameraStereoVideo_path->text());
3031 settings.setValue(
"path2",
_ui->lineEdit_cameraStereoVideo_path_2->text());
3032 settings.setValue(
"device2",
_ui->spinBox_stereo_right_device->value());
3033 settings.setValue(
"width",
_ui->spinBox_stereousbcam_streamWidth->value());
3034 settings.setValue(
"height",
_ui->spinBox_stereousbcam_streamHeight->value());
3035 settings.endGroup();
3037 settings.beginGroup(
"StereoZed");
3038 settings.setValue(
"resolution",
_ui->comboBox_stereoZed_resolution->currentIndex());
3039 settings.setValue(
"quality",
_ui->comboBox_stereoZed_quality->currentIndex());
3040 settings.setValue(
"self_calibration",
_ui->checkbox_stereoZed_selfCalibration->isChecked());
3041 settings.setValue(
"sensing_mode",
_ui->comboBox_stereoZed_sensingMode->currentIndex());
3042 settings.setValue(
"confidence_thr",
_ui->spinBox_stereoZed_confidenceThr->value());
3043 settings.setValue(
"textureness_confidence_thr",
_ui->spinBox_stereoZed_texturenessConfidenceThr->value());
3044 settings.setValue(
"svo_path",
_ui->lineEdit_zedSvoPath->text());
3045 settings.endGroup();
3047 settings.beginGroup(
"MyntEye");
3048 settings.setValue(
"rectify",
_ui->checkbox_stereoMyntEye_rectify->isChecked());
3049 settings.setValue(
"depth",
_ui->checkbox_stereoMyntEye_depth->isChecked());
3050 settings.setValue(
"auto_exposure",
_ui->checkbox_stereoMyntEye_autoExposure->isChecked());
3051 settings.setValue(
"gain",
_ui->spinBox_stereoMyntEye_gain->value());
3052 settings.setValue(
"brightness",
_ui->spinBox_stereoMyntEye_brightness->value());
3053 settings.setValue(
"contrast",
_ui->spinBox_stereoMyntEye_contrast->value());
3054 settings.setValue(
"ir_control",
_ui->spinBox_stereoMyntEye_irControl->value());
3055 settings.endGroup();
3057 settings.beginGroup(
"DepthAI");
3058 settings.setValue(
"resolution",
_ui->comboBox_depthai_resolution->currentIndex());
3059 settings.setValue(
"depth",
_ui->checkBox_depthai_depth->isChecked());
3060 settings.setValue(
"confidence",
_ui->spinBox_depthai_confidence->value());
3061 settings.setValue(
"imu_published",
_ui->checkBox_depthai_imu_published->isChecked());
3062 settings.setValue(
"imu_firmware_update",
_ui->checkBox_depthai_imu_firmware_update->isChecked());
3063 settings.endGroup();
3065 settings.beginGroup(
"Images");
3066 settings.setValue(
"path",
_ui->source_images_lineEdit_path->text());
3067 settings.setValue(
"startPos",
_ui->source_images_spinBox_startPos->value());
3068 settings.setValue(
"maxFrames",
_ui->source_images_spinBox_maxFrames->value());
3069 settings.setValue(
"bayerMode",
_ui->comboBox_cameraImages_bayerMode->currentIndex());
3070 settings.setValue(
"config_each_frame",
_ui->checkBox_cameraImages_configForEachFrame->isChecked());
3071 settings.setValue(
"filenames_as_stamps",
_ui->checkBox_cameraImages_timestamps->isChecked());
3072 settings.setValue(
"sync_stamps",
_ui->checkBox_cameraImages_syncTimeStamps->isChecked());
3073 settings.setValue(
"stamps",
_ui->lineEdit_cameraImages_timestamps->text());
3074 settings.setValue(
"path_scans",
_ui->lineEdit_cameraImages_path_scans->text());
3075 settings.setValue(
"scan_transform",
_ui->lineEdit_cameraImages_laser_transform->text());
3076 settings.setValue(
"scan_max_pts",
_ui->spinBox_cameraImages_max_scan_pts->value());
3077 settings.setValue(
"odom_path",
_ui->lineEdit_cameraImages_odom->text());
3078 settings.setValue(
"odom_format",
_ui->comboBox_cameraImages_odomFormat->currentIndex());
3079 settings.setValue(
"gt_path",
_ui->lineEdit_cameraImages_gt->text());
3080 settings.setValue(
"gt_format",
_ui->comboBox_cameraImages_gtFormat->currentIndex());
3081 settings.setValue(
"max_pose_time_diff",
_ui->doubleSpinBox_maxPoseTimeDiff->value());
3082 settings.setValue(
"imu_path",
_ui->lineEdit_cameraImages_path_imu->text());
3083 settings.setValue(
"imu_local_transform",
_ui->lineEdit_cameraImages_imu_transform->text());
3084 settings.setValue(
"imu_rate",
_ui->spinBox_cameraImages_max_imu_rate->value());
3085 settings.endGroup();
3087 settings.beginGroup(
"OdomSensor");
3088 settings.setValue(
"odom_sensor",
_ui->comboBox_odom_sensor->currentIndex());
3089 settings.setValue(
"odom_sensor_extrinsics",
_ui->lineEdit_odom_sensor_extrinsics->text());
3090 settings.setValue(
"odom_sensor_calibration_path",
_ui->lineEdit_odom_sensor_path_calibration->text());
3091 settings.setValue(
"odom_sensor_device",
_ui->lineEdit_odomSourceDevice->text());
3092 settings.setValue(
"odom_sensor_offset_time",
_ui->doubleSpinBox_odom_sensor_time_offset->value());
3093 settings.setValue(
"odom_sensor_scale_factor",
_ui->doubleSpinBox_odom_sensor_scale_factor->value());
3094 settings.setValue(
"odom_sensor_odom_as_gt",
_ui->checkBox_odom_sensor_use_as_gt->isChecked());
3095 settings.endGroup();
3097 settings.beginGroup(
"UsbCam");
3098 settings.setValue(
"width",
_ui->spinBox_usbcam_streamWidth->value());
3099 settings.setValue(
"height",
_ui->spinBox_usbcam_streamHeight->value());
3100 settings.endGroup();
3102 settings.beginGroup(
"Video");
3103 settings.setValue(
"path",
_ui->source_video_lineEdit_path->text());
3104 settings.endGroup();
3106 settings.beginGroup(
"IMU");
3107 settings.setValue(
"strategy",
_ui->comboBox_imuFilter_strategy->currentIndex());
3108 settings.setValue(
"madgwick_gain",
_ui->doubleSpinBox_imuFilterMadgwickGain->value());
3109 settings.setValue(
"madgwick_zeta",
_ui->doubleSpinBox_imuFilterMadgwickZeta->value());
3110 settings.setValue(
"complementary_gain_acc",
_ui->doubleSpinBox_imuFilterComplementaryGainAcc->value());
3111 settings.setValue(
"complementary_bias_alpha",
_ui->doubleSpinBox_imuFilterComplementaryBiasAlpha->value());
3112 settings.setValue(
"complementary_adaptive_gain",
_ui->checkBox_imuFilterComplementaryDoAdaptiveGain->isChecked());
3113 settings.setValue(
"complementary_biais_estimation",
_ui->checkBox_imuFilterComplementaryDoBiasEstimation->isChecked());
3114 settings.setValue(
"base_frame_conversion",
_ui->checkBox_imuFilter_baseFrameConversion->isChecked());
3115 settings.setValue(
"publish_inter_imu",
_ui->checkbox_publishInterIMU->isChecked());
3116 settings.endGroup();
3118 settings.beginGroup(
"Scan");
3119 settings.setValue(
"fromDepth",
_ui->checkBox_source_scanFromDepth->isChecked());
3120 settings.setValue(
"downsampleStep",
_ui->spinBox_source_scanDownsampleStep->value());
3121 settings.setValue(
"rangeMin",
_ui->doubleSpinBox_source_scanRangeMin->value());
3122 settings.setValue(
"rangeMax",
_ui->doubleSpinBox_source_scanRangeMax->value());
3123 settings.setValue(
"voxelSize",
_ui->doubleSpinBox_source_scanVoxelSize->value());
3124 settings.setValue(
"normalsK",
_ui->spinBox_source_scanNormalsK->value());
3125 settings.setValue(
"normalsRadius",
_ui->doubleSpinBox_source_scanNormalsRadius->value());
3126 settings.setValue(
"normalsUpF",
_ui->doubleSpinBox_source_scanNormalsForceGroundUp->value());
3127 settings.endGroup();
3129 settings.beginGroup(
"DepthFromScan");
3130 settings.setValue(
"depthFromScan",
_ui->groupBox_depthFromScan->isChecked());
3131 settings.setValue(
"depthFromScanFillHoles",
_ui->groupBox_depthFromScan_fillHoles->isChecked());
3132 settings.setValue(
"depthFromScanVertical",
_ui->radioButton_depthFromScan_vertical->isChecked());
3133 settings.setValue(
"depthFromScanHorizontal",
_ui->radioButton_depthFromScan_horizontal->isChecked());
3134 settings.setValue(
"depthFromScanFillBorders",
_ui->checkBox_depthFromScan_fillBorders->isChecked());
3135 settings.endGroup();
3137 settings.beginGroup(
"Database");
3138 settings.setValue(
"path",
_ui->source_database_lineEdit_path->text());
3139 settings.setValue(
"ignoreOdometry",
_ui->source_checkBox_ignoreOdometry->isChecked());
3140 settings.setValue(
"ignoreGoalDelay",
_ui->source_checkBox_ignoreGoalDelay->isChecked());
3141 settings.setValue(
"ignoreGoals",
_ui->source_checkBox_ignoreGoals->isChecked());
3142 settings.setValue(
"ignoreLandmarks",
_ui->source_checkBox_ignoreLandmarks->isChecked());
3143 settings.setValue(
"ignoreFeatures",
_ui->source_checkBox_ignoreFeatures->isChecked());
3144 settings.setValue(
"startId",
_ui->source_spinBox_databaseStartId->value());
3145 settings.setValue(
"stopId",
_ui->source_spinBox_databaseStopId->value());
3146 settings.setValue(
"cameraIndex",
_ui->source_spinBox_database_cameraIndex->value());
3147 settings.setValue(
"useDatabaseStamps",
_ui->source_checkBox_useDbStamps->isChecked());
3148 settings.endGroup();
3150 settings.endGroup();
3158 if(!filePath.isEmpty())
3168 #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))) 3169 #ifndef RTABMAP_NONFREE 3172 if(
_ui->comboBox_detector_strategy->currentIndex() <= 1 ||
_ui->comboBox_detector_strategy->currentIndex() == 12)
3174 QMessageBox::warning(
this, tr(
"Parameter warning"),
3175 tr(
"Selected feature type (SURF/SIFT) is not available. RTAB-Map is not built " 3176 "with the nonfree module from OpenCV. ORB is set instead for the bag-of-words dictionary."));
3180 if(
_ui->vis_feature_detector->currentIndex() <= 1 ||
_ui->vis_feature_detector->currentIndex() == 12)
3182 QMessageBox::warning(
this, tr(
"Parameter warning"),
3183 tr(
"Selected feature type (SURF/SIFT) is not available. RTAB-Map is not built " 3184 "with the nonfree module from OpenCV. Fast/Brief is set instead for the re-extraction " 3185 "of features on loop closure."));
3189 #else //>= 4.4.0 >= 3.4.11 3190 #ifndef RTABMAP_NONFREE 3193 if(
_ui->comboBox_detector_strategy->currentIndex() < 1 ||
_ui->comboBox_detector_strategy->currentIndex() == 12)
3195 QMessageBox::warning(
this, tr(
"Parameter warning"),
3196 tr(
"Selected feature type (SURF) is not available. RTAB-Map is not built " 3197 "with the nonfree module from OpenCV. SIFT is set instead for the bag-of-words dictionary."));
3201 if(
_ui->vis_feature_detector->currentIndex() < 1 ||
_ui->vis_feature_detector->currentIndex() == 12)
3203 QMessageBox::warning(
this, tr(
"Parameter warning"),
3204 tr(
"Selected feature type (SURF) is not available. RTAB-Map is not built " 3205 "with the nonfree module from OpenCV. Fast/Brief is set instead for the re-extraction " 3206 "of features on loop closure."));
3212 #if CV_MAJOR_VERSION < 3 3215 #ifdef RTABMAP_NONFREE 3216 QMessageBox::warning(
this, tr(
"Parameter warning"),
3217 tr(
"Selected feature type (KAZE) is not available on OpenCV2. SURF is set instead " 3218 "for the bag-of-words dictionary."));
3221 QMessageBox::warning(
this, tr(
"Parameter warning"),
3222 tr(
"Selected feature type (KAZE) is not available on OpenCV2. ORB is set instead " 3223 "for the bag-of-words dictionary."));
3229 #ifdef RTABMAP_NONFREE 3230 QMessageBox::warning(
this, tr(
"Parameter warning"),
3231 tr(
"Selected feature type (KAZE) is not available on OpenCV2. SURF is set instead " 3232 "for the re-extraction of features on loop closure."));
3235 QMessageBox::warning(
this, tr(
"Parameter warning"),
3236 tr(
"Selected feature type (KAZE) is not available on OpenCV2. ORB is set instead " 3237 "for the re-extraction of features on loop closure."));
3243 #ifndef RTABMAP_ORB_OCTREE 3246 QMessageBox::warning(
this, tr(
"Parameter warning"),
3247 tr(
"Selected feature type (ORB Octree) is not available. ORB is set instead " 3248 "for the bag-of-words dictionary."));
3253 QMessageBox::warning(
this, tr(
"Parameter warning"),
3254 tr(
"Selected feature type (ORB Octree) is not available on OpenCV2. ORB is set instead " 3255 "for the re-extraction of features on loop closure."));
3265 QMessageBox::warning(
this, tr(
"Parameter warning"),
3266 tr(
"Selected graph optimization strategy (TORO) is not available. RTAB-Map is not built " 3267 "with TORO. GTSAM is set instead for graph optimization strategy."));
3270 #ifndef RTABMAP_ORB_SLAM 3273 QMessageBox::warning(
this, tr(
"Parameter warning"),
3274 tr(
"Selected graph optimization strategy (TORO) is not available. RTAB-Map is not built " 3275 "with TORO. g2o is set instead for graph optimization strategy."));
3280 #ifdef RTABMAP_ORB_SLAM 3281 if(
_ui->graphOptimization_type->currentIndex() == 1)
3288 QMessageBox::warning(
this, tr(
"Parameter warning"),
3289 tr(
"Selected graph optimization strategy (g2o) is not available. RTAB-Map is not built " 3290 "with g2o. GTSAM is set instead for graph optimization strategy."));
3295 QMessageBox::warning(
this, tr(
"Parameter warning"),
3296 tr(
"Selected graph optimization strategy (g2o) is not available. RTAB-Map is not built " 3297 "with g2o. TORO is set instead for graph optimization strategy."));
3303 #ifndef RTABMAP_ORB_SLAM 3306 QMessageBox::warning(
this, tr(
"Parameter warning"),
3307 tr(
"Selected graph optimization strategy (GTSAM) is not available. RTAB-Map is not built " 3308 "with GTSAM. g2o is set instead for graph optimization strategy."));
3315 QMessageBox::warning(
this, tr(
"Parameter warning"),
3316 tr(
"Selected graph optimization strategy (GTSAM) is not available. RTAB-Map is not built " 3317 "with GTSAM. TORO is set instead for graph optimization strategy."));
3325 QMessageBox::warning(
this, tr(
"Parameter warning"),
3326 tr(
"Selected visual registration bundle adjustment optimization strategy (g2o) is not available. RTAB-Map is not built " 3327 "with g2o. Bundle adjustment is disabled."));
3328 _ui->loopClosure_bundle->setCurrentIndex(0);
3332 QMessageBox::warning(
this, tr(
"Parameter warning"),
3333 tr(
"Selected visual registration bundle adjustment optimization strategy (cvsba) is not available. RTAB-Map is not built " 3334 "with cvsba. Bundle adjustment is disabled."));
3335 _ui->loopClosure_bundle->setCurrentIndex(0);
3339 QMessageBox::warning(
this, tr(
"Parameter warning"),
3340 tr(
"Selected visual registration bundle adjustment optimization strategy (Ceres) is not available. RTAB-Map is not built " 3341 "with cERES. Bundle adjustment is disabled."));
3342 _ui->loopClosure_bundle->setCurrentIndex(0);
3348 QMessageBox::warning(
this, tr(
"Parameter warning"),
3349 tr(
"Selected odometry local bundle adjustment optimization strategy (g2o) is not available. RTAB-Map is not built " 3350 "with g2o. Bundle adjustment is disabled."));
3351 _ui->odom_f2m_bundleStrategy->setCurrentIndex(0);
3355 QMessageBox::warning(
this, tr(
"Parameter warning"),
3356 tr(
"Selected odometry local bundle adjustment optimization strategy (cvsba) is not available. RTAB-Map is not built " 3357 "with cvsba. Bundle adjustment is disabled."));
3358 _ui->odom_f2m_bundleStrategy->setCurrentIndex(0);
3362 QMessageBox::warning(
this, tr(
"Parameter warning"),
3363 tr(
"Selected odometry local bundle adjustment optimization strategy (Ceres) is not available. RTAB-Map is not built " 3364 "with Ceres. Bundle adjustment is disabled."));
3365 _ui->odom_f2m_bundleStrategy->setCurrentIndex(0);
3369 if(
_ui->graphOptimization_robust->isChecked() &&
_ui->graphOptimization_maxError->value()>0.0)
3371 QMessageBox::warning(
this, tr(
"Parameter warning"),
3372 tr(
"Robust graph optimization and maximum optimization error threshold cannot be " 3373 "both used at the same time. Disabling robust optimization."));
3374 _ui->graphOptimization_robust->setChecked(
false);
3381 QMessageBox::warning(
this, tr(
"Parameter warning"),
3382 tr(
"With the selected feature type (SURF or SIFT), parameter \"Visual word->Nearest Neighbor\" " 3383 "cannot be LSH (used for binary descriptor). KD-tree is set instead for the bag-of-words dictionary."));
3390 QMessageBox::warning(
this, tr(
"Parameter warning"),
3391 tr(
"With the selected feature type (SURF or SIFT), parameter \"Visual word->Nearest Neighbor\" " 3392 "cannot be LSH (used for binary descriptor). KD-tree is set instead for the re-extraction " 3393 "of features on loop closure."));
3397 if(
_ui->doubleSpinBox_freenect2MinDepth->value() >=
_ui->doubleSpinBox_freenect2MaxDepth->value())
3399 QMessageBox::warning(
this, tr(
"Parameter warning"),
3400 tr(
"Freenect2 minimum depth (%1 m) should be lower than maximum depth (%2 m). Setting maximum depth to %3 m.")
3401 .arg(
_ui->doubleSpinBox_freenect2MinDepth->value())
3402 .arg(
_ui->doubleSpinBox_freenect2MaxDepth->value())
3403 .arg(
_ui->doubleSpinBox_freenect2MaxDepth->value()+1));
3404 _ui->doubleSpinBox_freenect2MaxDepth->setValue(
_ui->doubleSpinBox_freenect2MaxDepth->value()+1);
3407 if(
_ui->surf_doubleSpinBox_maxDepth->value() > 0.0 &&
3408 _ui->surf_doubleSpinBox_minDepth->value() >=
_ui->surf_doubleSpinBox_maxDepth->value())
3410 QMessageBox::warning(
this, tr(
"Parameter warning"),
3411 tr(
"Visual word minimum depth (%1 m) should be lower than maximum depth (%2 m). Setting maximum depth to %3 m.")
3412 .arg(
_ui->surf_doubleSpinBox_minDepth->value())
3413 .arg(
_ui->surf_doubleSpinBox_maxDepth->value())
3414 .arg(
_ui->surf_doubleSpinBox_maxDepth->value()+1));
3415 _ui->doubleSpinBox_freenect2MinDepth->setValue(0);
3418 if(
_ui->loopClosure_bowMaxDepth->value() > 0.0 &&
3419 _ui->loopClosure_bowMinDepth->value() >=
_ui->loopClosure_bowMaxDepth->value())
3421 QMessageBox::warning(
this, tr(
"Parameter warning"),
3422 tr(
"Visual registration word minimum depth (%1 m) should be lower than maximum depth (%2 m). Setting maximum depth to %3 m.")
3423 .arg(
_ui->loopClosure_bowMinDepth->value())
3424 .arg(
_ui->loopClosure_bowMaxDepth->value())
3425 .arg(
_ui->loopClosure_bowMaxDepth->value()+1));
3426 _ui->loopClosure_bowMinDepth->setValue(0);
3429 if(
_ui->fastThresholdMax->value() <
_ui->fastThresholdMin->value())
3431 QMessageBox::warning(
this, tr(
"Parameter warning"),
3432 tr(
"FAST minimum threshold cannot be lower than maximum threshold. Setting minimum to 1."));
3433 _ui->fastThresholdMin->setValue(1);
3435 if(
_ui->fastThreshold->value() >
_ui->fastThresholdMax->value())
3437 QMessageBox::warning(
this, tr(
"Parameter warning"),
3438 tr(
"FAST threshold cannot be higher than maximum threshold. Maximum value set to current threshold."));
3439 _ui->fastThresholdMax->setValue(
_ui->fastThreshold->value());
3441 if(
_ui->fastThreshold->value() <
_ui->fastThresholdMin->value())
3443 QMessageBox::warning(
this, tr(
"Parameter warning"),
3444 tr(
"FAST threshold cannot be lower than minimum threshold. Minimum value set to current threshold."));
3445 _ui->fastThresholdMin->setValue(
_ui->fastThreshold->value());
3448 if(
_ui->checkbox_odomDisabled->isChecked() &&
3449 _ui->general_checkBox_SLAM_mode->isChecked() &&
3450 _ui->general_checkBox_activateRGBD->isChecked())
3452 QMessageBox::warning(
this, tr(
"Parameter warning"),
3453 tr(
"Odometry is disabled but incremental RGB-D SLAM is activated! Re-enabling odometry."));
3454 _ui->checkbox_odomDisabled->setChecked(
false);
3457 #if CV_MAJOR_VERSION < 3 || (CV_MAJOR_VERSION == 3 && (CV_MINOR_VERSION <4 || (CV_MINOR_VERSION ==4 && CV_SUBMINOR_VERSION<2))) 3458 if(
_ui->ArucoDictionary->currentIndex()>=17)
3460 QMessageBox::warning(
this, tr(
"Parameter warning"),
3461 tr(
"ArUco dictionary: cannot select AprilTag dictionary, OpenCV version should be at least 3.4.2. Setting back to 0."));
3462 _ui->ArucoDictionary->setCurrentIndex(0);
3471 return tr(
"Reading parameters from the configuration file...");
3479 _ui->lineEdit_dictionaryPath->setEnabled(
false);
3480 _ui->toolButton_dictionaryPath->setEnabled(
false);
3481 _ui->label_dictionaryPath->setEnabled(
false);
3483 _ui->groupBox_source0->setEnabled(
false);
3484 _ui->groupBox_odometry1->setEnabled(
false);
3486 this->setWindowTitle(tr(
"Preferences [Monitoring mode]"));
3490 _ui->lineEdit_dictionaryPath->setEnabled(
true);
3491 _ui->toolButton_dictionaryPath->setEnabled(
true);
3492 _ui->label_dictionaryPath->setEnabled(
true);
3494 _ui->groupBox_source0->setEnabled(
true);
3495 _ui->groupBox_odometry1->setEnabled(
true);
3497 this->setWindowTitle(tr(
"Preferences"));
3503 std::set<std::string> threadsCheckedSet(threadsChecked.begin(), threadsChecked.end());
3504 _ui->comboBox_loggerFilter->clear();
3505 for(std::map<std::string, unsigned long>::iterator iter=threads.begin(); iter!=threads.end(); ++iter)
3507 if(threadsCheckedSet.find(iter->first.c_str()) != threadsCheckedSet.end())
3509 _ui->comboBox_loggerFilter->addItem(QString(iter->first.c_str()), QVariant(
true));
3513 _ui->comboBox_loggerFilter->addItem(QString(iter->first.c_str()), QVariant(
false));
3531 QApplication::processEvents();
3536 if(this->isVisible())
3549 if(!window->objectName().isEmpty() && !window->isMaximized())
3552 settings.beginGroup(
"Gui");
3553 settings.beginGroup(window->objectName());
3554 settings.setValue(
"geometry", window->saveGeometry());
3555 settings.endGroup();
3556 settings.endGroup();
3559 settingsTmp.beginGroup(
"Gui");
3560 settingsTmp.beginGroup(window->objectName());
3561 settingsTmp.setValue(
"geometry", window->saveGeometry());
3562 settingsTmp.endGroup();
3563 settingsTmp.endGroup();
3569 if(!window->objectName().isEmpty())
3573 settings.beginGroup(
"Gui");
3574 settings.beginGroup(window->objectName());
3575 bytes = settings.value(
"geometry", QByteArray()).toByteArray();
3576 if(!bytes.isEmpty())
3578 window->restoreGeometry(bytes);
3580 settings.endGroup();
3581 settings.endGroup();
3584 settingsTmp.beginGroup(
"Gui");
3585 settingsTmp.beginGroup(window->objectName());
3586 settingsTmp.setValue(
"geometry", window->saveGeometry());
3587 settingsTmp.endGroup();
3588 settingsTmp.endGroup();
3594 if(!mainWindow->objectName().isEmpty())
3599 settings.beginGroup(
"Gui");
3600 settings.beginGroup(mainWindow->objectName());
3601 settings.setValue(
"state", mainWindow->saveState());
3602 settings.setValue(
"maximized", mainWindow->isMaximized());
3603 settings.setValue(
"status_bar", mainWindow->statusBar()->isVisible());
3604 settings.endGroup();
3605 settings.endGroup();
3608 settingsTmp.beginGroup(
"Gui");
3609 settingsTmp.beginGroup(mainWindow->objectName());
3610 settingsTmp.setValue(
"state", mainWindow->saveState());
3611 settingsTmp.setValue(
"maximized", mainWindow->isMaximized());
3612 settingsTmp.setValue(
"status_bar", mainWindow->statusBar()->isVisible());
3613 settingsTmp.endGroup();
3614 settingsTmp.endGroup();
3620 if(!mainWindow->objectName().isEmpty())
3626 settings.beginGroup(
"Gui");
3627 settings.beginGroup(mainWindow->objectName());
3628 bytes = settings.value(
"state", QByteArray()).toByteArray();
3629 if(!bytes.isEmpty())
3631 mainWindow->restoreState(bytes);
3633 maximized = settings.value(
"maximized",
false).toBool();
3634 statusBarShown = settings.value(
"status_bar",
false).toBool();
3635 mainWindow->statusBar()->setVisible(statusBarShown);
3636 settings.endGroup();
3637 settings.endGroup();
3640 settingsTmp.beginGroup(
"Gui");
3641 settingsTmp.beginGroup(mainWindow->objectName());
3642 settingsTmp.setValue(
"state", mainWindow->saveState());
3643 settingsTmp.setValue(
"maximized", maximized);
3644 settingsTmp.setValue(
"status_bar", statusBarShown);
3645 settingsTmp.endGroup();
3646 settingsTmp.endGroup();
3652 if(!widget->objectName().isEmpty())
3655 settings.beginGroup(
"Gui");
3656 settings.beginGroup(widget->objectName());
3659 settingsTmp.beginGroup(
"Gui");
3660 settingsTmp.beginGroup(widget->objectName());
3678 imageView->saveSettings(settings);
3679 imageView->saveSettings(settingsTmp);
3681 else if(exportCloudsDialog)
3683 exportCloudsDialog->saveSettings(settings);
3684 exportCloudsDialog->saveSettings(settingsTmp);
3686 else if(exportBundlerDialog)
3688 exportBundlerDialog->saveSettings(settings);
3689 exportBundlerDialog->saveSettings(settingsTmp);
3691 else if(postProcessingDialog)
3693 postProcessingDialog->saveSettings(settings);
3694 postProcessingDialog->saveSettings(settingsTmp);
3696 else if(graphViewer)
3698 graphViewer->saveSettings(settings);
3699 graphViewer->saveSettings(settingsTmp);
3701 else if(calibrationDialog)
3703 calibrationDialog->saveSettings(settings);
3704 calibrationDialog->saveSettings(settingsTmp);
3706 else if(depthCalibrationDialog)
3708 depthCalibrationDialog->saveSettings(settings);
3709 depthCalibrationDialog->saveSettings(settingsTmp);
3713 UERROR(
"Widget \"%s\" cannot be exported in config file.", widget->objectName().toStdString().c_str());
3716 settings.endGroup();
3717 settings.endGroup();
3718 settingsTmp.endGroup();
3719 settingsTmp.endGroup();
3725 if(!widget->objectName().isEmpty())
3729 settings.beginGroup(
"Gui");
3730 settings.beginGroup(widget->objectName());
3733 settingsTmp.beginGroup(
"Gui");
3734 settingsTmp.beginGroup(widget->objectName());
3752 imageView->loadSettings(settings);
3753 imageView->saveSettings(settingsTmp);
3755 else if(exportCloudsDialog)
3757 exportCloudsDialog->loadSettings(settings);
3758 exportCloudsDialog->saveSettings(settingsTmp);
3760 else if(exportBundlerDialog)
3762 exportBundlerDialog->loadSettings(settings);
3763 exportBundlerDialog->saveSettings(settingsTmp);
3765 else if(postProcessingDialog)
3767 postProcessingDialog->loadSettings(settings);
3768 postProcessingDialog->saveSettings(settingsTmp);
3770 else if(graphViewer)
3772 graphViewer->loadSettings(settings);
3773 graphViewer->saveSettings(settingsTmp);
3775 else if(calibrationDialog)
3777 calibrationDialog->loadSettings(settings);
3778 calibrationDialog->saveSettings(settingsTmp);
3780 else if(depthCalibrationDialog)
3782 depthCalibrationDialog->loadSettings(settings);
3783 depthCalibrationDialog->saveSettings(settingsTmp);
3787 UERROR(
"Widget \"%s\" cannot be loaded from config file.", widget->objectName().toStdString().c_str());
3790 settings.endGroup();
3791 settings.endGroup();
3792 settingsTmp.endGroup();
3793 settingsTmp.endGroup();
3801 settings.beginGroup(
"Gui");
3802 settings.beginGroup(section);
3803 settings.setValue(key, value);
3804 settings.endGroup();
3805 settings.endGroup();
3808 settingsTmp.beginGroup(
"Gui");
3809 settingsTmp.beginGroup(section);
3810 settingsTmp.setValue(key, value);
3811 settingsTmp.endGroup();
3812 settingsTmp.endGroup();
3819 settings.beginGroup(
"Gui");
3820 settings.beginGroup(section);
3821 value = settings.value(key, QString()).toString();
3822 settings.endGroup();
3823 settings.endGroup();
3826 settingsTmp.beginGroup(
"Gui");
3827 settingsTmp.beginGroup(section);
3828 settingsTmp.setValue(key, value);
3829 settingsTmp.endGroup();
3830 settingsTmp.endGroup();
3860 if(parameters.size())
3862 for(rtabmap::ParametersMap::const_iterator iter = parameters.begin(); iter!=parameters.end(); ++iter)
3866 if(setOtherParametersToDefault)
3872 if(parameters.find(iter->first) == parameters.end() &&
3873 iter->first.compare(Parameters::kRtabmapWorkingDirectory())!=0)
3879 if(!this->isVisible())
3888 if(
_ui->comboBox_imuFilter_strategy->currentIndex()==0)
3890 _ui->comboBox_imuFilter_strategy->setCurrentIndex(2);
3897 _ui->comboBox_sourceType->setCurrentIndex(0);
3898 _ui->comboBox_cameraRGBD->setCurrentIndex(src -
kSrcRGBD);
3901 _ui->lineEdit_openniOniPath->clear();
3905 _ui->lineEdit_openni2OniPath->clear();
3909 _ui->lineEdit_k4a_mkv->clear();
3917 _ui->spinBox_rs2_width->setValue(1280);
3918 _ui->spinBox_rs2_height->setValue(720);
3919 _ui->spinBox_rs2_rate->setValue(30);
3923 _ui->spinBox_rs2_width->setValue(848);
3924 _ui->spinBox_rs2_height->setValue(480);
3925 _ui->spinBox_rs2_rate->setValue(60);
3931 _ui->comboBox_sourceType->setCurrentIndex(1);
3932 _ui->comboBox_cameraStereo->setCurrentIndex(src -
kSrcStereo);
3937 _ui->comboBox_imuFilter_strategy->setCurrentIndex(0);
3941 _ui->checkBox_depthai_imu_published->setChecked(variant == 1);
3942 _ui->comboBox_depthai_resolution->setCurrentIndex(variant == 1?1:3);
3947 _ui->comboBox_sourceType->setCurrentIndex(2);
3948 _ui->source_comboBox_image_type->setCurrentIndex(src -
kSrcRGB);
3952 _ui->comboBox_sourceType->setCurrentIndex(3);
3975 QString dir =
_ui->source_database_lineEdit_path->text();
3980 QStringList paths = QFileDialog::getOpenFileNames(
this, tr(
"Select file"), dir, tr(
"RTAB-Map database files (*.db)"));
3983 int r = QMessageBox::question(
this, tr(
"Odometry in database..."), tr(
"Use odometry saved in database (if some saved)?"), QMessageBox::Yes | QMessageBox::No, QMessageBox::Yes);
3984 _ui->source_checkBox_ignoreOdometry->setChecked(r != QMessageBox::Yes);
3986 if (
_ui->general_doubleSpinBox_detectionRate->value() != 0 &&
_ui->general_spinBox_imagesBufferSize->value() != 0)
3988 r = QMessageBox::question(
this, tr(
"Detection rate..."),
3989 tr(
"Do you want to process all frames? \n\nClicking \"Yes\" will set " 3990 "RTAB-Map's detection rate (%1 Hz) and buffer size (%2) to 0 to make " 3991 "sure that all frames are processed.")
3992 .arg(
_ui->general_doubleSpinBox_detectionRate->value())
3993 .arg(
_ui->general_spinBox_imagesBufferSize->value()),
3994 QMessageBox::Yes | QMessageBox::No, QMessageBox::Yes);
3995 if (r == QMessageBox::Yes)
3997 _ui->general_doubleSpinBox_detectionRate->setValue(0.0);
3998 _ui->general_spinBox_imagesBufferSize->setValue(0);
4002 if(paths.size() > 1)
4004 std::vector<std::string> vFileNames(paths.size());
4005 for(
int i=0; i<paths.size(); ++i)
4007 vFileNames[i] = paths[i].toStdString();
4009 std::sort(vFileNames.begin(), vFileNames.end(),
sortCallback);
4010 for(
int i=0; i<paths.size(); ++i)
4012 paths[i] = vFileNames[i].c_str();
4016 _ui->source_database_lineEdit_path->setText(paths.size()==1?paths.front():paths.join(
";"));
4017 _ui->source_spinBox_databaseStartId->setValue(0);
4018 _ui->source_spinBox_databaseStopId->setValue(0);
4019 _ui->source_spinBox_database_cameraIndex->setValue(-1);
4026 viewer->setWindowModality(Qt::WindowModal);
4027 viewer->setAttribute(Qt::WA_DeleteOnClose,
true);
4041 if(!
_ui->lineEdit_source_distortionModel->text().isEmpty() &&
4042 QFileInfo(
_ui->lineEdit_source_distortionModel->text()).exists())
4045 model.
load(
_ui->lineEdit_source_distortionModel->text().toStdString());
4049 QString
name = QFileInfo(
_ui->lineEdit_source_distortionModel->text()).baseName()+
".png";
4050 cv::imwrite(name.toStdString(), img);
4051 QDesktopServices::openUrl(QUrl::fromLocalFile(name));
4055 QMessageBox::warning(
this, tr(
"Distortion Model"), tr(
"Model loaded from \"%1\" is not valid!").arg(
_ui->lineEdit_source_distortionModel->text()));
4060 QMessageBox::warning(
this, tr(
"Distortion Model"), tr(
"File \"%1\" doesn't exist!").arg(
_ui->lineEdit_source_distortionModel->text()));
4066 QString dir =
_ui->lineEdit_calibrationFile->text();
4071 else if(!dir.contains(
'.'))
4075 QString path = QFileDialog::getOpenFileName(
this, tr(
"Select file"), dir, tr(
"Calibration file (*.yaml)"));
4078 _ui->lineEdit_calibrationFile->setText(path);
4084 QString dir =
_ui->lineEdit_odom_sensor_path_calibration->text();
4089 else if(!dir.contains(
'.'))
4093 QString path = QFileDialog::getOpenFileName(
this, tr(
"Select file"), dir, tr(
"Calibration file (*.yaml)"));
4096 _ui->lineEdit_odom_sensor_path_calibration->setText(path);
4102 QString dir =
_ui->lineEdit_cameraImages_timestamps->text();
4107 QString path = QFileDialog::getOpenFileName(
this, tr(
"Select file"), dir, tr(
"Timestamps file (*.txt)"));
4110 _ui->lineEdit_cameraImages_timestamps->setText(path);
4116 QString dir =
_ui->lineEdit_cameraRGBDImages_path_rgb->text();
4121 QString path = QFileDialog::getExistingDirectory(
this, tr(
"Select RGB images directory"), dir);
4124 _ui->lineEdit_cameraRGBDImages_path_rgb->setText(path);
4131 QString dir =
_ui->lineEdit_cameraImages_path_scans->text();
4136 QString path = QFileDialog::getExistingDirectory(
this, tr(
"Select scans directory"), dir);
4139 _ui->lineEdit_cameraImages_path_scans->setText(path);
4145 QString dir =
_ui->lineEdit_cameraImages_path_imu->text();
4150 QString path = QFileDialog::getOpenFileName(
this, tr(
"Select file "), dir, tr(
"EuRoC IMU file (*.csv)"));
4153 _ui->lineEdit_cameraImages_path_imu->setText(path);
4160 QString dir =
_ui->lineEdit_cameraRGBDImages_path_depth->text();
4165 QString path = QFileDialog::getExistingDirectory(
this, tr(
"Select depth images directory"), dir);
4168 _ui->lineEdit_cameraRGBDImages_path_depth->setText(path);
4174 QString dir =
_ui->lineEdit_cameraImages_odom->text();
4179 QString path = QFileDialog::getOpenFileName(
this, tr(
"Select file"), dir, tr(
"Odometry (*.txt *.log *.toro *.g2o *.csv)"));
4183 for(
int i=0; i<
_ui->comboBox_cameraImages_odomFormat->count(); ++i)
4185 list.push_back(
_ui->comboBox_cameraImages_odomFormat->itemText(i));
4187 QString item = QInputDialog::getItem(
this, tr(
"Odometry Format"), tr(
"Format:"), list,
_ui->comboBox_cameraImages_odomFormat->currentIndex(),
false);
4190 _ui->lineEdit_cameraImages_odom->setText(path);
4191 _ui->comboBox_cameraImages_odomFormat->setCurrentIndex(
_ui->comboBox_cameraImages_odomFormat->findText(item));
4198 QString dir =
_ui->lineEdit_cameraImages_gt->text();
4203 QString path = QFileDialog::getOpenFileName(
this, tr(
"Select file"), dir, tr(
"Ground Truth (*.txt *.log *.toro *.g2o *.csv)"));
4207 for(
int i=0; i<
_ui->comboBox_cameraImages_gtFormat->count(); ++i)
4209 list.push_back(
_ui->comboBox_cameraImages_gtFormat->itemText(i));
4211 QString item = QInputDialog::getItem(
this, tr(
"Ground Truth Format"), tr(
"Format:"), list,
_ui->comboBox_cameraImages_gtFormat->currentIndex(),
false);
4214 _ui->lineEdit_cameraImages_gt->setText(path);
4215 _ui->comboBox_cameraImages_gtFormat->setCurrentIndex(
_ui->comboBox_cameraImages_gtFormat->findText(item));
4222 QString dir =
_ui->lineEdit_cameraStereoImages_path_left->text();
4227 QString path = QFileDialog::getExistingDirectory(
this, tr(
"Select left images directory"), dir);
4230 _ui->lineEdit_cameraStereoImages_path_left->setText(path);
4236 QString dir =
_ui->lineEdit_cameraStereoImages_path_right->text();
4241 QString path = QFileDialog::getExistingDirectory(
this, tr(
"Select right images directory"), dir);
4244 _ui->lineEdit_cameraStereoImages_path_right->setText(path);
4250 QString dir =
_ui->source_images_lineEdit_path->text();
4255 QString path = QFileDialog::getExistingDirectory(
this, tr(
"Select images directory"),
_ui->source_images_lineEdit_path->text());
4258 _ui->source_images_lineEdit_path->setText(path);
4259 _ui->source_images_spinBox_startPos->setValue(0);
4260 _ui->source_images_spinBox_maxFrames->setValue(0);
4266 QString dir =
_ui->source_video_lineEdit_path->text();
4271 QString path = QFileDialog::getOpenFileName(
this, tr(
"Select file"), dir, tr(
"Videos (*.avi *.mpg *.mp4 *.mov *.mkv)"));
4274 _ui->source_video_lineEdit_path->setText(path);
4280 QString dir =
_ui->lineEdit_cameraStereoVideo_path->text();
4285 QString path = QFileDialog::getOpenFileName(
this, tr(
"Select file"), dir, tr(
"Videos (*.avi *.mpg *.mp4 *.mov *.mkv)"));
4288 _ui->lineEdit_cameraStereoVideo_path->setText(path);
4294 QString dir =
_ui->lineEdit_cameraStereoVideo_path_2->text();
4299 QString path = QFileDialog::getOpenFileName(
this, tr(
"Select file"), dir, tr(
"Videos (*.avi *.mpg *.mp4 *.mov *.mkv)"));
4302 _ui->lineEdit_cameraStereoVideo_path_2->setText(path);
4308 QString dir =
_ui->lineEdit_source_distortionModel->text();
4313 QString path = QFileDialog::getOpenFileName(
this, tr(
"Select file"), dir, tr(
"Distortion model (*.bin *.txt)"));
4316 _ui->lineEdit_source_distortionModel->setText(path);
4322 QString dir =
_ui->lineEdit_openniOniPath->text();
4327 QString path = QFileDialog::getOpenFileName(
this, tr(
"Select file"), dir, tr(
"OpenNI (*.oni)"));
4330 _ui->lineEdit_openniOniPath->setText(path);
4336 QString dir =
_ui->lineEdit_openni2OniPath->text();
4341 QString path = QFileDialog::getOpenFileName(
this, tr(
"Select file"), dir, tr(
"OpenNI (*.oni)"));
4344 _ui->lineEdit_openni2OniPath->setText(path);
4350 QString dir =
_ui->lineEdit_k4a_mkv->text();
4355 QString path = QFileDialog::getOpenFileName(
this, tr(
"Select file"), dir, tr(
"K4A recording (*.mkv)"));
4356 if (!path.isEmpty())
4358 _ui->lineEdit_k4a_mkv->setText(path);
4364 QString dir =
_ui->lineEdit_zedSvoPath->text();
4369 QString path = QFileDialog::getOpenFileName(
this, tr(
"Select file"), dir, tr(
"ZED (*.svo)"));
4372 _ui->lineEdit_zedSvoPath->setText(path);
4378 QString dir =
_ui->lineEdit_rs2_jsonFile->text();
4383 QString path = QFileDialog::getOpenFileName(
this, tr(
"Select RealSense2 preset"), dir, tr(
"JSON (*.json)"));
4386 _ui->lineEdit_rs2_jsonFile->setText(path);
4392 UDEBUG(
"%s=%s", key.c_str(), value.c_str());
4393 QWidget * obj =
_ui->stackedWidget->findChild<QWidget*>(key.c_str());
4398 QSpinBox * spin = qobject_cast<QSpinBox *>(obj);
4399 QDoubleSpinBox * doubleSpin = qobject_cast<QDoubleSpinBox *>(obj);
4400 QComboBox * combo = qobject_cast<QComboBox *>(obj);
4401 QCheckBox * check = qobject_cast<QCheckBox *>(obj);
4402 QRadioButton * radio = qobject_cast<QRadioButton *>(obj);
4403 QLineEdit * lineEdit = qobject_cast<QLineEdit *>(obj);
4404 QGroupBox * groupBox = qobject_cast<QGroupBox *>(obj);
4408 spin->setValue(QString(value.c_str()).toInt(&ok));
4411 UERROR(
"Conversion failed from \"%s\" for parameter %s", value.c_str(), key.c_str());
4416 doubleSpin->setValue(QString(value.c_str()).toDouble(&ok));
4419 UERROR(
"Conversion failed from \"%s\" for parameter %s", value.c_str(), key.c_str());
4425 std::string valueCpy = value;
4426 if( key.compare(Parameters::kIcpStrategy()) == 0 ||
4427 key.compare(Parameters::kGridSensor()) == 0)
4429 if(value.compare(
"true") == 0)
4433 else if(value.compare(
"false") == 0)
4439 int valueInt = QString(valueCpy.c_str()).toInt(&ok);
4442 UERROR(
"Conversion failed from \"%s\" for parameter %s", valueCpy.c_str(), key.c_str());
4446 #ifndef RTABMAP_NONFREE 4448 (combo->objectName().toStdString().compare(Parameters::kKpDetectorStrategy()) == 0 ||
4449 combo->objectName().toStdString().compare(Parameters::kVisFeatureType()) == 0))
4451 UWARN(
"Trying to set \"%s\" to SURF but RTAB-Map isn't built " 4452 "with the nonfree module from OpenCV. Keeping default combo value: %s.",
4453 combo->objectName().toStdString().c_str(),
4454 combo->currentText().toStdString().c_str());
4457 #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))) 4459 (combo->objectName().toStdString().compare(Parameters::kKpDetectorStrategy()) == 0 ||
4460 combo->objectName().toStdString().compare(Parameters::kVisFeatureType()) == 0))
4462 UWARN(
"Trying to set \"%s\" to SIFT but RTAB-Map isn't built " 4463 "with the nonfree module from OpenCV. Keeping default combo value: %s.",
4464 combo->objectName().toStdString().c_str(),
4465 combo->currentText().toStdString().c_str());
4470 #ifndef RTABMAP_ORB_SLAM 4474 if(valueInt==1 && combo->objectName().toStdString().compare(Parameters::kOptimizerStrategy()) == 0)
4476 UWARN(
"Trying to set \"%s\" to g2o but RTAB-Map isn't built " 4477 "with g2o. Keeping default combo value: %s.",
4478 combo->objectName().toStdString().c_str(),
4479 combo->currentText().toStdString().c_str());
4485 if(valueInt==2 && combo->objectName().toStdString().compare(Parameters::kOptimizerStrategy()) == 0)
4487 UWARN(
"Trying to set \"%s\" to GTSAM but RTAB-Map isn't built " 4488 "with GTSAM. Keeping default combo value: %s.",
4489 combo->objectName().toStdString().c_str(),
4490 combo->currentText().toStdString().c_str());
4496 combo->setCurrentIndex(valueInt);
4503 _ui->checkBox_useOdomFeatures->blockSignals(
true);
4504 check->setChecked(
uStr2Bool(value.c_str()));
4505 _ui->checkBox_useOdomFeatures->blockSignals(
false);
4509 radio->setChecked(
uStr2Bool(value.c_str()));
4513 lineEdit->setText(value.c_str());
4517 groupBox->setChecked(
uStr2Bool(value.c_str()));
4521 ULOGGER_WARN(
"QObject called %s can't be cast to a supported widget", key.c_str());
4526 ULOGGER_WARN(
"Can't find the related QObject for parameter %s", key.c_str());
4538 ULOGGER_ERROR(
"This slot must be triggered by a signal, not a direct call...");
4550 ULOGGER_ERROR(
"This slot must be triggered by a signal, not a direct call...");
4562 ULOGGER_ERROR(
"This slot must be triggered by a signal, not a direct call...");
4574 ULOGGER_ERROR(
"This slot must be triggered by a signal, not a direct call...");
4582 const QComboBox * comboBox = qobject_cast<
const QComboBox*>(object);
4583 const QSpinBox * spinbox = qobject_cast<
const QSpinBox*>(object);
4584 if(comboBox || spinbox)
4587 UDEBUG(
"modify param %s=%s", object->objectName().toStdString().c_str(),
uNumber2Str(value).c_str());
4592 UWARN(
"Undefined object \"%s\"", object->objectName().toStdString().c_str());
4606 const QCheckBox * checkbox = qobject_cast<
const QCheckBox*>(object);
4607 const QRadioButton * radio = qobject_cast<
const QRadioButton*>(object);
4608 const QGroupBox * groupBox = qobject_cast<
const QGroupBox*>(object);
4609 if(checkbox || radio || groupBox)
4612 UDEBUG(
"modify param %s=%s", object->objectName().toStdString().c_str(),
uBool2Str(value).c_str());
4617 UWARN(
"Undefined object \"%s\"", object->objectName().toStdString().c_str());
4631 UDEBUG(
"modify param %s=%f", object->objectName().toStdString().c_str(), value);
4644 UDEBUG(
"modify param %s=%s", object->objectName().toStdString().c_str(), value.toStdString().c_str());
4656 for(
int i=0; i<children.size(); ++i)
4658 const QSpinBox * spin = qobject_cast<
const QSpinBox *>(children[i]);
4659 const QDoubleSpinBox * doubleSpin = qobject_cast<
const QDoubleSpinBox *>(children[i]);
4660 const QComboBox * combo = qobject_cast<
const QComboBox *>(children[i]);
4661 const QCheckBox * check = qobject_cast<
const QCheckBox *>(children[i]);
4662 const QRadioButton * radio = qobject_cast<
const QRadioButton *>(children[i]);
4663 const QLineEdit * lineEdit = qobject_cast<
const QLineEdit *>(children[i]);
4664 const QGroupBox * groupBox = qobject_cast<
const QGroupBox *>(children[i]);
4665 const QStackedWidget * stackedWidget = qobject_cast<
const QStackedWidget *>(children[i]);
4692 if(groupBox->isCheckable())
4701 else if(stackedWidget)
4714 for(
int i=0; i<stackedWidget->count(); ++i)
4716 const QObjectList & children = stackedWidget->widget(i)->children();
4722 UASSERT(panel<stackedWidget->count());
4723 const QObjectList & children = stackedWidget->widget(panel)->children();
4733 const QObjectList & children = box->children();
4743 if(sender() ==
_ui->general_doubleSpinBox_timeThr_2)
4745 _ui->general_doubleSpinBox_timeThr->setValue(
_ui->general_doubleSpinBox_timeThr_2->value());
4747 else if(sender() ==
_ui->general_doubleSpinBox_hardThr_2)
4749 _ui->general_doubleSpinBox_hardThr->setValue(
_ui->general_doubleSpinBox_hardThr_2->value());
4751 else if(sender() ==
_ui->general_doubleSpinBox_detectionRate_2)
4753 _ui->general_doubleSpinBox_detectionRate->setValue(
_ui->general_doubleSpinBox_detectionRate_2->value());
4755 else if(sender() ==
_ui->general_spinBox_imagesBufferSize_2)
4757 _ui->general_spinBox_imagesBufferSize->setValue(
_ui->general_spinBox_imagesBufferSize_2->value());
4759 else if(sender() ==
_ui->general_spinBox_maxStMemSize_2)
4761 _ui->general_spinBox_maxStMemSize->setValue(
_ui->general_spinBox_maxStMemSize_2->value());
4763 else if(sender() ==
_ui->groupBox_publishing)
4765 _ui->general_checkBox_publishStats_2->setChecked(
_ui->groupBox_publishing->isChecked());
4767 else if(sender() ==
_ui->general_checkBox_publishStats_2)
4769 _ui->groupBox_publishing->setChecked(
_ui->general_checkBox_publishStats_2->isChecked());
4771 else if(sender() ==
_ui->doubleSpinBox_similarityThreshold_2)
4773 _ui->doubleSpinBox_similarityThreshold->setValue(
_ui->doubleSpinBox_similarityThreshold_2->value());
4775 else if(sender() ==
_ui->general_checkBox_activateRGBD)
4777 _ui->general_checkBox_activateRGBD_2->setChecked(
_ui->general_checkBox_activateRGBD->isChecked());
4779 else if(sender() ==
_ui->general_checkBox_activateRGBD_2)
4781 _ui->general_checkBox_activateRGBD->setChecked(
_ui->general_checkBox_activateRGBD_2->isChecked());
4783 else if(sender() ==
_ui->general_checkBox_SLAM_mode)
4785 _ui->general_checkBox_SLAM_mode_2->setChecked(
_ui->general_checkBox_SLAM_mode->isChecked());
4787 else if(sender() ==
_ui->general_checkBox_SLAM_mode_2)
4789 _ui->general_checkBox_SLAM_mode->setChecked(
_ui->general_checkBox_SLAM_mode_2->isChecked());
4794 _ui->general_doubleSpinBox_timeThr->setValue(
_ui->general_doubleSpinBox_timeThr_2->value());
4795 _ui->general_doubleSpinBox_hardThr->setValue(
_ui->general_doubleSpinBox_hardThr_2->value());
4796 _ui->general_doubleSpinBox_detectionRate->setValue(
_ui->general_doubleSpinBox_detectionRate_2->value());
4797 _ui->general_spinBox_imagesBufferSize->setValue(
_ui->general_spinBox_imagesBufferSize_2->value());
4798 _ui->general_spinBox_maxStMemSize->setValue(
_ui->general_spinBox_maxStMemSize_2->value());
4799 _ui->doubleSpinBox_similarityThreshold->setValue(
_ui->doubleSpinBox_similarityThreshold_2->value());
4828 QList<QGroupBox*> boxes;
4829 for(
int i=0; i<
_ui->stackedWidget->count(); ++i)
4832 const QObjectList & children =
_ui->stackedWidget->widget(i)->children();
4833 for(
int j=0; j<children.size(); ++j)
4835 if((gb = qobject_cast<QGroupBox *>(children.at(j))))
4847 ULOGGER_ERROR(
"A QGroupBox must be included in the first level of children in stacked widget, index=%d", i);
4855 QStringList values =
_ui->lineEdit_bayes_predictionLC->text().simplified().split(
' ');
4856 if(values.size() < 2)
4858 UERROR(
"Error parsing prediction (must have at least 2 items) : %s",
4859 _ui->lineEdit_bayes_predictionLC->text().toStdString().c_str());
4862 QVector<qreal> dataX((values.size()-2)*2 + 1);
4863 QVector<qreal> dataY((values.size()-2)*2 + 1);
4869 int loopClosureIndex = (dataX.size()-1)/2;
4870 for(
int i=0; i<values.size(); ++i)
4872 value = values.at(i).toDouble(&ok);
4875 UERROR(
"Error parsing prediction : \"%s\"", values.at(i).toStdString().c_str());
4885 dataY[loopClosureIndex] = value;
4886 dataX[loopClosureIndex] = 0;
4890 dataY[loopClosureIndex-lvl] = value;
4891 dataX[loopClosureIndex-lvl] = -lvl;
4892 dataY[loopClosureIndex+lvl] = value;
4893 dataX[loopClosureIndex+lvl] = lvl;
4898 _ui->label_prediction_sum->setNum(sum);
4901 _ui->label_prediction_sum->setText(QString(
"<font color=#FF0000>") +
_ui->label_prediction_sum->text() +
"</font>");
4905 _ui->label_prediction_sum->setText(QString(
"<font color=#00FF00>") +
_ui->label_prediction_sum->text() +
"</font>");
4909 _ui->label_prediction_sum->setText(QString(
"<font color=#FFa500>") +
_ui->label_prediction_sum->text() +
"</font>");
4913 _ui->label_prediction_sum->setText(QString(
"<font color=#000000>") +
_ui->label_prediction_sum->text() +
"</font>");
4916 _ui->predictionPlot->removeCurves();
4917 _ui->predictionPlot->addCurve(
new UPlotCurve(
"Prediction", dataX, dataY,
_ui->predictionPlot));
4922 QStringList strings =
_ui->lineEdit_kp_roi->text().split(
' ');
4923 if(strings.size()!=4)
4925 UERROR(
"ROI must have 4 values (%s)",
_ui->lineEdit_kp_roi->text().toStdString().c_str());
4928 _ui->doubleSpinBox_kp_roi0->setValue(strings[0].toDouble()*100.0);
4929 _ui->doubleSpinBox_kp_roi1->setValue(strings[1].toDouble()*100.0);
4930 _ui->doubleSpinBox_kp_roi2->setValue(strings[2].toDouble()*100.0);
4931 _ui->doubleSpinBox_kp_roi3->setValue(strings[3].toDouble()*100.0);
4936 QStringList strings;
4937 strings.append(QString::number(
_ui->doubleSpinBox_kp_roi0->value()/100.0));
4938 strings.append(QString::number(
_ui->doubleSpinBox_kp_roi1->value()/100.0));
4939 strings.append(QString::number(
_ui->doubleSpinBox_kp_roi2->value()/100.0));
4940 strings.append(QString::number(
_ui->doubleSpinBox_kp_roi3->value()/100.0));
4941 _ui->lineEdit_kp_roi->setText(strings.join(
" "));
4947 _ui->checkbox_stereo_depthGenerated->setVisible(
4949 _ui->comboBox_stereoZed_quality->currentIndex() == 0);
4950 _ui->label_stereo_depthGenerated->setVisible(
4952 _ui->comboBox_stereoZed_quality->currentIndex() == 0);
4954 _ui->checkBox_stereo_rectify->setEnabled(
4961 _ui->checkBox_stereo_rectify->setVisible(
_ui->checkBox_stereo_rectify->isEnabled());
4962 _ui->label_stereo_rectify->setVisible(
_ui->checkBox_stereo_rectify->isEnabled());
4967 _ui->groupBox_pymatcher->setVisible(
_ui->reextract_nn->currentIndex() == 6);
4968 _ui->groupBox_gms->setVisible(
_ui->reextract_nn->currentIndex() == 7);
4975 _ui->stackedWidget_odometryType->setCurrentIndex(7);
4979 _ui->stackedWidget_odometryType->setCurrentIndex(index);
4981 _ui->groupBox_odomF2M->setVisible(index==0);
4982 _ui->groupBox_odomF2F->setVisible(index==1);
4983 _ui->groupBox_odomFovis->setVisible(index==2);
4984 _ui->groupBox_odomViso2->setVisible(index==3);
4985 _ui->groupBox_odomDVO->setVisible(index==4);
4986 _ui->groupBox_odomORBSLAM->setVisible(index==5);
4987 _ui->groupBox_odomOKVIS->setVisible(index==6);
4988 _ui->groupBox_odomLOAM->setVisible(index==7);
4989 _ui->groupBox_odomMSCKF->setVisible(index==8);
4990 _ui->groupBox_odomVINS->setVisible(index==9);
4991 _ui->groupBox_odomOpenVINS->setVisible(index==10);
4992 _ui->groupBox_odomOpen3D->setVisible(index==12);
4997 if(this->isVisible() &&
_ui->checkBox_useOdomFeatures->isChecked())
4999 int r = QMessageBox::question(
this, tr(
"Using odometry features for vocabulary..."),
5000 tr(
"Do you want to match vocabulary feature parameters " 5001 "with corresponding ones used for odometry?"), QMessageBox::Yes | QMessageBox::No, QMessageBox::Yes);
5003 if(r == QMessageBox::Yes)
5005 _ui->comboBox_detector_strategy->setCurrentIndex(
_ui->vis_feature_detector->currentIndex());
5006 _ui->surf_doubleSpinBox_maxDepth->setValue(
_ui->loopClosure_bowMaxDepth->value());
5007 _ui->surf_doubleSpinBox_minDepth->setValue(
_ui->loopClosure_bowMinDepth->value());
5008 _ui->surf_spinBox_wordsPerImageTarget->setValue(
_ui->reextract_maxFeatures->value());
5009 _ui->spinBox_KPGridRows->setValue(
_ui->reextract_gridrows->value());
5010 _ui->spinBox_KPGridCols->setValue(
_ui->reextract_gridcols->value());
5011 _ui->lineEdit_kp_roi->setText(
_ui->loopClosure_roi->text());
5012 _ui->subpix_winSize_kp->setValue(
_ui->subpix_winSize->value());
5013 _ui->subpix_iterations_kp->setValue(
_ui->subpix_iterations->value());
5014 _ui->subpix_eps_kp->setValue(
_ui->subpix_eps->value());
5021 QString directory = QFileDialog::getExistingDirectory(
this, tr(
"Working directory"),
_ui->lineEdit_workingDirectory->text());
5022 if(!directory.isEmpty())
5024 ULOGGER_DEBUG(
"New working directory = %s", directory.toStdString().c_str());
5025 _ui->lineEdit_workingDirectory->setText(directory);
5032 if(
_ui->lineEdit_dictionaryPath->text().isEmpty())
5034 path = QFileDialog::getOpenFileName(
this, tr(
"Dictionary"), this->
getWorkingDirectory(), tr(
"Dictionary (*.txt *.db)"));
5038 path = QFileDialog::getOpenFileName(
this, tr(
"Dictionary"),
_ui->lineEdit_dictionaryPath->text(), tr(
"Dictionary (*.txt *.db)"));
5042 _ui->lineEdit_dictionaryPath->setText(path);
5049 if(
_ui->lineEdit_OdomORBSLAMVocPath->text().isEmpty())
5051 path = QFileDialog::getOpenFileName(
this, tr(
"ORBSLAM Vocabulary"), this->
getWorkingDirectory(), tr(
"Vocabulary (*.txt)"));
5055 path = QFileDialog::getOpenFileName(
this, tr(
"ORBSLAM Vocabulary"),
_ui->lineEdit_OdomORBSLAMVocPath->text(), tr(
"Vocabulary (*.txt)"));
5059 _ui->lineEdit_OdomORBSLAMVocPath->setText(path);
5066 if(
_ui->lineEdit_OdomOkvisPath->text().isEmpty())
5068 path = QFileDialog::getOpenFileName(
this, tr(
"OKVIS Config"), this->
getWorkingDirectory(), tr(
"OKVIS config (*.yaml)"));
5072 path = QFileDialog::getOpenFileName(
this, tr(
"OKVIS Config"),
_ui->lineEdit_OdomOkvisPath->text(), tr(
"OKVIS config (*.yaml)"));
5076 _ui->lineEdit_OdomOkvisPath->setText(path);
5083 if(
_ui->lineEdit_OdomVinsPath->text().isEmpty())
5085 path = QFileDialog::getOpenFileName(
this, tr(
"VINS-Fusion Config"), this->
getWorkingDirectory(), tr(
"VINS-Fusion config (*.yaml)"));
5089 path = QFileDialog::getOpenFileName(
this, tr(
"VINS-Fusion Config"),
_ui->lineEdit_OdomVinsPath->text(), tr(
"VINS-Fusion config (*.yaml)"));
5093 _ui->lineEdit_OdomVinsPath->setText(path);
5100 if(
_ui->lineEdit_IcpPMConfigPath->text().isEmpty())
5102 path = QFileDialog::getOpenFileName(
this, tr(
"Select file"), this->
getWorkingDirectory(), tr(
"libpointmatcher (*.yaml)"));
5106 path = QFileDialog::getOpenFileName(
this, tr(
"Select file"),
_ui->lineEdit_IcpPMConfigPath->text(), tr(
"libpointmatcher (*.yaml)"));
5110 _ui->lineEdit_IcpPMConfigPath->setText(path);
5117 if(
_ui->lineEdit_sptorch_path->text().isEmpty())
5119 path = QFileDialog::getOpenFileName(
this, tr(
"Select file"), this->
getWorkingDirectory(), tr(
"SuperPoint weights (*.pt)"));
5123 path = QFileDialog::getOpenFileName(
this, tr(
"Select file"),
_ui->lineEdit_sptorch_path->text(), tr(
"SuperPoint weights (*.pt)"));
5127 _ui->lineEdit_sptorch_path->setText(path);
5134 if(
_ui->lineEdit_pymatcher_path->text().isEmpty())
5136 path = QFileDialog::getOpenFileName(
this, tr(
"Select file"), this->
getWorkingDirectory(), tr(
"Python wrapper (*.py)"));
5140 path = QFileDialog::getOpenFileName(
this, tr(
"Select file"),
_ui->lineEdit_pymatcher_path->text(), tr(
"Python wrapper (*.py)"));
5144 _ui->lineEdit_pymatcher_path->setText(path);
5151 if(
_ui->lineEdit_pymatcher_model->text().isEmpty())
5153 path = QFileDialog::getOpenFileName(
this, tr(
"Select file"), this->
getWorkingDirectory(), tr(
"PyTorch model (*.pth *.pt)"));
5157 path = QFileDialog::getOpenFileName(
this, tr(
"Select file"),
_ui->lineEdit_pymatcher_model->text(), tr(
"PyTorch model (*.pth *.pt)"));
5161 _ui->lineEdit_pymatcher_model->setText(path);
5168 if(
_ui->lineEdit_pydetector_path->text().isEmpty())
5170 path = QFileDialog::getOpenFileName(
this, tr(
"Select file"), this->
getWorkingDirectory(), tr(
"Python wrapper (*.py)"));
5174 path = QFileDialog::getOpenFileName(
this, tr(
"Select file"),
_ui->lineEdit_pydetector_path->text(), tr(
"Python wrapper (*.py)"));
5178 _ui->lineEdit_pydetector_path->setText(path);
5184 _ui->groupBox_sourceRGBD->setVisible(
_ui->comboBox_sourceType->currentIndex() == 0);
5185 _ui->groupBox_sourceStereo->setVisible(
_ui->comboBox_sourceType->currentIndex() == 1);
5186 _ui->groupBox_sourceRGB->setVisible(
_ui->comboBox_sourceType->currentIndex() == 2);
5187 _ui->groupBox_sourceDatabase->setVisible(
_ui->comboBox_sourceType->currentIndex() == 3);
5189 _ui->checkBox_source_scanFromDepth->setVisible(
_ui->comboBox_sourceType->currentIndex() <= 1 ||
_ui->comboBox_sourceType->currentIndex() == 3);
5190 _ui->label_source_scanFromDepth->setVisible(
_ui->comboBox_sourceType->currentIndex() <= 1 ||
_ui->comboBox_sourceType->currentIndex() == 3);
5192 _ui->stackedWidget_rgbd->setVisible(
_ui->comboBox_sourceType->currentIndex() == 0 &&
5201 _ui->groupBox_openni2->setVisible(
_ui->comboBox_sourceType->currentIndex() == 0 &&
_ui->comboBox_cameraRGBD->currentIndex() ==
kSrcOpenNI2-
kSrcRGBD);
5202 _ui->groupBox_freenect2->setVisible(
_ui->comboBox_sourceType->currentIndex() == 0 &&
_ui->comboBox_cameraRGBD->currentIndex() ==
kSrcFreenect2-
kSrcRGBD);
5203 _ui->groupBox_k4w2->setVisible(
_ui->comboBox_sourceType->currentIndex() == 0 &&
_ui->comboBox_cameraRGBD->currentIndex() ==
kSrcK4W2 -
kSrcRGBD);
5204 _ui->groupBox_k4a->setVisible(
_ui->comboBox_sourceType->currentIndex() == 0 &&
_ui->comboBox_cameraRGBD->currentIndex() ==
kSrcK4A -
kSrcRGBD);
5205 _ui->groupBox_realsense->setVisible(
_ui->comboBox_sourceType->currentIndex() == 0 &&
_ui->comboBox_cameraRGBD->currentIndex() ==
kSrcRealSense -
kSrcRGBD);
5206 _ui->groupBox_realsense2->setVisible(
_ui->comboBox_sourceType->currentIndex() == 0 &&
_ui->comboBox_cameraRGBD->currentIndex() ==
kSrcRealSense2 -
kSrcRGBD);
5207 _ui->groupBox_cameraRGBDImages->setVisible(
_ui->comboBox_sourceType->currentIndex() == 0 &&
_ui->comboBox_cameraRGBD->currentIndex() ==
kSrcRGBDImages-
kSrcRGBD);
5208 _ui->groupBox_openni->setVisible(
_ui->comboBox_sourceType->currentIndex() == 0 &&
_ui->comboBox_cameraRGBD->currentIndex() ==
kSrcOpenNI_PCL -
kSrcRGBD);
5210 _ui->stackedWidget_stereo->setVisible(
_ui->comboBox_sourceType->currentIndex() == 1 &&
5219 _ui->groupBox_cameraStereoVideo->setVisible(
_ui->comboBox_sourceType->currentIndex() == 1 &&
_ui->comboBox_cameraStereo->currentIndex() ==
kSrcStereoVideo -
kSrcStereo);
5220 _ui->groupBox_cameraStereoUsb->setVisible(
_ui->comboBox_sourceType->currentIndex() == 1 &&
_ui->comboBox_cameraStereo->currentIndex() ==
kSrcStereoUsb -
kSrcStereo);
5221 _ui->groupBox_cameraStereoZed->setVisible(
_ui->comboBox_sourceType->currentIndex() == 1 &&
_ui->comboBox_cameraStereo->currentIndex() ==
kSrcStereoZed -
kSrcStereo);
5223 _ui->groupBox_cameraStereoZedOC->setVisible(
_ui->comboBox_sourceType->currentIndex() == 1 &&
_ui->comboBox_cameraStereo->currentIndex() ==
kSrcStereoZedOC -
kSrcStereo);
5226 _ui->stackedWidget_image->setVisible(
_ui->comboBox_sourceType->currentIndex() == 2 &&
5230 _ui->source_groupBox_images->setVisible(
_ui->comboBox_sourceType->currentIndex() == 2 &&
_ui->source_comboBox_image_type->currentIndex() ==
kSrcImages-
kSrcRGB);
5231 _ui->source_groupBox_video->setVisible(
_ui->comboBox_sourceType->currentIndex() == 2 &&
_ui->source_comboBox_image_type->currentIndex() ==
kSrcVideo-
kSrcRGB);
5232 _ui->source_groupBox_usbcam->setVisible(
_ui->comboBox_sourceType->currentIndex() == 2 &&
_ui->source_comboBox_image_type->currentIndex() ==
kSrcUsbDevice-
kSrcRGB);
5234 _ui->groupBox_sourceImages_optional->setVisible(
5237 (
_ui->comboBox_sourceType->currentIndex() == 2 &&
_ui->source_comboBox_image_type->currentIndex() ==
kSrcImages-
kSrcRGB));
5239 _ui->groupBox_depthImageFiltering->setEnabled(
5240 _ui->comboBox_sourceType->currentIndex() == 0 ||
5241 _ui->comboBox_sourceType->currentIndex() == 3);
5242 _ui->groupBox_depthImageFiltering->setVisible(
_ui->groupBox_depthImageFiltering->isEnabled());
5244 _ui->groupBox_imuFiltering->setEnabled(
5247 (
_ui->comboBox_sourceType->currentIndex() == 2 &&
_ui->source_comboBox_image_type->currentIndex() ==
kSrcImages-
kSrcRGB) ||
5249 (
_ui->comboBox_sourceType->currentIndex() == 0 &&
_ui->comboBox_cameraRGBD->currentIndex() ==
kSrcK4A -
kSrcRGBD) ||
5256 _ui->stackedWidget_imuFilter->setVisible(
_ui->comboBox_imuFilter_strategy->currentIndex() > 0);
5257 _ui->groupBox_madgwickfilter->setVisible(
_ui->comboBox_imuFilter_strategy->currentIndex() == 1);
5258 _ui->groupBox_complementaryfilter->setVisible(
_ui->comboBox_imuFilter_strategy->currentIndex() == 2);
5259 _ui->groupBox_imuFiltering->setVisible(
_ui->groupBox_imuFiltering->isEnabled());
5263 _ui->groupBox_depthFromScan->setVisible(
_ui->comboBox_sourceType->currentIndex() == 2 &&
_ui->source_comboBox_image_type->currentIndex() ==
kSrcImages-
kSrcRGB);
5270 return _ui->comboBox_loggerLevel->currentIndex();
5274 return _ui->comboBox_loggerEventLevel->currentIndex();
5278 return _ui->comboBox_loggerPauseLevel->currentIndex();
5282 return _ui->comboBox_loggerType->currentIndex();
5286 return _ui->checkBox_logger_printTime->isChecked();
5290 return _ui->checkBox_logger_printThreadId->isChecked();
5294 std::vector<std::string> threads;
5295 for(
int i=0; i<
_ui->comboBox_loggerFilter->count(); ++i)
5297 if(
_ui->comboBox_loggerFilter->itemData(i).toBool())
5299 threads.push_back(
_ui->comboBox_loggerFilter->itemText(i).toStdString());
5306 return _ui->checkBox_verticalLayoutUsed->isChecked();
5310 return _ui->checkBox_imageRejectedShown->isChecked();
5314 return _ui->checkBox_imageHighestHypShown->isChecked();
5318 return _ui->checkBox_beep->isChecked();
5322 return _ui->checkBox_stamps->isChecked();
5326 return _ui->checkBox_cacheStatistics->isChecked();
5330 return _ui->checkBox_notifyWhenNewGlobalPathIsReceived->isChecked();
5334 return _ui->spinBox_odomQualityWarnThr->value();
5338 return _ui->checkBox_odom_onlyInliersShown->isChecked();
5342 return _ui->radioButton_posteriorGraphView->isChecked();
5346 return _ui->radioButton_wordsGraphView->isChecked();
5350 return _ui->radioButton_localizationsGraphView->isChecked();
5354 return _ui->radioButton_localizationsGraphViewOdomCache->isChecked();
5358 return _ui->checkbox_odomDisabled->isChecked();
5362 return _ui->checkBox_odom_sensor_use_as_gt->isChecked();
5366 return _ui->odom_registration->currentIndex();
5370 return _ui->odom_f2m_gravitySigma->value();
5374 return _ui->checkbox_groundTruthAlign->isChecked();
5379 UASSERT(index >= 0 && index <= 1);
5384 #ifdef RTABMAP_OCTOMAP 5385 return _ui->groupBox_octomap->isChecked();
5391 #ifdef RTABMAP_OCTOMAP 5392 return _ui->groupBox_octomap->isChecked() &&
_ui->checkBox_octomap_show3dMap->isChecked();
5398 return _ui->comboBox_octomap_renderingType->currentIndex();
5402 #ifdef RTABMAP_OCTOMAP 5403 return _ui->groupBox_octomap->isChecked() &&
_ui->checkBox_octomap_2dgrid->isChecked();
5409 return _ui->spinBox_octomap_treeDepth->value();
5413 return _ui->spinBox_octomap_pointSize->value();
5418 return _ui->doubleSpinBox_voxel->value();
5422 return _ui->doubleSpinBox_noiseRadius->value();
5426 return _ui->spinBox_noiseMinNeighbors->value();
5430 return _ui->doubleSpinBox_ceilingFilterHeight->value();
5434 return _ui->doubleSpinBox_floorFilterHeight->value();
5438 return _ui->spinBox_normalKSearch->value();
5442 return _ui->doubleSpinBox_normalRadiusSearch->value();
5446 return _ui->doubleSpinBox_ceilingFilterHeight_scan->value();
5450 return _ui->doubleSpinBox_floorFilterHeight_scan->value();
5454 return _ui->spinBox_normalKSearch_scan->value();
5458 return _ui->doubleSpinBox_normalRadiusSearch_scan->value();
5463 return _ui->checkBox_showGraphs->isChecked();
5467 return _ui->checkBox_showLabels->isChecked();
5471 return _ui->checkBox_showFrames->isChecked();
5475 return _ui->checkBox_showLandmarks->isChecked();
5479 return _ui->doubleSpinBox_landmarkSize->value();
5483 UASSERT(index >= 0 && index <= 1);
5488 UASSERT(index >= 0 && index <= 1);
5493 return _ui->checkBox_showIMUAcc->isChecked();
5497 return _ui->RGBDMarkerDetection->isChecked();
5501 return _ui->ArucoMarkerLength->value();
5505 return _ui->groupBox_organized->isChecked();
5509 return _ui->doubleSpinBox_mesh_angleTolerance->value()*
M_PI/180.0;
5513 return _ui->checkBox_mesh_quad->isChecked();
5517 return _ui->checkBox_mesh_texture->isChecked();
5521 return _ui->spinBox_mesh_triangleSize->value();
5525 UASSERT(index >= 0 && index <= 1);
5530 UASSERT(index >= 0 && index <= 1);
5535 UASSERT(index >= 0 && index <= 1);
5540 UASSERT(index >= 0 && index <= 1);
5541 std::vector<float> roiRatios;
5545 if(values.size() == 4)
5547 roiRatios.resize(4);
5548 for(
int i=0; i<values.size(); ++i)
5550 roiRatios[i] =
uStr2Float(values[i].toStdString().c_str());
5558 UASSERT(index >= 0 && index <= 1);
5563 UASSERT(index >= 0 && index <= 1);
5568 UASSERT(index >= 0 && index <= 1);
5574 UASSERT(index >= 0 && index <= 1);
5579 UASSERT(index >= 0 && index <= 1);
5584 UASSERT(index >= 0 && index <= 1);
5589 UASSERT(index >= 0 && index <= 1);
5594 UASSERT(index >= 0 && index <= 1);
5599 UASSERT(index >= 0 && index <= 1);
5604 UASSERT(index >= 0 && index <= 1);
5609 UASSERT(index >= 0 && index <= 1);
5615 UASSERT(index >= 0 && index <= 1);
5620 UASSERT(index >= 0 && index <= 1);
5625 UASSERT(index >= 0 && index <= 1);
5631 return _ui->radioButton_nodeFiltering->isChecked();
5635 return _ui->radioButton_subtractFiltering->isChecked();
5639 return _ui->doubleSpinBox_cloudFilterRadius->value();
5643 return _ui->doubleSpinBox_cloudFilterAngle->value();
5647 return _ui->spinBox_subtractFilteringMinPts->value();
5651 return _ui->doubleSpinBox_subtractFilteringRadius->value();
5655 return _ui->doubleSpinBox_subtractFilteringAngle->value()*
M_PI/180.0;
5659 return _ui->checkBox_map_shown->isChecked();
5663 return _ui->comboBox_grid_sensor->currentIndex();
5667 return _ui->checkBox_grid_projMapFrame->isChecked();
5671 return _ui->doubleSpinBox_grid_maxGroundAngle->value()*
M_PI/180.0;
5675 return _ui->doubleSpinBox_grid_maxGroundHeight->value();
5679 return _ui->spinBox_grid_minClusterSize->value();
5683 return _ui->doubleSpinBox_grid_maxObstacleHeight->value();
5687 return _ui->checkBox_grid_flatObstaclesDetected->isChecked();
5691 return _ui->doubleSpinBox_map_opacity->value();
5698 return _ui->general_doubleSpinBox_imgRate->value();
5702 return _ui->source_mirroring->isChecked();
5706 int index =
_ui->comboBox_sourceType->currentIndex();
5751 return _ui->comboBox_cameraRGBD->currentText();
5755 return _ui->comboBox_cameraStereo->currentText();
5759 return _ui->source_comboBox_image_type->currentText();
5770 return _ui->lineEdit_sourceDevice->text();
5775 if(
_ui->comboBox_odom_sensor->currentIndex() == 1)
5780 else if(
_ui->comboBox_odom_sensor->currentIndex() == 2)
5785 else if(
_ui->comboBox_odom_sensor->currentIndex() != 0)
5787 UERROR(
"Not implemented!");
5814 return _ui->lineEdit_cameraImages_path_imu->text();
5827 return _ui->spinBox_cameraImages_max_imu_rate->value();
5832 return _ui->source_checkBox_useDbStamps->isChecked();
5836 return _ui->checkbox_rgbd_colorOnly->isChecked();
5840 return _ui->comboBox_imuFilter_strategy->currentIndex();
5844 return _ui->checkBox_imuFilter_baseFrameConversion->isChecked();
5848 return _ui->groupBox_depthImageFiltering->isEnabled();
5852 return _ui->lineEdit_source_distortionModel->text();
5856 return _ui->groupBox_bilateral->isChecked();
5860 return _ui->doubleSpinBox_bilateral_sigmaS->value();
5864 return _ui->doubleSpinBox_bilateral_sigmaR->value();
5868 return _ui->spinBox_source_imageDecimation->value();
5872 return _ui->checkbox_stereo_depthGenerated->isChecked();
5876 return _ui->checkBox_stereo_exposureCompensation->isChecked();
5880 return _ui->checkBox_source_scanFromDepth->isChecked();
5884 return _ui->spinBox_source_scanDownsampleStep->value();
5888 return _ui->doubleSpinBox_source_scanRangeMin->value();
5892 return _ui->doubleSpinBox_source_scanRangeMax->value();
5896 return _ui->doubleSpinBox_source_scanVoxelSize->value();
5900 return _ui->spinBox_source_scanNormalsK->value();
5904 return _ui->doubleSpinBox_source_scanNormalsRadius->value();
5908 return _ui->doubleSpinBox_source_scanNormalsForceGroundUp->value();
5915 _ui->lineEdit_sourceDevice->text(),
5916 _ui->lineEdit_calibrationFile->text(),
5926 const QString & calibrationPath,
5930 bool odomSensorExtrinsicsCalib)
5934 QMessageBox::warning(
this, tr(
"Odometry Sensor"),
5935 tr(
"Driver \%1 cannot support odometry only mode.").arg(driver), QMessageBox::Ok);
5945 QMessageBox::warning(
this, tr(
"Calibration"),
5946 tr(
"Using raw images for \"OpenNI\" driver is not yet supported. " 5947 "Factory calibration loaded from OpenNI is used."), QMessageBox::Ok);
5953 _ui->lineEdit_openniOniPath->text().isEmpty()?device.toStdString():
_ui->lineEdit_openniOniPath->text().toStdString(),
5961 _ui->lineEdit_openni2OniPath->text().isEmpty()?device.toStdString():
_ui->lineEdit_openni2OniPath->text().toStdString(),
5969 device.isEmpty()?0:atoi(device.toStdString().c_str()),
5979 QMessageBox::warning(
this, tr(
"Calibration"),
5980 tr(
"Using raw images for \"OpenNI\" driver is not yet supported. " 5981 "Factory calibration loaded from OpenNI is used."), QMessageBox::Ok);
5995 device.isEmpty()?0:atoi(device.toStdString().c_str()),
5999 _ui->doubleSpinBox_freenect2MinDepth->value(),
6000 _ui->doubleSpinBox_freenect2MaxDepth->value(),
6001 _ui->checkBox_freenect2BilateralFiltering->isChecked(),
6002 _ui->checkBox_freenect2EdgeAwareFiltering->isChecked(),
6003 _ui->checkBox_freenect2NoiseFiltering->isChecked(),
6004 _ui->lineEdit_freenect2Pipeline->text().toStdString());
6009 device.isEmpty() ? 0 : atoi(device.toStdString().c_str()),
6016 if (!
_ui->lineEdit_k4a_mkv->text().isEmpty())
6020 _ui->lineEdit_k4a_mkv->text().toStdString().c_str(),
6027 device.isEmpty() ? 0 : atoi(device.toStdString().c_str()),
6033 ((
CameraK4A*)camera)->setPreferences(
_ui->comboBox_k4a_rgb_resolution->currentIndex(),
6034 _ui->comboBox_k4a_framerate->currentIndex(),
6035 _ui->comboBox_k4a_depth_resolution->currentIndex());
6039 if(useRawImages &&
_ui->comboBox_realsenseRGBSource->currentIndex()!=2)
6041 QMessageBox::warning(
this, tr(
"Calibration"),
6042 tr(
"Using raw images for \"RealSense\" driver is not yet supported for color and infrared streams. " 6043 "Factory calibration loaded from RealSense is used."), QMessageBox::Ok);
6049 device.isEmpty() ? 0 : atoi(device.toStdString().c_str()),
6050 _ui->comboBox_realsensePresetRGB->currentIndex(),
6051 _ui->comboBox_realsensePresetDepth->currentIndex(),
6052 _ui->checkbox_realsenseOdom->isChecked(),
6063 QMessageBox::warning(
this, tr(
"Calibration"),
6064 tr(
"Using raw images for \"RealSense\" driver is not yet supported. " 6065 "Factory calibration loaded from RealSense2 is used."), QMessageBox::Ok);
6077 ((
CameraRealSense2*)camera)->setImagesRectified((
_ui->checkBox_stereo_rectify->isEnabled() &&
_ui->checkBox_stereo_rectify->isChecked()) && !useRawImages);
6078 ((
CameraRealSense2*)camera)->setOdomProvided(
_ui->comboBox_odom_sensor->currentIndex() == 1 || odomOnly, odomOnly, odomSensorExtrinsicsCalib);
6083 ((
CameraRealSense2*)camera)->setIRFormat(
_ui->checkbox_rs2_irMode->isChecked(),
_ui->checkbox_rs2_irDepth->isChecked());
6084 ((
CameraRealSense2*)camera)->setResolution(
_ui->spinBox_rs2_width->value(),
_ui->spinBox_rs2_height->value(),
_ui->spinBox_rs2_rate->value());
6085 ((
CameraRealSense2*)camera)->setDepthResolution(
_ui->spinBox_rs2_width_depth->value(),
_ui->spinBox_rs2_height_depth->value(),
_ui->spinBox_rs2_rate_depth->value());
6086 ((
CameraRealSense2*)camera)->setGlobalTimeSync(
_ui->checkbox_rs2_globalTimeStync->isChecked());
6088 ((
CameraRealSense2*)camera)->setJsonConfig(
_ui->lineEdit_rs2_jsonFile->text().toStdString());
6096 QMessageBox::warning(
this, tr(
"Calibration"),
6097 tr(
"Using raw images for \"MyntEye\" driver is not yet supported. " 6098 "Factory calibration loaded from MyntEye is used."), QMessageBox::Ok);
6104 device.toStdString(),
6105 _ui->checkbox_stereoMyntEye_rectify->isChecked(),
6106 _ui->checkbox_stereoMyntEye_depth->isChecked(),
6110 if(
_ui->checkbox_stereoMyntEye_autoExposure->isChecked())
6117 _ui->spinBox_stereoMyntEye_gain->value(),
6118 _ui->spinBox_stereoMyntEye_brightness->value(),
6119 _ui->spinBox_stereoMyntEye_contrast->value());
6122 _ui->spinBox_stereoMyntEye_irControl->value());
6128 _ui->lineEdit_cameraRGBDImages_path_rgb->text().append(QDir::separator()).toStdString(),
6129 _ui->lineEdit_cameraRGBDImages_path_depth->text().append(QDir::separator()).toStdString(),
6130 _ui->doubleSpinBox_cameraRGBDImages_scale->value(),
6134 ((
CameraRGBDImages*)camera)->setMaxFrames(
_ui->spinBox_cameraRGBDImages_maxFrames->value());
6135 ((
CameraRGBDImages*)camera)->setBayerMode(
_ui->comboBox_cameraImages_bayerMode->currentIndex()-1);
6136 ((
CameraRGBDImages*)camera)->setOdometryPath(
_ui->lineEdit_cameraImages_odom->text().toStdString(),
_ui->comboBox_cameraImages_odomFormat->currentIndex());
6137 ((
CameraRGBDImages*)camera)->setGroundTruthPath(
_ui->lineEdit_cameraImages_gt->text().toStdString(),
_ui->comboBox_cameraImages_gtFormat->currentIndex());
6138 ((
CameraRGBDImages*)camera)->setMaxPoseTimeDiff(
_ui->doubleSpinBox_maxPoseTimeDiff->value());
6140 _ui->lineEdit_cameraImages_path_scans->text().isEmpty()?
"":
_ui->lineEdit_cameraImages_path_scans->text().append(QDir::separator()).toStdString(),
6141 _ui->spinBox_cameraImages_max_scan_pts->value(),
6144 _ui->checkBox_cameraImages_timestamps->isChecked(),
6145 _ui->lineEdit_cameraImages_timestamps->text().toStdString(),
6146 _ui->checkBox_cameraImages_syncTimeStamps->isChecked());
6147 ((
CameraRGBDImages*)camera)->setConfigForEachFrame(
_ui->checkBox_cameraImages_configForEachFrame->isChecked());
6159 QMessageBox::warning(
this, tr(
"Calibration"),
6160 tr(
"Using raw images for \"FlyCapture2\" driver is not yet supported. " 6161 "Factory calibration loaded from FlyCapture2 is used."), QMessageBox::Ok);
6174 _ui->lineEdit_cameraStereoImages_path_left->text().append(QDir::separator()).toStdString(),
6175 _ui->lineEdit_cameraStereoImages_path_right->text().append(QDir::separator()).toStdString(),
6176 (
_ui->checkBox_stereo_rectify->isEnabled() &&
_ui->checkBox_stereo_rectify->isChecked()) && !useRawImages,
6181 ((
CameraStereoImages*)camera)->setBayerMode(
_ui->comboBox_cameraImages_bayerMode->currentIndex()-1);
6182 ((
CameraStereoImages*)camera)->setOdometryPath(
_ui->lineEdit_cameraImages_odom->text().toStdString(),
_ui->comboBox_cameraImages_odomFormat->currentIndex());
6183 ((
CameraStereoImages*)camera)->setGroundTruthPath(
_ui->lineEdit_cameraImages_gt->text().toStdString(),
_ui->comboBox_cameraImages_gtFormat->currentIndex());
6186 _ui->lineEdit_cameraImages_path_scans->text().isEmpty()?
"":
_ui->lineEdit_cameraImages_path_scans->text().append(QDir::separator()).toStdString(),
6187 _ui->spinBox_cameraImages_max_scan_pts->value(),
6190 _ui->checkBox_cameraImages_timestamps->isChecked(),
6191 _ui->lineEdit_cameraImages_timestamps->text().toStdString(),
6192 _ui->checkBox_cameraImages_syncTimeStamps->isChecked());
6193 ((
CameraRGBDImages*)camera)->setConfigForEachFrame(
_ui->checkBox_cameraImages_configForEachFrame->isChecked());
6198 if(
_ui->spinBox_stereo_right_device->value()>=0)
6201 device.isEmpty() ? 0 : atoi(device.toStdString().c_str()),
6202 _ui->spinBox_stereo_right_device->value(),
6203 (
_ui->checkBox_stereo_rectify->isEnabled() &&
_ui->checkBox_stereo_rectify->isChecked()) && !useRawImages,
6210 device.isEmpty() ? 0 : atoi(device.toStdString().c_str()),
6211 (
_ui->checkBox_stereo_rectify->isEnabled() &&
_ui->checkBox_stereo_rectify->isChecked()) && !useRawImages,
6219 if(!
_ui->lineEdit_cameraStereoVideo_path_2->text().isEmpty())
6223 _ui->lineEdit_cameraStereoVideo_path->text().toStdString(),
6224 _ui->lineEdit_cameraStereoVideo_path_2->text().toStdString(),
6225 (
_ui->checkBox_stereo_rectify->isEnabled() &&
_ui->checkBox_stereo_rectify->isChecked()) && !useRawImages,
6233 _ui->lineEdit_cameraStereoVideo_path->text().toStdString(),
6234 (
_ui->checkBox_stereo_rectify->isEnabled() &&
_ui->checkBox_stereo_rectify->isChecked()) && !useRawImages,
6244 device.isEmpty()?0:atoi(device.toStdString().c_str()),
6245 (
_ui->checkBox_stereo_rectify->isEnabled() &&
_ui->checkBox_stereo_rectify->isChecked()) && !useRawImages,
6253 if(!
_ui->lineEdit_zedSvoPath->text().isEmpty())
6256 _ui->lineEdit_zedSvoPath->text().toStdString(),
6257 _ui->comboBox_stereoZed_quality->currentIndex(),
6258 _ui->comboBox_stereoZed_sensingMode->currentIndex(),
6259 _ui->spinBox_stereoZed_confidenceThr->value(),
6260 _ui->comboBox_odom_sensor->currentIndex() == 2,
6263 _ui->checkbox_stereoZed_selfCalibration->isChecked(),
6264 _ui->loopClosure_bowForce2D->isChecked(),
6265 _ui->spinBox_stereoZed_texturenessConfidenceThr->value());
6270 device.isEmpty()?0:atoi(device.toStdString().c_str()),
6271 _ui->comboBox_stereoZed_resolution->currentIndex(),
6273 _ui->comboBox_stereoZed_quality->currentIndex()==0&&odomOnly?1:
_ui->comboBox_stereoZed_quality->currentIndex(),
6274 _ui->comboBox_stereoZed_sensingMode->currentIndex(),
6275 _ui->spinBox_stereoZed_confidenceThr->value(),
6276 _ui->comboBox_odom_sensor->currentIndex() == 2 || odomOnly,
6279 _ui->checkbox_stereoZed_selfCalibration->isChecked(),
6280 _ui->loopClosure_bowForce2D->isChecked(),
6281 _ui->spinBox_stereoZed_texturenessConfidenceThr->value());
6289 device.isEmpty()?-1:atoi(device.toStdString().c_str()),
6290 _ui->comboBox_stereoZedOC_resolution->currentIndex(),
6298 device.toStdString().c_str(),
6299 _ui->comboBox_depthai_resolution->currentIndex(),
6303 ((
CameraDepthAI*)camera)->setIMUFirmwareUpdate(
_ui->checkBox_depthai_imu_firmware_update->isChecked());
6304 ((
CameraDepthAI*)camera)->setIMUPublished(
_ui->checkBox_depthai_imu_published->isChecked());
6309 device.isEmpty()?0:atoi(device.toStdString().c_str()),
6310 (
_ui->checkBox_rgb_rectify->isEnabled() &&
_ui->checkBox_rgb_rectify->isChecked()) && !useRawImages,
6318 _ui->source_video_lineEdit_path->text().toStdString(),
6319 (
_ui->checkBox_rgb_rectify->isEnabled() &&
_ui->checkBox_rgb_rectify->isChecked()) && !useRawImages,
6326 _ui->source_images_lineEdit_path->text().toStdString(),
6331 ((
CameraImages*)camera)->setMaxFrames(
_ui->source_images_spinBox_maxFrames->value());
6332 ((
CameraImages*)camera)->setImagesRectified((
_ui->checkBox_rgb_rectify->isEnabled() &&
_ui->checkBox_rgb_rectify->isChecked()) && !useRawImages);
6334 ((
CameraImages*)camera)->setBayerMode(
_ui->comboBox_cameraImages_bayerMode->currentIndex()-1);
6336 _ui->lineEdit_cameraImages_odom->text().toStdString(),
6337 _ui->comboBox_cameraImages_odomFormat->currentIndex());
6339 _ui->lineEdit_cameraImages_gt->text().toStdString(),
6340 _ui->comboBox_cameraImages_gtFormat->currentIndex());
6341 ((
CameraImages*)camera)->setMaxPoseTimeDiff(
_ui->doubleSpinBox_maxPoseTimeDiff->value());
6343 _ui->lineEdit_cameraImages_path_scans->text().isEmpty()?
"":
_ui->lineEdit_cameraImages_path_scans->text().append(QDir::separator()).toStdString(),
6344 _ui->spinBox_cameraImages_max_scan_pts->value(),
6347 _ui->groupBox_depthFromScan->isChecked(),
6348 !
_ui->groupBox_depthFromScan_fillHoles->isChecked()?0:
_ui->radioButton_depthFromScan_vertical->isChecked()?1:-1,
6349 _ui->checkBox_depthFromScan_fillBorders->isChecked());
6351 _ui->checkBox_cameraImages_timestamps->isChecked(),
6352 _ui->lineEdit_cameraImages_timestamps->text().toStdString(),
6353 _ui->checkBox_cameraImages_syncTimeStamps->isChecked());
6354 ((
CameraRGBDImages*)camera)->setConfigForEachFrame(
_ui->checkBox_cameraImages_configForEachFrame->isChecked());
6358 camera =
new DBReader(
_ui->source_database_lineEdit_path->text().toStdString(),
6360 _ui->source_checkBox_ignoreOdometry->isChecked(),
6361 _ui->source_checkBox_ignoreGoalDelay->isChecked(),
6362 _ui->source_checkBox_ignoreGoals->isChecked(),
6363 _ui->source_spinBox_databaseStartId->value(),
6364 _ui->source_spinBox_database_cameraIndex->value(),
6365 _ui->source_spinBox_databaseStopId->value(),
6366 !
_ui->general_checkBox_createIntermediateNodes->isChecked(),
6367 _ui->source_checkBox_ignoreLandmarks->isChecked(),
6368 _ui->source_checkBox_ignoreFeatures->isChecked());
6372 UFATAL(
"Source driver undefined (%d)!", driver);
6379 QString calibrationFile = calibrationPath;
6382 calibrationFile.remove(
"_left.yaml").remove(
"_right.yaml").remove(
"_pose.yaml").remove(
"_rgb.yaml").remove(
"_depth.yaml");
6384 QString
name = QFileInfo(calibrationFile.remove(
".yaml")).fileName();
6385 if(!calibrationPath.isEmpty())
6387 QDir
d = QFileInfo(calibrationPath).dir();
6388 QString tmp = calibrationPath;
6389 if(!tmp.remove(QFileInfo(calibrationPath).baseName()).isEmpty())
6391 dir = d.absolutePath();
6395 UDEBUG(
"useRawImages=%d dir=%s", useRawImages?1:0, dir.toStdString().c_str());
6397 if(!camera->
init(useRawImages?
"":dir.toStdString(), name.toStdString()))
6399 UWARN(
"init camera failed... ");
6400 QMessageBox::warning(
this,
6402 tr(
"Camera initialization failed..."));
6411 ((
CameraOpenNI2*)camera)->setAutoWhiteBalance(
_ui->openni2_autoWhiteBalance->isChecked());
6412 ((
CameraOpenNI2*)camera)->setAutoExposure(
_ui->openni2_autoExposure->isChecked());
6413 ((
CameraOpenNI2*)camera)->setMirroring(
_ui->openni2_mirroring->isChecked());
6414 ((
CameraOpenNI2*)camera)->setOpenNI2StampsAndIDsUsed(
_ui->openni2_stampsIdsUsed->isChecked());
6420 ((
CameraOpenNI2*)camera)->setIRDepthShift(
_ui->openni2_hshift->value(),
_ui->openni2_vshift->value());
6421 ((
CameraOpenNI2*)camera)->setMirroring(
_ui->openni2_mirroring->isChecked());
6422 ((
CameraOpenNI2*)camera)->setDepthDecimation(
_ui->openni2_depth_decimation->value());
6437 _ui->lineEdit_odomSourceDevice->text().compare(
_ui->lineEdit_sourceDevice->text()) == 0)
6439 QMessageBox::warning(
this, tr(
"Odometry Sensor"),
6440 tr(
"Cannot create an odometry sensor with same driver than camera AND with same " 6441 "device. Change device ID of the odometry or camera sensor. To use odometry option " 6442 "from a single camera, look at the parameters of that driver to enable it, " 6443 "then disable odometry sensor. "), QMessageBox::Ok);
6447 extrinsics =
Transform::fromString(
_ui->lineEdit_odom_sensor_extrinsics->text().replace(
"PI_2", QString::number(3.141592/2.0)).toStdString());
6448 timeOffset =
_ui->doubleSpinBox_odom_sensor_time_offset->value()/1000.0;
6449 scaleFactor = (float)
_ui->doubleSpinBox_odom_sensor_scale_factor->value();
6451 return createCamera(driver,
_ui->lineEdit_odomSourceDevice->text(),
_ui->lineEdit_odom_sensor_path_calibration->text(),
false,
true,
true,
false);
6458 return _ui->groupBox_publishing->isChecked();
6462 return _ui->general_doubleSpinBox_hardThr->value();
6466 return _ui->general_doubleSpinBox_vp->value();
6470 return _ui->doubleSpinBox_similarityThreshold->value();
6474 return _ui->odom_strategy->currentIndex();
6478 return _ui->odom_dataBufferSize->value();
6488 return _ui->general_checkBox_imagesKept->isChecked();
6492 return _ui->general_checkBox_missing_cache_republished->isChecked();
6496 return _ui->general_checkBox_cloudsKept->isChecked();
6500 return _ui->general_doubleSpinBox_timeThr->value();
6504 return _ui->general_doubleSpinBox_detectionRate->value();
6508 return _ui->general_checkBox_SLAM_mode->isChecked();
6512 return _ui->general_checkBox_activateRGBD->isChecked();
6516 return _ui->surf_spinBox_wordsPerImageTarget->value();
6520 return _ui->graphOptimization_priorsIgnored->isChecked();
6527 if(
_ui->general_doubleSpinBox_imgRate->value() != value)
6529 _ui->general_doubleSpinBox_imgRate->setValue(value);
6544 if(
_ui->general_doubleSpinBox_detectionRate->value() != value)
6546 _ui->general_doubleSpinBox_detectionRate->setValue(value);
6561 if(
_ui->general_doubleSpinBox_timeThr->value() != value)
6563 _ui->general_doubleSpinBox_timeThr->setValue(value);
6578 if(
_ui->general_checkBox_SLAM_mode->isChecked() != enabled)
6580 _ui->general_checkBox_SLAM_mode->setChecked(enabled);
6604 !
_ui->lineEdit_cameraImages_path_imu->text().isEmpty())
6611 QMessageBox::warning(
this, tr(
"Source IMU Path"),
6612 tr(
"IMU path is set but odometry chosen doesn't support asynchronous IMU, ignoring IMU..."), QMessageBox::Ok);
6617 if(!imuThread->
init(
_ui->lineEdit_cameraImages_path_imu->text().toStdString()))
6619 QMessageBox::warning(
this, tr(
"Source IMU Path"),
6620 tr(
"Initialization of IMU data has failed! Path=%1.").arg(
_ui->lineEdit_cameraImages_path_imu->text()), QMessageBox::Ok);
6634 int odomStrategy = Parameters::defaultOdomStrategy();
6636 if(odomStrategy != 1)
6639 parameters.erase(Parameters::kVisCorType());
6646 _ui->odom_dataBufferSize->value());
6650 _ui->spinBox_decimation_odom->value(),
6652 _ui->doubleSpinBox_maxDepth_odom->value(),
6656 odomViewer->setWindowTitle(tr(
"Odometry viewer"));
6657 odomViewer->resize(1280, 480+QPushButton().minimumHeight());
6667 _ui->checkBox_source_scanFromDepth->isChecked(),
6668 _ui->spinBox_source_scanDownsampleStep->value(),
6669 _ui->doubleSpinBox_source_scanRangeMin->value(),
6670 _ui->doubleSpinBox_source_scanRangeMax->value(),
6671 _ui->doubleSpinBox_source_scanVoxelSize->value(),
6672 _ui->spinBox_source_scanNormalsK->value(),
6673 _ui->doubleSpinBox_source_scanNormalsRadius->value(),
6674 (float)
_ui->doubleSpinBox_source_scanNormalsForceGroundUp->value());
6675 if(
_ui->comboBox_imuFilter_strategy->currentIndex()>0 &&
dynamic_cast<DBReader*
>(camera) == 0)
6681 if(
_ui->groupBox_bilateral->isChecked())
6684 _ui->doubleSpinBox_bilateral_sigmaS->value(),
6685 _ui->doubleSpinBox_bilateral_sigmaR->value());
6687 if(!
_ui->lineEdit_source_distortionModel->text().isEmpty())
6702 cameraThread.
start();
6714 imuThread->
join(
true);
6717 cameraThread.
join(
true);
6718 odomThread.join(
true);
6724 window->setWindowTitle(tr(
"Camera viewer"));
6725 window->resize(1280, 480+QPushButton().minimumHeight());
6738 _ui->checkBox_source_scanFromDepth->isChecked(),
6739 _ui->spinBox_source_scanDownsampleStep->value(),
6740 _ui->doubleSpinBox_source_scanRangeMin->value(),
6741 _ui->doubleSpinBox_source_scanRangeMax->value(),
6742 _ui->doubleSpinBox_source_scanVoxelSize->value(),
6743 _ui->spinBox_source_scanNormalsK->value(),
6744 _ui->doubleSpinBox_source_scanNormalsRadius->value(),
6745 (float)
_ui->doubleSpinBox_source_scanNormalsForceGroundUp->value());
6746 if(
_ui->comboBox_imuFilter_strategy->currentIndex()>0 &&
dynamic_cast<DBReader*
>(camera) == 0)
6752 if(
_ui->groupBox_bilateral->isChecked())
6755 _ui->doubleSpinBox_bilateral_sigmaS->value(),
6756 _ui->doubleSpinBox_bilateral_sigmaR->value());
6758 if(!
_ui->lineEdit_source_distortionModel->text().isEmpty())
6765 cameraThread.
start();
6768 cameraThread.
join(
true);
6780 QMessageBox::warning(
this,
6782 tr(
"Cannot calibrate database source!"));
6792 if(!dir.mkpath(this->getCameraInfoDir()))
6794 UWARN(
"Could create camera_info directory: \"%s\"", this->
getCameraInfoDir().toStdString().c_str());
6803 QMessageBox::StandardButton button = QMessageBox::question(
this, tr(
"Calibration"),
6804 tr(
"With \"%1\" driver, Color and IR cameras cannot be streamed at the " 6805 "same time. A 3-steps calibration is required (Color -> IR -> extrinsics). We will " 6806 "start with the Color camera calibration. Do you want to continue?").arg(this->
getSourceDriverStr()),
6807 QMessageBox::Yes | QMessageBox::No | QMessageBox::Ignore, QMessageBox::Yes);
6809 if(button == QMessageBox::Yes || button == QMessageBox::Ignore)
6816 if(button != QMessageBox::Ignore)
6829 cameraThread.
start();
6832 cameraThread.
join(
true);
6836 button = QMessageBox::question(
this, tr(
"Calibration"),
6837 tr(
"We will now calibrate the IR camera. Hide the IR projector with a Post-It and " 6838 "make sure you have enough ambient IR light (e.g., external IR source or sunlight!) to see the " 6839 "checkerboard with the IR camera. Do you want to continue?"),
6840 QMessageBox::Yes | QMessageBox::No | QMessageBox::Ignore, QMessageBox::Yes);
6841 if(button == QMessageBox::Yes || button == QMessageBox::Ignore)
6844 if(button != QMessageBox::Ignore)
6857 cameraThread.
start();
6860 cameraThread.
join(
true);
6864 button = QMessageBox::question(
this, tr(
"Calibration"),
6865 tr(
"We will now calibrate the extrinsics. Important: Make sure " 6866 "the cameras and the checkerboard don't move and that both " 6867 "cameras can see the checkerboard. We will repeat this " 6868 "multiple times. Each time, you will have to move the camera (or " 6869 "checkerboard) for a different point of view. Do you want to " 6871 QMessageBox::Yes | QMessageBox::No, QMessageBox::Yes);
6874 int totalSamples = 0;
6875 if(button == QMessageBox::Yes)
6877 totalSamples = QInputDialog::getInt(
this, tr(
"Calibration"), tr(
"Samples: "), 1, 1, 99, 1, &ok);
6891 for(;count < totalSamples && button == QMessageBox::Yes; )
6922 if(count < totalSamples)
6924 button = QMessageBox::question(
this, tr(
"Calibration"),
6925 tr(
"A stereo pair has been taken (total=%1/%2). Move the checkerboard or " 6926 "camera to another position. Press \"Yes\" when you are ready " 6927 "for the next capture.").arg(count).arg(totalSamples),
6928 QMessageBox::Yes | QMessageBox::Abort, QMessageBox::Yes);
6933 button = QMessageBox::question(
this, tr(
"Calibration"),
6934 tr(
"Could not detect the checkerboard on both images or " 6935 "the point of view didn't change enough. Try again?"),
6936 QMessageBox::Yes | QMessageBox::No, QMessageBox::Yes);
6941 button = QMessageBox::question(
this, tr(
"Calibration"),
6942 tr(
"Failed to start the camera. Try again?"), QMessageBox::Yes | QMessageBox::No, QMessageBox::Yes);
6945 if(count == totalSamples && button == QMessageBox::Yes)
6948 stereoModel.
setName(stereoModel.
name(),
"depth",
"rgb");
6951 QMessageBox::warning(
this, tr(
"Calibration"),
6952 tr(
"Extrinsic calibration has failed! Look on the terminal " 6953 "for possible error messages. Make sure corresponding calibration files exist " 6954 "in \"%1\" folder for camera \"%2\" or calibration name set. If not, re-do " 6955 "step 1 and 2 and make sure to export the calibration files.").arg(this->
getCameraInfoDir()).arg(serial.c_str()), QMessageBox::Ok);
6959 QMessageBox::information(
this, tr(
"Calibration"),
6960 tr(
"Calibration is completed! Extrinsics have been saved to \"%1/%2_pose.yaml\"").arg(this->
getCameraInfoDir()).arg(stereoModel.
name().c_str()), QMessageBox::Ok);
6987 cameraThread.
start();
6992 cameraThread.
join(
true);
7009 QMessageBox::warning(
this,
7011 tr(
"Cannot calibrate database source!"));
7021 if(!dir.mkpath(this->getCameraInfoDir()))
7023 UWARN(
"Could create camera_info directory: \"%s\"", this->
getCameraInfoDir().toStdString().c_str());
7029 if(
_ui->comboBox_odom_sensor->currentIndex() == 0)
7031 QMessageBox::warning(
this,
7033 tr(
"No odometry sensor selected!"));
7036 else if(
_ui->comboBox_odom_sensor->currentIndex() == 1)
7040 else if(
_ui->comboBox_odom_sensor->currentIndex() == 2)
7046 UERROR(
"Odom sensor %d not implemented",
_ui->comboBox_odom_sensor->currentIndex());
7052 QMessageBox::StandardButton button = QMessageBox::question(
this, tr(
"Calibration"),
7053 tr(
"We will calibrate the extrinsics. Important: Make sure " 7054 "the cameras and the checkerboard don't move and that both " 7055 "cameras can see the checkerboard. We will repeat this " 7056 "multiple times. Each time, you will have to move the camera (or " 7057 "checkerboard) for a different point of view. Do you want to " 7059 QMessageBox::Yes | QMessageBox::No, QMessageBox::Yes);
7061 if(button == QMessageBox::Yes)
7066 int totalSamples = 0;
7067 if(button == QMessageBox::Yes)
7069 QDialog dialog(
this);
7070 QFormLayout form(&dialog);
7073 QSpinBox * samples =
new QSpinBox(&dialog);
7074 samples->setMinimum(1);
7075 samples->setMaximum(99);
7076 samples->setValue(1);
7077 QSpinBox * boardWidth =
new QSpinBox(&dialog);
7078 boardWidth->setMinimum(2);
7079 boardWidth->setMaximum(99);
7081 QSpinBox * boardHeight =
new QSpinBox(&dialog);
7082 boardHeight->setMinimum(2);
7083 boardHeight->setMaximum(99);
7085 QDoubleSpinBox * squareSize =
new QDoubleSpinBox(&dialog);
7086 squareSize->setDecimals(4);
7087 squareSize->setMinimum(0.0001);
7088 squareSize->setMaximum(9);
7090 squareSize->setSuffix(
" m");
7091 form.addRow(
"Samples: ", samples);
7092 form.addRow(
"Checkerboard Width: ", boardWidth);
7093 form.addRow(
"Checkerboard Height: ", boardHeight);
7094 form.addRow(
"Checkerboard Square Size: ", squareSize);
7097 QDialogButtonBox buttonBox(QDialogButtonBox::Ok | QDialogButtonBox::Cancel,
7098 Qt::Horizontal, &dialog);
7099 form.addRow(&buttonBox);
7100 QObject::connect(&buttonBox, SIGNAL(accepted()), &dialog, SLOT(accept()));
7101 QObject::connect(&buttonBox, SIGNAL(rejected()), &dialog, SLOT(reject()));
7104 if (dialog.exec() == QDialog::Accepted) {
7108 totalSamples = samples->value();
7125 for(;count < totalSamples && button == QMessageBox::Yes; )
7130 _ui->lineEdit_odomSourceDevice->text(),
7131 _ui->lineEdit_odom_sensor_path_calibration->text(),
7132 false,
true,
false,
true);
7140 tr(
"Odom sensor is not calibrated. Camera and odometry sensor should be individually calibrated (intrinsics) before calibrating the extrinsics between them. Aborting..."), QMessageBox::Ok);
7153 int currentIndex =
_ui->comboBox_odom_sensor->currentIndex();
7154 _ui->comboBox_odom_sensor->setCurrentIndex(0);
7156 _ui->comboBox_odom_sensor->setCurrentIndex(currentIndex);
7164 tr(
"Odom sensor is not calibrated. Camera and odometry sensor should be individually calibrated (intrinsics) before calibrating the extrinsics between them. Aborting..."), QMessageBox::Ok);
7185 if(count < totalSamples)
7188 tr(
"A stereo pair has been taken (total=%1/%2). Move the checkerboard or " 7189 "camera to another position. Press \"Yes\" when you are ready " 7190 "for the next capture.").arg(count).arg(totalSamples),
7191 QMessageBox::Yes | QMessageBox::Abort, QMessageBox::Yes);
7197 tr(
"Could not detect the checkerboard on both images or " 7198 "the point of view didn't change enough. Try again?"),
7199 QMessageBox::Yes | QMessageBox::No, QMessageBox::Yes);
7205 tr(
"Failed to start the camera. Try again?"), QMessageBox::Yes | QMessageBox::No, QMessageBox::Yes);
7208 if(count == totalSamples && button == QMessageBox::Yes)
7212 odomSensorModel =
CameraModel(
"odom_sensor", odomSensorModel.
imageSize(), odomSensorModel.
K(), cv::Mat::zeros(1,5,CV_64FC1), cv::Mat(), cv::Mat(), odomSensorModel.
localTransform());
7215 stereoModel.
setName(stereoModel.name(),
"camera",
"odom_sensor");
7216 if(stereoModel.stereoTransform().isNull())
7219 tr(
"Extrinsic calibration has failed! Look on the terminal " 7220 "for possible error messages."), QMessageBox::Ok);
7221 std::cout <<
"stereoModel: " << stereoModel << std::endl;
7226 UINFO(
"Extrinsics (odom left cam to camera left cam): %s", stereoModel.stereoTransform().prettyPrint().c_str());
7229 UINFO(
"Odom sensor frame to camera frame: %s", t.prettyPrint().c_str());
7232 t.getTranslationAndEulerAngles(x, y, z, roll, pitch, yaw);
7233 _ui->lineEdit_odom_sensor_extrinsics->setText(QString(
"%1 %2 %3 %4 %5 %6")
7234 .arg(x).arg(y).arg(z)
7235 .arg(roll).arg(pitch).arg(yaw));
7237 tr(
"Calibration is completed! Extrinsics have been computed: %1. " 7238 "You can close the calibration dialog.").arg(t.prettyPrint().c_str()), QMessageBox::Ok);
GLM_FUNC_DECL T roll(detail::tquat< T, P > const &x)
bool parseModel(QList< QGroupBox *> &boxes, QStandardItem *parentItem, int currentLevel, int &absoluteIndex)
static bool parse(const ParametersMap ¶meters, const std::string &key, bool &value)
bool notifyWhenNewGlobalPathIsReceived() const
void selectSourceImagesPathScans()
void processImages(const cv::Mat &imageLeft, const cv::Mat &imageRight, const QString &cameraName)
const cv::Size & imageSize() const
QVector< QSpinBox * > _3dRenderingDownsamplingScan
void setParameter(const std::string &key, const std::string &value)
Camera * createCamera(bool useRawImages=false, bool useColor=true)
void saveMainWindowState(const QMainWindow *mainWindow)
double getLoopThr() const
bool imageRejectedShown() const
void updateParameters(const ParametersMap ¶meters, bool setOtherParametersToDefault=false)
QString getIMUPath() const
bool getGeneralLoggerPrintThreadId() const
bool projFlatObstaclesDetected() const
static void createPipe(const UEventsSender *sender, const UEventsHandler *receiver, const std::string &eventName)
bool isSubtractFiltering() const
double getBilateralSigmaR() const
void updateOdometryStackedIndex(int index)
bool isCloudFiltering() const
void setStereoExposureCompensation(bool enabled)
rtabmap::ParametersMap _parameters
static bool isCSparseAvailable()
virtual QString getTmpIniFilePath() const
int getNormalKSearch() const
int getGeneralLoggerEventLevel() const
bool saveStereoTransform(const std::string &directory) const
bool init(const std::string &path)
bool isRelocalizationColorOdomCacheGraphView() const
int getCloudColorScheme(int index) const
void setBoardWidth(int width)
bool isDepthFilteringAvailable() const
double UTILITE_EXP uStr2Double(const std::string &str)
bool projMapFrame() const
StereoCameraModel stereoCalibration(const CameraModel &left, const CameraModel &right, bool ignoreStereoRectification) const
rtabmap::ParametersMap getAllParameters() const
virtual QString getDefaultWorkingDirectory() const
PreferencesDialog::Src getSourceType() const
bool isGroundTruthAligned() const
void selectSourceImagesPathOdom()
void saveSettings(QSettings &settings, const QString &group="") const
void setOutputDepth(bool enabled, int confidence=200)
void changeOdometryOKVISConfigPath()
bool getGeneralLoggerPrintTime() const
int getOdomRegistrationApproach() const
virtual void readCameraSettings(const QString &filePath=QString())
double getCloudOpacity(int index) const
void setSLAMMode(bool enabled)
bool isImagesKept() const
CalibrationDialog * _calibrationDialog
void selectSourceSvoPath()
int uStrNumCmp(const std::string &a, const std::string &b)
void setDepthScaledToRGBSize(bool enabled)
int getScanPointSize(int index) const
virtual ~PreferencesDialog()
int getSourceScanDownsampleStep() const
void changeOdometryVINSConfigPath()
void loadSettings(QSettings &settings, const QString &group="")
std::pair< std::string, std::string > ParametersPair
int projMinClusterSize() const
bool UTILITE_EXP uStr2Bool(const char *str)
bool isOdomDisabled() const
void setTimeLimit(float value)
double getGeneralInputRate() const
bool isOdomSensorAsGt() const
void updatePredictionPlot()
void enableBilateralFiltering(float sigmaS, float sigmaR)
float getTimeLimit() const
double getFloorFilteringHeight() const
static std::map< std::string, unsigned long > getRegisteredThreads()
bool isSourceMirroring() const
QStandardItemModel * _indexModel
double getCloudVoxelSizeScan(int index) const
float UTILITE_EXP uStr2Float(const std::string &str)
const std::vector< StereoCameraModel > & stereoCameraModels() const
bool isCloudMeshingQuad() const
bool isScansShown(int index) const
QString getWorkingDirectory() const
double squareSize() const
int getSubtractFilteringMinPts() const
virtual QString getIniFilePath() const
std::map< std::string, std::string > ParametersMap
std::string UTILITE_EXP uBool2Str(bool boolean)
bool getGridMapShown() const
Transform getSourceLocalTransform() const
void readSettings(const QString &filePath=QString())
int getCloudMeshingTriangleSize()
void calibrateOdomSensorExtrinsics()
static bool isCholmodAvailable()
static void writeINI(const std::string &configFile, const ParametersMap ¶meters)
void makeObsoleteCloudRenderingPanel()
double getCloudMaxDepth(int index) const
double getIMUGravityLength(int index) const
void setSquareSize(double size)
PreferencesDialog::Src getOdomSourceDriver() const
int getOdomQualityWarnThr() const
virtual void writeCameraSettings(const QString &filePath=QString()) const
Some conversion functions.
int getOctomapRenderingType() const
void setSwitchedImages(bool switched)
virtual void readGuiSettings(const QString &filePath=QString())
const QString & cameraName() const
QString getCameraInfoDir() const
GLM_FUNC_DECL T pitch(detail::tquat< T, P > const &x)
void selectSourceMKVPath()
double projMaxObstaclesHeight() const
void addParameter(int value)
static Transform opticalRotation()
bool isCloudMeshing() const
int getGeneralLoggerType() const
double getCloudMeshingAngle() const
static bool isAvailable(Optimizer::Type type)
int getIMUFilteringStrategy() const
bool isLabelsShown() const
bool getIMUFilteringBaseFrameConversion() const
bool isOdomOnlyInliersShown() const
void setBoardHeight(int height)
bool isCloudMeshingTexture() const
const std::string & name() const
double getScanNormalRadiusSearch() const
bool isOctomap2dGrid() const
void loadMainWindowState(QMainWindow *mainWindow, bool &maximized, bool &statusBarShown)
void selectSourceImagesPathGt()
QVector< QCheckBox * > _3dRenderingGravity
void updateBasicParameter()
double getScanOpacity(int index) const
virtual bool readCoreSettings(const QString &filePath=QString())
void publishInterIMU(bool enabled)
QVector< QSpinBox * > _3dRenderingPtSize
int getStereoPairs() const
int getGridMapSensor() const
int getFeaturesPointSize(int index) const
virtual void closeEvent(QCloseEvent *event)
QVector< QDoubleSpinBox * > _3dRenderingVoxelSizeScan
void changeIcpPMConfigPath()
QVector< QCheckBox * > _3dRenderingShowFrustums
virtual std::string getSerial() const =0
bool isFeaturesShown(int index) const
void saveCustomConfig(const QString §ion, const QString &key, const QString &value)
void setSavingDirectory(const QString &savingDirectory)
virtual bool init(const std::string &calibrationFolder=".", const std::string &cameraName="")=0
void selectSourceImagesStamps()
#define UASSERT(condition)
void setColorOnly(bool colorOnly)
SensorData takeImage(CameraInfo *info=0)
void updateSourceGrpVisibility()
Wrappers of STL for convenient functions.
bool isSourceDatabaseStampsUsed() const
void selectSourceStereoVideoPath()
virtual bool isCalibrated() const =0
const std::vector< CameraModel > & cameraModels() const
void changeOdometryORBSLAMVocabulary()
void selectSourceVideoPath()
double getCeilingFilteringHeight() const
bool isTimeUsedInFigures() const
QVector< QSpinBox * > _3dRenderingPtSizeFeatures
#define ULOGGER_DEBUG(...)
double getMarkerLength() const
void visualizeDistortionModel()
int getScanColorScheme(int index) const
static Odometry * create(const ParametersMap ¶meters=ParametersMap())
virtual void setStartIndex(int index)
void setDetectionRate(double value)
QVector< QSpinBox * > _3dRenderingPtSizeScan
Transform getIMULocalTransform() const
double getSourceScanVoxelSize() const
double getCloudMinDepth(int index) const
void setScanParameters(bool fromDepth, int downsampleStep=1, float rangeMin=0.0f, float rangeMax=0.0f, float voxelSize=0.0f, int normalsK=0, int normalsRadius=0.0f, float groundNormalsUp=0.0f)
const cv::Mat & imageRaw() const
bool isPriorIgnored() const
bool isMarkerDetection() const
void enableIMUFiltering(int filteringStrategy=1, const ParametersMap ¶meters=ParametersMap(), bool baseFrameConversion=false)
virtual void writeCoreSettings(const QString &filePath=QString()) const
void setCameraInfoDir(const QString &folder)
Transform stereoTransform() const
virtual void writeGuiSettings(const QString &filePath=QString()) const
QVector< QLineEdit * > _3dRenderingRoiRatios
double getCloudFilteringRadius() const
QList< QGroupBox * > getGroupBoxes()
int getSourceImageDecimation() const
cv::Mat visualize(const std::string &path="") const
QVector< QDoubleSpinBox * > _3dRenderingGravityLength
int getOdomBufferSize() const
void updateFeatureMatchingVisibility()
virtual void setStartIndex(int index)
bool isFrustumsShown(int index) const
const Transform & localTransform() const
void setIRDepthFormat(bool enabled)
void setResolution(int width, int height)
void init(const QString &iniFilePath="")
Ui_preferencesDialog * _ui
void saveWindowGeometry(const QWidget *window)
double projMaxGroundHeight() const
double getSubtractFilteringAngle() const
bool isIMUGravityShown(int index) const
bool isCloudsShown(int index) const
int getDownsamplingStepScan(int index) const
float getDetectionRate() const
void selectSourceStereoVideoPath2()
int getGeneralLoggerPauseLevel() const
bool isSourceRGBDColorOnly() const
QVector< QDoubleSpinBox * > _3dRenderingOpacity
void setDistortionModel(const std::string &path)
double getSubtractFilteringRadius() const
virtual void showEvent(QShowEvent *event)
QVector< QSpinBox * > _3dRenderingDecimation
bool openDatabase(const QString &path)
void setMirroringEnabled(bool enabled)
bool uContains(const std::list< V > &list, const V &value)
void load(const std::string &path)
void selectSourceStereoImagesPathRight()
void selectSourceRGBDImagesPathRGB()
void selectCalibrationPath()
void setImageDecimation(int decimation)
QVector< QDoubleSpinBox * > _3dRenderingMaxDepth
int getSourceScanNormalsK() const
void registerToEventsManager()
QVector< QCheckBox * > _3dRenderingShowFeatures
bool isSourceStereoDepthGenerated() const
static std::string getType(const std::string ¶mKey)
void closeDialog(QAbstractButton *button)
int getKpMaxFeatures() const
QString getSourceDriverStr() const
void changePyMatcherModel()
void changeDictionaryPath()
QVector< QSpinBox * > _3dRenderingColorSchemeScan
void publishInterIMU(bool enabled)
static const ParametersMap & getDefaultParameters()
std::string getParameter(const std::string &key) const
double getScanFloorFilteringHeight() const
void openDatabaseViewer()
void resetSettings(int panelNumber)
QString loadCustomConfig(const QString §ion, const QString &key)
QVector< QDoubleSpinBox * > _3dRenderingOpacityScan
void selectSourceOniPath()
bool isGraphsShown() const
void selectOdomSensorCalibrationPath()
int getOctomapPointSize() const
void setStereoToDepth(bool enabled)
void setStereoMode(bool stereo, const QString &leftSuffix="left", const QString &rightSuffix="right")
bool isLocalizationsCountGraphView() const
void setProgressVisibility(bool visible)
bool isStatisticsPublished() const
void saveWidgetState(const QWidget *widget)
std::vector< std::string > getGeneralLoggerThreads() const
int getOctomapTreeDepth() const
void selectSourceStereoImagesPathLeft()
void showCloseButton(bool visible=true)
bool isWordsCountGraphView() const
void loadSettings(QSettings &settings, const QString &group="")
bool isOctomapShown() const
void selectSourceRealsense2JsonPath()
void makeObsoleteLoggingPanel()
double getNoiseRadius() const
QVector< QDoubleSpinBox * > _3dRenderingMinDepth
QString getSourceDistortionModel() const
void saveSettings(QSettings &settings, const QString &group="") const
bool isSourceScanFromDepth() const
PreferencesDialog::Src getSourceDriver() const
QString getSourceDevice() const
PANEL_FLAGS _obsoletePanels
int getScanNormalKSearch() const
double getSourceScanForceGroundNormalsUp() const
void selectSourceDriver(Src src, int variant=0)
#define ULOGGER_WARN(...)
void setCurrentPanelToSource()
virtual void setStartIndex(int index)
ULogger class and convenient macros.
void selectSourceRGBDImagesPathDepth()
void loadWindowGeometry(QWidget *window)
double getSourceScanNormalsRadius() const
PreferencesDialog(QWidget *parent=0)
void setInputRate(double value)
double getScanCeilingFilteringHeight() const
bool isPosteriorGraphView() const
void setName(const std::string &name, const std::string &leftSuffix="left", const std::string &rightSuffix="right")
void settingsChanged(PreferencesDialog::PANEL_FLAGS)
void makeObsoleteGeneralPanel()
bool isCacheSavedInFigures() const
GLM_FUNC_DECL T yaw(detail::tquat< T, P > const &x)
double getSourceScanRangeMin() const
void writeSettings(const QString &filePath=QString())
static void readINI(const std::string &configFile, ParametersMap ¶meters, bool modifiedOnly=false)
void updateStereoDisparityVisibility()
QProgressDialog * _progressDialog
double getBilateralSigmaS() const
void resetApply(QAbstractButton *button)
virtual QString getParamMessage()
int getOdomStrategy() const
double getOdomF2MGravitySigma() const
bool sortCallback(const std::string &a, const std::string &b)
double getGridMapOpacity() const
void unregisterFromEventsManager()
Transform getLaserLocalTransform() const
bool isCloudsKept() const
QVector< QDoubleSpinBox * > _3dRenderingMinRange
double getScanMaxRange(int index) const
void clicked(const QModelIndex ¤t, const QModelIndex &previous)
void changeSuperPointModelPath()
bool isOctomapUpdated() const
std::vector< float > getCloudRoiRatios(int index) const
void join(bool killFirst=false)
bool isMissingCacheRepublished() const
double projMaxGroundAngle() const
QVector< QCheckBox * > _3dRenderingShowScans
void selectSourceImagesPathIMU()
void changePyMatcherPath()
double getCloudFilteringAngle() const
static bool exposureGainAvailable()
#define ULOGGER_ERROR(...)
void setCameraName(const QString &name)
QVector< QSpinBox * > _3dRenderingColorScheme
QVector< QDoubleSpinBox * > _3dRenderingMaxRange
void loadWidgetState(QWidget *widget)
void changeWorkingDirectory()
void publishInterIMU(bool enabled)
void setResolution(int width, int height)
bool isIMUAccShown() const
int getCloudDecimation(int index) const
void changePyDetectorPath()
void selectSourceDatabase()
rtabmap::ParametersMap _modifiedParameters
int getNoiseMinNeighbors() const
std::string UTILITE_EXP uNumber2Str(unsigned int number)
void addParameters(const QObjectList &children)
bool isVerticalLayoutUsed() const
double getNormalRadiusSearch() const
int getGeneralLoggerLevel() const
double getScanMinRange(int index) const
bool isBilateralFiltering() const
double getSourceScanRangeMax() const
void selectSourceOni2Path()
void setFisheyeImages(bool enabled)
static std::string createDefaultWorkingDirectory()
int getCloudPointSize(int index) const
void selectSourceDistortionModel()
bool isSourceStereoExposureCompensation() const
double landmarkVisSize() const
QVector< QCheckBox * > _3dRenderingShowClouds
void uInsert(std::map< K, V > &map, const std::pair< K, V > &pair)
void selectSourceImagesPath()
bool isFramesShown() const
Camera * createOdomSensor(Transform &extrinsics, double &timeOffset, float &scaleFactor)
void makeObsoleteSourcePanel()
bool isLandmarksShown() const
bool imageHighestHypShown() const
CreateSimpleCalibrationDialog * _createCalibrationDialog