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 <QDesktopServices> 48 #include <QtGui/QCloseEvent> 50 #include "ui_preferencesDialog.h" 52 #include "rtabmap/core/Version.h" 85 #include <opencv2/opencv_modules.hpp> 86 #if CV_MAJOR_VERSION < 3 87 #ifdef HAVE_OPENCV_GPU 88 #include <opencv2/gpu/gpu.hpp> 91 #ifdef HAVE_OPENCV_CUDAFEATURES2D 92 #include <opencv2/core/cuda.hpp> 102 _obsoletePanels(kPanelDummy),
106 _progressDialog(new QProgressDialog(this)),
118 _ui =
new Ui_preferencesDialog();
121 bool haveCuda =
false;
122 #if CV_MAJOR_VERSION < 3 123 #ifdef HAVE_OPENCV_GPU 124 haveCuda = cv::gpu::getCudaEnabledDeviceCount() != 0;
127 #ifdef HAVE_OPENCV_CUDAFEATURES2D 128 haveCuda = cv::cuda::getCudaEnabledDeviceCount() != 0;
133 _ui->surf_checkBox_gpuVersion->setChecked(
false);
134 _ui->surf_checkBox_gpuVersion->setEnabled(
false);
135 _ui->label_surf_checkBox_gpuVersion->setEnabled(
false);
136 _ui->surf_doubleSpinBox_gpuKeypointsRatio->setEnabled(
false);
137 _ui->label_surf_checkBox_gpuKeypointsRatio->setEnabled(
false);
139 _ui->fastGpu->setChecked(
false);
140 _ui->fastGpu->setEnabled(
false);
141 _ui->label_fastGPU->setEnabled(
false);
142 _ui->fastKeypointRatio->setEnabled(
false);
143 _ui->label_fastGPUKptRatio->setEnabled(
false);
145 _ui->checkBox_ORBGpu->setChecked(
false);
146 _ui->checkBox_ORBGpu->setEnabled(
false);
147 _ui->label_orbGpu->setEnabled(
false);
150 _ui->comboBox_dictionary_strategy->removeItem(4);
151 _ui->reextract_nn->removeItem(4);
154 #ifndef RTABMAP_OCTOMAP 155 _ui->groupBox_octomap->setChecked(
false);
156 _ui->groupBox_octomap->setEnabled(
false);
159 #ifndef RTABMAP_REALSENSE_SLAM 160 _ui->checkbox_realsenseOdom->setChecked(
false);
161 _ui->checkbox_realsenseOdom->setEnabled(
false);
162 _ui->label_realsenseOdom->setEnabled(
false);
165 #ifndef RTABMAP_FOVIS 166 _ui->odom_strategy->setItemData(2, 0, Qt::UserRole - 1);
168 #ifndef RTABMAP_VISO2 169 _ui->odom_strategy->setItemData(3, 0, Qt::UserRole - 1);
172 _ui->odom_strategy->setItemData(4, 0, Qt::UserRole - 1);
174 #ifndef RTABMAP_ORB_SLAM2 175 _ui->odom_strategy->setItemData(5, 0, Qt::UserRole - 1);
177 #ifndef RTABMAP_OKVIS 178 _ui->odom_strategy->setItemData(6, 0, Qt::UserRole - 1);
181 _ui->odom_strategy->setItemData(7, 0, Qt::UserRole - 1);
183 #ifndef RTABMAP_MSCKF_VIO 184 _ui->odom_strategy->setItemData(8, 0, Qt::UserRole - 1);
187 #ifndef RTABMAP_NONFREE 188 _ui->comboBox_detector_strategy->setItemData(0, 0, Qt::UserRole - 1);
189 _ui->comboBox_detector_strategy->setItemData(1, 0, Qt::UserRole - 1);
190 _ui->reextract_type->setItemData(0, 0, Qt::UserRole - 1);
191 _ui->reextract_type->setItemData(1, 0, Qt::UserRole - 1);
193 #if CV_MAJOR_VERSION >= 3 194 _ui->comboBox_detector_strategy->setItemData(0, 0, Qt::UserRole - 1);
195 _ui->comboBox_detector_strategy->setItemData(1, 0, Qt::UserRole - 1);
196 _ui->comboBox_detector_strategy->setItemData(3, 0, Qt::UserRole - 1);
197 _ui->comboBox_detector_strategy->setItemData(4, 0, Qt::UserRole - 1);
198 _ui->comboBox_detector_strategy->setItemData(5, 0, Qt::UserRole - 1);
199 _ui->comboBox_detector_strategy->setItemData(6, 0, Qt::UserRole - 1);
200 _ui->reextract_type->setItemData(0, 0, Qt::UserRole - 1);
201 _ui->reextract_type->setItemData(1, 0, Qt::UserRole - 1);
202 _ui->reextract_type->setItemData(3, 0, Qt::UserRole - 1);
203 _ui->reextract_type->setItemData(4, 0, Qt::UserRole - 1);
204 _ui->reextract_type->setItemData(5, 0, Qt::UserRole - 1);
205 _ui->reextract_type->setItemData(6, 0, Qt::UserRole - 1);
209 #if CV_MAJOR_VERSION >= 3 210 _ui->groupBox_fast_opencv2->setEnabled(
false);
212 _ui->comboBox_detector_strategy->setItemData(9, 0, Qt::UserRole - 1);
213 _ui->reextract_type->setItemData(9, 0, Qt::UserRole - 1);
216 _ui->comboBox_cameraImages_odomFormat->setItemData(4, 0, Qt::UserRole - 1);
217 _ui->comboBox_cameraImages_gtFormat->setItemData(4, 0, Qt::UserRole - 1);
220 _ui->graphOptimization_type->setItemData(1, 0, Qt::UserRole - 1);
221 _ui->odom_f2m_bundleStrategy->setItemData(1, 0, Qt::UserRole - 1);
222 _ui->loopClosure_bundle->setItemData(1, 0, Qt::UserRole - 1);
223 _ui->groupBoxx_g2o->setEnabled(
false);
225 #ifdef RTABMAP_ORB_SLAM2 229 _ui->graphOptimization_type->setItemData(1, 0, Qt::UserRole - 1);
234 _ui->comboBox_g2o_solver->setItemData(0, 0, Qt::UserRole - 1);
238 _ui->comboBox_g2o_solver->setItemData(2, 0, Qt::UserRole - 1);
242 _ui->graphOptimization_type->setItemData(0, 0, Qt::UserRole - 1);
246 _ui->graphOptimization_type->setItemData(2, 0, Qt::UserRole - 1);
250 _ui->odom_f2m_bundleStrategy->setItemData(2, 0, Qt::UserRole - 1);
251 _ui->loopClosure_bundle->setItemData(2, 0, Qt::UserRole - 1);
253 #ifdef RTABMAP_VERTIGO 257 _ui->graphOptimization_robust->setEnabled(
false);
259 #ifndef RTABMAP_POINTMATCHER 260 _ui->groupBox_libpointmatcher->setEnabled(
false);
310 #if PCL_VERSION_COMPARE(<, 1, 7, 2) 311 _ui->checkBox_showFrustums->setEnabled(
false);
312 _ui->checkBox_showFrustums->setChecked(
false);
313 _ui->checkBox_showOdomFrustums->setEnabled(
false);
314 _ui->checkBox_showOdomFrustums->setChecked(
false);
318 UASSERT(
_ui->odom_registration->count() == 4);
327 _ui->predictionPlot->showLegend(
false);
329 QButtonGroup * buttonGroup =
new QButtonGroup(
this);
330 buttonGroup->addButton(
_ui->radioButton_basic);
331 buttonGroup->addButton(
_ui->radioButton_advanced);
334 connect(
_ui->buttonBox_global, SIGNAL(
clicked(QAbstractButton *)),
this, SLOT(
closeDialog(QAbstractButton *)));
335 connect(
_ui->buttonBox_local, SIGNAL(
clicked(QAbstractButton *)),
this, SLOT(
resetApply(QAbstractButton *)));
339 connect(
_ui->radioButton_basic, SIGNAL(toggled(
bool)),
this, SLOT(
setupTreeView()));
440 for(
int i=0; i<2; ++i)
510 _ui->comboBox_loggerFilter->SetDisplayText(
"Select:");
515 connect(
_ui->general_doubleSpinBox_imgRate, SIGNAL(valueChanged(
double)),
_ui->doubleSpinBox_OdomORBSLAM2Fps, SLOT(setValue(
double)));
519 _ui->stackedWidget_src->setCurrentIndex(
_ui->comboBox_sourceType->currentIndex());
520 connect(
_ui->comboBox_sourceType, SIGNAL(currentIndexChanged(
int)),
_ui->stackedWidget_src, SLOT(setCurrentIndex(
int)));
526 _ui->stackedWidget_image->setCurrentIndex(
_ui->source_comboBox_image_type->currentIndex());
527 connect(
_ui->source_comboBox_image_type, SIGNAL(currentIndexChanged(
int)),
_ui->stackedWidget_image, SLOT(setCurrentIndex(
int)));
551 _ui->stackedWidget_rgbd->setCurrentIndex(
_ui->comboBox_cameraRGBD->currentIndex());
552 connect(
_ui->comboBox_cameraRGBD, SIGNAL(currentIndexChanged(
int)),
_ui->stackedWidget_rgbd, SLOT(setCurrentIndex(
int)));
554 _ui->stackedWidget_stereo->setCurrentIndex(
_ui->comboBox_cameraStereo->currentIndex());
555 connect(
_ui->comboBox_cameraStereo, SIGNAL(currentIndexChanged(
int)),
_ui->stackedWidget_stereo, SLOT(setCurrentIndex(
int)));
589 connect(
_ui->lineEdit_cameraRGBDImages_path_rgb, SIGNAL(textChanged(
const QString &)),
this, SLOT(
makeObsoleteSourcePanel()));
590 connect(
_ui->lineEdit_cameraRGBDImages_path_depth, SIGNAL(textChanged(
const QString &)),
this, SLOT(
makeObsoleteSourcePanel()));
596 connect(
_ui->lineEdit_cameraImages_laser_transform, SIGNAL(textChanged(
const QString &)),
this, SLOT(
makeObsoleteSourcePanel()));
606 connect(
_ui->lineEdit_cameraImages_imu_transform, SIGNAL(textChanged(
const QString &)),
this, SLOT(
makeObsoleteSourcePanel()));
616 connect(
_ui->lineEdit_cameraStereoImages_path_left, SIGNAL(textChanged(
const QString &)),
this, SLOT(
makeObsoleteSourcePanel()));
617 connect(
_ui->lineEdit_cameraStereoImages_path_right, SIGNAL(textChanged(
const QString &)),
this, SLOT(
makeObsoleteSourcePanel()));
658 connect(
_ui->doubleSpinBox_cameraSCanFromDepth_maxDepth, SIGNAL(valueChanged(
double)),
this, SLOT(
makeObsoleteSourcePanel()));
661 connect(
_ui->doubleSpinBox_cameraImages_scanNormalsRadius, SIGNAL(valueChanged(
double)),
this, SLOT(
makeObsoleteSourcePanel()));
662 connect(
_ui->checkBox_cameraImages_scanForceGroundNormalsUp, SIGNAL(stateChanged(
int)),
this, SLOT(
makeObsoleteSourcePanel()));
666 connect(
_ui->general_doubleSpinBox_timeThr, SIGNAL(valueChanged(
double)),
_ui->general_doubleSpinBox_timeThr_2, SLOT(setValue(
double)));
667 connect(
_ui->general_doubleSpinBox_hardThr, SIGNAL(valueChanged(
double)),
_ui->general_doubleSpinBox_hardThr_2, SLOT(setValue(
double)));
668 connect(
_ui->doubleSpinBox_similarityThreshold, SIGNAL(valueChanged(
double)),
_ui->doubleSpinBox_similarityThreshold_2, SLOT(setValue(
double)));
669 connect(
_ui->general_doubleSpinBox_detectionRate, SIGNAL(valueChanged(
double)),
_ui->general_doubleSpinBox_detectionRate_2, SLOT(setValue(
double)));
670 connect(
_ui->general_spinBox_imagesBufferSize, SIGNAL(valueChanged(
int)),
_ui->general_spinBox_imagesBufferSize_2, SLOT(setValue(
int)));
671 connect(
_ui->general_spinBox_maxStMemSize, SIGNAL(valueChanged(
int)),
_ui->general_spinBox_maxStMemSize_2, SLOT(setValue(
int)));
675 connect(
_ui->doubleSpinBox_similarityThreshold_2, SIGNAL(editingFinished()),
this, SLOT(
updateBasicParameter()));
676 connect(
_ui->general_doubleSpinBox_detectionRate_2, SIGNAL(editingFinished()),
this, SLOT(
updateBasicParameter()));
677 connect(
_ui->general_spinBox_imagesBufferSize_2, SIGNAL(editingFinished()),
this, SLOT(
updateBasicParameter()));
688 _ui->groupBox_publishing->setObjectName(Parameters::kRtabmapPublishStats().c_str());
689 _ui->general_checkBox_publishRawData->setObjectName(Parameters::kRtabmapPublishLastSignature().c_str());
690 _ui->general_checkBox_publishPdf->setObjectName(Parameters::kRtabmapPublishPdf().c_str());
691 _ui->general_checkBox_publishLikelihood->setObjectName(Parameters::kRtabmapPublishLikelihood().c_str());
692 _ui->general_checkBox_publishRMSE->setObjectName(Parameters::kRtabmapComputeRMSE().c_str());
693 _ui->general_checkBox_saveWMState->setObjectName(Parameters::kRtabmapSaveWMState().c_str());
694 _ui->general_checkBox_publishRAM->setObjectName(Parameters::kRtabmapPublishRAMUsage().c_str());
695 _ui->general_checkBox_statisticLogsBufferedInRAM->setObjectName(Parameters::kRtabmapStatisticLogsBufferedInRAM().c_str());
696 _ui->groupBox_statistics->setObjectName(Parameters::kRtabmapStatisticLogged().c_str());
697 _ui->general_checkBox_statisticLoggedHeaders->setObjectName(Parameters::kRtabmapStatisticLoggedHeaders().c_str());
698 _ui->general_doubleSpinBox_timeThr->setObjectName(Parameters::kRtabmapTimeThr().c_str());
699 _ui->general_spinBox_memoryThr->setObjectName(Parameters::kRtabmapMemoryThr().c_str());
700 _ui->general_doubleSpinBox_detectionRate->setObjectName(Parameters::kRtabmapDetectionRate().c_str());
701 _ui->general_spinBox_imagesBufferSize->setObjectName(Parameters::kRtabmapImageBufferSize().c_str());
702 _ui->general_checkBox_createIntermediateNodes->setObjectName(Parameters::kRtabmapCreateIntermediateNodes().c_str());
703 _ui->general_spinBox_maxRetrieved->setObjectName(Parameters::kRtabmapMaxRetrieved().c_str());
704 _ui->general_checkBox_startNewMapOnLoopClosure->setObjectName(Parameters::kRtabmapStartNewMapOnLoopClosure().c_str());
705 _ui->general_checkBox_startNewMapOnGoodSignature->setObjectName(Parameters::kRtabmapStartNewMapOnGoodSignature().c_str());
706 _ui->general_checkBox_imagesAlreadyRectified->setObjectName(Parameters::kRtabmapImagesAlreadyRectified().c_str());
707 _ui->general_checkBox_rectifyOnlyFeatures->setObjectName(Parameters::kRtabmapRectifyOnlyFeatures().c_str());
708 _ui->lineEdit_workingDirectory->setObjectName(Parameters::kRtabmapWorkingDirectory().c_str());
712 _ui->general_checkBox_keepRawData->setObjectName(Parameters::kMemImageKept().c_str());
713 _ui->general_checkBox_keepBinaryData->setObjectName(Parameters::kMemBinDataKept().c_str());
714 _ui->general_checkBox_saveIntermediateNodeData->setObjectName(Parameters::kMemIntermediateNodeDataKept().c_str());
715 _ui->general_checkBox_keepDescriptors->setObjectName(Parameters::kMemRawDescriptorsKept().c_str());
716 _ui->general_checkBox_saveDepth16bits->setObjectName(Parameters::kMemSaveDepth16Format().c_str());
717 _ui->general_checkBox_compressionParallelized->setObjectName(Parameters::kMemCompressionParallelized().c_str());
718 _ui->general_checkBox_reduceGraph->setObjectName(Parameters::kMemReduceGraph().c_str());
719 _ui->general_checkBox_keepNotLinkedNodes->setObjectName(Parameters::kMemNotLinkedNodesKept().c_str());
720 _ui->general_spinBox_maxStMemSize->setObjectName(Parameters::kMemSTMSize().c_str());
721 _ui->doubleSpinBox_similarityThreshold->setObjectName(Parameters::kMemRehearsalSimilarity().c_str());
722 _ui->general_checkBox_SLAM_mode->setObjectName(Parameters::kMemIncrementalMemory().c_str());
723 _ui->general_doubleSpinBox_recentWmRatio->setObjectName(Parameters::kMemRecentWmRatio().c_str());
724 _ui->general_checkBox_transferSortingByWeightId->setObjectName(Parameters::kMemTransferSortingByWeightId().c_str());
725 _ui->general_checkBox_RehearsalIdUpdatedToNewOne->setObjectName(Parameters::kMemRehearsalIdUpdatedToNewOne().c_str());
726 _ui->general_checkBox_generateIds->setObjectName(Parameters::kMemGenerateIds().c_str());
727 _ui->general_checkBox_badSignaturesIgnored->setObjectName(Parameters::kMemBadSignaturesIgnored().c_str());
728 _ui->general_checkBox_createMapLabels->setObjectName(Parameters::kMemMapLabelsAdded().c_str());
729 _ui->general_checkBox_initWMWithAllNodes->setObjectName(Parameters::kMemInitWMWithAllNodes().c_str());
730 _ui->checkBox_localSpaceScanMatchingIDsSaved->setObjectName(Parameters::kRGBDScanMatchingIdsSavedInLinks().c_str());
731 _ui->spinBox_imagePreDecimation->setObjectName(Parameters::kMemImagePreDecimation().c_str());
732 _ui->spinBox_imagePostDecimation->setObjectName(Parameters::kMemImagePostDecimation().c_str());
733 _ui->general_spinBox_laserScanDownsample->setObjectName(Parameters::kMemLaserScanDownsampleStepSize().c_str());
734 _ui->general_doubleSpinBox_laserScanVoxelSize->setObjectName(Parameters::kMemLaserScanVoxelSize().c_str());
735 _ui->general_spinBox_laserScanNormalK->setObjectName(Parameters::kMemLaserScanNormalK().c_str());
736 _ui->general_doubleSpinBox_laserScanNormalRadius->setObjectName(Parameters::kMemLaserScanNormalRadius().c_str());
737 _ui->checkBox_useOdomFeatures->setObjectName(Parameters::kMemUseOdomFeatures().c_str());
738 _ui->memCovOffDiagIgnored->setObjectName(Parameters::kMemCovOffDiagIgnored().c_str());
741 _ui->checkBox_dbInMemory->setObjectName(Parameters::kDbSqlite3InMemory().c_str());
742 _ui->spinBox_dbCacheSize->setObjectName(Parameters::kDbSqlite3CacheSize().c_str());
743 _ui->comboBox_dbJournalMode->setObjectName(Parameters::kDbSqlite3JournalMode().c_str());
744 _ui->comboBox_dbSynchronous->setObjectName(Parameters::kDbSqlite3Synchronous().c_str());
745 _ui->comboBox_dbTempStore->setObjectName(Parameters::kDbSqlite3TempStore().c_str());
748 _ui->general_doubleSpinBox_hardThr->setObjectName(Parameters::kRtabmapLoopThr().c_str());
749 _ui->general_doubleSpinBox_loopRatio->setObjectName(Parameters::kRtabmapLoopRatio().c_str());
752 _ui->general_doubleSpinBox_vp->setObjectName(Parameters::kBayesVirtualPlacePriorThr().c_str());
753 _ui->lineEdit_bayes_predictionLC->setObjectName(Parameters::kBayesPredictionLC().c_str());
754 _ui->checkBox_bayes_fullPredictionUpdate->setObjectName(Parameters::kBayesFullPredictionUpdate().c_str());
755 connect(
_ui->lineEdit_bayes_predictionLC, SIGNAL(textChanged(
const QString &)),
this, SLOT(
updatePredictionPlot()));
758 _ui->comboBox_dictionary_strategy->setObjectName(Parameters::kKpNNStrategy().c_str());
759 _ui->checkBox_dictionary_incremental->setObjectName(Parameters::kKpIncrementalDictionary().c_str());
760 _ui->checkBox_kp_incrementalFlann->setObjectName(Parameters::kKpIncrementalFlann().c_str());
761 _ui->surf_doubleSpinBox_rebalancingFactor->setObjectName(Parameters::kKpFlannRebalancingFactor().c_str());
762 _ui->comboBox_detector_strategy->setObjectName(Parameters::kKpDetectorStrategy().c_str());
763 _ui->surf_doubleSpinBox_nndrRatio->setObjectName(Parameters::kKpNndrRatio().c_str());
764 _ui->surf_doubleSpinBox_maxDepth->setObjectName(Parameters::kKpMaxDepth().c_str());
765 _ui->surf_doubleSpinBox_minDepth->setObjectName(Parameters::kKpMinDepth().c_str());
766 _ui->checkBox_memDepthAsMask->setObjectName(Parameters::kMemDepthAsMask().c_str());
767 _ui->surf_spinBox_wordsPerImageTarget->setObjectName(Parameters::kKpMaxFeatures().c_str());
768 _ui->spinBox_KPGridRows->setObjectName(Parameters::kKpGridRows().c_str());
769 _ui->spinBox_KPGridCols->setObjectName(Parameters::kKpGridCols().c_str());
770 _ui->surf_doubleSpinBox_ratioBadSign->setObjectName(Parameters::kKpBadSignRatio().c_str());
771 _ui->checkBox_kp_tfIdfLikelihoodUsed->setObjectName(Parameters::kKpTfIdfLikelihoodUsed().c_str());
772 _ui->checkBox_kp_parallelized->setObjectName(Parameters::kKpParallelized().c_str());
773 _ui->lineEdit_kp_roi->setObjectName(Parameters::kKpRoiRatios().c_str());
774 _ui->lineEdit_dictionaryPath->setObjectName(Parameters::kKpDictionaryPath().c_str());
776 _ui->checkBox_kp_newWordsComparedTogether->setObjectName(Parameters::kKpNewWordsComparedTogether().c_str());
777 _ui->subpix_winSize_kp->setObjectName(Parameters::kKpSubPixWinSize().c_str());
778 _ui->subpix_iterations_kp->setObjectName(Parameters::kKpSubPixIterations().c_str());
779 _ui->subpix_eps_kp->setObjectName(Parameters::kKpSubPixEps().c_str());
781 _ui->subpix_winSize->setObjectName(Parameters::kKpSubPixWinSize().c_str());
782 _ui->subpix_iterations->setObjectName(Parameters::kKpSubPixIterations().c_str());
783 _ui->subpix_eps->setObjectName(Parameters::kKpSubPixEps().c_str());
786 _ui->surf_doubleSpinBox_hessianThr->setObjectName(Parameters::kSURFHessianThreshold().c_str());
787 _ui->surf_spinBox_octaves->setObjectName(Parameters::kSURFOctaves().c_str());
788 _ui->surf_spinBox_octaveLayers->setObjectName(Parameters::kSURFOctaveLayers().c_str());
789 _ui->checkBox_surfExtended->setObjectName(Parameters::kSURFExtended().c_str());
790 _ui->surf_checkBox_upright->setObjectName(Parameters::kSURFUpright().c_str());
791 _ui->surf_checkBox_gpuVersion->setObjectName(Parameters::kSURFGpuVersion().c_str());
792 _ui->surf_doubleSpinBox_gpuKeypointsRatio->setObjectName(Parameters::kSURFGpuKeypointsRatio().c_str());
795 _ui->sift_spinBox_nFeatures->setObjectName(Parameters::kSIFTNFeatures().c_str());
796 _ui->sift_spinBox_nOctaveLayers->setObjectName(Parameters::kSIFTNOctaveLayers().c_str());
797 _ui->sift_doubleSpinBox_contrastThr->setObjectName(Parameters::kSIFTContrastThreshold().c_str());
798 _ui->sift_doubleSpinBox_edgeThr->setObjectName(Parameters::kSIFTEdgeThreshold().c_str());
799 _ui->sift_doubleSpinBox_sigma->setObjectName(Parameters::kSIFTSigma().c_str());
802 _ui->briefBytes->setObjectName(Parameters::kBRIEFBytes().c_str());
805 _ui->fastSuppressNonMax->setObjectName(Parameters::kFASTNonmaxSuppression().c_str());
806 _ui->fastThreshold->setObjectName(Parameters::kFASTThreshold().c_str());
807 _ui->fastThresholdMin->setObjectName(Parameters::kFASTMinThreshold().c_str());
808 _ui->fastThresholdMax->setObjectName(Parameters::kFASTMaxThreshold().c_str());
809 _ui->fastGridRows->setObjectName(Parameters::kFASTGridRows().c_str());
810 _ui->fastGridCols->setObjectName(Parameters::kFASTGridCols().c_str());
811 _ui->fastGpu->setObjectName(Parameters::kFASTGpu().c_str());
812 _ui->fastKeypointRatio->setObjectName(Parameters::kFASTGpuKeypointsRatio().c_str());
815 _ui->doubleSpinBox_ORBScaleFactor->setObjectName(Parameters::kORBScaleFactor().c_str());
816 _ui->spinBox_ORBNLevels->setObjectName(Parameters::kORBNLevels().c_str());
817 _ui->spinBox_ORBEdgeThreshold->setObjectName(Parameters::kORBEdgeThreshold().c_str());
818 _ui->spinBox_ORBFirstLevel->setObjectName(Parameters::kORBFirstLevel().c_str());
819 _ui->spinBox_ORBWTA_K->setObjectName(Parameters::kORBWTA_K().c_str());
820 _ui->spinBox_ORBScoreType->setObjectName(Parameters::kORBScoreType().c_str());
821 _ui->spinBox_ORBPatchSize->setObjectName(Parameters::kORBPatchSize().c_str());
822 _ui->checkBox_ORBGpu->setObjectName(Parameters::kORBGpu().c_str());
825 _ui->checkBox_FREAKOrientationNormalized->setObjectName(Parameters::kFREAKOrientationNormalized().c_str());
826 _ui->checkBox_FREAKScaleNormalized->setObjectName(Parameters::kFREAKScaleNormalized().c_str());
827 _ui->doubleSpinBox_FREAKPatternScale->setObjectName(Parameters::kFREAKPatternScale().c_str());
828 _ui->spinBox_FREAKNOctaves->setObjectName(Parameters::kFREAKNOctaves().c_str());
831 _ui->doubleSpinBox_GFTT_qualityLevel->setObjectName(Parameters::kGFTTQualityLevel().c_str());
832 _ui->doubleSpinBox_GFTT_minDistance->setObjectName(Parameters::kGFTTMinDistance().c_str());
833 _ui->spinBox_GFTT_blockSize->setObjectName(Parameters::kGFTTBlockSize().c_str());
834 _ui->checkBox_GFTT_useHarrisDetector->setObjectName(Parameters::kGFTTUseHarrisDetector().c_str());
835 _ui->doubleSpinBox_GFTT_k->setObjectName(Parameters::kGFTTK().c_str());
838 _ui->spinBox_BRISK_thresh->setObjectName(Parameters::kBRISKThresh().c_str());
839 _ui->spinBox_BRISK_octaves->setObjectName(Parameters::kBRISKOctaves().c_str());
840 _ui->doubleSpinBox_BRISK_patterScale->setObjectName(Parameters::kBRISKPatternScale().c_str());
843 _ui->checkBox_kaze_extended->setObjectName(Parameters::kKAZEExtended().c_str());
844 _ui->checkBox_kaze_upright->setObjectName(Parameters::kKAZEUpright().c_str());
845 _ui->doubleSpinBox_kaze_threshold->setObjectName(Parameters::kKAZEThreshold().c_str());
846 _ui->spinBox_kaze_octaves->setObjectName(Parameters::kKAZENOctaves().c_str());
847 _ui->spinBox_kaze_octavelayers->setObjectName(Parameters::kKAZENOctaveLayers().c_str());
848 _ui->spinBox_kaze_diffusivity->setObjectName(Parameters::kKAZEDiffusivity().c_str());
851 _ui->groupBox_vh_epipolar2->setObjectName(Parameters::kVhEpEnabled().c_str());
852 _ui->surf_spinBox_matchCountMinAccepted->setObjectName(Parameters::kVhEpMatchCountMin().c_str());
853 _ui->surf_doubleSpinBox_ransacParam1->setObjectName(Parameters::kVhEpRansacParam1().c_str());
854 _ui->surf_doubleSpinBox_ransacParam2->setObjectName(Parameters::kVhEpRansacParam2().c_str());
857 _ui->general_checkBox_activateRGBD->setObjectName(Parameters::kRGBDEnabled().c_str());
858 _ui->rgdb_linearUpdate->setObjectName(Parameters::kRGBDLinearUpdate().c_str());
859 _ui->rgdb_angularUpdate->setObjectName(Parameters::kRGBDAngularUpdate().c_str());
860 _ui->rgdb_linearSpeedUpdate->setObjectName(Parameters::kRGBDLinearSpeedUpdate().c_str());
861 _ui->rgdb_angularSpeedUpdate->setObjectName(Parameters::kRGBDAngularSpeedUpdate().c_str());
862 _ui->rgbd_savedLocalizationIgnored->setObjectName(Parameters::kRGBDSavedLocalizationIgnored().c_str());
863 _ui->rgdb_rehearsalWeightIgnoredWhileMoving->setObjectName(Parameters::kMemRehearsalWeightIgnoredWhileMoving().c_str());
864 _ui->rgdb_newMapOdomChange->setObjectName(Parameters::kRGBDNewMapOdomChangeDistance().c_str());
865 _ui->odomScanHistory->setObjectName(Parameters::kRGBDNeighborLinkRefining().c_str());
866 _ui->spinBox_maxLocalLocationsRetrieved->setObjectName(Parameters::kRGBDMaxLocalRetrieved().c_str());
868 _ui->graphOptimization_type->setObjectName(Parameters::kOptimizerStrategy().c_str());
869 _ui->graphOptimization_iterations->setObjectName(Parameters::kOptimizerIterations().c_str());
870 _ui->graphOptimization_covarianceIgnored->setObjectName(Parameters::kOptimizerVarianceIgnored().c_str());
871 _ui->graphOptimization_fromGraphEnd->setObjectName(Parameters::kRGBDOptimizeFromGraphEnd().c_str());
872 _ui->graphOptimization_maxError->setObjectName(Parameters::kRGBDOptimizeMaxError().c_str());
873 _ui->graphOptimization_stopEpsilon->setObjectName(Parameters::kOptimizerEpsilon().c_str());
874 _ui->graphOptimization_robust->setObjectName(Parameters::kOptimizerRobust().c_str());
875 _ui->graphOptimization_priorsIgnored->setObjectName(Parameters::kOptimizerPriorsIgnored().c_str());
877 _ui->comboBox_g2o_solver->setObjectName(Parameters::kg2oSolver().c_str());
878 _ui->comboBox_g2o_optimizer->setObjectName(Parameters::kg2oOptimizer().c_str());
879 _ui->doubleSpinBox_g2o_pixelVariance->setObjectName(Parameters::kg2oPixelVariance().c_str());
880 _ui->doubleSpinBox_g2o_robustKernelDelta->setObjectName(Parameters::kg2oRobustKernelDelta().c_str());
881 _ui->doubleSpinBox_g2o_baseline->setObjectName(Parameters::kg2oBaseline().c_str());
883 _ui->comboBox_gtsam_optimizer->setObjectName(Parameters::kGTSAMOptimizer().c_str());
885 _ui->graphPlan_goalReachedRadius->setObjectName(Parameters::kRGBDGoalReachedRadius().c_str());
886 _ui->graphPlan_goalsSavedInUserData->setObjectName(Parameters::kRGBDGoalsSavedInUserData().c_str());
887 _ui->graphPlan_stuckIterations->setObjectName(Parameters::kRGBDPlanStuckIterations().c_str());
888 _ui->graphPlan_linearVelocity->setObjectName(Parameters::kRGBDPlanLinearVelocity().c_str());
889 _ui->graphPlan_angularVelocity->setObjectName(Parameters::kRGBDPlanAngularVelocity().c_str());
891 _ui->groupBox_localDetection_time->setObjectName(Parameters::kRGBDProximityByTime().c_str());
892 _ui->groupBox_localDetection_space->setObjectName(Parameters::kRGBDProximityBySpace().c_str());
893 _ui->localDetection_radius->setObjectName(Parameters::kRGBDLocalRadius().c_str());
894 _ui->localDetection_maxDiffID->setObjectName(Parameters::kRGBDProximityMaxGraphDepth().c_str());
895 _ui->localDetection_maxNeighbors->setObjectName(Parameters::kRGBDProximityPathMaxNeighbors().c_str());
896 _ui->localDetection_maxPaths->setObjectName(Parameters::kRGBDProximityMaxPaths().c_str());
897 _ui->localDetection_pathFilteringRadius->setObjectName(Parameters::kRGBDProximityPathFilteringRadius().c_str());
898 _ui->localDetection_angle->setObjectName(Parameters::kRGBDProximityAngle().c_str());
899 _ui->checkBox_localSpacePathOdomPosesUsed->setObjectName(Parameters::kRGBDProximityPathRawPosesUsed().c_str());
900 _ui->rgdb_localImmunizationRatio->setObjectName(Parameters::kRGBDLocalImmunizationRatio().c_str());
901 _ui->loopClosure_reextract->setObjectName(Parameters::kRGBDLoopClosureReextractFeatures().c_str());
902 _ui->loopClosure_bunlde->setObjectName(Parameters::kRGBDLocalBundleOnLoopClosure().c_str());
903 _ui->checkbox_rgbd_createOccupancyGrid->setObjectName(Parameters::kRGBDCreateOccupancyGrid().c_str());
906 _ui->reg_repeatOnce->setObjectName(Parameters::kRegRepeatOnce().c_str());
907 _ui->comboBox_registrationStrategy->setObjectName(Parameters::kRegStrategy().c_str());
908 _ui->loopClosure_bowForce2D->setObjectName(Parameters::kRegForce3DoF().c_str());
911 _ui->loopClosure_bowMinInliers->setObjectName(Parameters::kVisMinInliers().c_str());
912 _ui->loopClosure_bowInlierDistance->setObjectName(Parameters::kVisInlierDistance().c_str());
913 _ui->loopClosure_bowIterations->setObjectName(Parameters::kVisIterations().c_str());
914 _ui->loopClosure_bowRefineIterations->setObjectName(Parameters::kVisRefineIterations().c_str());
915 _ui->loopClosure_estimationType->setObjectName(Parameters::kVisEstimationType().c_str());
916 connect(
_ui->loopClosure_estimationType, SIGNAL(currentIndexChanged(
int)),
_ui->stackedWidget_loopClosureEstimation, SLOT(setCurrentIndex(
int)));
917 _ui->stackedWidget_loopClosureEstimation->setCurrentIndex(Parameters::defaultVisEstimationType());
918 _ui->loopClosure_forwardEst->setObjectName(Parameters::kVisForwardEstOnly().c_str());
919 _ui->loopClosure_bowEpipolarGeometryVar->setObjectName(Parameters::kVisEpipolarGeometryVar().c_str());
920 _ui->loopClosure_pnpReprojError->setObjectName(Parameters::kVisPnPReprojError().c_str());
921 _ui->loopClosure_pnpFlags->setObjectName(Parameters::kVisPnPFlags().c_str());
922 _ui->loopClosure_pnpRefineIterations->setObjectName(Parameters::kVisPnPRefineIterations().c_str());
923 _ui->reextract_nn->setObjectName(Parameters::kVisCorNNType().c_str());
924 _ui->reextract_nndrRatio->setObjectName(Parameters::kVisCorNNDR().c_str());
925 _ui->spinBox_visCorGuessWinSize->setObjectName(Parameters::kVisCorGuessWinSize().c_str());
926 _ui->checkBox__visCorGuessMatchToProjection->setObjectName(Parameters::kVisCorGuessMatchToProjection().c_str());
927 _ui->reextract_type->setObjectName(Parameters::kVisFeatureType().c_str());
928 _ui->reextract_maxFeatures->setObjectName(Parameters::kVisMaxFeatures().c_str());
929 _ui->reextract_gridrows->setObjectName(Parameters::kVisGridRows().c_str());
930 _ui->reextract_gridcols->setObjectName(Parameters::kVisGridCols().c_str());
931 _ui->loopClosure_bowMaxDepth->setObjectName(Parameters::kVisMaxDepth().c_str());
932 _ui->loopClosure_bowMinDepth->setObjectName(Parameters::kVisMinDepth().c_str());
933 _ui->checkBox_visDepthAsMask->setObjectName(Parameters::kVisDepthAsMask().c_str());
934 _ui->loopClosure_roi->setObjectName(Parameters::kVisRoiRatios().c_str());
935 _ui->subpix_winSize->setObjectName(Parameters::kVisSubPixWinSize().c_str());
936 _ui->subpix_iterations->setObjectName(Parameters::kVisSubPixIterations().c_str());
937 _ui->subpix_eps->setObjectName(Parameters::kVisSubPixEps().c_str());
938 _ui->odom_flow_winSize_2->setObjectName(Parameters::kVisCorFlowWinSize().c_str());
939 _ui->odom_flow_maxLevel_2->setObjectName(Parameters::kVisCorFlowMaxLevel().c_str());
940 _ui->odom_flow_iterations_2->setObjectName(Parameters::kVisCorFlowIterations().c_str());
941 _ui->odom_flow_eps_2->setObjectName(Parameters::kVisCorFlowEps().c_str());
942 _ui->loopClosure_bundle->setObjectName(Parameters::kVisBundleAdjustment().c_str());
945 _ui->globalDetection_icpMaxTranslation->setObjectName(Parameters::kIcpMaxTranslation().c_str());
946 _ui->globalDetection_icpMaxRotation->setObjectName(Parameters::kIcpMaxRotation().c_str());
947 _ui->loopClosure_icpVoxelSize->setObjectName(Parameters::kIcpVoxelSize().c_str());
948 _ui->loopClosure_icpDownsamplingStep->setObjectName(Parameters::kIcpDownsamplingStep().c_str());
949 _ui->loopClosure_icpMaxCorrespondenceDistance->setObjectName(Parameters::kIcpMaxCorrespondenceDistance().c_str());
950 _ui->loopClosure_icpIterations->setObjectName(Parameters::kIcpIterations().c_str());
951 _ui->loopClosure_icpEpsilon->setObjectName(Parameters::kIcpEpsilon().c_str());
952 _ui->loopClosure_icpRatio->setObjectName(Parameters::kIcpCorrespondenceRatio().c_str());
953 _ui->loopClosure_icpPointToPlane->setObjectName(Parameters::kIcpPointToPlane().c_str());
954 _ui->loopClosure_icpPointToPlaneNormals->setObjectName(Parameters::kIcpPointToPlaneK().c_str());
955 _ui->loopClosure_icpPointToPlaneNormalsRadius->setObjectName(Parameters::kIcpPointToPlaneRadius().c_str());
956 _ui->loopClosure_icpPointToPlaneNormalsMinComplexity->setObjectName(Parameters::kIcpPointToPlaneMinComplexity().c_str());
958 _ui->groupBox_libpointmatcher->setObjectName(Parameters::kIcpPM().c_str());
959 _ui->lineEdit_IcpPMConfigPath->setObjectName(Parameters::kIcpPMConfig().c_str());
961 _ui->doubleSpinBox_icpPMOutlierRatio->setObjectName(Parameters::kIcpPMOutlierRatio().c_str());
962 _ui->spinBox_icpPMMatcherKnn->setObjectName(Parameters::kIcpPMMatcherKnn().c_str());
963 _ui->doubleSpinBox_icpPMMatcherEpsilon->setObjectName(Parameters::kIcpPMMatcherEpsilon().c_str());
966 _ui->groupBox_grid_3d->setObjectName(Parameters::kGrid3D().c_str());
967 _ui->checkBox_grid_groundObstacle->setObjectName(Parameters::kGridGroundIsObstacle().c_str());
968 _ui->doubleSpinBox_grid_resolution->setObjectName(Parameters::kGridCellSize().c_str());
969 _ui->checkBox_grid_preVoxelFiltering->setObjectName(Parameters::kGridPreVoxelFiltering().c_str());
970 _ui->spinBox_grid_decimation->setObjectName(Parameters::kGridDepthDecimation().c_str());
971 _ui->doubleSpinBox_grid_maxDepth->setObjectName(Parameters::kGridRangeMax().c_str());
972 _ui->doubleSpinBox_grid_minDepth->setObjectName(Parameters::kGridRangeMin().c_str());
973 _ui->lineEdit_grid_roi->setObjectName(Parameters::kGridDepthRoiRatios().c_str());
974 _ui->checkBox_grid_projRayTracing->setObjectName(Parameters::kGridRayTracing().c_str());
975 _ui->doubleSpinBox_grid_footprintLength->setObjectName(Parameters::kGridFootprintLength().c_str());
976 _ui->doubleSpinBox_grid_footprintWidth->setObjectName(Parameters::kGridFootprintWidth().c_str());
977 _ui->doubleSpinBox_grid_footprintHeight->setObjectName(Parameters::kGridFootprintHeight().c_str());
978 _ui->checkBox_grid_flatObstaclesDetected->setObjectName(Parameters::kGridFlatObstacleDetected().c_str());
979 _ui->groupBox_grid_fromDepthImage->setObjectName(Parameters::kGridFromDepth().c_str());
980 _ui->checkBox_grid_projMapFrame->setObjectName(Parameters::kGridMapFrameProjection().c_str());
981 _ui->doubleSpinBox_grid_maxGroundAngle->setObjectName(Parameters::kGridMaxGroundAngle().c_str());
982 _ui->spinBox_grid_normalK->setObjectName(Parameters::kGridNormalK().c_str());
983 _ui->doubleSpinBox_grid_maxGroundHeight->setObjectName(Parameters::kGridMaxGroundHeight().c_str());
984 _ui->doubleSpinBox_grid_maxObstacleHeight->setObjectName(Parameters::kGridMaxObstacleHeight().c_str());
985 _ui->doubleSpinBox_grid_clusterRadius->setObjectName(Parameters::kGridClusterRadius().c_str());
986 _ui->spinBox_grid_minClusterSize->setObjectName(Parameters::kGridMinClusterSize().c_str());
987 _ui->doubleSpinBox_grid_minGroundHeight->setObjectName(Parameters::kGridMinGroundHeight().c_str());
988 _ui->spinBox_grid_noiseMinNeighbors->setObjectName(Parameters::kGridNoiseFilteringMinNeighbors().c_str());
989 _ui->doubleSpinBox_grid_noiseRadius->setObjectName(Parameters::kGridNoiseFilteringRadius().c_str());
990 _ui->groupBox_grid_normalsSegmentation->setObjectName(Parameters::kGridNormalsSegmentation().c_str());
991 _ui->checkBox_grid_unknownSpaceFilled->setObjectName(Parameters::kGridScan2dUnknownSpaceFilled().c_str());
992 _ui->spinBox_grid_scanDecimation->setObjectName(Parameters::kGridScanDecimation().c_str());
994 _ui->checkBox_grid_fullUpdate->setObjectName(Parameters::kGridGlobalFullUpdate().c_str());
995 _ui->doubleSpinBox_grid_updateError->setObjectName(Parameters::kGridGlobalUpdateError().c_str());
996 _ui->doubleSpinBox_grid_minMapSize->setObjectName(Parameters::kGridGlobalMinSize().c_str());
997 _ui->spinBox_grid_maxNodes->setObjectName(Parameters::kGridGlobalMaxNodes().c_str());
998 _ui->doubleSpinBox_grid_footprintRadius->setObjectName(Parameters::kGridGlobalFootprintRadius().c_str());
999 _ui->doubleSpinBox_grid_occThr->setObjectName(Parameters::kGridGlobalOccupancyThr().c_str());
1000 _ui->doubleSpinBox_grid_probHit->setObjectName(Parameters::kGridGlobalProbHit().c_str());
1001 _ui->doubleSpinBox_grid_probMiss->setObjectName(Parameters::kGridGlobalProbMiss().c_str());
1002 _ui->doubleSpinBox_grid_clampingMin->setObjectName(Parameters::kGridGlobalProbClampingMin().c_str());
1003 _ui->doubleSpinBox_grid_clampingMax->setObjectName(Parameters::kGridGlobalProbClampingMax().c_str());
1004 _ui->checkBox_grid_erode->setObjectName(Parameters::kGridGlobalEroded().c_str());
1007 _ui->odom_strategy->setObjectName(Parameters::kOdomStrategy().c_str());
1008 connect(
_ui->odom_strategy, SIGNAL(currentIndexChanged(
int)),
_ui->stackedWidget_odometryType, SLOT(setCurrentIndex(
int)));
1009 _ui->odom_strategy->setCurrentIndex(Parameters::defaultOdomStrategy());
1010 _ui->stackedWidget_odometryType->setCurrentIndex(Parameters::defaultOdomStrategy());
1011 _ui->odom_countdown->setObjectName(Parameters::kOdomResetCountdown().c_str());
1012 _ui->odom_holonomic->setObjectName(Parameters::kOdomHolonomic().c_str());
1013 _ui->odom_fillInfoData->setObjectName(Parameters::kOdomFillInfoData().c_str());
1014 _ui->odom_dataBufferSize->setObjectName(Parameters::kOdomImageBufferSize().c_str());
1015 _ui->odom_flow_keyframeThr->setObjectName(Parameters::kOdomKeyFrameThr().c_str());
1016 _ui->odom_VisKeyFrameThr->setObjectName(Parameters::kOdomVisKeyFrameThr().c_str());
1017 _ui->odom_flow_scanKeyframeThr->setObjectName(Parameters::kOdomScanKeyFrameThr().c_str());
1018 _ui->odom_flow_guessMotion->setObjectName(Parameters::kOdomGuessMotion().c_str());
1019 _ui->odom_imageDecimation->setObjectName(Parameters::kOdomImageDecimation().c_str());
1020 _ui->odom_alignWithGround->setObjectName(Parameters::kOdomAlignWithGround().c_str());
1023 _ui->odom_localHistory->setObjectName(Parameters::kOdomF2MMaxSize().c_str());
1024 _ui->spinBox_odom_f2m_maxNewFeatures->setObjectName(Parameters::kOdomF2MMaxNewFeatures().c_str());
1025 _ui->spinBox_odom_f2m_scanMaxSize->setObjectName(Parameters::kOdomF2MScanMaxSize().c_str());
1026 _ui->doubleSpinBox_odom_f2m_scanRadius->setObjectName(Parameters::kOdomF2MScanSubtractRadius().c_str());
1027 _ui->doubleSpinBox_odom_f2m_scanAngle->setObjectName(Parameters::kOdomF2MScanSubtractAngle().c_str());
1028 _ui->odom_f2m_bundleStrategy->setObjectName(Parameters::kOdomF2MBundleAdjustment().c_str());
1029 _ui->odom_f2m_bundleMaxFrames->setObjectName(Parameters::kOdomF2MBundleAdjustmentMaxFrames().c_str());
1032 _ui->comboBox_odomf2f_corType->setObjectName(Parameters::kVisCorType().c_str());
1035 _ui->doubleSpinBox_minFlow->setObjectName(Parameters::kOdomMonoInitMinFlow().c_str());
1036 _ui->doubleSpinBox_minInitTranslation->setObjectName(Parameters::kOdomMonoInitMinTranslation().c_str());
1037 _ui->doubleSpinBox_minTranslation->setObjectName(Parameters::kOdomMonoMinTranslation().c_str());
1038 _ui->doubleSpinBox_maxVariance->setObjectName(Parameters::kOdomMonoMaxVariance().c_str());
1041 _ui->odom_filteringStrategy->setObjectName(Parameters::kOdomFilteringStrategy().c_str());
1042 _ui->stackedWidget_odometryFiltering->setCurrentIndex(
_ui->odom_filteringStrategy->currentIndex());
1043 connect(
_ui->odom_filteringStrategy, SIGNAL(currentIndexChanged(
int)),
_ui->stackedWidget_odometryFiltering, SLOT(setCurrentIndex(
int)));
1044 _ui->spinBox_particleSize->setObjectName(Parameters::kOdomParticleSize().c_str());
1045 _ui->doubleSpinBox_particleNoiseT->setObjectName(Parameters::kOdomParticleNoiseT().c_str());
1046 _ui->doubleSpinBox_particleLambdaT->setObjectName(Parameters::kOdomParticleLambdaT().c_str());
1047 _ui->doubleSpinBox_particleNoiseR->setObjectName(Parameters::kOdomParticleNoiseR().c_str());
1048 _ui->doubleSpinBox_particleLambdaR->setObjectName(Parameters::kOdomParticleLambdaR().c_str());
1051 _ui->doubleSpinBox_kalmanProcessNoise->setObjectName(Parameters::kOdomKalmanProcessNoise().c_str());
1052 _ui->doubleSpinBox_kalmanMeasurementNoise->setObjectName(Parameters::kOdomKalmanMeasurementNoise().c_str());
1055 _ui->spinBox_OdomFovisFeatureWindowSize->setObjectName(Parameters::kOdomFovisFeatureWindowSize().c_str());
1056 _ui->spinBox_OdomFovisMaxPyramidLevel->setObjectName(Parameters::kOdomFovisMaxPyramidLevel().c_str());
1057 _ui->spinBox_OdomFovisMinPyramidLevel->setObjectName(Parameters::kOdomFovisMinPyramidLevel().c_str());
1058 _ui->spinBox_OdomFovisTargetPixelsPerFeature->setObjectName(Parameters::kOdomFovisTargetPixelsPerFeature().c_str());
1059 _ui->spinBox_OdomFovisFastThreshold->setObjectName(Parameters::kOdomFovisFastThreshold().c_str());
1060 _ui->checkBox_OdomFovisUseAdaptiveThreshold->setObjectName(Parameters::kOdomFovisUseAdaptiveThreshold().c_str());
1061 _ui->doubleSpinBox_OdomFovisFastThresholdAdaptiveGain->setObjectName(Parameters::kOdomFovisFastThresholdAdaptiveGain().c_str());
1062 _ui->checkBox_OdomFovisUseHomographyInitialization->setObjectName(Parameters::kOdomFovisUseHomographyInitialization().c_str());
1064 _ui->checkBox_OdomFovisUseBucketing->setObjectName(Parameters::kOdomFovisUseBucketing().c_str());
1065 _ui->spinBox_OdomFovisBucketWidth->setObjectName(Parameters::kOdomFovisBucketWidth().c_str());
1066 _ui->spinBox_OdomFovisBucketHeight->setObjectName(Parameters::kOdomFovisBucketHeight().c_str());
1067 _ui->spinBox_OdomFovisMaxKeypointsPerBucket->setObjectName(Parameters::kOdomFovisMaxKeypointsPerBucket().c_str());
1068 _ui->checkBox_OdomFovisUseImageNormalization->setObjectName(Parameters::kOdomFovisUseImageNormalization().c_str());
1070 _ui->doubleSpinBox_OdomFovisInlierMaxReprojectionError->setObjectName(Parameters::kOdomFovisInlierMaxReprojectionError().c_str());
1071 _ui->doubleSpinBox_OdomFovisCliqueInlierThreshold->setObjectName(Parameters::kOdomFovisCliqueInlierThreshold().c_str());
1072 _ui->spinBox_OdomFovisMinFeaturesForEstimate->setObjectName(Parameters::kOdomFovisMinFeaturesForEstimate().c_str());
1073 _ui->doubleSpinBox_OdomFovisMaxMeanReprojectionError->setObjectName(Parameters::kOdomFovisMaxMeanReprojectionError().c_str());
1074 _ui->checkBox_OdomFovisUseSubpixelRefinement->setObjectName(Parameters::kOdomFovisUseSubpixelRefinement().c_str());
1075 _ui->spinBox_OdomFovisFeatureSearchWindow->setObjectName(Parameters::kOdomFovisFeatureSearchWindow().c_str());
1076 _ui->checkBox_OdomFovisUpdateTargetFeaturesWithRefined->setObjectName(Parameters::kOdomFovisUpdateTargetFeaturesWithRefined().c_str());
1078 _ui->checkBox_OdomFovisStereoRequireMutualMatch->setObjectName(Parameters::kOdomFovisStereoRequireMutualMatch().c_str());
1079 _ui->doubleSpinBox_OdomFovisStereoMaxDistEpipolarLine->setObjectName(Parameters::kOdomFovisStereoMaxDistEpipolarLine().c_str());
1080 _ui->doubleSpinBox_OdomFovisStereoMaxRefinementDisplacement->setObjectName(Parameters::kOdomFovisStereoMaxRefinementDisplacement().c_str());
1081 _ui->spinBox_OdomFovisStereoMaxDisparity->setObjectName(Parameters::kOdomFovisStereoMaxDisparity().c_str());
1084 _ui->spinBox_OdomViso2RansacIters->setObjectName(Parameters::kOdomViso2RansacIters().c_str());
1085 _ui->doubleSpinBox_OdomViso2InlierThreshold->setObjectName(Parameters::kOdomViso2InlierThreshold().c_str());
1086 _ui->checkBox_OdomViso2Reweighting->setObjectName(Parameters::kOdomViso2Reweighting().c_str());
1088 _ui->spinBox_OdomViso2MatchNmsN->setObjectName(Parameters::kOdomViso2MatchNmsN().c_str());
1089 _ui->spinBox_OdomViso2MatchNmsTau->setObjectName(Parameters::kOdomViso2MatchNmsTau().c_str());
1090 _ui->spinBox_OdomViso2MatchBinsize->setObjectName(Parameters::kOdomViso2MatchBinsize().c_str());
1091 _ui->spinBox_OdomViso2MatchRadius->setObjectName(Parameters::kOdomViso2MatchRadius().c_str());
1092 _ui->spinBox_OdomViso2MatchDispTolerance->setObjectName(Parameters::kOdomViso2MatchDispTolerance().c_str());
1093 _ui->spinBox_OdomViso2MatchOutlierDispTolerance->setObjectName(Parameters::kOdomViso2MatchOutlierDispTolerance().c_str());
1094 _ui->spinBox_OdomViso2MatchOutlierFlowTolerance->setObjectName(Parameters::kOdomViso2MatchOutlierFlowTolerance().c_str());
1095 _ui->checkBox_OdomViso2MatchMultiStage->setObjectName(Parameters::kOdomViso2MatchMultiStage().c_str());
1096 _ui->checkBox_OdomViso2MatchHalfResolution->setObjectName(Parameters::kOdomViso2MatchHalfResolution().c_str());
1097 _ui->spinBox_OdomViso2MatchRefinement->setObjectName(Parameters::kOdomViso2MatchRefinement().c_str());
1099 _ui->spinBox_OdomViso2BucketMaxFeatures->setObjectName(Parameters::kOdomViso2BucketMaxFeatures().c_str());
1100 _ui->doubleSpinBox_OdomViso2BucketWidth->setObjectName(Parameters::kOdomViso2BucketWidth().c_str());
1101 _ui->doubleSpinBox_OdomViso2BucketHeight->setObjectName(Parameters::kOdomViso2BucketHeight().c_str());
1104 _ui->lineEdit_OdomORBSLAM2VocPath->setObjectName(Parameters::kOdomORBSLAM2VocPath().c_str());
1106 _ui->doubleSpinBox_OdomORBSLAM2Bf->setObjectName(Parameters::kOdomORBSLAM2Bf().c_str());
1107 _ui->doubleSpinBox_OdomORBSLAM2ThDepth->setObjectName(Parameters::kOdomORBSLAM2ThDepth().c_str());
1108 _ui->doubleSpinBox_OdomORBSLAM2Fps->setObjectName(Parameters::kOdomORBSLAM2Fps().c_str());
1109 _ui->spinBox_OdomORBSLAM2MaxFeatures->setObjectName(Parameters::kOdomORBSLAM2MaxFeatures().c_str());
1110 _ui->spinBox_OdomORBSLAM2MapSize->setObjectName(Parameters::kOdomORBSLAM2MapSize().c_str());
1113 _ui->lineEdit_OdomOkvisPath->setObjectName(Parameters::kOdomOKVISConfigPath().c_str());
1117 _ui->odom_loam_sensor->setObjectName(Parameters::kOdomLOAMSensor().c_str());
1118 _ui->odom_loam_scan_period->setObjectName(Parameters::kOdomLOAMScanPeriod().c_str());
1119 _ui->odom_loam_linvar->setObjectName(Parameters::kOdomLOAMLinVar().c_str());
1120 _ui->odom_loam_angvar->setObjectName(Parameters::kOdomLOAMAngVar().c_str());
1121 _ui->odom_loam_localMapping->setObjectName(Parameters::kOdomLOAMLocalMapping().c_str());
1124 _ui->OdomMSCKFGridRow->setObjectName(Parameters::kOdomMSCKFGridRow().c_str());
1125 _ui->OdomMSCKFGridCol->setObjectName(Parameters::kOdomMSCKFGridCol().c_str());
1126 _ui->OdomMSCKFGridMinFeatureNum->setObjectName(Parameters::kOdomMSCKFGridMinFeatureNum().c_str());
1127 _ui->OdomMSCKFGridMaxFeatureNum->setObjectName(Parameters::kOdomMSCKFGridMaxFeatureNum().c_str());
1128 _ui->OdomMSCKFPyramidLevels->setObjectName(Parameters::kOdomMSCKFPyramidLevels().c_str());
1129 _ui->OdomMSCKFPatchSize->setObjectName(Parameters::kOdomMSCKFPatchSize().c_str());
1130 _ui->OdomMSCKFFastThreshold->setObjectName(Parameters::kOdomMSCKFFastThreshold().c_str());
1131 _ui->OdomMSCKFMaxIteration->setObjectName(Parameters::kOdomMSCKFMaxIteration().c_str());
1132 _ui->OdomMSCKFMaxCamStateSize->setObjectName(Parameters::kOdomMSCKFMaxCamStateSize().c_str());
1133 _ui->OdomMSCKFTrackPrecision->setObjectName(Parameters::kOdomMSCKFTrackPrecision().c_str());
1134 _ui->OdomMSCKFRansacThreshold->setObjectName(Parameters::kOdomMSCKFRansacThreshold().c_str());
1135 _ui->OdomMSCKFStereoThreshold->setObjectName(Parameters::kOdomMSCKFStereoThreshold().c_str());
1136 _ui->OdomMSCKFPositionStdThreshold->setObjectName(Parameters::kOdomMSCKFPositionStdThreshold().c_str());
1137 _ui->OdomMSCKFRotationThreshold->setObjectName(Parameters::kOdomMSCKFRotationThreshold().c_str());
1138 _ui->OdomMSCKFTranslationThreshold->setObjectName(Parameters::kOdomMSCKFTranslationThreshold().c_str());
1139 _ui->OdomMSCKFTrackingRateThreshold->setObjectName(Parameters::kOdomMSCKFTrackingRateThreshold().c_str());
1140 _ui->OdomMSCKFOptTranslationThreshold->setObjectName(Parameters::kOdomMSCKFOptTranslationThreshold().c_str());
1141 _ui->OdomMSCKFNoiseGyro->setObjectName(Parameters::kOdomMSCKFNoiseGyro().c_str());
1142 _ui->OdomMSCKFNoiseAcc->setObjectName(Parameters::kOdomMSCKFNoiseAcc().c_str());
1143 _ui->OdomMSCKFNoiseGyroBias->setObjectName(Parameters::kOdomMSCKFNoiseGyroBias().c_str());
1144 _ui->OdomMSCKFNoiseAccBias->setObjectName(Parameters::kOdomMSCKFNoiseAccBias().c_str());
1145 _ui->OdomMSCKFNoiseFeature->setObjectName(Parameters::kOdomMSCKFNoiseFeature().c_str());
1146 _ui->OdomMSCKFInitCovVel->setObjectName(Parameters::kOdomMSCKFInitCovVel().c_str());
1147 _ui->OdomMSCKFInitCovGyroBias->setObjectName(Parameters::kOdomMSCKFInitCovGyroBias().c_str());
1148 _ui->OdomMSCKFInitCovAccBias->setObjectName(Parameters::kOdomMSCKFInitCovAccBias().c_str());
1149 _ui->OdomMSCKFInitCovExRot->setObjectName(Parameters::kOdomMSCKFInitCovExRot().c_str());
1150 _ui->OdomMSCKFInitCovExTrans->setObjectName(Parameters::kOdomMSCKFInitCovExTrans().c_str());
1153 _ui->stereo_winWidth->setObjectName(Parameters::kStereoWinWidth().c_str());
1154 _ui->stereo_winHeight->setObjectName(Parameters::kStereoWinHeight().c_str());
1155 _ui->stereo_maxLevel->setObjectName(Parameters::kStereoMaxLevel().c_str());
1156 _ui->stereo_iterations->setObjectName(Parameters::kStereoIterations().c_str());
1157 _ui->stereo_minDisparity->setObjectName(Parameters::kStereoMinDisparity().c_str());
1158 _ui->stereo_maxDisparity->setObjectName(Parameters::kStereoMaxDisparity().c_str());
1159 _ui->stereo_ssd->setObjectName(Parameters::kStereoSSD().c_str());
1160 _ui->stereo_flow_eps->setObjectName(Parameters::kStereoEps().c_str());
1161 _ui->stereo_opticalFlow->setObjectName(Parameters::kStereoOpticalFlow().c_str());
1164 _ui->stereobm_blockSize->setObjectName(Parameters::kStereoBMBlockSize().c_str());
1165 _ui->stereobm_minDisparity->setObjectName(Parameters::kStereoBMMinDisparity().c_str());
1166 _ui->stereobm_numDisparities->setObjectName(Parameters::kStereoBMNumDisparities().c_str());
1167 _ui->stereobm_preFilterCap->setObjectName(Parameters::kStereoBMPreFilterCap().c_str());
1168 _ui->stereobm_preFilterSize->setObjectName(Parameters::kStereoBMPreFilterSize().c_str());
1169 _ui->stereobm_speckleRange->setObjectName(Parameters::kStereoBMSpeckleRange().c_str());
1170 _ui->stereobm_speckleWinSize->setObjectName(Parameters::kStereoBMSpeckleWindowSize().c_str());
1171 _ui->stereobm_tetureThreshold->setObjectName(Parameters::kStereoBMTextureThreshold().c_str());
1172 _ui->stereobm_uniquessRatio->setObjectName(Parameters::kStereoBMUniquenessRatio().c_str());
1184 connect(
_ui->doubleSpinBox_kp_roi0, SIGNAL(valueChanged(
double)),
this, SLOT(
updateKpROI()));
1185 connect(
_ui->doubleSpinBox_kp_roi1, SIGNAL(valueChanged(
double)),
this, SLOT(
updateKpROI()));
1186 connect(
_ui->doubleSpinBox_kp_roi2, SIGNAL(valueChanged(
double)),
this, SLOT(
updateKpROI()));
1187 connect(
_ui->doubleSpinBox_kp_roi3, SIGNAL(valueChanged(
double)),
this, SLOT(
updateKpROI()));
1188 connect(
_ui->checkBox_useOdomFeatures, SIGNAL(toggled(
bool)),
this, SLOT(
useOdomFeatures()));
1192 _ui->stackedWidget->setCurrentIndex(0);
1209 for(ParametersMap::const_iterator iter=defaults.begin(); iter!=defaults.end(); ++iter)
1223 for(
int i =0;i<boxes.size();++i)
1225 if(boxes[i] ==
_ui->groupBox_source0)
1227 _ui->stackedWidget->setCurrentIndex(i);
1243 _ui->treeView->setModel(0);
1249 if(
_ui->radioButton_basic->isChecked())
1251 boxes = boxes.mid(0,7);
1258 QStandardItem * parentItem =
_indexModel->invisibleRootItem();
1260 this->
parseModel(boxes, parentItem, 0, index);
1261 if(
_ui->radioButton_advanced->isChecked() && index !=
_ui->stackedWidget->count()-1)
1263 ULOGGER_ERROR(
"The tree model is not the same size of the stacked widgets...%d vs %d advanced stacks", index,
_ui->stackedWidget->count()-1);
1265 int currentIndex =
_ui->stackedWidget->currentIndex();
1266 if(
_ui->radioButton_basic->isChecked())
1268 if(currentIndex >= 6)
1270 _ui->stackedWidget->setCurrentIndex(6);
1276 if(currentIndex == 6)
1278 _ui->stackedWidget->setCurrentIndex(7);
1282 _ui->treeView->expandToDepth(1);
1285 connect(
_ui->treeView->selectionModel(), SIGNAL(currentChanged(
const QModelIndex &,
const QModelIndex &)),
this, SLOT(
clicked(
const QModelIndex &,
const QModelIndex &)));
1297 QStandardItem * currentItem = 0;
1298 while(absoluteIndex < boxes.size())
1300 QString objectName = boxes.at(absoluteIndex)->objectName();
1301 QString title = boxes.at(absoluteIndex)->title();
1303 int lvl = QString(objectName.at(objectName.size()-1)).toInt(&ok);
1306 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());
1311 if(lvl == currentLevel)
1313 QStandardItem * item =
new QStandardItem(title);
1314 item->setData(absoluteIndex);
1317 parentItem->appendRow(item);
1320 else if(lvl > currentLevel)
1322 if(lvl>currentLevel+1)
1324 ULOGGER_ERROR(
"Intermediary lvl doesn't exist, lvl %d to %d, indexes %d and %d", currentLevel, lvl, absoluteIndex-1, absoluteIndex);
1329 parseModel(boxes, currentItem, currentLevel+1, absoluteIndex);
1343 for(rtabmap::ParametersMap::const_iterator iter=parameters.begin(); iter!=parameters.end(); ++iter)
1345 QWidget * obj =
_ui->stackedWidget->findChild<QWidget*>((*iter).first.c_str());
1349 obj->setToolTip(tr(
"%1 (Default=\"%2\")").arg(iter->first.c_str()).arg(iter->second.c_str()));
1351 QSpinBox * spin = qobject_cast<QSpinBox *>(obj);
1352 QDoubleSpinBox * doubleSpin = qobject_cast<QDoubleSpinBox *>(obj);
1353 QComboBox * combo = qobject_cast<QComboBox *>(obj);
1354 QCheckBox * check = qobject_cast<QCheckBox *>(obj);
1355 QRadioButton * radio = qobject_cast<QRadioButton *>(obj);
1356 QLineEdit * lineEdit = qobject_cast<QLineEdit *>(obj);
1357 QGroupBox * groupBox = qobject_cast<QGroupBox *>(obj);
1360 connect(spin, SIGNAL(valueChanged(
int)),
this, SLOT(
addParameter(
int)));
1364 connect(doubleSpin, SIGNAL(valueChanged(
double)),
this, SLOT(
addParameter(
double)));
1368 connect(combo, SIGNAL(currentIndexChanged(
int)),
this, SLOT(
addParameter(
int)));
1372 connect(check, SIGNAL(toggled(
bool)),
this, SLOT(
addParameter(
bool)));
1376 connect(radio, SIGNAL(toggled(
bool)),
this, SLOT(
addParameter(
bool)));
1380 connect(lineEdit, SIGNAL(textChanged(
const QString &)),
this, SLOT(
addParameter(
const QString &)));
1384 connect(groupBox, SIGNAL(toggled(
bool)),
this, SLOT(
addParameter(
bool)));
1388 ULOGGER_WARN(
"QWidget called %s can't be cast to a supported widget", (*iter).first.c_str());
1393 ULOGGER_WARN(
"Can't find the related QWidget for parameter %s", (*iter).first.c_str());
1400 QStandardItem * item =
_indexModel->itemFromIndex(current);
1401 if(item && item->isEnabled())
1403 int index = item->data().toInt();
1404 if(
_ui->radioButton_advanced->isChecked() && index >= 6)
1408 _ui->stackedWidget->setCurrentIndex(index);
1409 _ui->scrollArea->horizontalScrollBar()->setValue(0);
1410 _ui->scrollArea->verticalScrollBar()->setValue(0);
1428 QDialogButtonBox::ButtonRole role =
_ui->buttonBox_global->buttonRole(button);
1431 case QDialogButtonBox::RejectRole:
1439 case QDialogButtonBox::AcceptRole:
1462 QDialogButtonBox::ButtonRole role =
_ui->buttonBox_local->buttonRole(button);
1465 case QDialogButtonBox::ApplyRole:
1473 case QDialogButtonBox::ResetRole:
1484 if(groupBox->objectName() ==
_ui->groupBox_generalSettingsGui0->objectName())
1486 _ui->general_checkBox_imagesKept->setChecked(
true);
1487 _ui->general_checkBox_cloudsKept->setChecked(
true);
1488 _ui->checkBox_beep->setChecked(
false);
1489 _ui->checkBox_stamps->setChecked(
true);
1490 _ui->checkBox_cacheStatistics->setChecked(
true);
1491 _ui->checkBox_notifyWhenNewGlobalPathIsReceived->setChecked(
false);
1492 _ui->checkBox_verticalLayoutUsed->setChecked(
true);
1493 _ui->checkBox_imageRejectedShown->setChecked(
true);
1494 _ui->checkBox_imageHighestHypShown->setChecked(
false);
1495 _ui->spinBox_odomQualityWarnThr->setValue(50);
1496 _ui->checkBox_odom_onlyInliersShown->setChecked(
false);
1497 _ui->radioButton_posteriorGraphView->setChecked(
true);
1498 _ui->radioButton_wordsGraphView->setChecked(
false);
1499 _ui->radioButton_localizationsGraphView->setChecked(
false);
1500 _ui->radioButton_nochangeGraphView->setChecked(
false);
1501 _ui->checkbox_odomDisabled->setChecked(
false);
1502 _ui->checkbox_groundTruthAlign->setChecked(
true);
1504 else if(groupBox->objectName() ==
_ui->groupBox_cloudRendering1->objectName())
1506 for(
int i=0; i<2; ++i)
1529 _ui->doubleSpinBox_voxel->setValue(0);
1530 _ui->doubleSpinBox_noiseRadius->setValue(0);
1531 _ui->spinBox_noiseMinNeighbors->setValue(5);
1533 _ui->doubleSpinBox_ceilingFilterHeight->setValue(0);
1534 _ui->doubleSpinBox_floorFilterHeight->setValue(0);
1535 _ui->spinBox_normalKSearch->setValue(10);
1536 _ui->doubleSpinBox_normalRadiusSearch->setValue(0.0);
1538 _ui->doubleSpinBox_ceilingFilterHeight_scan->setValue(0);
1539 _ui->doubleSpinBox_floorFilterHeight_scan->setValue(0);
1540 _ui->spinBox_normalKSearch_scan->setValue(0);
1541 _ui->doubleSpinBox_normalRadiusSearch_scan->setValue(0.0);
1543 _ui->checkBox_showGraphs->setChecked(
true);
1544 _ui->checkBox_showLabels->setChecked(
false);
1546 _ui->doubleSpinBox_mesh_angleTolerance->setValue(15.0);
1547 _ui->groupBox_organized->setChecked(
false);
1548 #if PCL_VERSION_COMPARE(>=, 1, 7, 2) 1549 _ui->checkBox_mesh_quad->setChecked(
true);
1551 _ui->checkBox_mesh_quad->setChecked(
false);
1553 _ui->checkBox_mesh_texture->setChecked(
false);
1554 _ui->spinBox_mesh_triangleSize->setValue(2);
1556 else if(groupBox->objectName() ==
_ui->groupBox_filtering2->objectName())
1558 _ui->radioButton_noFiltering->setChecked(
true);
1559 _ui->radioButton_nodeFiltering->setChecked(
false);
1560 _ui->radioButton_subtractFiltering->setChecked(
false);
1561 _ui->doubleSpinBox_cloudFilterRadius->setValue(0.1);
1562 _ui->doubleSpinBox_cloudFilterAngle->setValue(30);
1563 _ui->spinBox_subtractFilteringMinPts->setValue(5);
1564 _ui->doubleSpinBox_subtractFilteringRadius->setValue(0.02);
1565 _ui->doubleSpinBox_subtractFilteringAngle->setValue(0);
1567 else if(groupBox->objectName() ==
_ui->groupBox_gridMap2->objectName())
1569 _ui->checkBox_map_shown->setChecked(
false);
1570 _ui->doubleSpinBox_map_opacity->setValue(0.75);
1572 _ui->groupBox_octomap->setChecked(
false);
1573 _ui->spinBox_octomap_treeDepth->setValue(16);
1574 _ui->checkBox_octomap_2dgrid->setChecked(
true);
1575 _ui->checkBox_octomap_show3dMap->setChecked(
true);
1576 _ui->comboBox_octomap_renderingType->setCurrentIndex(0);
1577 _ui->spinBox_octomap_pointSize->setValue(5);
1579 else if(groupBox->objectName() ==
_ui->groupBox_logging1->objectName())
1581 _ui->comboBox_loggerLevel->setCurrentIndex(2);
1582 _ui->comboBox_loggerEventLevel->setCurrentIndex(3);
1583 _ui->comboBox_loggerPauseLevel->setCurrentIndex(3);
1584 _ui->checkBox_logger_printTime->setChecked(
true);
1585 _ui->checkBox_logger_printThreadId->setChecked(
false);
1586 _ui->comboBox_loggerType->setCurrentIndex(1);
1587 for(
int i=0; i<
_ui->comboBox_loggerFilter->count(); ++i)
1589 _ui->comboBox_loggerFilter->setItemChecked(i,
false);
1592 else if(groupBox->objectName() ==
_ui->groupBox_source0->objectName())
1594 _ui->general_doubleSpinBox_imgRate->setValue(0.0);
1595 _ui->source_mirroring->setChecked(
false);
1596 _ui->lineEdit_calibrationFile->clear();
1597 _ui->comboBox_sourceType->setCurrentIndex(
kSrcRGBD);
1598 _ui->lineEdit_sourceDevice->setText(
"");
1599 _ui->lineEdit_sourceLocalTransform->setText(
"0 0 1 -1 0 0 0 -1 0");
1602 _ui->source_images_spinBox_startPos->setValue(0);
1603 _ui->checkBox_rgb_rectify->setChecked(
false);
1604 _ui->comboBox_cameraImages_bayerMode->setCurrentIndex(0);
1606 _ui->source_checkBox_ignoreOdometry->setChecked(
false);
1607 _ui->source_checkBox_ignoreGoalDelay->setChecked(
true);
1608 _ui->source_checkBox_ignoreGoals->setChecked(
true);
1609 _ui->source_spinBox_databaseStartPos->setValue(0);
1610 _ui->source_spinBox_database_cameraIndex->setValue(-1);
1611 _ui->source_checkBox_useDbStamps->setChecked(
true);
1642 _ui->checkbox_rgbd_colorOnly->setChecked(
false);
1643 _ui->spinBox_source_imageDecimation->setValue(1);
1644 _ui->checkbox_stereo_depthGenerated->setChecked(
false);
1645 _ui->checkBox_stereo_exposureCompensation->setChecked(
false);
1646 _ui->openni2_autoWhiteBalance->setChecked(
true);
1647 _ui->openni2_autoExposure->setChecked(
true);
1648 _ui->openni2_exposure->setValue(0);
1649 _ui->openni2_gain->setValue(100);
1650 _ui->openni2_mirroring->setChecked(
false);
1651 _ui->openni2_stampsIdsUsed->setChecked(
false);
1652 _ui->openni2_hshift->setValue(0);
1653 _ui->openni2_vshift->setValue(0);
1654 _ui->comboBox_freenect2Format->setCurrentIndex(1);
1655 _ui->doubleSpinBox_freenect2MinDepth->setValue(0.3);
1656 _ui->doubleSpinBox_freenect2MaxDepth->setValue(12.0);
1657 _ui->checkBox_freenect2BilateralFiltering->setChecked(
true);
1658 _ui->checkBox_freenect2EdgeAwareFiltering->setChecked(
true);
1659 _ui->checkBox_freenect2NoiseFiltering->setChecked(
true);
1660 _ui->lineEdit_freenect2Pipeline->setText(
"");
1661 _ui->comboBox_k4w2Format->setCurrentIndex(1);
1662 _ui->comboBox_realsensePresetRGB->setCurrentIndex(0);
1663 _ui->comboBox_realsensePresetDepth->setCurrentIndex(2);
1664 _ui->checkbox_realsenseOdom->setChecked(
false);
1665 _ui->checkbox_realsenseDepthScaledToRGBSize->setChecked(
false);
1666 _ui->comboBox_realsenseRGBSource->setCurrentIndex(0);
1667 _ui->checkbox_rs2_emitter->setChecked(
true);
1668 _ui->checkbox_rs2_irDepth->setChecked(
false);
1669 _ui->lineEdit_openniOniPath->clear();
1670 _ui->lineEdit_openni2OniPath->clear();
1671 _ui->lineEdit_cameraRGBDImages_path_rgb->setText(
"");
1672 _ui->lineEdit_cameraRGBDImages_path_depth->setText(
"");
1673 _ui->doubleSpinBox_cameraRGBDImages_scale->setValue(1.0);
1674 _ui->spinBox_cameraRGBDImages_startIndex->setValue(0);
1675 _ui->lineEdit_source_distortionModel->setText(
"");
1676 _ui->groupBox_bilateral->setChecked(
false);
1677 _ui->doubleSpinBox_bilateral_sigmaS->setValue(10.0);
1678 _ui->doubleSpinBox_bilateral_sigmaR->setValue(0.1);
1681 _ui->lineEdit_cameraStereoImages_path_left->setText(
"");
1682 _ui->lineEdit_cameraStereoImages_path_right->setText(
"");
1683 _ui->checkBox_stereo_rectify->setChecked(
false);
1684 _ui->spinBox_cameraStereoImages_startIndex->setValue(0);
1685 _ui->lineEdit_cameraStereoVideo_path->setText(
"");
1686 _ui->lineEdit_cameraStereoVideo_path_2->setText(
"");
1687 _ui->spinBox_stereo_right_device->setValue(-1);
1688 _ui->comboBox_stereoZed_resolution->setCurrentIndex(2);
1689 _ui->comboBox_stereoZed_quality->setCurrentIndex(1);
1690 _ui->checkbox_stereoZed_selfCalibration->setChecked(
true);
1691 _ui->comboBox_stereoZed_sensingMode->setCurrentIndex(0);
1692 _ui->spinBox_stereoZed_confidenceThr->setValue(100);
1693 _ui->checkbox_stereoZed_odom->setChecked(
false);
1694 _ui->lineEdit_zedSvoPath->clear();
1696 _ui->checkBox_cameraImages_timestamps->setChecked(
false);
1697 _ui->checkBox_cameraImages_syncTimeStamps->setChecked(
true);
1698 _ui->lineEdit_cameraImages_timestamps->setText(
"");
1699 _ui->lineEdit_cameraImages_path_scans->setText(
"");
1700 _ui->lineEdit_cameraImages_laser_transform->setText(
"0 0 0 0 0 0");
1701 _ui->spinBox_cameraImages_max_scan_pts->setValue(0);
1702 _ui->spinBox_cameraImages_scanDownsampleStep->setValue(1);
1703 _ui->doubleSpinBox_cameraImages_scanVoxelSize->setValue(0.0
f);
1704 _ui->lineEdit_cameraImages_odom->setText(
"");
1705 _ui->comboBox_cameraImages_odomFormat->setCurrentIndex(0);
1706 _ui->lineEdit_cameraImages_gt->setText(
"");
1707 _ui->comboBox_cameraImages_gtFormat->setCurrentIndex(0);
1708 _ui->doubleSpinBox_maxPoseTimeDiff->setValue(0.02);
1709 _ui->lineEdit_cameraImages_path_imu->setText(
"");
1710 _ui->lineEdit_cameraImages_imu_transform->setText(
"0 0 1 0 -1 0 1 0 0");
1711 _ui->spinBox_cameraImages_max_imu_rate->setValue(0);
1713 _ui->groupBox_scanFromDepth->setChecked(
false);
1714 _ui->spinBox_cameraScanFromDepth_decimation->setValue(8);
1715 _ui->doubleSpinBox_cameraSCanFromDepth_maxDepth->setValue(4.0);
1716 _ui->doubleSpinBox_cameraImages_scanVoxelSize->setValue(0.025
f);
1717 _ui->spinBox_cameraImages_scanNormalsK->setValue(20);
1718 _ui->doubleSpinBox_cameraImages_scanNormalsRadius->setValue(0.0);
1719 _ui->checkBox_cameraImages_scanForceGroundNormalsUp->setChecked(
false);
1721 _ui->groupBox_depthFromScan->setChecked(
false);
1722 _ui->groupBox_depthFromScan_fillHoles->setChecked(
true);
1723 _ui->radioButton_depthFromScan_vertical->setChecked(
true);
1724 _ui->radioButton_depthFromScan_horizontal->setChecked(
false);
1725 _ui->checkBox_depthFromScan_fillBorders->setChecked(
false);
1727 else if(groupBox->objectName() ==
_ui->groupBox_rtabmap_basic0->objectName())
1729 _ui->general_doubleSpinBox_timeThr_2->setValue(Parameters::defaultRtabmapTimeThr());
1730 _ui->general_doubleSpinBox_hardThr_2->setValue(Parameters::defaultRtabmapLoopThr());
1731 _ui->doubleSpinBox_similarityThreshold_2->setValue(Parameters::defaultMemRehearsalSimilarity());
1732 _ui->general_spinBox_imagesBufferSize_2->setValue(Parameters::defaultRtabmapImageBufferSize());
1733 _ui->general_spinBox_maxStMemSize_2->setValue(Parameters::defaultMemSTMSize());
1734 _ui->general_checkBox_publishStats_2->setChecked(Parameters::defaultRtabmapPublishStats());
1735 _ui->general_checkBox_activateRGBD_2->setChecked(Parameters::defaultRGBDEnabled());
1736 _ui->general_checkBox_SLAM_mode_2->setChecked(Parameters::defaultMemIncrementalMemory());
1737 _ui->general_doubleSpinBox_detectionRate_2->setValue(Parameters::defaultRtabmapDetectionRate());
1739 _ui->general_doubleSpinBox_timeThr->setValue(Parameters::defaultRtabmapTimeThr());
1740 _ui->general_doubleSpinBox_hardThr->setValue(Parameters::defaultRtabmapLoopThr());
1741 _ui->doubleSpinBox_similarityThreshold->setValue(Parameters::defaultMemRehearsalSimilarity());
1742 _ui->general_spinBox_imagesBufferSize->setValue(Parameters::defaultRtabmapImageBufferSize());
1743 _ui->general_spinBox_maxStMemSize->setValue(Parameters::defaultMemSTMSize());
1744 _ui->general_doubleSpinBox_detectionRate->setValue(Parameters::defaultRtabmapDetectionRate());
1748 QObjectList children = groupBox->children();
1751 for(
int i=0; i<children.size(); ++i)
1753 key = children.at(i)->objectName().toStdString();
1756 if(key.compare(Parameters::kRtabmapWorkingDirectory().c_str()) == 0)
1764 if(qobject_cast<const QGroupBox*>(children.at(i)))
1769 else if(qobject_cast<const QGroupBox*>(children.at(i)))
1773 else if(qobject_cast<const QStackedWidget*>(children.at(i)))
1775 QStackedWidget * stackedWidget = (QStackedWidget*)children.at(i);
1776 for(
int j=0; j<stackedWidget->count(); ++j)
1778 const QObjectList & children2 = stackedWidget->widget(j)->children();
1779 for(
int k=0; k<children2.size(); ++k)
1781 if(qobject_cast<QGroupBox *>(children2.at(k)))
1790 if(groupBox->findChild<QLineEdit*>(
_ui->lineEdit_kp_roi->objectName()))
1795 if(groupBox->objectName() ==
_ui->groupBox_odometry1->objectName())
1797 _ui->odom_registration->setCurrentIndex(3);
1805 if(panelNumber >= 0 && panelNumber < boxes.size())
1809 else if(panelNumber == -1)
1811 for(QList<QGroupBox*>::iterator iter = boxes.begin(); iter!=boxes.end(); ++iter)
1818 ULOGGER_WARN(
"panel number and the number of stacked widget doesn't match");
1825 return _ui->lineEdit_workingDirectory->text();
1830 QString privatePath = QDir::homePath() +
"/.rtabmap";
1831 if(!QDir(privatePath).exists())
1833 QDir::home().mkdir(
".rtabmap");
1835 return privatePath +
"/rtabmap.ini";
1845 QString path = QFileDialog::getOpenFileName(
this, tr(
"Load settings..."), this->
getWorkingDirectory(),
"*.ini");
1863 QStandardItem * parentItem =
_indexModel->invisibleRootItem();
1866 for(
int i=1; i<parentItem->rowCount(); ++i)
1868 parentItem->child(i)->setEnabled(
false);
1871 _ui->radioButton_basic->setEnabled(
false);
1872 _ui->radioButton_advanced->setEnabled(
false);
1877 QStandardItem * parentItem =
_indexModel->invisibleRootItem();
1880 for(
int i=0; i<parentItem->rowCount(); ++i)
1882 parentItem->child(i)->setEnabled(
true);
1885 _ui->radioButton_basic->setEnabled(
true);
1886 _ui->radioButton_advanced->setEnabled(
true);
1893 if(!filePath.isEmpty())
1897 QSettings settings(path, QSettings::IniFormat);
1898 settings.beginGroup(
"Gui");
1899 settings.beginGroup(
"General");
1900 _ui->general_checkBox_imagesKept->setChecked(settings.value(
"imagesKept",
_ui->general_checkBox_imagesKept->isChecked()).toBool());
1901 _ui->general_checkBox_cloudsKept->setChecked(settings.value(
"cloudsKept",
_ui->general_checkBox_cloudsKept->isChecked()).toBool());
1902 _ui->comboBox_loggerLevel->setCurrentIndex(settings.value(
"loggerLevel",
_ui->comboBox_loggerLevel->currentIndex()).toInt());
1903 _ui->comboBox_loggerEventLevel->setCurrentIndex(settings.value(
"loggerEventLevel",
_ui->comboBox_loggerEventLevel->currentIndex()).toInt());
1904 _ui->comboBox_loggerPauseLevel->setCurrentIndex(settings.value(
"loggerPauseLevel",
_ui->comboBox_loggerPauseLevel->currentIndex()).toInt());
1905 _ui->comboBox_loggerType->setCurrentIndex(settings.value(
"loggerType",
_ui->comboBox_loggerType->currentIndex()).toInt());
1906 _ui->checkBox_logger_printTime->setChecked(settings.value(
"loggerPrintTime",
_ui->checkBox_logger_printTime->isChecked()).toBool());
1907 _ui->checkBox_logger_printThreadId->setChecked(settings.value(
"loggerPrintThreadId",
_ui->checkBox_logger_printThreadId->isChecked()).toBool());
1908 _ui->checkBox_verticalLayoutUsed->setChecked(settings.value(
"verticalLayoutUsed",
_ui->checkBox_verticalLayoutUsed->isChecked()).toBool());
1909 _ui->checkBox_imageRejectedShown->setChecked(settings.value(
"imageRejectedShown",
_ui->checkBox_imageRejectedShown->isChecked()).toBool());
1910 _ui->checkBox_imageHighestHypShown->setChecked(settings.value(
"imageHighestHypShown",
_ui->checkBox_imageHighestHypShown->isChecked()).toBool());
1911 _ui->checkBox_beep->setChecked(settings.value(
"beep",
_ui->checkBox_beep->isChecked()).toBool());
1912 _ui->checkBox_stamps->setChecked(settings.value(
"figure_time",
_ui->checkBox_stamps->isChecked()).toBool());
1913 _ui->checkBox_cacheStatistics->setChecked(settings.value(
"figure_cache",
_ui->checkBox_cacheStatistics->isChecked()).toBool());
1914 _ui->checkBox_notifyWhenNewGlobalPathIsReceived->setChecked(settings.value(
"notifyNewGlobalPath",
_ui->checkBox_notifyWhenNewGlobalPathIsReceived->isChecked()).toBool());
1915 _ui->spinBox_odomQualityWarnThr->setValue(settings.value(
"odomQualityThr",
_ui->spinBox_odomQualityWarnThr->value()).toInt());
1916 _ui->checkBox_odom_onlyInliersShown->setChecked(settings.value(
"odomOnlyInliersShown",
_ui->checkBox_odom_onlyInliersShown->isChecked()).toBool());
1917 _ui->radioButton_posteriorGraphView->setChecked(settings.value(
"posteriorGraphView",
_ui->radioButton_posteriorGraphView->isChecked()).toBool());
1918 _ui->radioButton_wordsGraphView->setChecked(settings.value(
"wordsGraphView",
_ui->radioButton_wordsGraphView->isChecked()).toBool());
1919 _ui->radioButton_localizationsGraphView->setChecked(settings.value(
"localizationsGraphView",
_ui->radioButton_localizationsGraphView->isChecked()).toBool());
1920 _ui->radioButton_nochangeGraphView->setChecked(settings.value(
"nochangeGraphView",
_ui->radioButton_nochangeGraphView->isChecked()).toBool());
1921 _ui->checkbox_odomDisabled->setChecked(settings.value(
"odomDisabled",
_ui->checkbox_odomDisabled->isChecked()).toBool());
1922 _ui->odom_registration->setCurrentIndex(settings.value(
"odomRegistration",
_ui->odom_registration->currentIndex()).toInt());
1923 _ui->checkbox_groundTruthAlign->setChecked(settings.value(
"gtAlign",
_ui->checkbox_groundTruthAlign->isChecked()).toBool());
1925 for(
int i=0; i<2; ++i)
1948 _ui->doubleSpinBox_voxel->setValue(settings.value(
"cloudVoxel",
_ui->doubleSpinBox_voxel->value()).toDouble());
1949 _ui->doubleSpinBox_noiseRadius->setValue(settings.value(
"cloudNoiseRadius",
_ui->doubleSpinBox_noiseRadius->value()).toDouble());
1950 _ui->spinBox_noiseMinNeighbors->setValue(settings.value(
"cloudNoiseMinNeighbors",
_ui->spinBox_noiseMinNeighbors->value()).toInt());
1951 _ui->doubleSpinBox_ceilingFilterHeight->setValue(settings.value(
"cloudCeilingHeight",
_ui->doubleSpinBox_ceilingFilterHeight->value()).toDouble());
1952 _ui->doubleSpinBox_floorFilterHeight->setValue(settings.value(
"cloudFloorHeight",
_ui->doubleSpinBox_floorFilterHeight->value()).toDouble());
1953 _ui->spinBox_normalKSearch->setValue(settings.value(
"normalKSearch",
_ui->spinBox_normalKSearch->value()).toInt());
1954 _ui->doubleSpinBox_normalRadiusSearch->setValue(settings.value(
"normalRadiusSearch",
_ui->doubleSpinBox_normalRadiusSearch->value()).toDouble());
1955 _ui->doubleSpinBox_ceilingFilterHeight_scan->setValue(settings.value(
"scanCeilingHeight",
_ui->doubleSpinBox_ceilingFilterHeight_scan->value()).toDouble());
1956 _ui->doubleSpinBox_floorFilterHeight_scan->setValue(settings.value(
"scanFloorHeight",
_ui->doubleSpinBox_floorFilterHeight_scan->value()).toDouble());
1957 _ui->spinBox_normalKSearch_scan->setValue(settings.value(
"scanNormalKSearch",
_ui->spinBox_normalKSearch_scan->value()).toInt());
1958 _ui->doubleSpinBox_normalRadiusSearch_scan->setValue(settings.value(
"scanNormalRadiusSearch",
_ui->doubleSpinBox_normalRadiusSearch_scan->value()).toDouble());
1960 _ui->checkBox_showGraphs->setChecked(settings.value(
"showGraphs",
_ui->checkBox_showGraphs->isChecked()).toBool());
1961 _ui->checkBox_showLabels->setChecked(settings.value(
"showLabels",
_ui->checkBox_showLabels->isChecked()).toBool());
1963 _ui->radioButton_noFiltering->setChecked(settings.value(
"noFiltering",
_ui->radioButton_noFiltering->isChecked()).toBool());
1964 _ui->radioButton_nodeFiltering->setChecked(settings.value(
"cloudFiltering",
_ui->radioButton_nodeFiltering->isChecked()).toBool());
1965 _ui->doubleSpinBox_cloudFilterRadius->setValue(settings.value(
"cloudFilteringRadius",
_ui->doubleSpinBox_cloudFilterRadius->value()).toDouble());
1966 _ui->doubleSpinBox_cloudFilterAngle->setValue(settings.value(
"cloudFilteringAngle",
_ui->doubleSpinBox_cloudFilterAngle->value()).toDouble());
1967 _ui->radioButton_subtractFiltering->setChecked(settings.value(
"subtractFiltering",
_ui->radioButton_subtractFiltering->isChecked()).toBool());
1968 _ui->spinBox_subtractFilteringMinPts->setValue(settings.value(
"subtractFilteringMinPts",
_ui->spinBox_subtractFilteringMinPts->value()).toInt());
1969 _ui->doubleSpinBox_subtractFilteringRadius->setValue(settings.value(
"subtractFilteringRadius",
_ui->doubleSpinBox_subtractFilteringRadius->value()).toDouble());
1970 _ui->doubleSpinBox_subtractFilteringAngle->setValue(settings.value(
"subtractFilteringAngle",
_ui->doubleSpinBox_subtractFilteringAngle->value()).toDouble());
1972 _ui->checkBox_map_shown->setChecked(settings.value(
"gridMapShown",
_ui->checkBox_map_shown->isChecked()).toBool());
1973 _ui->doubleSpinBox_map_opacity->setValue(settings.value(
"gridMapOpacity",
_ui->doubleSpinBox_map_opacity->value()).toDouble());
1975 _ui->groupBox_octomap->setChecked(settings.value(
"octomap",
_ui->groupBox_octomap->isChecked()).toBool());
1976 _ui->spinBox_octomap_treeDepth->setValue(settings.value(
"octomap_depth",
_ui->spinBox_octomap_treeDepth->value()).toInt());
1977 _ui->checkBox_octomap_2dgrid->setChecked(settings.value(
"octomap_2dgrid",
_ui->checkBox_octomap_2dgrid->isChecked()).toBool());
1978 _ui->checkBox_octomap_show3dMap->setChecked(settings.value(
"octomap_3dmap",
_ui->checkBox_octomap_show3dMap->isChecked()).toBool());
1979 _ui->comboBox_octomap_renderingType->setCurrentIndex(settings.value(
"octomap_rendering_type",
_ui->comboBox_octomap_renderingType->currentIndex()).toInt());
1980 _ui->spinBox_octomap_pointSize->setValue(settings.value(
"octomap_point_size",
_ui->spinBox_octomap_pointSize->value()).toInt());
1982 _ui->groupBox_organized->setChecked(settings.value(
"meshing",
_ui->groupBox_organized->isChecked()).toBool());
1983 _ui->doubleSpinBox_mesh_angleTolerance->setValue(settings.value(
"meshing_angle",
_ui->doubleSpinBox_mesh_angleTolerance->value()).toDouble());
1984 _ui->checkBox_mesh_quad->setChecked(settings.value(
"meshing_quad",
_ui->checkBox_mesh_quad->isChecked()).toBool());
1985 _ui->checkBox_mesh_texture->setChecked(settings.value(
"meshing_texture",
_ui->checkBox_mesh_texture->isChecked()).toBool());
1986 _ui->spinBox_mesh_triangleSize->setValue(settings.value(
"meshing_triangle_size",
_ui->spinBox_mesh_triangleSize->value()).toInt());
1988 settings.endGroup();
1990 settings.endGroup();
1996 if(!filePath.isEmpty())
2000 QSettings settings(path, QSettings::IniFormat);
2002 settings.beginGroup(
"Camera");
2003 _ui->general_doubleSpinBox_imgRate->setValue(settings.value(
"imgRate",
_ui->general_doubleSpinBox_imgRate->value()).toDouble());
2004 _ui->source_mirroring->setChecked(settings.value(
"mirroring",
_ui->source_mirroring->isChecked()).toBool());
2005 _ui->lineEdit_calibrationFile->setText(settings.value(
"calibrationName",
_ui->lineEdit_calibrationFile->text()).toString());
2006 _ui->comboBox_sourceType->setCurrentIndex(settings.value(
"type",
_ui->comboBox_sourceType->currentIndex()).toInt());
2007 _ui->lineEdit_sourceDevice->setText(settings.value(
"device",
_ui->lineEdit_sourceDevice->text()).toString());
2008 _ui->lineEdit_sourceLocalTransform->setText(settings.value(
"localTransform",
_ui->lineEdit_sourceLocalTransform->text()).toString());
2009 _ui->spinBox_source_imageDecimation->setValue(settings.value(
"imageDecimation",
_ui->spinBox_source_imageDecimation->value()).toInt());
2011 settings.beginGroup(
"rgbd");
2012 _ui->comboBox_cameraRGBD->setCurrentIndex(settings.value(
"driver",
_ui->comboBox_cameraRGBD->currentIndex()).toInt());
2013 _ui->checkbox_rgbd_colorOnly->setChecked(settings.value(
"rgbdColorOnly",
_ui->checkbox_rgbd_colorOnly->isChecked()).toBool());
2014 _ui->lineEdit_source_distortionModel->setText(settings.value(
"distortion_model",
_ui->lineEdit_source_distortionModel->text()).toString());
2015 _ui->groupBox_bilateral->setChecked(settings.value(
"bilateral",
_ui->groupBox_bilateral->isChecked()).toBool());
2016 _ui->doubleSpinBox_bilateral_sigmaS->setValue(settings.value(
"bilateral_sigma_s",
_ui->doubleSpinBox_bilateral_sigmaS->value()).toDouble());
2017 _ui->doubleSpinBox_bilateral_sigmaR->setValue(settings.value(
"bilateral_sigma_r",
_ui->doubleSpinBox_bilateral_sigmaR->value()).toDouble());
2018 settings.endGroup();
2020 settings.beginGroup(
"stereo");
2021 _ui->comboBox_cameraStereo->setCurrentIndex(settings.value(
"driver",
_ui->comboBox_cameraStereo->currentIndex()).toInt());
2022 _ui->checkbox_stereo_depthGenerated->setChecked(settings.value(
"depthGenerated",
_ui->checkbox_stereo_depthGenerated->isChecked()).toBool());
2023 _ui->checkBox_stereo_exposureCompensation->setChecked(settings.value(
"exposureCompensation",
_ui->checkBox_stereo_exposureCompensation->isChecked()).toBool());
2024 settings.endGroup();
2026 settings.beginGroup(
"rgb");
2027 _ui->source_comboBox_image_type->setCurrentIndex(settings.value(
"driver",
_ui->source_comboBox_image_type->currentIndex()).toInt());
2028 _ui->checkBox_rgb_rectify->setChecked(settings.value(
"rectify",
_ui->checkBox_rgb_rectify->isChecked()).toBool());
2029 settings.endGroup();
2031 settings.beginGroup(
"Openni");
2032 _ui->lineEdit_openniOniPath->setText(settings.value(
"oniPath",
_ui->lineEdit_openniOniPath->text()).toString());
2033 settings.endGroup();
2035 settings.beginGroup(
"Openni2");
2036 _ui->openni2_autoWhiteBalance->setChecked(settings.value(
"autoWhiteBalance",
_ui->openni2_autoWhiteBalance->isChecked()).toBool());
2037 _ui->openni2_autoExposure->setChecked(settings.value(
"autoExposure",
_ui->openni2_autoExposure->isChecked()).toBool());
2038 _ui->openni2_exposure->setValue(settings.value(
"exposure",
_ui->openni2_exposure->value()).toInt());
2039 _ui->openni2_gain->setValue(settings.value(
"gain",
_ui->openni2_gain->value()).toInt());
2040 _ui->openni2_mirroring->setChecked(settings.value(
"mirroring",
_ui->openni2_mirroring->isChecked()).toBool());
2041 _ui->openni2_stampsIdsUsed->setChecked(settings.value(
"stampsIdsUsed",
_ui->openni2_stampsIdsUsed->isChecked()).toBool());
2042 _ui->lineEdit_openni2OniPath->setText(settings.value(
"oniPath",
_ui->lineEdit_openni2OniPath->text()).toString());
2043 _ui->openni2_hshift->setValue(settings.value(
"hshift",
_ui->openni2_hshift->value()).toInt());
2044 _ui->openni2_vshift->setValue(settings.value(
"vshift",
_ui->openni2_vshift->value()).toInt());
2045 settings.endGroup();
2047 settings.beginGroup(
"Freenect2");
2048 _ui->comboBox_freenect2Format->setCurrentIndex(settings.value(
"format",
_ui->comboBox_freenect2Format->currentIndex()).toInt());
2049 _ui->doubleSpinBox_freenect2MinDepth->setValue(settings.value(
"minDepth",
_ui->doubleSpinBox_freenect2MinDepth->value()).toDouble());
2050 _ui->doubleSpinBox_freenect2MaxDepth->setValue(settings.value(
"maxDepth",
_ui->doubleSpinBox_freenect2MaxDepth->value()).toDouble());
2051 _ui->checkBox_freenect2BilateralFiltering->setChecked(settings.value(
"bilateralFiltering",
_ui->checkBox_freenect2BilateralFiltering->isChecked()).toBool());
2052 _ui->checkBox_freenect2EdgeAwareFiltering->setChecked(settings.value(
"edgeAwareFiltering",
_ui->checkBox_freenect2EdgeAwareFiltering->isChecked()).toBool());
2053 _ui->checkBox_freenect2NoiseFiltering->setChecked(settings.value(
"noiseFiltering",
_ui->checkBox_freenect2NoiseFiltering->isChecked()).toBool());
2054 _ui->lineEdit_freenect2Pipeline->setText(settings.value(
"pipeline",
_ui->lineEdit_freenect2Pipeline->text()).toString());
2055 settings.endGroup();
2057 settings.beginGroup(
"K4W2");
2058 _ui->comboBox_k4w2Format->setCurrentIndex(settings.value(
"format",
_ui->comboBox_k4w2Format->currentIndex()).toInt());
2059 settings.endGroup();
2061 settings.beginGroup(
"RealSense");
2062 _ui->comboBox_realsensePresetRGB->setCurrentIndex(settings.value(
"presetRGB",
_ui->comboBox_realsensePresetRGB->currentIndex()).toInt());
2063 _ui->comboBox_realsensePresetDepth->setCurrentIndex(settings.value(
"presetDepth",
_ui->comboBox_realsensePresetDepth->currentIndex()).toInt());
2064 _ui->checkbox_realsenseOdom->setChecked(settings.value(
"odom",
_ui->checkbox_realsenseOdom->isChecked()).toBool());
2065 _ui->checkbox_realsenseDepthScaledToRGBSize->setChecked(settings.value(
"depthScaled",
_ui->checkbox_realsenseDepthScaledToRGBSize->isChecked()).toBool());
2066 _ui->comboBox_realsenseRGBSource->setCurrentIndex(settings.value(
"rgbSource",
_ui->comboBox_realsenseRGBSource->currentIndex()).toInt());
2067 settings.endGroup();
2069 settings.beginGroup(
"RealSense2");
2070 _ui->checkbox_rs2_emitter->setChecked(settings.value(
"emitter",
_ui->checkbox_rs2_emitter->isChecked()).toBool());
2071 _ui->checkbox_rs2_irDepth->setChecked(settings.value(
"irdepth",
_ui->checkbox_rs2_irDepth->isChecked()).toBool());
2072 settings.endGroup();
2074 settings.beginGroup(
"RGBDImages");
2075 _ui->lineEdit_cameraRGBDImages_path_rgb->setText(settings.value(
"path_rgb",
_ui->lineEdit_cameraRGBDImages_path_rgb->text()).toString());
2076 _ui->lineEdit_cameraRGBDImages_path_depth->setText(settings.value(
"path_depth",
_ui->lineEdit_cameraRGBDImages_path_depth->text()).toString());
2077 _ui->doubleSpinBox_cameraRGBDImages_scale->setValue(settings.value(
"scale",
_ui->doubleSpinBox_cameraRGBDImages_scale->value()).toDouble());
2078 _ui->spinBox_cameraRGBDImages_startIndex->setValue(settings.value(
"start_index",
_ui->spinBox_cameraRGBDImages_startIndex->value()).toInt());
2079 settings.endGroup();
2081 settings.beginGroup(
"StereoImages");
2082 _ui->lineEdit_cameraStereoImages_path_left->setText(settings.value(
"path_left",
_ui->lineEdit_cameraStereoImages_path_left->text()).toString());
2083 _ui->lineEdit_cameraStereoImages_path_right->setText(settings.value(
"path_right",
_ui->lineEdit_cameraStereoImages_path_right->text()).toString());
2084 _ui->checkBox_stereo_rectify->setChecked(settings.value(
"rectify",
_ui->checkBox_stereo_rectify->isChecked()).toBool());
2085 _ui->spinBox_cameraStereoImages_startIndex->setValue(settings.value(
"start_index",
_ui->spinBox_cameraStereoImages_startIndex->value()).toInt());
2086 settings.endGroup();
2088 settings.beginGroup(
"StereoVideo");
2089 _ui->lineEdit_cameraStereoVideo_path->setText(settings.value(
"path",
_ui->lineEdit_cameraStereoVideo_path->text()).toString());
2090 _ui->lineEdit_cameraStereoVideo_path_2->setText(settings.value(
"path2",
_ui->lineEdit_cameraStereoVideo_path_2->text()).toString());
2091 _ui->spinBox_stereo_right_device->setValue(settings.value(
"device2",
_ui->spinBox_stereo_right_device->value()).toInt());
2092 settings.endGroup();
2094 settings.beginGroup(
"StereoZed");
2095 _ui->comboBox_stereoZed_resolution->setCurrentIndex(settings.value(
"resolution",
_ui->comboBox_stereoZed_resolution->currentIndex()).toInt());
2096 _ui->comboBox_stereoZed_quality->setCurrentIndex(settings.value(
"quality",
_ui->comboBox_stereoZed_quality->currentIndex()).toInt());
2097 _ui->checkbox_stereoZed_selfCalibration->setChecked(settings.value(
"self_calibration",
_ui->checkbox_stereoZed_selfCalibration->isChecked()).toBool());
2098 _ui->comboBox_stereoZed_sensingMode->setCurrentIndex(settings.value(
"sensing_mode",
_ui->comboBox_stereoZed_sensingMode->currentIndex()).toInt());
2099 _ui->spinBox_stereoZed_confidenceThr->setValue(settings.value(
"confidence_thr",
_ui->spinBox_stereoZed_confidenceThr->value()).toInt());
2100 _ui->checkbox_stereoZed_odom->setChecked(settings.value(
"odom",
_ui->checkbox_stereoZed_odom->isChecked()).toBool());
2101 _ui->lineEdit_zedSvoPath->setText(settings.value(
"svo_path",
_ui->lineEdit_zedSvoPath->text()).toString());
2102 settings.endGroup();
2105 settings.beginGroup(
"Images");
2106 _ui->source_images_lineEdit_path->setText(settings.value(
"path",
_ui->source_images_lineEdit_path->text()).toString());
2107 _ui->source_images_spinBox_startPos->setValue(settings.value(
"startPos",
_ui->source_images_spinBox_startPos->value()).toInt());
2108 _ui->comboBox_cameraImages_bayerMode->setCurrentIndex(settings.value(
"bayerMode",
_ui->comboBox_cameraImages_bayerMode->currentIndex()).toInt());
2110 _ui->checkBox_cameraImages_timestamps->setChecked(settings.value(
"filenames_as_stamps",
_ui->checkBox_cameraImages_timestamps->isChecked()).toBool());
2111 _ui->checkBox_cameraImages_syncTimeStamps->setChecked(settings.value(
"sync_stamps",
_ui->checkBox_cameraImages_syncTimeStamps->isChecked()).toBool());
2112 _ui->lineEdit_cameraImages_timestamps->setText(settings.value(
"stamps",
_ui->lineEdit_cameraImages_timestamps->text()).toString());
2113 _ui->lineEdit_cameraImages_path_scans->setText(settings.value(
"path_scans",
_ui->lineEdit_cameraImages_path_scans->text()).toString());
2114 _ui->lineEdit_cameraImages_laser_transform->setText(settings.value(
"scan_transform",
_ui->lineEdit_cameraImages_laser_transform->text()).toString());
2115 _ui->spinBox_cameraImages_max_scan_pts->setValue(settings.value(
"scan_max_pts",
_ui->spinBox_cameraImages_max_scan_pts->value()).toInt());
2116 _ui->spinBox_cameraImages_scanDownsampleStep->setValue(settings.value(
"scan_downsample_step",
_ui->spinBox_cameraImages_scanDownsampleStep->value()).toInt());
2117 _ui->doubleSpinBox_cameraImages_scanVoxelSize->setValue(settings.value(
"scan_voxel_size",
_ui->doubleSpinBox_cameraImages_scanVoxelSize->value()).toDouble());
2118 _ui->lineEdit_cameraImages_odom->setText(settings.value(
"odom_path",
_ui->lineEdit_cameraImages_odom->text()).toString());
2119 _ui->comboBox_cameraImages_odomFormat->setCurrentIndex(settings.value(
"odom_format",
_ui->comboBox_cameraImages_odomFormat->currentIndex()).toInt());
2120 _ui->lineEdit_cameraImages_gt->setText(settings.value(
"gt_path",
_ui->lineEdit_cameraImages_gt->text()).toString());
2121 _ui->comboBox_cameraImages_gtFormat->setCurrentIndex(settings.value(
"gt_format",
_ui->comboBox_cameraImages_gtFormat->currentIndex()).toInt());
2122 _ui->doubleSpinBox_maxPoseTimeDiff->setValue(settings.value(
"max_pose_time_diff",
_ui->doubleSpinBox_maxPoseTimeDiff->value()).toDouble());
2124 _ui->lineEdit_cameraImages_path_imu->setText(settings.value(
"imu_path",
_ui->lineEdit_cameraImages_path_imu->text()).toString());
2125 _ui->lineEdit_cameraImages_imu_transform->setText(settings.value(
"imu_local_transform",
_ui->lineEdit_cameraImages_imu_transform->text()).toString());
2126 _ui->spinBox_cameraImages_max_imu_rate->setValue(settings.value(
"imu_rate",
_ui->spinBox_cameraImages_max_imu_rate->value()).toInt());
2127 settings.endGroup();
2129 settings.beginGroup(
"Video");
2130 _ui->source_video_lineEdit_path->setText(settings.value(
"path",
_ui->source_video_lineEdit_path->text()).toString());
2131 settings.endGroup();
2133 settings.beginGroup(
"ScanFromDepth");
2134 _ui->groupBox_scanFromDepth->setChecked(settings.value(
"enabled",
_ui->groupBox_scanFromDepth->isChecked()).toBool());
2135 _ui->spinBox_cameraScanFromDepth_decimation->setValue(settings.value(
"decimation",
_ui->spinBox_cameraScanFromDepth_decimation->value()).toInt());
2136 _ui->doubleSpinBox_cameraSCanFromDepth_maxDepth->setValue(settings.value(
"maxDepth",
_ui->doubleSpinBox_cameraSCanFromDepth_maxDepth->value()).toDouble());
2137 _ui->doubleSpinBox_cameraImages_scanVoxelSize->setValue(settings.value(
"voxelSize",
_ui->doubleSpinBox_cameraImages_scanVoxelSize->value()).toDouble());
2138 _ui->spinBox_cameraImages_scanNormalsK->setValue(settings.value(
"normalsK",
_ui->spinBox_cameraImages_scanNormalsK->value()).toInt());
2139 _ui->doubleSpinBox_cameraImages_scanNormalsRadius->setValue(settings.value(
"normalsRadius",
_ui->doubleSpinBox_cameraImages_scanNormalsRadius->value()).toDouble());
2140 _ui->checkBox_cameraImages_scanForceGroundNormalsUp->setChecked(settings.value(
"normalsUp",
_ui->checkBox_cameraImages_scanForceGroundNormalsUp->isChecked()).toBool());
2142 settings.endGroup();
2144 settings.beginGroup(
"DepthFromScan");
2145 _ui->groupBox_depthFromScan->setChecked(settings.value(
"depthFromScan",
_ui->groupBox_depthFromScan->isChecked()).toBool());
2146 _ui->groupBox_depthFromScan_fillHoles->setChecked(settings.value(
"depthFromScanFillHoles",
_ui->groupBox_depthFromScan_fillHoles->isChecked()).toBool());
2147 _ui->radioButton_depthFromScan_vertical->setChecked(settings.value(
"depthFromScanVertical",
_ui->radioButton_depthFromScan_vertical->isChecked()).toBool());
2148 _ui->radioButton_depthFromScan_horizontal->setChecked(settings.value(
"depthFromScanHorizontal",
_ui->radioButton_depthFromScan_horizontal->isChecked()).toBool());
2149 _ui->checkBox_depthFromScan_fillBorders->setChecked(settings.value(
"depthFromScanFillBorders",
_ui->checkBox_depthFromScan_fillBorders->isChecked()).toBool());
2150 settings.endGroup();
2152 settings.beginGroup(
"Database");
2153 _ui->source_database_lineEdit_path->setText(settings.value(
"path",
_ui->source_database_lineEdit_path->text()).toString());
2154 _ui->source_checkBox_ignoreOdometry->setChecked(settings.value(
"ignoreOdometry",
_ui->source_checkBox_ignoreOdometry->isChecked()).toBool());
2155 _ui->source_checkBox_ignoreGoalDelay->setChecked(settings.value(
"ignoreGoalDelay",
_ui->source_checkBox_ignoreGoalDelay->isChecked()).toBool());
2156 _ui->source_checkBox_ignoreGoals->setChecked(settings.value(
"ignoreGoals",
_ui->source_checkBox_ignoreGoals->isChecked()).toBool());
2157 _ui->source_spinBox_databaseStartPos->setValue(settings.value(
"startPos",
_ui->source_spinBox_databaseStartPos->value()).toInt());
2158 _ui->source_spinBox_database_cameraIndex->setValue(settings.value(
"cameraIndex",
_ui->source_spinBox_database_cameraIndex->value()).toInt());
2159 _ui->source_checkBox_useDbStamps->setChecked(settings.value(
"useDatabaseStamps",
_ui->source_checkBox_useDbStamps->isChecked()).toBool());
2160 settings.endGroup();
2162 settings.endGroup();
2176 if(!filePath.isEmpty())
2181 UDEBUG(
"%s", path.toStdString().c_str());
2183 if(!QFile::exists(path))
2185 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));
2191 for(rtabmap::ParametersMap::const_iterator iter = parameters.begin(); iter!=parameters.end(); ++iter)
2193 std::string value = iter->second;
2194 if(iter->first.compare(Parameters::kRtabmapWorkingDirectory()) == 0)
2201 UWARN(
"Reading config: Not existing working directory \"%s\". Keeping old one (\"%s\").",
2209 UWARN(
"Reading config: Not existing working directory \"%s\". Using default one (\"%s\").",
2211 defaultWorkingDir.c_str());
2212 value = defaultWorkingDir;
2220 if(parameters.find(Parameters::kRtabmapWorkingDirectory()) == parameters.end())
2224 QMessageBox::information(
this,
2225 tr(
"Working directory"),
2226 tr(
"RTAB-Map needs a working directory to put the database.\n\n" 2227 "By default, the directory \"%1\" is used.\n\n" 2228 "The working directory can be changed any time in the " 2240 QString path = QFileDialog::getSaveFileName(
this, tr(
"Save settings..."), this->
getWorkingDirectory()+QDir::separator()+
"config.ini",
"*.ini");
2253 int button = QMessageBox::warning(
this,
2254 tr(
"Reset settings..."),
2255 tr(
"This will reset all settings. Restore all settings to default without saving them first?"),
2256 QMessageBox::Cancel | QMessageBox::Yes | QMessageBox::Save,
2257 QMessageBox::Cancel);
2258 if(button == QMessageBox::Yes ||
2287 if (
_parameters.at(iter->first).compare(iter->second) != 0)
2289 bool different =
true;
2300 UINFO(
"modified %s = %s->%s", iter->first.c_str(),
_parameters.at(iter->first).c_str(), iter->second.c_str());
2313 if(!filePath.isEmpty())
2317 QSettings settings(path, QSettings::IniFormat);
2318 settings.beginGroup(
"Gui");
2320 settings.beginGroup(
"General");
2321 settings.remove(
"");
2322 settings.setValue(
"imagesKept",
_ui->general_checkBox_imagesKept->isChecked());
2323 settings.setValue(
"cloudsKept",
_ui->general_checkBox_cloudsKept->isChecked());
2324 settings.setValue(
"loggerLevel",
_ui->comboBox_loggerLevel->currentIndex());
2325 settings.setValue(
"loggerEventLevel",
_ui->comboBox_loggerEventLevel->currentIndex());
2326 settings.setValue(
"loggerPauseLevel",
_ui->comboBox_loggerPauseLevel->currentIndex());
2327 settings.setValue(
"loggerType",
_ui->comboBox_loggerType->currentIndex());
2328 settings.setValue(
"loggerPrintTime",
_ui->checkBox_logger_printTime->isChecked());
2329 settings.setValue(
"loggerPrintThreadId",
_ui->checkBox_logger_printThreadId->isChecked());
2330 settings.setValue(
"verticalLayoutUsed",
_ui->checkBox_verticalLayoutUsed->isChecked());
2331 settings.setValue(
"imageRejectedShown",
_ui->checkBox_imageRejectedShown->isChecked());
2332 settings.setValue(
"imageHighestHypShown",
_ui->checkBox_imageHighestHypShown->isChecked());
2333 settings.setValue(
"beep",
_ui->checkBox_beep->isChecked());
2334 settings.setValue(
"figure_time",
_ui->checkBox_stamps->isChecked());
2335 settings.setValue(
"figure_cache",
_ui->checkBox_cacheStatistics->isChecked());
2336 settings.setValue(
"notifyNewGlobalPath",
_ui->checkBox_notifyWhenNewGlobalPathIsReceived->isChecked());
2337 settings.setValue(
"odomQualityThr",
_ui->spinBox_odomQualityWarnThr->value());
2338 settings.setValue(
"odomOnlyInliersShown",
_ui->checkBox_odom_onlyInliersShown->isChecked());
2339 settings.setValue(
"posteriorGraphView",
_ui->radioButton_posteriorGraphView->isChecked());
2340 settings.setValue(
"wordsGraphView",
_ui->radioButton_wordsGraphView->isChecked());
2341 settings.setValue(
"localizationsGraphView",
_ui->radioButton_localizationsGraphView->isChecked());
2342 settings.setValue(
"nochangeGraphView",
_ui->radioButton_nochangeGraphView->isChecked());
2343 settings.setValue(
"odomDisabled",
_ui->checkbox_odomDisabled->isChecked());
2344 settings.setValue(
"odomRegistration",
_ui->odom_registration->currentIndex());
2345 settings.setValue(
"gtAlign",
_ui->checkbox_groundTruthAlign->isChecked());
2347 for(
int i=0; i<2; ++i)
2370 settings.setValue(
"cloudVoxel",
_ui->doubleSpinBox_voxel->value());
2371 settings.setValue(
"cloudNoiseRadius",
_ui->doubleSpinBox_noiseRadius->value());
2372 settings.setValue(
"cloudNoiseMinNeighbors",
_ui->spinBox_noiseMinNeighbors->value());
2373 settings.setValue(
"cloudCeilingHeight",
_ui->doubleSpinBox_ceilingFilterHeight->value());
2374 settings.setValue(
"cloudFloorHeight",
_ui->doubleSpinBox_floorFilterHeight->value());
2375 settings.setValue(
"normalKSearch",
_ui->spinBox_normalKSearch->value());
2376 settings.setValue(
"normalRadiusSearch",
_ui->doubleSpinBox_normalRadiusSearch->value());
2377 settings.setValue(
"scanCeilingHeight",
_ui->doubleSpinBox_ceilingFilterHeight_scan->value());
2378 settings.setValue(
"scanFloorHeight",
_ui->doubleSpinBox_floorFilterHeight_scan->value());
2379 settings.setValue(
"scanNormalKSearch",
_ui->spinBox_normalKSearch_scan->value());
2380 settings.setValue(
"scanNormalRadiusSearch",
_ui->doubleSpinBox_normalRadiusSearch_scan->value());
2382 settings.setValue(
"showGraphs",
_ui->checkBox_showGraphs->isChecked());
2383 settings.setValue(
"showLabels",
_ui->checkBox_showLabels->isChecked());
2385 settings.setValue(
"noFiltering",
_ui->radioButton_noFiltering->isChecked());
2386 settings.setValue(
"cloudFiltering",
_ui->radioButton_nodeFiltering->isChecked());
2387 settings.setValue(
"cloudFilteringRadius",
_ui->doubleSpinBox_cloudFilterRadius->value());
2388 settings.setValue(
"cloudFilteringAngle",
_ui->doubleSpinBox_cloudFilterAngle->value());
2389 settings.setValue(
"subtractFiltering",
_ui->radioButton_subtractFiltering->isChecked());
2390 settings.setValue(
"subtractFilteringMinPts",
_ui->spinBox_subtractFilteringMinPts->value());
2391 settings.setValue(
"subtractFilteringRadius",
_ui->doubleSpinBox_subtractFilteringRadius->value());
2392 settings.setValue(
"subtractFilteringAngle",
_ui->doubleSpinBox_subtractFilteringAngle->value());
2394 settings.setValue(
"gridMapShown",
_ui->checkBox_map_shown->isChecked());
2395 settings.setValue(
"gridMapOpacity",
_ui->doubleSpinBox_map_opacity->value());
2397 settings.setValue(
"octomap",
_ui->groupBox_octomap->isChecked());
2398 settings.setValue(
"octomap_depth",
_ui->spinBox_octomap_treeDepth->value());
2399 settings.setValue(
"octomap_2dgrid",
_ui->checkBox_octomap_2dgrid->isChecked());
2400 settings.setValue(
"octomap_3dmap",
_ui->checkBox_octomap_show3dMap->isChecked());
2401 settings.setValue(
"octomap_rendering_type",
_ui->comboBox_octomap_renderingType->currentIndex());
2402 settings.setValue(
"octomap_point_size",
_ui->spinBox_octomap_pointSize->value());
2405 settings.setValue(
"meshing",
_ui->groupBox_organized->isChecked());
2406 settings.setValue(
"meshing_angle",
_ui->doubleSpinBox_mesh_angleTolerance->value());
2407 settings.setValue(
"meshing_quad",
_ui->checkBox_mesh_quad->isChecked());
2408 settings.setValue(
"meshing_texture",
_ui->checkBox_mesh_texture->isChecked());
2409 settings.setValue(
"meshing_triangle_size",
_ui->spinBox_mesh_triangleSize->value());
2411 settings.endGroup();
2413 settings.endGroup();
2419 if(!filePath.isEmpty())
2423 QSettings settings(path, QSettings::IniFormat);
2425 settings.beginGroup(
"Camera");
2426 settings.remove(
"");
2427 settings.setValue(
"imgRate",
_ui->general_doubleSpinBox_imgRate->value());
2428 settings.setValue(
"mirroring",
_ui->source_mirroring->isChecked());
2429 settings.setValue(
"calibrationName",
_ui->lineEdit_calibrationFile->text());
2430 settings.setValue(
"type",
_ui->comboBox_sourceType->currentIndex());
2431 settings.setValue(
"device",
_ui->lineEdit_sourceDevice->text());
2432 settings.setValue(
"localTransform",
_ui->lineEdit_sourceLocalTransform->text());
2433 settings.setValue(
"imageDecimation",
_ui->spinBox_source_imageDecimation->value());
2435 settings.beginGroup(
"rgbd");
2436 settings.setValue(
"driver",
_ui->comboBox_cameraRGBD->currentIndex());
2437 settings.setValue(
"rgbdColorOnly",
_ui->checkbox_rgbd_colorOnly->isChecked());
2438 settings.setValue(
"distortion_model",
_ui->lineEdit_source_distortionModel->text());
2439 settings.setValue(
"bilateral",
_ui->groupBox_bilateral->isChecked());
2440 settings.setValue(
"bilateral_sigma_s",
_ui->doubleSpinBox_bilateral_sigmaS->value());
2441 settings.setValue(
"bilateral_sigma_r",
_ui->doubleSpinBox_bilateral_sigmaR->value());
2442 settings.endGroup();
2444 settings.beginGroup(
"stereo");
2445 settings.setValue(
"driver",
_ui->comboBox_cameraStereo->currentIndex());
2446 settings.setValue(
"depthGenerated",
_ui->checkbox_stereo_depthGenerated->isChecked());
2447 settings.setValue(
"exposureCompensation",
_ui->checkBox_stereo_exposureCompensation->isChecked());
2448 settings.endGroup();
2450 settings.beginGroup(
"rgb");
2451 settings.setValue(
"driver",
_ui->source_comboBox_image_type->currentIndex());
2452 settings.setValue(
"rectify",
_ui->checkBox_rgb_rectify->isChecked());
2453 settings.endGroup();
2455 settings.beginGroup(
"Openni");
2456 settings.setValue(
"oniPath",
_ui->lineEdit_openniOniPath->text());
2457 settings.endGroup();
2459 settings.beginGroup(
"Openni2");
2460 settings.setValue(
"autoWhiteBalance",
_ui->openni2_autoWhiteBalance->isChecked());
2461 settings.setValue(
"autoExposure",
_ui->openni2_autoExposure->isChecked());
2462 settings.setValue(
"exposure",
_ui->openni2_exposure->value());
2463 settings.setValue(
"gain",
_ui->openni2_gain->value());
2464 settings.setValue(
"mirroring",
_ui->openni2_mirroring->isChecked());
2465 settings.setValue(
"stampsIdsUsed",
_ui->openni2_stampsIdsUsed->isChecked());
2466 settings.setValue(
"oniPath",
_ui->lineEdit_openni2OniPath->text());
2467 settings.setValue(
"hshift",
_ui->openni2_hshift->value());
2468 settings.setValue(
"vshift",
_ui->openni2_vshift->value());
2469 settings.endGroup();
2471 settings.beginGroup(
"Freenect2");
2472 settings.setValue(
"format",
_ui->comboBox_freenect2Format->currentIndex());
2473 settings.setValue(
"minDepth",
_ui->doubleSpinBox_freenect2MinDepth->value());
2474 settings.setValue(
"maxDepth",
_ui->doubleSpinBox_freenect2MaxDepth->value());
2475 settings.setValue(
"bilateralFiltering",
_ui->checkBox_freenect2BilateralFiltering->isChecked());
2476 settings.setValue(
"edgeAwareFiltering",
_ui->checkBox_freenect2EdgeAwareFiltering->isChecked());
2477 settings.setValue(
"noiseFiltering",
_ui->checkBox_freenect2NoiseFiltering->isChecked());
2478 settings.setValue(
"pipeline",
_ui->lineEdit_freenect2Pipeline->text());
2479 settings.endGroup();
2481 settings.beginGroup(
"K4W2");
2482 settings.setValue(
"format",
_ui->comboBox_k4w2Format->currentIndex());
2483 settings.endGroup();
2485 settings.beginGroup(
"RealSense");
2486 settings.setValue(
"presetRGB",
_ui->comboBox_realsensePresetRGB->currentIndex());
2487 settings.setValue(
"presetDepth",
_ui->comboBox_realsensePresetDepth->currentIndex());
2488 settings.setValue(
"odom",
_ui->checkbox_realsenseOdom->isChecked());
2489 settings.setValue(
"depthScaled",
_ui->checkbox_realsenseDepthScaledToRGBSize->isChecked());
2490 settings.setValue(
"rgbSource",
_ui->comboBox_realsenseRGBSource->currentIndex());
2491 settings.endGroup();
2493 settings.beginGroup(
"RealSense2");
2494 settings.setValue(
"emitter",
_ui->checkbox_rs2_emitter->isChecked());
2495 settings.setValue(
"irdepth",
_ui->checkbox_rs2_irDepth->isChecked());
2496 settings.endGroup();
2498 settings.beginGroup(
"RGBDImages");
2499 settings.setValue(
"path_rgb",
_ui->lineEdit_cameraRGBDImages_path_rgb->text());
2500 settings.setValue(
"path_depth",
_ui->lineEdit_cameraRGBDImages_path_depth->text());
2501 settings.setValue(
"scale",
_ui->doubleSpinBox_cameraRGBDImages_scale->value());
2502 settings.setValue(
"start_index",
_ui->spinBox_cameraRGBDImages_startIndex->value());
2503 settings.endGroup();
2505 settings.beginGroup(
"StereoImages");
2506 settings.setValue(
"path_left",
_ui->lineEdit_cameraStereoImages_path_left->text());
2507 settings.setValue(
"path_right",
_ui->lineEdit_cameraStereoImages_path_right->text());
2508 settings.setValue(
"rectify",
_ui->checkBox_stereo_rectify->isChecked());
2509 settings.setValue(
"start_index",
_ui->spinBox_cameraStereoImages_startIndex->value());
2510 settings.endGroup();
2512 settings.beginGroup(
"StereoVideo");
2513 settings.setValue(
"path",
_ui->lineEdit_cameraStereoVideo_path->text());
2514 settings.setValue(
"path2",
_ui->lineEdit_cameraStereoVideo_path_2->text());
2515 settings.setValue(
"device2",
_ui->spinBox_stereo_right_device->value());
2516 settings.endGroup();
2518 settings.beginGroup(
"StereoZed");
2519 settings.setValue(
"resolution",
_ui->comboBox_stereoZed_resolution->currentIndex());
2520 settings.setValue(
"quality",
_ui->comboBox_stereoZed_quality->currentIndex());
2521 settings.setValue(
"self_calibration",
_ui->checkbox_stereoZed_selfCalibration->isChecked());
2522 settings.setValue(
"sensing_mode",
_ui->comboBox_stereoZed_sensingMode->currentIndex());
2523 settings.setValue(
"confidence_thr",
_ui->spinBox_stereoZed_confidenceThr->value());
2524 settings.setValue(
"odom",
_ui->checkbox_stereoZed_odom->isChecked());
2525 settings.setValue(
"svo_path",
_ui->lineEdit_zedSvoPath->text());
2526 settings.endGroup();
2530 settings.beginGroup(
"Images");
2531 settings.setValue(
"path",
_ui->source_images_lineEdit_path->text());
2532 settings.setValue(
"startPos",
_ui->source_images_spinBox_startPos->value());
2533 settings.setValue(
"bayerMode",
_ui->comboBox_cameraImages_bayerMode->currentIndex());
2534 settings.setValue(
"filenames_as_stamps",
_ui->checkBox_cameraImages_timestamps->isChecked());
2535 settings.setValue(
"sync_stamps",
_ui->checkBox_cameraImages_syncTimeStamps->isChecked());
2536 settings.setValue(
"stamps",
_ui->lineEdit_cameraImages_timestamps->text());
2537 settings.setValue(
"path_scans",
_ui->lineEdit_cameraImages_path_scans->text());
2538 settings.setValue(
"scan_transform",
_ui->lineEdit_cameraImages_laser_transform->text());
2539 settings.setValue(
"scan_max_pts",
_ui->spinBox_cameraImages_max_scan_pts->value());
2540 settings.setValue(
"scan_downsample_step",
_ui->spinBox_cameraImages_scanDownsampleStep->value());
2541 settings.setValue(
"scan_voxel_size",
_ui->doubleSpinBox_cameraImages_scanVoxelSize->value());
2542 settings.setValue(
"odom_path",
_ui->lineEdit_cameraImages_odom->text());
2543 settings.setValue(
"odom_format",
_ui->comboBox_cameraImages_odomFormat->currentIndex());
2544 settings.setValue(
"gt_path",
_ui->lineEdit_cameraImages_gt->text());
2545 settings.setValue(
"gt_format",
_ui->comboBox_cameraImages_gtFormat->currentIndex());
2546 settings.setValue(
"max_pose_time_diff",
_ui->doubleSpinBox_maxPoseTimeDiff->value());
2547 settings.setValue(
"imu_path",
_ui->lineEdit_cameraImages_path_imu->text());
2548 settings.setValue(
"imu_local_transform",
_ui->lineEdit_cameraImages_imu_transform->text());
2549 settings.setValue(
"imu_rate",
_ui->spinBox_cameraImages_max_imu_rate->value());
2550 settings.endGroup();
2552 settings.beginGroup(
"Video");
2553 settings.setValue(
"path",
_ui->source_video_lineEdit_path->text());
2554 settings.endGroup();
2556 settings.beginGroup(
"ScanFromDepth");
2557 settings.setValue(
"enabled",
_ui->groupBox_scanFromDepth->isChecked());
2558 settings.setValue(
"decimation",
_ui->spinBox_cameraScanFromDepth_decimation->value());
2559 settings.setValue(
"maxDepth",
_ui->doubleSpinBox_cameraSCanFromDepth_maxDepth->value());
2560 settings.setValue(
"voxelSize",
_ui->doubleSpinBox_cameraImages_scanVoxelSize->value());
2561 settings.setValue(
"normalsK",
_ui->spinBox_cameraImages_scanNormalsK->value());
2562 settings.setValue(
"normalsRadius",
_ui->doubleSpinBox_cameraImages_scanNormalsRadius->value());
2563 settings.setValue(
"normalsUp",
_ui->checkBox_cameraImages_scanForceGroundNormalsUp->isChecked());
2564 settings.endGroup();
2566 settings.beginGroup(
"DepthFromScan");
2567 settings.setValue(
"depthFromScan",
_ui->groupBox_depthFromScan->isChecked());
2568 settings.setValue(
"depthFromScanFillHoles",
_ui->groupBox_depthFromScan_fillHoles->isChecked());
2569 settings.setValue(
"depthFromScanVertical",
_ui->radioButton_depthFromScan_vertical->isChecked());
2570 settings.setValue(
"depthFromScanHorizontal",
_ui->radioButton_depthFromScan_horizontal->isChecked());
2571 settings.setValue(
"depthFromScanFillBorders",
_ui->checkBox_depthFromScan_fillBorders->isChecked());
2572 settings.endGroup();
2574 settings.beginGroup(
"Database");
2575 settings.setValue(
"path",
_ui->source_database_lineEdit_path->text());
2576 settings.setValue(
"ignoreOdometry",
_ui->source_checkBox_ignoreOdometry->isChecked());
2577 settings.setValue(
"ignoreGoalDelay",
_ui->source_checkBox_ignoreGoalDelay->isChecked());
2578 settings.setValue(
"ignoreGoals",
_ui->source_checkBox_ignoreGoals->isChecked());
2579 settings.setValue(
"startPos",
_ui->source_spinBox_databaseStartPos->value());
2580 settings.setValue(
"cameraIndex",
_ui->source_spinBox_database_cameraIndex->value());
2581 settings.setValue(
"useDatabaseStamps",
_ui->source_checkBox_useDbStamps->isChecked());
2582 settings.endGroup();
2584 settings.endGroup();
2592 if(!filePath.isEmpty())
2602 #ifndef RTABMAP_NONFREE 2605 if(
_ui->comboBox_detector_strategy->currentIndex() <= 1)
2607 QMessageBox::warning(
this, tr(
"Parameter warning"),
2608 tr(
"Selected feature type (SURF/SIFT) is not available. RTAB-Map is not built " 2609 "with the nonfree module from OpenCV. ORB is set instead for the bag-of-words dictionary."));
2613 if(
_ui->reextract_type->currentIndex() <= 1)
2615 QMessageBox::warning(
this, tr(
"Parameter warning"),
2616 tr(
"Selected feature type (SURF/SIFT) is not available. RTAB-Map is not built " 2617 "with the nonfree module from OpenCV. Fast/Brief is set instead for the re-extraction " 2618 "of features on loop closure."));
2623 #if CV_MAJOR_VERSION < 3 2626 #ifdef RTABMAP_NONFREE 2627 QMessageBox::warning(
this, tr(
"Parameter warning"),
2628 tr(
"Selected feature type (KAZE) is not available on OpenCV2. SURF is set instead " 2629 "for the bag-of-words dictionary."));
2632 QMessageBox::warning(
this, tr(
"Parameter warning"),
2633 tr(
"Selected feature type (KAZE) is not available on OpenCV2. ORB is set instead " 2634 "for the bag-of-words dictionary."));
2640 #ifdef RTABMAP_NONFREE 2641 QMessageBox::warning(
this, tr(
"Parameter warning"),
2642 tr(
"Selected feature type (KAZE) is not available on OpenCV2. SURF is set instead " 2643 "for the re-extraction of features on loop closure."));
2646 QMessageBox::warning(
this, tr(
"Parameter warning"),
2647 tr(
"Selected feature type (KAZE) is not available on OpenCV2. ORB is set instead " 2648 "for the re-extraction of features on loop closure."));
2659 QMessageBox::warning(
this, tr(
"Parameter warning"),
2660 tr(
"Selected graph optimization strategy (TORO) is not available. RTAB-Map is not built " 2661 "with TORO. GTSAM is set instead for graph optimization strategy."));
2664 #ifndef RTABMAP_ORB_SLAM2 2667 QMessageBox::warning(
this, tr(
"Parameter warning"),
2668 tr(
"Selected graph optimization strategy (TORO) is not available. RTAB-Map is not built " 2669 "with TORO. g2o is set instead for graph optimization strategy."));
2674 #ifdef RTABMAP_ORB_SLAM2 2675 if(
_ui->graphOptimization_type->currentIndex() == 1)
2682 QMessageBox::warning(
this, tr(
"Parameter warning"),
2683 tr(
"Selected graph optimization strategy (g2o) is not available. RTAB-Map is not built " 2684 "with g2o. GTSAM is set instead for graph optimization strategy."));
2689 QMessageBox::warning(
this, tr(
"Parameter warning"),
2690 tr(
"Selected graph optimization strategy (g2o) is not available. RTAB-Map is not built " 2691 "with g2o. TORO is set instead for graph optimization strategy."));
2697 #ifndef RTABMAP_ORB_SLAM2 2700 QMessageBox::warning(
this, tr(
"Parameter warning"),
2701 tr(
"Selected graph optimization strategy (GTSAM) is not available. RTAB-Map is not built " 2702 "with GTSAM. g2o is set instead for graph optimization strategy."));
2709 QMessageBox::warning(
this, tr(
"Parameter warning"),
2710 tr(
"Selected graph optimization strategy (GTSAM) is not available. RTAB-Map is not built " 2711 "with GTSAM. TORO is set instead for graph optimization strategy."));
2719 QMessageBox::warning(
this, tr(
"Parameter warning"),
2720 tr(
"Selected visual registration bundle adjustment optimization strategy (g2o) is not available. RTAB-Map is not built " 2721 "with g2o. Bundle adjustment is disabled."));
2722 _ui->loopClosure_bundle->setCurrentIndex(0);
2726 QMessageBox::warning(
this, tr(
"Parameter warning"),
2727 tr(
"Selected visual registration bundle adjustment optimization strategy (cvsba) is not available. RTAB-Map is not built " 2728 "with cvsba. Bundle adjustment is disabled."));
2729 _ui->loopClosure_bundle->setCurrentIndex(0);
2735 QMessageBox::warning(
this, tr(
"Parameter warning"),
2736 tr(
"Selected odometry local bundle adjustment optimization strategy (g2o) is not available. RTAB-Map is not built " 2737 "with g2o. Bundle adjustment is disabled."));
2738 _ui->odom_f2m_bundleStrategy->setCurrentIndex(0);
2742 QMessageBox::warning(
this, tr(
"Parameter warning"),
2743 tr(
"Selected odometry local bundle adjustment optimization strategy (cvsba) is not available. RTAB-Map is not built " 2744 "with cvsba. Bundle adjustment is disabled."));
2745 _ui->odom_f2m_bundleStrategy->setCurrentIndex(0);
2749 if(
_ui->graphOptimization_robust->isChecked() &&
_ui->graphOptimization_maxError->value()>0.0)
2751 QMessageBox::warning(
this, tr(
"Parameter warning"),
2752 tr(
"Robust graph optimization and maximum optimization error threshold cannot be " 2753 "both used at the same time. Disabling robust optimization."));
2754 _ui->graphOptimization_robust->setChecked(
false);
2761 QMessageBox::warning(
this, tr(
"Parameter warning"),
2762 tr(
"With the selected feature type (SURF or SIFT), parameter \"Visual word->Nearest Neighbor\" " 2763 "cannot be LSH (used for binary descriptor). KD-tree is set instead for the bag-of-words dictionary."));
2770 QMessageBox::warning(
this, tr(
"Parameter warning"),
2771 tr(
"With the selected feature type (SURF or SIFT), parameter \"Visual word->Nearest Neighbor\" " 2772 "cannot be LSH (used for binary descriptor). KD-tree is set instead for the re-extraction " 2773 "of features on loop closure."));
2777 if(
_ui->doubleSpinBox_freenect2MinDepth->value() >=
_ui->doubleSpinBox_freenect2MaxDepth->value())
2779 QMessageBox::warning(
this, tr(
"Parameter warning"),
2780 tr(
"Freenect2 minimum depth (%1 m) should be lower than maximum depth (%2 m). Setting maximum depth to %3 m.")
2781 .arg(
_ui->doubleSpinBox_freenect2MinDepth->value())
2782 .arg(
_ui->doubleSpinBox_freenect2MaxDepth->value())
2783 .arg(
_ui->doubleSpinBox_freenect2MaxDepth->value()+1));
2784 _ui->doubleSpinBox_freenect2MaxDepth->setValue(
_ui->doubleSpinBox_freenect2MaxDepth->value()+1);
2787 if(
_ui->surf_doubleSpinBox_maxDepth->value() > 0.0 &&
2788 _ui->surf_doubleSpinBox_minDepth->value() >=
_ui->surf_doubleSpinBox_maxDepth->value())
2790 QMessageBox::warning(
this, tr(
"Parameter warning"),
2791 tr(
"Visual word minimum depth (%1 m) should be lower than maximum depth (%2 m). Setting maximum depth to %3 m.")
2792 .arg(
_ui->surf_doubleSpinBox_minDepth->value())
2793 .arg(
_ui->surf_doubleSpinBox_maxDepth->value())
2794 .arg(
_ui->surf_doubleSpinBox_maxDepth->value()+1));
2795 _ui->doubleSpinBox_freenect2MinDepth->setValue(0);
2798 if(
_ui->loopClosure_bowMaxDepth->value() > 0.0 &&
2799 _ui->loopClosure_bowMinDepth->value() >=
_ui->loopClosure_bowMaxDepth->value())
2801 QMessageBox::warning(
this, tr(
"Parameter warning"),
2802 tr(
"Visual registration word minimum depth (%1 m) should be lower than maximum depth (%2 m). Setting maximum depth to %3 m.")
2803 .arg(
_ui->loopClosure_bowMinDepth->value())
2804 .arg(
_ui->loopClosure_bowMaxDepth->value())
2805 .arg(
_ui->loopClosure_bowMaxDepth->value()+1));
2806 _ui->loopClosure_bowMinDepth->setValue(0);
2809 if(
_ui->fastThresholdMax->value() <
_ui->fastThresholdMin->value())
2811 QMessageBox::warning(
this, tr(
"Parameter warning"),
2812 tr(
"FAST minimum threshold cannot be lower than maximum threshold. Setting minimum to 1."));
2813 _ui->fastThresholdMin->setValue(1);
2815 if(
_ui->fastThreshold->value() >
_ui->fastThresholdMax->value())
2817 QMessageBox::warning(
this, tr(
"Parameter warning"),
2818 tr(
"FAST threshold cannot be higher than maximum threshold. Maximum value set to current threshold."));
2819 _ui->fastThresholdMax->setValue(
_ui->fastThreshold->value());
2821 if(
_ui->fastThreshold->value() <
_ui->fastThresholdMin->value())
2823 QMessageBox::warning(
this, tr(
"Parameter warning"),
2824 tr(
"FAST threshold cannot be lower than minimum threshold. Minimum value set to current threshold."));
2825 _ui->fastThresholdMin->setValue(
_ui->fastThreshold->value());
2828 if(
_ui->checkbox_odomDisabled->isChecked() &&
2829 _ui->general_checkBox_SLAM_mode->isChecked() &&
2830 _ui->general_checkBox_activateRGBD->isChecked())
2832 QMessageBox::warning(
this, tr(
"Parameter warning"),
2833 tr(
"Odometry is disabled but incremental RGB-D SLAM is activated! Re-enabling odometry."));
2834 _ui->checkbox_odomDisabled->setChecked(
false);
2842 return tr(
"Reading parameters from the configuration file...");
2850 _ui->lineEdit_dictionaryPath->setEnabled(
false);
2851 _ui->toolButton_dictionaryPath->setEnabled(
false);
2852 _ui->label_dictionaryPath->setEnabled(
false);
2854 _ui->groupBox_source0->setEnabled(
false);
2855 _ui->groupBox_odometry1->setEnabled(
false);
2857 _ui->checkBox_useOdomFeatures->setChecked(
false);
2858 _ui->checkBox_useOdomFeatures->setEnabled(
false);
2860 this->setWindowTitle(tr(
"Preferences [Monitoring mode]"));
2864 _ui->lineEdit_dictionaryPath->setEnabled(
true);
2865 _ui->toolButton_dictionaryPath->setEnabled(
true);
2866 _ui->label_dictionaryPath->setEnabled(
true);
2868 _ui->groupBox_source0->setEnabled(
true);
2869 _ui->groupBox_odometry1->setEnabled(
true);
2871 _ui->checkBox_useOdomFeatures->setEnabled(
true);
2873 this->setWindowTitle(tr(
"Preferences"));
2879 std::set<std::string> threadsCheckedSet(threadsChecked.begin(), threadsChecked.end());
2880 _ui->comboBox_loggerFilter->clear();
2881 for(std::map<std::string, unsigned long>::iterator iter=threads.begin(); iter!=threads.end(); ++iter)
2883 if(threadsCheckedSet.find(iter->first.c_str()) != threadsCheckedSet.end())
2885 _ui->comboBox_loggerFilter->addItem(QString(iter->first.c_str()), QVariant(
true));
2889 _ui->comboBox_loggerFilter->addItem(QString(iter->first.c_str()), QVariant(
false));
2907 QApplication::processEvents();
2912 if(this->isVisible())
2925 if(!window->objectName().isEmpty() && !window->isMaximized())
2928 settings.beginGroup(
"Gui");
2929 settings.beginGroup(window->objectName());
2930 settings.setValue(
"geometry", window->saveGeometry());
2931 settings.endGroup();
2932 settings.endGroup();
2935 settingsTmp.beginGroup(
"Gui");
2936 settingsTmp.beginGroup(window->objectName());
2937 settingsTmp.setValue(
"geometry", window->saveGeometry());
2938 settingsTmp.endGroup();
2939 settingsTmp.endGroup();
2945 if(!window->objectName().isEmpty())
2949 settings.beginGroup(
"Gui");
2950 settings.beginGroup(window->objectName());
2951 bytes = settings.value(
"geometry", QByteArray()).toByteArray();
2952 if(!bytes.isEmpty())
2954 window->restoreGeometry(bytes);
2956 settings.endGroup();
2957 settings.endGroup();
2960 settingsTmp.beginGroup(
"Gui");
2961 settingsTmp.beginGroup(window->objectName());
2962 settingsTmp.setValue(
"geometry", window->saveGeometry());
2963 settingsTmp.endGroup();
2964 settingsTmp.endGroup();
2970 if(!mainWindow->objectName().isEmpty())
2975 settings.beginGroup(
"Gui");
2976 settings.beginGroup(mainWindow->objectName());
2977 settings.setValue(
"state", mainWindow->saveState());
2978 settings.setValue(
"maximized", mainWindow->isMaximized());
2979 settings.setValue(
"status_bar", mainWindow->statusBar()->isVisible());
2980 settings.endGroup();
2981 settings.endGroup();
2984 settingsTmp.beginGroup(
"Gui");
2985 settingsTmp.beginGroup(mainWindow->objectName());
2986 settingsTmp.setValue(
"state", mainWindow->saveState());
2987 settingsTmp.setValue(
"maximized", mainWindow->isMaximized());
2988 settingsTmp.setValue(
"status_bar", mainWindow->statusBar()->isVisible());
2989 settingsTmp.endGroup();
2990 settingsTmp.endGroup();
2996 if(!mainWindow->objectName().isEmpty())
3002 settings.beginGroup(
"Gui");
3003 settings.beginGroup(mainWindow->objectName());
3004 bytes = settings.value(
"state", QByteArray()).toByteArray();
3005 if(!bytes.isEmpty())
3007 mainWindow->restoreState(bytes);
3009 maximized = settings.value(
"maximized",
false).toBool();
3010 statusBarShown = settings.value(
"status_bar",
false).toBool();
3011 mainWindow->statusBar()->setVisible(statusBarShown);
3012 settings.endGroup();
3013 settings.endGroup();
3016 settingsTmp.beginGroup(
"Gui");
3017 settingsTmp.beginGroup(mainWindow->objectName());
3018 settingsTmp.setValue(
"state", mainWindow->saveState());
3019 settingsTmp.setValue(
"maximized", maximized);
3020 settingsTmp.setValue(
"status_bar", statusBarShown);
3021 settingsTmp.endGroup();
3022 settingsTmp.endGroup();
3028 if(!widget->objectName().isEmpty())
3031 settings.beginGroup(
"Gui");
3032 settings.beginGroup(widget->objectName());
3035 settingsTmp.beginGroup(
"Gui");
3036 settingsTmp.beginGroup(widget->objectName());
3054 imageView->saveSettings(settings);
3055 imageView->saveSettings(settingsTmp);
3057 else if(exportCloudsDialog)
3059 exportCloudsDialog->saveSettings(settings);
3060 exportCloudsDialog->saveSettings(settingsTmp);
3062 else if(exportBundlerDialog)
3064 exportBundlerDialog->saveSettings(settings);
3065 exportBundlerDialog->saveSettings(settingsTmp);
3067 else if(postProcessingDialog)
3069 postProcessingDialog->saveSettings(settings);
3070 postProcessingDialog->saveSettings(settingsTmp);
3072 else if(graphViewer)
3074 graphViewer->saveSettings(settings);
3075 graphViewer->saveSettings(settingsTmp);
3077 else if(calibrationDialog)
3079 calibrationDialog->saveSettings(settings);
3080 calibrationDialog->saveSettings(settingsTmp);
3082 else if(depthCalibrationDialog)
3084 depthCalibrationDialog->saveSettings(settings);
3085 depthCalibrationDialog->saveSettings(settingsTmp);
3089 UERROR(
"Widget \"%s\" cannot be exported in config file.", widget->objectName().toStdString().c_str());
3092 settings.endGroup();
3093 settings.endGroup();
3094 settingsTmp.endGroup();
3095 settingsTmp.endGroup();
3101 if(!widget->objectName().isEmpty())
3105 settings.beginGroup(
"Gui");
3106 settings.beginGroup(widget->objectName());
3109 settingsTmp.beginGroup(
"Gui");
3110 settingsTmp.beginGroup(widget->objectName());
3128 imageView->loadSettings(settings);
3129 imageView->saveSettings(settingsTmp);
3131 else if(exportCloudsDialog)
3133 exportCloudsDialog->loadSettings(settings);
3134 exportCloudsDialog->saveSettings(settingsTmp);
3136 else if(exportBundlerDialog)
3138 exportBundlerDialog->loadSettings(settings);
3139 exportBundlerDialog->saveSettings(settingsTmp);
3141 else if(postProcessingDialog)
3143 postProcessingDialog->loadSettings(settings);
3144 postProcessingDialog->saveSettings(settingsTmp);
3146 else if(graphViewer)
3148 graphViewer->loadSettings(settings);
3149 graphViewer->saveSettings(settingsTmp);
3151 else if(calibrationDialog)
3153 calibrationDialog->loadSettings(settings);
3154 calibrationDialog->saveSettings(settingsTmp);
3156 else if(depthCalibrationDialog)
3158 depthCalibrationDialog->loadSettings(settings);
3159 depthCalibrationDialog->saveSettings(settingsTmp);
3163 UERROR(
"Widget \"%s\" cannot be loaded from config file.", widget->objectName().toStdString().c_str());
3166 settings.endGroup();
3167 settings.endGroup();
3168 settingsTmp.endGroup();
3169 settingsTmp.endGroup();
3177 settings.beginGroup(
"Gui");
3178 settings.beginGroup(section);
3179 settings.setValue(key, value);
3180 settings.endGroup();
3181 settings.endGroup();
3184 settingsTmp.beginGroup(
"Gui");
3185 settingsTmp.beginGroup(section);
3186 settingsTmp.setValue(key, value);
3187 settingsTmp.endGroup();
3188 settingsTmp.endGroup();
3195 settings.beginGroup(
"Gui");
3196 settings.beginGroup(section);
3197 value = settings.value(key, QString()).toString();
3198 settings.endGroup();
3199 settings.endGroup();
3202 settingsTmp.beginGroup(
"Gui");
3203 settingsTmp.beginGroup(section);
3204 settingsTmp.setValue(key, value);
3205 settingsTmp.endGroup();
3206 settingsTmp.endGroup();
3221 parameters.erase(Parameters::kVisCorType());
3239 if(parameters.size())
3241 for(rtabmap::ParametersMap::const_iterator iter = parameters.begin(); iter!=parameters.end(); ++iter)
3245 if(setOtherParametersToDefault)
3251 if(parameters.find(iter->first) == parameters.end() &&
3252 iter->first.compare(Parameters::kRtabmapWorkingDirectory())!=0)
3258 if(!this->isVisible())
3269 _ui->comboBox_sourceType->setCurrentIndex(0);
3270 _ui->comboBox_cameraRGBD->setCurrentIndex(src -
kSrcRGBD);
3273 _ui->lineEdit_openniOniPath->clear();
3277 _ui->lineEdit_openni2OniPath->clear();
3282 _ui->comboBox_sourceType->setCurrentIndex(1);
3283 _ui->comboBox_cameraStereo->setCurrentIndex(src -
kSrcStereo);
3287 _ui->comboBox_sourceType->setCurrentIndex(2);
3288 _ui->source_comboBox_image_type->setCurrentIndex(src -
kSrcRGB);
3292 _ui->comboBox_sourceType->setCurrentIndex(3);
3315 QString dir =
_ui->source_database_lineEdit_path->text();
3320 QStringList paths = QFileDialog::getOpenFileNames(
this, tr(
"Select file"), dir, tr(
"RTAB-Map database files (*.db)"));
3323 int r = QMessageBox::question(
this, tr(
"Odometry in database..."), tr(
"Use odometry saved in database (if some saved)?"), QMessageBox::Yes | QMessageBox::No, QMessageBox::Yes);
3324 _ui->source_checkBox_ignoreOdometry->setChecked(r != QMessageBox::Yes);
3326 if (
_ui->general_doubleSpinBox_detectionRate->value() != 0 &&
_ui->general_spinBox_imagesBufferSize->value() != 0)
3328 r = QMessageBox::question(
this, tr(
"Detection rate..."),
3329 tr(
"Do you want to process all frames? \n\nClicking \"Yes\" will set " 3330 "RTAB-Map's detection rate (%1 Hz) and buffer size (%2) to 0 to make " 3331 "sure that all frames are processed.")
3332 .arg(
_ui->general_doubleSpinBox_detectionRate->value())
3333 .arg(
_ui->general_spinBox_imagesBufferSize->value()),
3334 QMessageBox::Yes | QMessageBox::No, QMessageBox::Yes);
3335 if (r == QMessageBox::Yes)
3337 _ui->general_doubleSpinBox_detectionRate->setValue(0.0);
3338 _ui->general_spinBox_imagesBufferSize->setValue(0);
3342 if(paths.size() > 1)
3344 std::vector<std::string> vFileNames(paths.size());
3345 for(
int i=0; i<paths.size(); ++i)
3347 vFileNames[i] = paths[i].toStdString();
3349 std::sort(vFileNames.begin(), vFileNames.end(),
sortCallback);
3350 for(
int i=0; i<paths.size(); ++i)
3352 paths[i] = vFileNames[i].c_str();
3356 _ui->source_database_lineEdit_path->setText(paths.size()==1?paths.front():paths.join(
";"));
3357 _ui->source_spinBox_databaseStartPos->setValue(0);
3358 _ui->source_spinBox_database_cameraIndex->setValue(-1);
3365 viewer->setWindowModality(Qt::WindowModal);
3366 viewer->setAttribute(Qt::WA_DeleteOnClose,
true);
3380 if(!
_ui->lineEdit_source_distortionModel->text().isEmpty() &&
3381 QFileInfo(
_ui->lineEdit_source_distortionModel->text()).exists())
3384 model.
load(
_ui->lineEdit_source_distortionModel->text().toStdString());
3388 QString name = QFileInfo(
_ui->lineEdit_source_distortionModel->text()).baseName()+
".png";
3389 cv::imwrite(name.toStdString(), img);
3390 QDesktopServices::openUrl(QUrl::fromLocalFile(name));
3394 QMessageBox::warning(
this, tr(
"Distortion Model"), tr(
"Model loaded from \"%1\" is not valid!").arg(
_ui->lineEdit_source_distortionModel->text()));
3399 QMessageBox::warning(
this, tr(
"Distortion Model"), tr(
"File \"%1\" doesn't exist!").arg(
_ui->lineEdit_source_distortionModel->text()));
3405 QString dir =
_ui->lineEdit_calibrationFile->text();
3410 else if(!dir.contains(
'.'))
3414 QString path = QFileDialog::getOpenFileName(
this, tr(
"Select file"), dir, tr(
"Calibration file (*.yaml)"));
3417 _ui->lineEdit_calibrationFile->setText(path);
3423 QString dir =
_ui->lineEdit_cameraImages_timestamps->text();
3428 QString path = QFileDialog::getOpenFileName(
this, tr(
"Select file"), dir, tr(
"Timestamps file (*.txt)"));
3431 _ui->lineEdit_cameraImages_timestamps->setText(path);
3437 QString dir =
_ui->lineEdit_cameraRGBDImages_path_rgb->text();
3442 QString path = QFileDialog::getExistingDirectory(
this, tr(
"Select RGB images directory"), dir);
3445 _ui->lineEdit_cameraRGBDImages_path_rgb->setText(path);
3452 QString dir =
_ui->lineEdit_cameraImages_path_scans->text();
3457 QString path = QFileDialog::getExistingDirectory(
this, tr(
"Select scans directory"), dir);
3460 _ui->lineEdit_cameraImages_path_scans->setText(path);
3466 QString dir =
_ui->lineEdit_cameraImages_path_imu->text();
3471 QString path = QFileDialog::getOpenFileName(
this, tr(
"Select file "), dir, tr(
"EuRoC IMU file (*.csv)"));
3474 _ui->lineEdit_cameraImages_path_imu->setText(path);
3481 QString dir =
_ui->lineEdit_cameraRGBDImages_path_depth->text();
3486 QString path = QFileDialog::getExistingDirectory(
this, tr(
"Select depth images directory"), dir);
3489 _ui->lineEdit_cameraRGBDImages_path_depth->setText(path);
3495 QString dir =
_ui->lineEdit_cameraImages_odom->text();
3500 QString path = QFileDialog::getOpenFileName(
this, tr(
"Select file"), dir, tr(
"Odometry (*.txt *.log *.toro *.g2o *.csv)"));
3504 for(
int i=0; i<
_ui->comboBox_cameraImages_odomFormat->count(); ++i)
3506 list.push_back(
_ui->comboBox_cameraImages_odomFormat->itemText(i));
3508 QString item = QInputDialog::getItem(
this, tr(
"Odometry Format"), tr(
"Format:"), list,
_ui->comboBox_cameraImages_odomFormat->currentIndex(),
false);
3511 _ui->lineEdit_cameraImages_odom->setText(path);
3512 _ui->comboBox_cameraImages_odomFormat->setCurrentIndex(
_ui->comboBox_cameraImages_odomFormat->findText(item));
3519 QString dir =
_ui->lineEdit_cameraImages_gt->text();
3524 QString path = QFileDialog::getOpenFileName(
this, tr(
"Select file"), dir, tr(
"Ground Truth (*.txt *.log *.toro *.g2o *.csv)"));
3528 for(
int i=0; i<
_ui->comboBox_cameraImages_gtFormat->count(); ++i)
3530 list.push_back(
_ui->comboBox_cameraImages_gtFormat->itemText(i));
3532 QString item = QInputDialog::getItem(
this, tr(
"Ground Truth Format"), tr(
"Format:"), list,
_ui->comboBox_cameraImages_gtFormat->currentIndex(),
false);
3535 _ui->lineEdit_cameraImages_gt->setText(path);
3536 _ui->comboBox_cameraImages_gtFormat->setCurrentIndex(
_ui->comboBox_cameraImages_gtFormat->findText(item));
3543 QString dir =
_ui->lineEdit_cameraStereoImages_path_left->text();
3548 QString path = QFileDialog::getExistingDirectory(
this, tr(
"Select left images directory"), dir);
3551 _ui->lineEdit_cameraStereoImages_path_left->setText(path);
3557 QString dir =
_ui->lineEdit_cameraStereoImages_path_right->text();
3562 QString path = QFileDialog::getExistingDirectory(
this, tr(
"Select right images directory"), dir);
3565 _ui->lineEdit_cameraStereoImages_path_right->setText(path);
3571 QString dir =
_ui->source_images_lineEdit_path->text();
3576 QString path = QFileDialog::getExistingDirectory(
this, tr(
"Select images directory"),
_ui->source_images_lineEdit_path->text());
3579 _ui->source_images_lineEdit_path->setText(path);
3580 _ui->source_images_spinBox_startPos->setValue(0);
3586 QString dir =
_ui->source_video_lineEdit_path->text();
3591 QString path = QFileDialog::getOpenFileName(
this, tr(
"Select file"),
_ui->source_video_lineEdit_path->text(), tr(
"Videos (*.avi *.mpg *.mp4 *.mov *.mkv)"));
3594 _ui->source_video_lineEdit_path->setText(path);
3600 QString dir =
_ui->lineEdit_cameraStereoVideo_path->text();
3605 QString path = QFileDialog::getOpenFileName(
this, tr(
"Select file"),
_ui->lineEdit_cameraStereoVideo_path->text(), tr(
"Videos (*.avi *.mpg *.mp4 *.mov *.mkv)"));
3608 _ui->lineEdit_cameraStereoVideo_path->setText(path);
3614 QString dir =
_ui->lineEdit_cameraStereoVideo_path_2->text();
3619 QString path = QFileDialog::getOpenFileName(
this, tr(
"Select file"),
_ui->lineEdit_cameraStereoVideo_path_2->text(), tr(
"Videos (*.avi *.mpg *.mp4 *.mov *.mkv)"));
3622 _ui->lineEdit_cameraStereoVideo_path_2->setText(path);
3628 QString dir =
_ui->lineEdit_source_distortionModel->text();
3633 QString path = QFileDialog::getOpenFileName(
this, tr(
"Select file"),
_ui->lineEdit_source_distortionModel->text(), tr(
"Distortion model (*.bin *.txt)"));
3636 _ui->lineEdit_source_distortionModel->setText(path);
3642 QString dir =
_ui->lineEdit_openniOniPath->text();
3647 QString path = QFileDialog::getOpenFileName(
this, tr(
"Select file"),
_ui->lineEdit_openniOniPath->text(), tr(
"OpenNI (*.oni)"));
3650 _ui->lineEdit_openniOniPath->setText(path);
3656 QString dir =
_ui->lineEdit_openni2OniPath->text();
3661 QString path = QFileDialog::getOpenFileName(
this, tr(
"Select file"),
_ui->lineEdit_openni2OniPath->text(), tr(
"OpenNI (*.oni)"));
3664 _ui->lineEdit_openni2OniPath->setText(path);
3670 QString dir =
_ui->lineEdit_zedSvoPath->text();
3675 QString path = QFileDialog::getOpenFileName(
this, tr(
"Select file"),
_ui->lineEdit_zedSvoPath->text(), tr(
"ZED (*.svo)"));
3678 _ui->lineEdit_zedSvoPath->setText(path);
3684 UDEBUG(
"%s=%s", key.c_str(), value.c_str());
3685 QWidget * obj =
_ui->stackedWidget->findChild<QWidget*>(key.c_str());
3690 QSpinBox * spin = qobject_cast<QSpinBox *>(obj);
3691 QDoubleSpinBox * doubleSpin = qobject_cast<QDoubleSpinBox *>(obj);
3692 QComboBox * combo = qobject_cast<QComboBox *>(obj);
3693 QCheckBox * check = qobject_cast<QCheckBox *>(obj);
3694 QRadioButton * radio = qobject_cast<QRadioButton *>(obj);
3695 QLineEdit * lineEdit = qobject_cast<QLineEdit *>(obj);
3696 QGroupBox * groupBox = qobject_cast<QGroupBox *>(obj);
3700 spin->setValue(QString(value.c_str()).toInt(&ok));
3703 UERROR(
"Conversion failed from \"%s\" for parameter %s", value.c_str(), key.c_str());
3708 doubleSpin->setValue(QString(value.c_str()).toDouble(&ok));
3711 UERROR(
"Conversion failed from \"%s\" for parameter %s", value.c_str(), key.c_str());
3716 int valueInt = QString(value.c_str()).toInt(&ok);
3719 UERROR(
"Conversion failed from \"%s\" for parameter %s", value.c_str(), key.c_str());
3723 #ifndef RTABMAP_NONFREE 3725 (combo->objectName().toStdString().compare(Parameters::kKpDetectorStrategy()) == 0 ||
3726 combo->objectName().toStdString().compare(Parameters::kVisFeatureType()) == 0))
3728 UWARN(
"Trying to set \"%s\" to SIFT/SURF but RTAB-Map isn't built " 3729 "with the nonfree module from OpenCV. Keeping default combo value: %s.",
3730 combo->objectName().toStdString().c_str(),
3731 combo->currentText().toStdString().c_str());
3735 #ifndef RTABMAP_ORB_SLAM2 3739 if(valueInt==1 && combo->objectName().toStdString().compare(Parameters::kOptimizerStrategy()) == 0)
3741 UWARN(
"Trying to set \"%s\" to g2o but RTAB-Map isn't built " 3742 "with g2o. Keeping default combo value: %s.",
3743 combo->objectName().toStdString().c_str(),
3744 combo->currentText().toStdString().c_str());
3750 if(valueInt==2 && combo->objectName().toStdString().compare(Parameters::kOptimizerStrategy()) == 0)
3752 UWARN(
"Trying to set \"%s\" to GTSAM but RTAB-Map isn't built " 3753 "with GTSAM. Keeping default combo value: %s.",
3754 combo->objectName().toStdString().c_str(),
3755 combo->currentText().toStdString().c_str());
3761 combo->setCurrentIndex(valueInt);
3768 _ui->checkBox_useOdomFeatures->blockSignals(
true);
3769 check->setChecked(
uStr2Bool(value.c_str()));
3770 _ui->checkBox_useOdomFeatures->blockSignals(
false);
3774 radio->setChecked(
uStr2Bool(value.c_str()));
3778 lineEdit->setText(value.c_str());
3782 groupBox->setChecked(
uStr2Bool(value.c_str()));
3786 ULOGGER_WARN(
"QObject called %s can't be cast to a supported widget", key.c_str());
3791 ULOGGER_WARN(
"Can't find the related QObject for parameter %s", key.c_str());
3803 ULOGGER_ERROR(
"This slot must be triggered by a signal, not a direct call...");
3815 ULOGGER_ERROR(
"This slot must be triggered by a signal, not a direct call...");
3827 ULOGGER_ERROR(
"This slot must be triggered by a signal, not a direct call...");
3839 ULOGGER_ERROR(
"This slot must be triggered by a signal, not a direct call...");
3847 const QComboBox * comboBox = qobject_cast<
const QComboBox*>(object);
3848 const QSpinBox * spinbox = qobject_cast<
const QSpinBox*>(object);
3849 if(comboBox || spinbox)
3852 UDEBUG(
"modify param %s=%s", object->objectName().toStdString().c_str(),
uNumber2Str(value).c_str());
3857 UWARN(
"Undefined object \"%s\"", object->objectName().toStdString().c_str());
3871 const QCheckBox * checkbox = qobject_cast<
const QCheckBox*>(object);
3872 const QRadioButton * radio = qobject_cast<
const QRadioButton*>(object);
3873 const QGroupBox * groupBox = qobject_cast<
const QGroupBox*>(object);
3874 if(checkbox || radio || groupBox)
3877 UDEBUG(
"modify param %s=%s", object->objectName().toStdString().c_str(),
uBool2Str(value).c_str());
3882 UWARN(
"Undefined object \"%s\"", object->objectName().toStdString().c_str());
3896 UDEBUG(
"modify param %s=%f", object->objectName().toStdString().c_str(), value);
3909 UDEBUG(
"modify param %s=%s", object->objectName().toStdString().c_str(), value.toStdString().c_str());
3921 for(
int i=0; i<children.size(); ++i)
3923 const QSpinBox * spin = qobject_cast<
const QSpinBox *>(children[i]);
3924 const QDoubleSpinBox * doubleSpin = qobject_cast<
const QDoubleSpinBox *>(children[i]);
3925 const QComboBox * combo = qobject_cast<
const QComboBox *>(children[i]);
3926 const QCheckBox * check = qobject_cast<
const QCheckBox *>(children[i]);
3927 const QRadioButton * radio = qobject_cast<
const QRadioButton *>(children[i]);
3928 const QLineEdit * lineEdit = qobject_cast<
const QLineEdit *>(children[i]);
3929 const QGroupBox * groupBox = qobject_cast<
const QGroupBox *>(children[i]);
3930 const QStackedWidget * stackedWidget = qobject_cast<
const QStackedWidget *>(children[i]);
3957 if(groupBox->isCheckable())
3966 else if(stackedWidget)
3979 for(
int i=0; i<stackedWidget->count(); ++i)
3981 const QObjectList & children = stackedWidget->widget(i)->children();
3987 UASSERT(panel<stackedWidget->count());
3988 const QObjectList & children = stackedWidget->widget(panel)->children();
3998 const QObjectList & children = box->children();
4008 if(sender() ==
_ui->general_doubleSpinBox_timeThr_2)
4010 _ui->general_doubleSpinBox_timeThr->setValue(
_ui->general_doubleSpinBox_timeThr_2->value());
4012 else if(sender() ==
_ui->general_doubleSpinBox_hardThr_2)
4014 _ui->general_doubleSpinBox_hardThr->setValue(
_ui->general_doubleSpinBox_hardThr_2->value());
4016 else if(sender() ==
_ui->general_doubleSpinBox_detectionRate_2)
4018 _ui->general_doubleSpinBox_detectionRate->setValue(
_ui->general_doubleSpinBox_detectionRate_2->value());
4020 else if(sender() ==
_ui->general_spinBox_imagesBufferSize_2)
4022 _ui->general_spinBox_imagesBufferSize->setValue(
_ui->general_spinBox_imagesBufferSize_2->value());
4024 else if(sender() ==
_ui->general_spinBox_maxStMemSize_2)
4026 _ui->general_spinBox_maxStMemSize->setValue(
_ui->general_spinBox_maxStMemSize_2->value());
4028 else if(sender() ==
_ui->groupBox_publishing)
4030 _ui->general_checkBox_publishStats_2->setChecked(
_ui->groupBox_publishing->isChecked());
4032 else if(sender() ==
_ui->general_checkBox_publishStats_2)
4034 _ui->groupBox_publishing->setChecked(
_ui->general_checkBox_publishStats_2->isChecked());
4036 else if(sender() ==
_ui->doubleSpinBox_similarityThreshold_2)
4038 _ui->doubleSpinBox_similarityThreshold->setValue(
_ui->doubleSpinBox_similarityThreshold_2->value());
4040 else if(sender() ==
_ui->general_checkBox_activateRGBD)
4042 _ui->general_checkBox_activateRGBD_2->setChecked(
_ui->general_checkBox_activateRGBD->isChecked());
4044 else if(sender() ==
_ui->general_checkBox_activateRGBD_2)
4046 _ui->general_checkBox_activateRGBD->setChecked(
_ui->general_checkBox_activateRGBD_2->isChecked());
4048 else if(sender() ==
_ui->general_checkBox_SLAM_mode)
4050 _ui->general_checkBox_SLAM_mode_2->setChecked(
_ui->general_checkBox_SLAM_mode->isChecked());
4052 else if(sender() ==
_ui->general_checkBox_SLAM_mode_2)
4054 _ui->general_checkBox_SLAM_mode->setChecked(
_ui->general_checkBox_SLAM_mode_2->isChecked());
4059 _ui->general_doubleSpinBox_timeThr->setValue(
_ui->general_doubleSpinBox_timeThr_2->value());
4060 _ui->general_doubleSpinBox_hardThr->setValue(
_ui->general_doubleSpinBox_hardThr_2->value());
4061 _ui->general_doubleSpinBox_detectionRate->setValue(
_ui->general_doubleSpinBox_detectionRate_2->value());
4062 _ui->general_spinBox_imagesBufferSize->setValue(
_ui->general_spinBox_imagesBufferSize_2->value());
4063 _ui->general_spinBox_maxStMemSize->setValue(
_ui->general_spinBox_maxStMemSize_2->value());
4064 _ui->doubleSpinBox_similarityThreshold->setValue(
_ui->doubleSpinBox_similarityThreshold_2->value());
4093 QList<QGroupBox*> boxes;
4094 for(
int i=0; i<
_ui->stackedWidget->count(); ++i)
4097 const QObjectList & children =
_ui->stackedWidget->widget(i)->children();
4098 for(
int j=0; j<children.size(); ++j)
4100 if((gb = qobject_cast<QGroupBox *>(children.at(j))))
4112 ULOGGER_ERROR(
"A QGroupBox must be included in the first level of children in stacked widget, index=%d", i);
4120 QStringList values =
_ui->lineEdit_bayes_predictionLC->text().simplified().split(
' ');
4121 if(values.size() < 2)
4123 UERROR(
"Error parsing prediction (must have at least 2 items) : %s",
4124 _ui->lineEdit_bayes_predictionLC->text().toStdString().c_str());
4127 QVector<float> dataX((values.size()-2)*2 + 1);
4128 QVector<float> dataY((values.size()-2)*2 + 1);
4134 int loopClosureIndex = (dataX.size()-1)/2;
4135 for(
int i=0; i<values.size(); ++i)
4137 value = values.at(i).toDouble(&ok);
4140 UERROR(
"Error parsing prediction : \"%s\"", values.at(i).toStdString().c_str());
4150 dataY[loopClosureIndex] = value;
4151 dataX[loopClosureIndex] = 0;
4155 dataY[loopClosureIndex-lvl] = value;
4156 dataX[loopClosureIndex-lvl] = -lvl;
4157 dataY[loopClosureIndex+lvl] = value;
4158 dataX[loopClosureIndex+lvl] = lvl;
4163 _ui->label_prediction_sum->setNum(sum);
4166 _ui->label_prediction_sum->setText(QString(
"<font color=#FF0000>") +
_ui->label_prediction_sum->text() +
"</font>");
4170 _ui->label_prediction_sum->setText(QString(
"<font color=#00FF00>") +
_ui->label_prediction_sum->text() +
"</font>");
4174 _ui->label_prediction_sum->setText(QString(
"<font color=#FFa500>") +
_ui->label_prediction_sum->text() +
"</font>");
4178 _ui->label_prediction_sum->setText(QString(
"<font color=#000000>") +
_ui->label_prediction_sum->text() +
"</font>");
4181 _ui->predictionPlot->removeCurves();
4182 _ui->predictionPlot->addCurve(
new UPlotCurve(
"Prediction", dataX, dataY,
_ui->predictionPlot));
4187 QStringList strings =
_ui->lineEdit_kp_roi->text().split(
' ');
4188 if(strings.size()!=4)
4190 UERROR(
"ROI must have 4 values (%s)",
_ui->lineEdit_kp_roi->text().toStdString().c_str());
4193 _ui->doubleSpinBox_kp_roi0->setValue(strings[0].toDouble()*100.0);
4194 _ui->doubleSpinBox_kp_roi1->setValue(strings[1].toDouble()*100.0);
4195 _ui->doubleSpinBox_kp_roi2->setValue(strings[2].toDouble()*100.0);
4196 _ui->doubleSpinBox_kp_roi3->setValue(strings[3].toDouble()*100.0);
4201 QStringList strings;
4202 strings.append(QString::number(
_ui->doubleSpinBox_kp_roi0->value()/100.0));
4203 strings.append(QString::number(
_ui->doubleSpinBox_kp_roi1->value()/100.0));
4204 strings.append(QString::number(
_ui->doubleSpinBox_kp_roi2->value()/100.0));
4205 strings.append(QString::number(
_ui->doubleSpinBox_kp_roi3->value()/100.0));
4206 _ui->lineEdit_kp_roi->setText(strings.join(
" "));
4212 _ui->checkbox_stereo_depthGenerated->setVisible(
4214 _ui->comboBox_stereoZed_quality->currentIndex() == 0);
4215 _ui->label_stereo_depthGenerated->setVisible(
4217 _ui->comboBox_stereoZed_quality->currentIndex() == 0);
4219 _ui->checkBox_stereo_rectify->setEnabled(
4224 _ui->checkBox_stereo_rectify->setVisible(
_ui->checkBox_stereo_rectify->isEnabled());
4225 _ui->label_stereo_rectify->setVisible(
_ui->checkBox_stereo_rectify->isEnabled());
4230 if(this->isVisible() &&
_ui->checkBox_useOdomFeatures->isChecked())
4232 int r = QMessageBox::question(
this, tr(
"Using odometry features for vocabulary..."),
4233 tr(
"Do you want to match vocabulary feature parameters " 4234 "with corresponding ones used for odometry?"), QMessageBox::Yes | QMessageBox::No, QMessageBox::Yes);
4236 if(r == QMessageBox::Yes)
4238 _ui->comboBox_detector_strategy->setCurrentIndex(
_ui->reextract_type->currentIndex());
4239 _ui->surf_doubleSpinBox_maxDepth->setValue(
_ui->loopClosure_bowMaxDepth->value());
4240 _ui->surf_doubleSpinBox_minDepth->setValue(
_ui->loopClosure_bowMinDepth->value());
4241 _ui->surf_spinBox_wordsPerImageTarget->setValue(
_ui->reextract_maxFeatures->value());
4242 _ui->spinBox_KPGridRows->setValue(
_ui->reextract_gridrows->value());
4243 _ui->spinBox_KPGridCols->setValue(
_ui->reextract_gridcols->value());
4244 _ui->lineEdit_kp_roi->setText(
_ui->loopClosure_roi->text());
4245 _ui->subpix_winSize_kp->setValue(
_ui->subpix_winSize->value());
4246 _ui->subpix_iterations_kp->setValue(
_ui->subpix_iterations->value());
4247 _ui->subpix_eps_kp->setValue(
_ui->subpix_eps->value());
4254 QString directory = QFileDialog::getExistingDirectory(
this, tr(
"Working directory"),
_ui->lineEdit_workingDirectory->text());
4255 if(!directory.isEmpty())
4257 ULOGGER_DEBUG(
"New working directory = %s", directory.toStdString().c_str());
4258 _ui->lineEdit_workingDirectory->setText(directory);
4265 if(
_ui->lineEdit_dictionaryPath->text().isEmpty())
4267 path = QFileDialog::getOpenFileName(
this, tr(
"Dictionary"), this->
getWorkingDirectory(), tr(
"Dictionary (*.txt *.db)"));
4271 path = QFileDialog::getOpenFileName(
this, tr(
"Dictionary"),
_ui->lineEdit_dictionaryPath->text(), tr(
"Dictionary (*.txt *.db)"));
4275 _ui->lineEdit_dictionaryPath->setText(path);
4282 if(
_ui->lineEdit_OdomORBSLAM2VocPath->text().isEmpty())
4284 path = QFileDialog::getOpenFileName(
this, tr(
"ORBSLAM2 Vocabulary"), this->
getWorkingDirectory(), tr(
"Vocabulary (*.txt)"));
4288 path = QFileDialog::getOpenFileName(
this, tr(
"ORBSLAM2 Vocabulary"),
_ui->lineEdit_OdomORBSLAM2VocPath->text(), tr(
"Vocabulary (*.txt)"));
4292 _ui->lineEdit_OdomORBSLAM2VocPath->setText(path);
4299 if(
_ui->lineEdit_OdomOkvisPath->text().isEmpty())
4301 path = QFileDialog::getOpenFileName(
this, tr(
"OKVIS Config"), this->
getWorkingDirectory(), tr(
"OKVIS config (*.yaml)"));
4305 path = QFileDialog::getOpenFileName(
this, tr(
"OKVIS Config"),
_ui->lineEdit_OdomOkvisPath->text(), tr(
"OKVIS config (*.yaml)"));
4309 _ui->lineEdit_OdomOkvisPath->setText(path);
4316 if(
_ui->lineEdit_IcpPMConfigPath->text().isEmpty())
4318 path = QFileDialog::getOpenFileName(
this, tr(
"Select file"), this->
getWorkingDirectory(), tr(
"libpointmatcher (*.yaml)"));
4322 path = QFileDialog::getOpenFileName(
this, tr(
"Select file"),
_ui->lineEdit_IcpPMConfigPath->text(), tr(
"libpointmatcher (*.yaml)"));
4326 _ui->lineEdit_IcpPMConfigPath->setText(path);
4332 _ui->groupBox_sourceRGBD->setVisible(
_ui->comboBox_sourceType->currentIndex() == 0);
4333 _ui->groupBox_sourceStereo->setVisible(
_ui->comboBox_sourceType->currentIndex() == 1);
4334 _ui->groupBox_sourceRGB->setVisible(
_ui->comboBox_sourceType->currentIndex() == 2);
4335 _ui->groupBox_sourceDatabase->setVisible(
_ui->comboBox_sourceType->currentIndex() == 3);
4337 _ui->groupBox_scanFromDepth->setVisible(
_ui->comboBox_sourceType->currentIndex() <= 1 ||
_ui->comboBox_sourceType->currentIndex() == 3);
4339 _ui->stackedWidget_rgbd->setVisible(
_ui->comboBox_sourceType->currentIndex() == 0 &&
4347 _ui->groupBox_openni2->setVisible(
_ui->comboBox_sourceType->currentIndex() == 0 &&
_ui->comboBox_cameraRGBD->currentIndex() ==
kSrcOpenNI2-
kSrcRGBD);
4348 _ui->groupBox_freenect2->setVisible(
_ui->comboBox_sourceType->currentIndex() == 0 &&
_ui->comboBox_cameraRGBD->currentIndex() ==
kSrcFreenect2-
kSrcRGBD);
4349 _ui->groupBox_k4w2->setVisible(
_ui->comboBox_sourceType->currentIndex() == 0 &&
_ui->comboBox_cameraRGBD->currentIndex() ==
kSrcK4W2 -
kSrcRGBD);
4350 _ui->groupBox_realsense->setVisible(
_ui->comboBox_sourceType->currentIndex() == 0 &&
_ui->comboBox_cameraRGBD->currentIndex() ==
kSrcRealSense -
kSrcRGBD);
4351 _ui->groupBox_realsense2->setVisible(
_ui->comboBox_sourceType->currentIndex() == 0 &&
_ui->comboBox_cameraRGBD->currentIndex() ==
kSrcRealSense2 -
kSrcRGBD);
4352 _ui->groupBox_cameraRGBDImages->setVisible(
_ui->comboBox_sourceType->currentIndex() == 0 &&
_ui->comboBox_cameraRGBD->currentIndex() ==
kSrcRGBDImages-
kSrcRGBD);
4353 _ui->groupBox_openni->setVisible(
_ui->comboBox_sourceType->currentIndex() == 0 &&
_ui->comboBox_cameraRGBD->currentIndex() ==
kSrcOpenNI_PCL-
kSrcRGBD);
4355 _ui->stackedWidget_stereo->setVisible(
_ui->comboBox_sourceType->currentIndex() == 1 &&
4361 _ui->groupBox_cameraStereoVideo->setVisible(
_ui->comboBox_sourceType->currentIndex() == 1 &&
_ui->comboBox_cameraStereo->currentIndex() ==
kSrcStereoVideo -
kSrcStereo);
4362 _ui->groupBox_cameraStereoUsb->setVisible(
_ui->comboBox_sourceType->currentIndex() == 1 &&
_ui->comboBox_cameraStereo->currentIndex() ==
kSrcStereoUsb -
kSrcStereo);
4363 _ui->groupBox_cameraStereoZed->setVisible(
_ui->comboBox_sourceType->currentIndex() == 1 &&
_ui->comboBox_cameraStereo->currentIndex() ==
kSrcStereoZed -
kSrcStereo);
4365 _ui->stackedWidget_image->setVisible(
_ui->comboBox_sourceType->currentIndex() == 2 && (
_ui->source_comboBox_image_type->currentIndex() ==
kSrcImages-
kSrcRGB ||
_ui->source_comboBox_image_type->currentIndex() ==
kSrcVideo-
kSrcRGB));
4366 _ui->source_groupBox_images->setVisible(
_ui->comboBox_sourceType->currentIndex() == 2 &&
_ui->source_comboBox_image_type->currentIndex() ==
kSrcImages-
kSrcRGB);
4367 _ui->source_groupBox_video->setVisible(
_ui->comboBox_sourceType->currentIndex() == 2 &&
_ui->source_comboBox_image_type->currentIndex() ==
kSrcVideo-
kSrcRGB);
4369 _ui->groupBox_sourceImages_optional->setVisible(
4372 (
_ui->comboBox_sourceType->currentIndex() == 2 &&
_ui->source_comboBox_image_type->currentIndex() ==
kSrcImages-
kSrcRGB));
4374 _ui->groupBox_depthImageFiltering->setEnabled(
4375 _ui->comboBox_sourceType->currentIndex() == 0 ||
4376 _ui->comboBox_sourceType->currentIndex() == 3);
4377 _ui->groupBox_depthImageFiltering->setVisible(
_ui->groupBox_depthImageFiltering->isEnabled());
4381 _ui->groupBox_depthFromScan->setVisible(
_ui->comboBox_sourceType->currentIndex() == 2 &&
_ui->source_comboBox_image_type->currentIndex() ==
kSrcImages-
kSrcRGB);
4388 return _ui->comboBox_loggerLevel->currentIndex();
4392 return _ui->comboBox_loggerEventLevel->currentIndex();
4396 return _ui->comboBox_loggerPauseLevel->currentIndex();
4400 return _ui->comboBox_loggerType->currentIndex();
4404 return _ui->checkBox_logger_printTime->isChecked();
4408 return _ui->checkBox_logger_printThreadId->isChecked();
4412 std::vector<std::string> threads;
4413 for(
int i=0; i<
_ui->comboBox_loggerFilter->count(); ++i)
4415 if(
_ui->comboBox_loggerFilter->itemData(i).toBool())
4417 threads.push_back(
_ui->comboBox_loggerFilter->itemText(i).toStdString());
4424 return _ui->checkBox_verticalLayoutUsed->isChecked();
4428 return _ui->checkBox_imageRejectedShown->isChecked();
4432 return _ui->checkBox_imageHighestHypShown->isChecked();
4436 return _ui->checkBox_beep->isChecked();
4440 return _ui->checkBox_stamps->isChecked();
4444 return _ui->checkBox_cacheStatistics->isChecked();
4448 return _ui->checkBox_notifyWhenNewGlobalPathIsReceived->isChecked();
4452 return _ui->spinBox_odomQualityWarnThr->value();
4456 return _ui->checkBox_odom_onlyInliersShown->isChecked();
4460 return _ui->radioButton_posteriorGraphView->isChecked();
4464 return _ui->radioButton_wordsGraphView->isChecked();
4468 return _ui->radioButton_localizationsGraphView->isChecked();
4472 return _ui->checkbox_odomDisabled->isChecked();
4476 return _ui->odom_registration->currentIndex();
4480 return _ui->checkbox_groundTruthAlign->isChecked();
4485 UASSERT(index >= 0 && index <= 1);
4490 #ifdef RTABMAP_OCTOMAP 4491 return _ui->groupBox_octomap->isChecked();
4497 #ifdef RTABMAP_OCTOMAP 4498 return _ui->groupBox_octomap->isChecked() &&
_ui->checkBox_octomap_show3dMap->isChecked();
4504 return _ui->comboBox_octomap_renderingType->currentIndex();
4508 #ifdef RTABMAP_OCTOMAP 4509 return _ui->groupBox_octomap->isChecked() &&
_ui->checkBox_octomap_2dgrid->isChecked();
4515 return _ui->spinBox_octomap_treeDepth->value();
4519 return _ui->spinBox_octomap_pointSize->value();
4524 return _ui->doubleSpinBox_voxel->value();
4528 return _ui->doubleSpinBox_noiseRadius->value();
4532 return _ui->spinBox_noiseMinNeighbors->value();
4536 return _ui->doubleSpinBox_ceilingFilterHeight->value();
4540 return _ui->doubleSpinBox_floorFilterHeight->value();
4544 return _ui->spinBox_normalKSearch->value();
4548 return _ui->doubleSpinBox_normalRadiusSearch->value();
4552 return _ui->doubleSpinBox_ceilingFilterHeight_scan->value();
4556 return _ui->doubleSpinBox_floorFilterHeight_scan->value();
4560 return _ui->spinBox_normalKSearch_scan->value();
4564 return _ui->doubleSpinBox_normalRadiusSearch_scan->value();
4569 return _ui->checkBox_showGraphs->isChecked();
4573 return _ui->checkBox_showLabels->isChecked();
4577 return _ui->groupBox_organized->isChecked();
4581 return _ui->doubleSpinBox_mesh_angleTolerance->value()*
M_PI/180.0;
4585 return _ui->checkBox_mesh_quad->isChecked();
4589 return _ui->checkBox_mesh_texture->isChecked();
4593 return _ui->spinBox_mesh_triangleSize->value();
4597 UASSERT(index >= 0 && index <= 1);
4602 UASSERT(index >= 0 && index <= 1);
4607 UASSERT(index >= 0 && index <= 1);
4612 UASSERT(index >= 0 && index <= 1);
4613 std::vector<float> roiRatios;
4617 if(values.size() == 4)
4619 roiRatios.resize(4);
4620 for(
int i=0; i<values.size(); ++i)
4622 roiRatios[i] =
uStr2Float(values[i].toStdString().c_str());
4630 UASSERT(index >= 0 && index <= 1);
4635 UASSERT(index >= 0 && index <= 1);
4640 UASSERT(index >= 0 && index <= 1);
4646 UASSERT(index >= 0 && index <= 1);
4651 UASSERT(index >= 0 && index <= 1);
4656 UASSERT(index >= 0 && index <= 1);
4661 UASSERT(index >= 0 && index <= 1);
4666 UASSERT(index >= 0 && index <= 1);
4671 UASSERT(index >= 0 && index <= 1);
4676 UASSERT(index >= 0 && index <= 1);
4681 UASSERT(index >= 0 && index <= 1);
4687 UASSERT(index >= 0 && index <= 1);
4692 UASSERT(index >= 0 && index <= 1);
4697 UASSERT(index >= 0 && index <= 1);
4703 return _ui->radioButton_nodeFiltering->isChecked();
4707 return _ui->radioButton_subtractFiltering->isChecked();
4711 return _ui->doubleSpinBox_cloudFilterRadius->value();
4715 return _ui->doubleSpinBox_cloudFilterAngle->value();
4719 return _ui->spinBox_subtractFilteringMinPts->value();
4723 return _ui->doubleSpinBox_subtractFilteringRadius->value();
4727 return _ui->doubleSpinBox_subtractFilteringAngle->value()*
M_PI/180.0;
4731 return _ui->checkBox_map_shown->isChecked();
4735 return _ui->groupBox_grid_fromDepthImage->isChecked();
4739 return _ui->checkBox_grid_projMapFrame->isChecked();
4743 return _ui->doubleSpinBox_grid_maxGroundAngle->value()*
M_PI/180.0;
4747 return _ui->doubleSpinBox_grid_maxGroundHeight->value();
4751 return _ui->spinBox_grid_minClusterSize->value();
4755 return _ui->doubleSpinBox_grid_maxObstacleHeight->value();
4759 return _ui->checkBox_grid_flatObstaclesDetected->isChecked();
4763 return _ui->doubleSpinBox_map_opacity->value();
4770 return _ui->general_doubleSpinBox_imgRate->value();
4774 return _ui->source_mirroring->isChecked();
4778 int index =
_ui->comboBox_sourceType->currentIndex();
4823 return _ui->comboBox_cameraRGBD->currentText();
4827 return _ui->comboBox_cameraStereo->currentText();
4831 return _ui->source_comboBox_image_type->currentText();
4842 return _ui->lineEdit_sourceDevice->text();
4867 return _ui->lineEdit_cameraImages_path_imu->text();
4880 return _ui->spinBox_cameraImages_max_imu_rate->value();
4885 return _ui->source_checkBox_useDbStamps->isChecked();
4889 return _ui->checkbox_rgbd_colorOnly->isChecked();
4893 return _ui->groupBox_depthImageFiltering->isEnabled();
4897 return _ui->lineEdit_source_distortionModel->text();
4901 return _ui->groupBox_bilateral->isChecked();
4905 return _ui->doubleSpinBox_bilateral_sigmaS->value();
4909 return _ui->doubleSpinBox_bilateral_sigmaR->value();
4913 return _ui->spinBox_source_imageDecimation->value();
4917 return _ui->checkbox_stereo_depthGenerated->isChecked();
4921 return _ui->checkBox_stereo_exposureCompensation->isChecked();
4925 return _ui->groupBox_scanFromDepth->isChecked();
4929 return _ui->spinBox_cameraScanFromDepth_decimation->value();
4933 return _ui->doubleSpinBox_cameraSCanFromDepth_maxDepth->value();
4937 return _ui->doubleSpinBox_cameraImages_scanVoxelSize->value();
4941 return _ui->spinBox_cameraImages_scanNormalsK->value();
4945 return _ui->doubleSpinBox_cameraImages_scanNormalsRadius->value();
4957 QMessageBox::warning(
this, tr(
"Calibration"),
4958 tr(
"Using raw images for \"OpenNI\" driver is not yet supported. " 4959 "Factory calibration loaded from OpenNI is used."), QMessageBox::Ok);
4965 _ui->lineEdit_openniOniPath->text().isEmpty()?this->
getSourceDevice().toStdString():
_ui->lineEdit_openniOniPath->text().toStdString(),
4973 _ui->lineEdit_openni2OniPath->text().isEmpty()?this->
getSourceDevice().toStdString():
_ui->lineEdit_openni2OniPath->text().toStdString(),
4991 QMessageBox::warning(
this, tr(
"Calibration"),
4992 tr(
"Using raw images for \"OpenNI\" driver is not yet supported. " 4993 "Factory calibration loaded from OpenNI is used."), QMessageBox::Ok);
5011 _ui->doubleSpinBox_freenect2MinDepth->value(),
5012 _ui->doubleSpinBox_freenect2MaxDepth->value(),
5013 _ui->checkBox_freenect2BilateralFiltering->isChecked(),
5014 _ui->checkBox_freenect2EdgeAwareFiltering->isChecked(),
5015 _ui->checkBox_freenect2NoiseFiltering->isChecked(),
5016 _ui->lineEdit_freenect2Pipeline->text().toStdString());
5028 if(useRawImages &&
_ui->comboBox_realsenseRGBSource->currentIndex()!=2)
5030 QMessageBox::warning(
this, tr(
"Calibration"),
5031 tr(
"Using raw images for \"RealSense\" driver is not yet supported for color and infrared streams. " 5032 "Factory calibration loaded from RealSense is used."), QMessageBox::Ok);
5039 _ui->comboBox_realsensePresetRGB->currentIndex(),
5040 _ui->comboBox_realsensePresetDepth->currentIndex(),
5041 _ui->checkbox_realsenseOdom->isChecked(),
5052 QMessageBox::warning(
this, tr(
"Calibration"),
5053 tr(
"Using raw images for \"RealSense\" driver is not yet supported. " 5054 "Factory calibration loaded from RealSense2 is used."), QMessageBox::Ok);
5070 _ui->lineEdit_cameraRGBDImages_path_rgb->text().append(QDir::separator()).toStdString(),
5071 _ui->lineEdit_cameraRGBDImages_path_depth->text().append(QDir::separator()).toStdString(),
5072 _ui->doubleSpinBox_cameraRGBDImages_scale->value(),
5076 ((
CameraRGBDImages*)camera)->setBayerMode(
_ui->comboBox_cameraImages_bayerMode->currentIndex()-1);
5077 ((
CameraRGBDImages*)camera)->setOdometryPath(
_ui->lineEdit_cameraImages_odom->text().toStdString(),
_ui->comboBox_cameraImages_odomFormat->currentIndex());
5078 ((
CameraRGBDImages*)camera)->setGroundTruthPath(
_ui->lineEdit_cameraImages_gt->text().toStdString(),
_ui->comboBox_cameraImages_gtFormat->currentIndex());
5079 ((
CameraRGBDImages*)camera)->setMaxPoseTimeDiff(
_ui->doubleSpinBox_maxPoseTimeDiff->value());
5081 _ui->lineEdit_cameraImages_path_scans->text().isEmpty()?
"":
_ui->lineEdit_cameraImages_path_scans->text().append(QDir::separator()).toStdString(),
5082 _ui->spinBox_cameraImages_max_scan_pts->value(),
5083 _ui->spinBox_cameraImages_scanDownsampleStep->value(),
5084 _ui->doubleSpinBox_cameraImages_scanVoxelSize->value(),
5085 _ui->spinBox_cameraImages_scanNormalsK->value(),
5086 _ui->doubleSpinBox_cameraImages_scanNormalsRadius->value(),
5088 _ui->checkBox_cameraImages_scanForceGroundNormalsUp->isChecked());
5090 _ui->checkBox_cameraImages_timestamps->isChecked(),
5091 _ui->lineEdit_cameraImages_timestamps->text().toStdString(),
5092 _ui->checkBox_cameraImages_syncTimeStamps->isChecked());
5104 QMessageBox::warning(
this, tr(
"Calibration"),
5105 tr(
"Using raw images for \"FlyCapture2\" driver is not yet supported. " 5106 "Factory calibration loaded from FlyCapture2 is used."), QMessageBox::Ok);
5119 _ui->lineEdit_cameraStereoImages_path_left->text().append(QDir::separator()).toStdString(),
5120 _ui->lineEdit_cameraStereoImages_path_right->text().append(QDir::separator()).toStdString(),
5121 _ui->checkBox_stereo_rectify->isChecked() && !useRawImages,
5125 ((
CameraStereoImages*)camera)->setBayerMode(
_ui->comboBox_cameraImages_bayerMode->currentIndex()-1);
5126 ((
CameraStereoImages*)camera)->setOdometryPath(
_ui->lineEdit_cameraImages_odom->text().toStdString(),
_ui->comboBox_cameraImages_odomFormat->currentIndex());
5127 ((
CameraStereoImages*)camera)->setGroundTruthPath(
_ui->lineEdit_cameraImages_gt->text().toStdString(),
_ui->comboBox_cameraImages_gtFormat->currentIndex());
5130 _ui->lineEdit_cameraImages_path_scans->text().isEmpty()?
"":
_ui->lineEdit_cameraImages_path_scans->text().append(QDir::separator()).toStdString(),
5131 _ui->spinBox_cameraImages_max_scan_pts->value(),
5132 _ui->spinBox_cameraImages_scanDownsampleStep->value(),
5133 _ui->doubleSpinBox_cameraImages_scanVoxelSize->value(),
5134 _ui->spinBox_cameraImages_scanNormalsK->value(),
5135 _ui->doubleSpinBox_cameraImages_scanNormalsRadius->value(),
5137 _ui->checkBox_cameraImages_scanForceGroundNormalsUp->isChecked());
5139 _ui->checkBox_cameraImages_timestamps->isChecked(),
5140 _ui->lineEdit_cameraImages_timestamps->text().toStdString(),
5141 _ui->checkBox_cameraImages_syncTimeStamps->isChecked());
5146 if(
_ui->spinBox_stereo_right_device->value()>=0)
5150 _ui->spinBox_stereo_right_device->value(),
5151 _ui->checkBox_stereo_rectify->isChecked() && !useRawImages,
5159 _ui->checkBox_stereo_rectify->isChecked() && !useRawImages,
5166 if(!
_ui->lineEdit_cameraStereoVideo_path_2->text().isEmpty())
5170 _ui->lineEdit_cameraStereoVideo_path->text().toStdString(),
5171 _ui->lineEdit_cameraStereoVideo_path_2->text().toStdString(),
5172 _ui->checkBox_stereo_rectify->isChecked() && !useRawImages,
5180 _ui->lineEdit_cameraStereoVideo_path->text().toStdString(),
5181 _ui->checkBox_stereo_rectify->isChecked() && !useRawImages,
5189 if(!
_ui->lineEdit_zedSvoPath->text().isEmpty())
5192 _ui->lineEdit_zedSvoPath->text().toStdString(),
5193 _ui->comboBox_stereoZed_quality->currentIndex(),
5194 _ui->comboBox_stereoZed_sensingMode->currentIndex(),
5195 _ui->spinBox_stereoZed_confidenceThr->value(),
5196 _ui->checkbox_stereoZed_odom->isChecked(),
5199 _ui->checkbox_stereoZed_selfCalibration->isChecked());
5205 _ui->comboBox_stereoZed_resolution->currentIndex(),
5206 _ui->comboBox_stereoZed_quality->currentIndex(),
5207 _ui->comboBox_stereoZed_sensingMode->currentIndex(),
5208 _ui->spinBox_stereoZed_confidenceThr->value(),
5209 _ui->checkbox_stereoZed_odom->isChecked(),
5212 _ui->checkbox_stereoZed_selfCalibration->isChecked());
5219 _ui->checkBox_rgb_rectify->isChecked() && !useRawImages,
5226 _ui->source_video_lineEdit_path->text().toStdString(),
5227 _ui->checkBox_rgb_rectify->isChecked() && !useRawImages,
5234 _ui->source_images_lineEdit_path->text().toStdString(),
5239 ((
CameraImages*)camera)->setImagesRectified(
_ui->checkBox_rgb_rectify->isChecked() && !useRawImages);
5241 ((
CameraImages*)camera)->setBayerMode(
_ui->comboBox_cameraImages_bayerMode->currentIndex()-1);
5243 _ui->lineEdit_cameraImages_odom->text().toStdString(),
5244 _ui->comboBox_cameraImages_odomFormat->currentIndex());
5246 _ui->lineEdit_cameraImages_gt->text().toStdString(),
5247 _ui->comboBox_cameraImages_gtFormat->currentIndex());
5248 ((
CameraImages*)camera)->setMaxPoseTimeDiff(
_ui->doubleSpinBox_maxPoseTimeDiff->value());
5250 _ui->lineEdit_cameraImages_path_scans->text().isEmpty()?
"":
_ui->lineEdit_cameraImages_path_scans->text().append(QDir::separator()).toStdString(),
5251 _ui->spinBox_cameraImages_max_scan_pts->value(),
5252 _ui->spinBox_cameraImages_scanDownsampleStep->value(),
5253 _ui->doubleSpinBox_cameraImages_scanVoxelSize->value(),
5254 _ui->spinBox_cameraImages_scanNormalsK->value(),
5255 _ui->doubleSpinBox_cameraImages_scanNormalsRadius->value(),
5257 _ui->checkBox_cameraImages_scanForceGroundNormalsUp->isChecked());
5259 _ui->groupBox_depthFromScan->isChecked(),
5260 !
_ui->groupBox_depthFromScan_fillHoles->isChecked()?0:
_ui->radioButton_depthFromScan_vertical->isChecked()?1:-1,
5261 _ui->checkBox_depthFromScan_fillBorders->isChecked());
5263 _ui->checkBox_cameraImages_timestamps->isChecked(),
5264 _ui->lineEdit_cameraImages_timestamps->text().toStdString(),
5265 _ui->checkBox_cameraImages_syncTimeStamps->isChecked());
5269 camera =
new DBReader(
_ui->source_database_lineEdit_path->text().toStdString(),
5271 _ui->source_checkBox_ignoreOdometry->isChecked(),
5272 _ui->source_checkBox_ignoreGoalDelay->isChecked(),
5273 _ui->source_checkBox_ignoreGoals->isChecked(),
5274 _ui->source_spinBox_databaseStartPos->value(),
5275 _ui->source_spinBox_database_cameraIndex->value());
5279 UFATAL(
"Source driver undefined (%d)!", driver);
5286 QString calibrationFile =
_ui->lineEdit_calibrationFile->text();
5289 calibrationFile.remove(
"_left.yaml").remove(
"_right.yaml").remove(
"_pose.yaml").remove(
"_rgb.yaml").remove(
"_depth.yaml");
5291 QString name = QFileInfo(calibrationFile.remove(
".yaml")).baseName();
5292 if(!
_ui->lineEdit_calibrationFile->text().isEmpty())
5294 QDir
d = QFileInfo(
_ui->lineEdit_calibrationFile->text()).dir();
5295 if(!
_ui->lineEdit_calibrationFile->text().remove(QFileInfo(
_ui->lineEdit_calibrationFile->text()).baseName()).isEmpty())
5297 dir = d.absolutePath();
5302 if(!camera->
init(useRawImages?
"":dir.toStdString(), name.toStdString()))
5304 UWARN(
"init camera failed... ");
5305 QMessageBox::warning(
this,
5307 tr(
"Camera initialization failed..."));
5316 ((
CameraOpenNI2*)camera)->setAutoWhiteBalance(
_ui->openni2_autoWhiteBalance->isChecked());
5317 ((
CameraOpenNI2*)camera)->setAutoExposure(
_ui->openni2_autoExposure->isChecked());
5318 ((
CameraOpenNI2*)camera)->setMirroring(
_ui->openni2_mirroring->isChecked());
5319 ((
CameraOpenNI2*)camera)->setOpenNI2StampsAndIDsUsed(
_ui->openni2_stampsIdsUsed->isChecked());
5325 ((
CameraOpenNI2*)camera)->setIRDepthShift(
_ui->openni2_hshift->value(),
_ui->openni2_vshift->value());
5326 ((
CameraOpenNI2*)camera)->setMirroring(
_ui->openni2_mirroring->isChecked());
5337 return _ui->groupBox_publishing->isChecked();
5341 return _ui->general_doubleSpinBox_hardThr->value();
5345 return _ui->general_doubleSpinBox_vp->value();
5349 return _ui->doubleSpinBox_similarityThreshold->value();
5353 return _ui->odom_strategy->currentIndex();
5357 return _ui->odom_dataBufferSize->value();
5367 return _ui->general_checkBox_imagesKept->isChecked();
5371 return _ui->general_checkBox_cloudsKept->isChecked();
5375 return _ui->general_doubleSpinBox_timeThr->value();
5379 return _ui->general_doubleSpinBox_detectionRate->value();
5383 return _ui->general_checkBox_SLAM_mode->isChecked();
5387 return _ui->general_checkBox_activateRGBD->isChecked();
5391 return _ui->surf_spinBox_wordsPerImageTarget->value();
5398 if(
_ui->general_doubleSpinBox_imgRate->value() != value)
5400 _ui->general_doubleSpinBox_imgRate->setValue(value);
5415 if(
_ui->general_doubleSpinBox_detectionRate->value() != value)
5417 _ui->general_doubleSpinBox_detectionRate->setValue(value);
5432 if(
_ui->general_doubleSpinBox_timeThr->value() != value)
5434 _ui->general_doubleSpinBox_timeThr->setValue(value);
5449 if(
_ui->general_checkBox_SLAM_mode->isChecked() != enabled)
5451 _ui->general_checkBox_SLAM_mode->setChecked(enabled);
5475 !
_ui->lineEdit_cameraImages_path_imu->text().isEmpty())
5479 QMessageBox::warning(
this, tr(
"Source IMU Path"),
5480 tr(
"IMU path is set but odometry chosen doesn't support IMU, ignoring IMU..."), QMessageBox::Ok);
5485 if(!imuThread->
init(
_ui->lineEdit_cameraImages_path_imu->text().toStdString()))
5487 QMessageBox::warning(
this, tr(
"Source IMU Path"),
5488 tr(
"Initialization of IMU data has failed! Path=%1.").arg(
_ui->lineEdit_cameraImages_path_imu->text()), QMessageBox::Ok);
5502 int odomStrategy = Parameters::defaultOdomStrategy();
5504 if(odomStrategy == 1)
5514 _ui->odom_dataBufferSize->value());
5518 _ui->spinBox_decimation_odom->value(),
5520 _ui->doubleSpinBox_maxDepth_odom->value(),
5524 odomViewer->setWindowTitle(tr(
"Odometry viewer"));
5525 odomViewer->resize(1280, 480+QPushButton().minimumHeight());
5535 _ui->groupBox_scanFromDepth->isChecked(),
5536 _ui->spinBox_cameraScanFromDepth_decimation->value(),
5537 _ui->doubleSpinBox_cameraSCanFromDepth_maxDepth->value(),
5538 _ui->doubleSpinBox_cameraImages_scanVoxelSize->value(),
5539 _ui->spinBox_cameraImages_scanNormalsK->value(),
5540 _ui->doubleSpinBox_cameraImages_scanNormalsRadius->value());
5543 if(
_ui->groupBox_bilateral->isChecked())
5546 _ui->doubleSpinBox_bilateral_sigmaS->value(),
5547 _ui->doubleSpinBox_bilateral_sigmaR->value());
5549 if(!
_ui->lineEdit_source_distortionModel->text().isEmpty())
5564 cameraThread.
start();
5576 imuThread->
join(
true);
5579 cameraThread.
join(
true);
5580 odomThread.join(
true);
5586 window->setWindowTitle(tr(
"Camera viewer"));
5587 window->resize(1280, 480+QPushButton().minimumHeight());
5600 _ui->groupBox_scanFromDepth->isChecked(),
5601 _ui->spinBox_cameraScanFromDepth_decimation->value(),
5602 _ui->doubleSpinBox_cameraSCanFromDepth_maxDepth->value(),
5603 _ui->doubleSpinBox_cameraImages_scanVoxelSize->value(),
5604 _ui->spinBox_cameraImages_scanNormalsK->value(),
5605 _ui->doubleSpinBox_cameraImages_scanNormalsRadius->value());
5608 if(
_ui->groupBox_bilateral->isChecked())
5611 _ui->doubleSpinBox_bilateral_sigmaS->value(),
5612 _ui->doubleSpinBox_bilateral_sigmaR->value());
5614 if(!
_ui->lineEdit_source_distortionModel->text().isEmpty())
5621 cameraThread.
start();
5624 cameraThread.
join(
true);
5636 QMessageBox::warning(
this,
5638 tr(
"Cannot calibrate database source!"));
5648 if(!dir.mkpath(this->getCameraInfoDir()))
5650 UWARN(
"Could create camera_info directory: \"%s\"", this->
getCameraInfoDir().toStdString().c_str());
5659 QMessageBox::StandardButton button = QMessageBox::question(
this, tr(
"Calibration"),
5660 tr(
"With \"%1\" driver, Color and IR cameras cannot be streamed at the " 5661 "same time. A 3-steps calibration is required (Color -> IR -> extrinsics). We will " 5662 "start with the Color camera calibration. Do you want to continue?").arg(this->
getSourceDriverStr()),
5663 QMessageBox::Yes | QMessageBox::No | QMessageBox::Ignore, QMessageBox::Yes);
5665 if(button == QMessageBox::Yes || button == QMessageBox::Ignore)
5672 if(button != QMessageBox::Ignore)
5685 cameraThread.
start();
5688 cameraThread.
join(
true);
5692 button = QMessageBox::question(
this, tr(
"Calibration"),
5693 tr(
"We will now calibrate the IR camera. Hide the IR projector with a Post-It and " 5694 "make sure you have enough ambient IR light (e.g., external IR source or sunlight!) to see the " 5695 "checkboard with the IR camera. Do you want to continue?"),
5696 QMessageBox::Yes | QMessageBox::No | QMessageBox::Ignore, QMessageBox::Yes);
5697 if(button == QMessageBox::Yes || button == QMessageBox::Ignore)
5700 if(button != QMessageBox::Ignore)
5713 cameraThread.
start();
5716 cameraThread.
join(
true);
5720 button = QMessageBox::question(
this, tr(
"Calibration"),
5721 tr(
"We will now calibrate the extrinsics. Important: Make sure " 5722 "the cameras and the checkboard don't move and that both " 5723 "cameras can see the checkboard. We will repeat this " 5724 "multiple times. Each time, you will have to move the camera (or " 5725 "checkboard) for a different point of view. Do you want to " 5727 QMessageBox::Yes | QMessageBox::No, QMessageBox::Yes);
5730 int totalSamples = 0;
5731 if(button == QMessageBox::Yes)
5733 totalSamples = QInputDialog::getInt(
this, tr(
"Calibration"), tr(
"Samples: "), 3, 1, 99, 1, &ok);
5747 for(;count < totalSamples && button == QMessageBox::Yes; )
5778 if(count < totalSamples)
5780 button = QMessageBox::question(
this, tr(
"Calibration"),
5781 tr(
"A stereo pair has been taken (total=%1/%2). Move the checkboard or " 5782 "camera to another position. Press \"Yes\" when you are ready " 5783 "for the next capture.").arg(count).arg(totalSamples),
5784 QMessageBox::Yes | QMessageBox::Abort, QMessageBox::Yes);
5789 button = QMessageBox::question(
this, tr(
"Calibration"),
5790 tr(
"Could not detect the checkboard on both images or " 5791 "the point of view didn't change enough. Try again?"),
5792 QMessageBox::Yes | QMessageBox::No, QMessageBox::Yes);
5797 button = QMessageBox::question(
this, tr(
"Calibration"),
5798 tr(
"Failed to start the camera. Try again?"), QMessageBox::Yes | QMessageBox::No, QMessageBox::Yes);
5801 if(count == totalSamples && button == QMessageBox::Yes)
5804 stereoModel.
setName(stereoModel.
name(),
"depth",
"rgb");
5807 QMessageBox::warning(
this, tr(
"Calibration"),
5808 tr(
"Extrinsic calibration has failed! Look on the terminal " 5809 "for possible error messages. Make sure corresponding calibration files exist " 5810 "in \"%1\" folder for camera \"%2\" or calibration name set. If not, re-do " 5811 "step 1 and 2 and make sure to export the calibration files.").arg(this->
getCameraInfoDir()).arg(serial.c_str()), QMessageBox::Ok);
5815 QMessageBox::information(
this, tr(
"Calibration"),
5816 tr(
"Calibration is completed! Extrinsics have been saved to \"%1/%2_pose.yaml\"").arg(this->
getCameraInfoDir()).arg(stereoModel.
name().c_str()), QMessageBox::Ok);
5840 cameraThread.
start();
5845 cameraThread.
join(
true);
int getOctomapTreeDepth() const
double getCloudFilteringAngle() const
int getCloudColorScheme(int index) const
static bool parse(const ParametersMap ¶meters, const std::string &key, bool &value)
bool isSourceDatabaseStampsUsed() const
void selectSourceImagesPathScans()
void processImages(const cv::Mat &imageLeft, const cv::Mat &imageRight, const QString &cameraName)
int getNoiseMinNeighbors() const
QVector< QSpinBox * > _3dRenderingDownsamplingScan
void setParameter(const std::string &key, const std::string &value)
Camera * createCamera(bool useRawImages=false, bool useColor=true)
int projMinClusterSize() const
double getScanMinRange(int index) const
void saveMainWindowState(const QMainWindow *mainWindow)
int getGeneralLoggerPauseLevel() const
void updateParameters(const ParametersMap ¶meters, bool setOtherParametersToDefault=false)
QString getIMUPath() const
int getScanNormalKSearch() const
static void createPipe(const UEventsSender *sender, const UEventsHandler *receiver, const std::string &eventName)
bool isOdomOnlyInliersShown() const
bool getGridMapShown() const
void setStereoExposureCompensation(bool enabled)
rtabmap::ParametersMap _parameters
static bool isCSparseAvailable()
bool isCloudMeshingQuad() const
double getSubtractFilteringRadius() const
bool init(const std::string &path)
int getGeneralLoggerLevel() const
double getCeilingFilteringHeight() const
double UTILITE_EXP uStr2Double(const std::string &str)
rtabmap::ParametersMap getAllParameters() const
void selectSourceImagesPathOdom()
void changeOdometryOKVISConfigPath()
Transform stereoTransform() const
virtual void readCameraSettings(const QString &filePath=QString())
void setSLAMMode(bool enabled)
CalibrationDialog * _calibrationDialog
void selectSourceSvoPath()
int uStrNumCmp(const std::string &a, const std::string &b)
void setDepthScaledToRGBSize(bool enabled)
virtual ~PreferencesDialog()
void changeOdometryORBSLAM2Vocabulary()
void loadSettings(QSettings &settings, const QString &group="")
std::pair< std::string, std::string > ParametersPair
cv::Mat visualize(const std::string &path="") const
int getKpMaxFeatures() const
bool imageHighestHypShown() const
bool UTILITE_EXP uStr2Bool(const char *str)
PreferencesDialog::Src getSourceType() const
bool isStatisticsPublished() const
virtual QString getIniFilePath() const
void setTimeLimit(float value)
void updatePredictionPlot()
void enableBilateralFiltering(float sigmaS, float sigmaR)
Transform getLaserLocalTransform() const
static std::map< std::string, unsigned long > getRegisteredThreads()
QStandardItemModel * _indexModel
QString getWorkingDirectory() const
int getOctomapRenderingType() const
bool isSourceRGBDColorOnly() const
float UTILITE_EXP uStr2Float(const std::string &str)
std::vector< float > getCloudRoiRatios(int index) const
std::map< std::string, std::string > ParametersMap
std::string UTILITE_EXP uBool2Str(bool boolean)
double getGeneralInputRate() const
void readSettings(const QString &filePath=QString())
int getCloudMeshingTriangleSize()
static bool isCholmodAvailable()
static void writeINI(const std::string &configFile, const ParametersMap ¶meters)
void makeObsoleteCloudRenderingPanel()
Some conversion functions.
bool isLocalizationsCountGraphView() const
void setSwitchedImages(bool switched)
virtual void readGuiSettings(const QString &filePath=QString())
double getScanMaxRange(int index) const
bool isGraphsShown() const
std::vector< std::string > getGeneralLoggerThreads() const
const cv::Mat & imageRaw() const
void addParameter(int value)
static bool isAvailable(Optimizer::Type type)
int getSourceScanFromDepthDecimation() const
bool parseModel(QList< QGroupBox * > &boxes, QStandardItem *parentItem, int currentLevel, int &absoluteIndex)
bool isGroundTruthAligned() const
double projMaxGroundAngle() const
double getCloudVoxelSizeScan(int index) const
Transform getIMULocalTransform() const
bool isOdomDisabled() const
double getCloudOpacity(int index) const
void loadMainWindowState(QMainWindow *mainWindow, bool &maximized, bool &statusBarShown)
void selectSourceImagesPathGt()
void updateBasicParameter()
virtual bool readCoreSettings(const QString &filePath=QString())
QVector< QSpinBox * > _3dRenderingPtSize
int getGeneralLoggerEventLevel() const
bool isSubtractFiltering() const
virtual void closeEvent(QCloseEvent *event)
QVector< QDoubleSpinBox * > _3dRenderingVoxelSizeScan
void changeIcpPMConfigPath()
QVector< QCheckBox * > _3dRenderingShowFrustums
virtual std::string getSerial() const =0
PreferencesDialog::Src getSourceDriver() 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)
QString getSourceDistortionModel() const
void setColorOnly(bool colorOnly)
SensorData takeImage(CameraInfo *info=0)
void updateSourceGrpVisibility()
Wrappers of STL for convenient functions.
double getSourceScanNormalsRadius() const
bool isSourceMirroring() const
void selectSourceStereoVideoPath()
int getStereoPairs() const
double getFloorFilteringHeight() const
float getDetectionRate() const
void selectSourceDriver(Src src)
void selectSourceVideoPath()
bool isBilateralFiltering() const
QVector< QSpinBox * > _3dRenderingPtSizeFeatures
#define ULOGGER_DEBUG(...)
void visualizeDistortionModel()
bool isPosteriorGraphView() const
virtual void setStartIndex(int index)
bool isSourceStereoDepthGenerated() const
void setDetectionRate(double value)
QVector< QSpinBox * > _3dRenderingPtSizeScan
double getScanNormalRadiusSearch() const
bool isTimeUsedInFigures() const
void saveSettings(QSettings &settings, const QString &group="") const
double getCloudFilteringRadius() const
bool isLabelsShown() const
double getNoiseRadius() const
int getDownsamplingStepScan(int index) const
bool isCloudMeshingTexture() const
double getSourceScanVoxelSize() const
void setCameraInfoDir(const QString &folder)
QVector< QLineEdit * > _3dRenderingRoiRatios
QList< QGroupBox * > getGroupBoxes()
int getCloudDecimation(int index) const
virtual void writeGuiSettings(const QString &filePath=QString()) const
bool isWordsCountGraphView() const
bool saveStereoTransform(const std::string &directory) const
int getScanPointSize(int index) const
int getOctomapPointSize() const
bool isSourceStereoExposureCompensation() const
virtual void setStartIndex(int index)
int getSourceImageDecimation() const
bool isCloudMeshing() const
static Odometry * create(const ParametersMap ¶meters)
Ui_preferencesDialog * _ui
void saveWindowGeometry(const QWidget *window)
bool isCacheSavedInFigures() const
bool isFeaturesShown(int index) const
void selectSourceStereoVideoPath2()
int getCloudPointSize(int index) const
QVector< QDoubleSpinBox * > _3dRenderingOpacity
void setDistortionModel(const std::string &path)
virtual void showEvent(QShowEvent *event)
QVector< QSpinBox * > _3dRenderingDecimation
bool openDatabase(const QString &path)
int getSubtractFilteringMinPts() const
bool isScansShown(int index) const
virtual void writeCameraSettings(const QString &filePath=QString()) const
void setMirroringEnabled(bool enabled)
bool uContains(const std::list< V > &list, const V &value)
double getCloudMeshingAngle() const
void load(const std::string &path)
void selectSourceStereoImagesPathRight()
bool isFrustumsShown(int index) const
double getScanCeilingFilteringHeight() const
void selectSourceRGBDImagesPathRGB()
void selectCalibrationPath()
virtual void writeCoreSettings(const QString &filePath=QString()) const
void setImageDecimation(int decimation)
int getNormalKSearch() const
QVector< QDoubleSpinBox * > _3dRenderingMaxDepth
bool isVerticalLayoutUsed() const
void registerToEventsManager()
QVector< QCheckBox * > _3dRenderingShowFeatures
static std::string getType(const std::string ¶mKey)
void closeDialog(QAbstractButton *button)
double getScanOpacity(int index) const
void changeDictionaryPath()
QVector< QSpinBox * > _3dRenderingColorSchemeScan
static const ParametersMap & getDefaultParameters()
void openDatabaseViewer()
void resetSettings(int panelNumber)
QString loadCustomConfig(const QString §ion, const QString &key)
const std::vector< CameraModel > & cameraModels() const
std::string getParameter(const std::string &key) const
QVector< QDoubleSpinBox * > _3dRenderingOpacityScan
void selectSourceOniPath()
bool isGridMapFrom3DCloud() const
void setScanFromDepth(bool enabled, int decimation=4, float maxDepth=4.0f, float voxelSize=0.0f, int normalsK=0, int normalsRadius=0.0f)
void setStereoToDepth(bool enabled)
void setStereoMode(bool stereo, const QString &leftSuffix="left", const QString &rightSuffix="right")
bool isSourceScanFromDepth() const
virtual QString getDefaultWorkingDirectory() const
void setProgressVisibility(bool visible)
void saveWidgetState(const QWidget *widget)
QString getSourceDevice() const
double projMaxObstaclesHeight() const
bool getGeneralLoggerPrintThreadId() const
void selectSourceStereoImagesPathLeft()
int getFeaturesPointSize(int index) const
void showCloseButton(bool visible=true)
void loadSettings(QSettings &settings, const QString &group="")
void makeObsoleteLoggingPanel()
double getNormalRadiusSearch() const
QVector< QDoubleSpinBox * > _3dRenderingMinDepth
bool isCloudsKept() const
PANEL_FLAGS _obsoletePanels
QString getSourceDriverStr() const
bool isOctomapUpdated() const
#define ULOGGER_WARN(...)
void setCurrentPanelToSource()
virtual void setStartIndex(int index)
ULogger class and convenient macros.
void selectSourceRGBDImagesPathDepth()
void loadWindowGeometry(QWidget *window)
PreferencesDialog(QWidget *parent=0)
double getBilateralSigmaR() const
bool projFlatObstaclesDetected() const
void setInputRate(double value)
void setName(const std::string &name, const std::string &leftSuffix="left", const std::string &rightSuffix="right")
void settingsChanged(PreferencesDialog::PANEL_FLAGS)
void makeObsoleteGeneralPanel()
bool getGeneralLoggerPrintTime() const
void writeSettings(const QString &filePath=QString())
bool isCloudFiltering() const
bool isImagesKept() const
bool isOctomapShown() const
static void readINI(const std::string &configFile, ParametersMap ¶meters, bool modifiedOnly=false)
void updateStereoDisparityVisibility()
const QString & cameraName() const
int getOdomStrategy() const
QProgressDialog * _progressDialog
double getSourceScanFromDepthMaxDepth() const
double getBilateralSigmaS() const
QString getCameraInfoDir() const
double getScanFloorFilteringHeight() const
void resetApply(QAbstractButton *button)
bool isDepthFilteringAvailable() const
virtual QString getParamMessage()
bool sortCallback(const std::string &a, const std::string &b)
double getLoopThr() const
void unregisterFromEventsManager()
QVector< QDoubleSpinBox * > _3dRenderingMinRange
void clicked(const QModelIndex ¤t, const QModelIndex &previous)
bool projMapFrame() const
void join(bool killFirst=false)
void saveSettings(QSettings &settings, const QString &group="") const
QVector< QCheckBox * > _3dRenderingShowScans
void selectSourceImagesPathIMU()
double getSubtractFilteringAngle() const
double getCloudMaxDepth(int index) const
static bool exposureGainAvailable()
#define ULOGGER_ERROR(...)
void setCameraName(const QString &name)
QVector< QSpinBox * > _3dRenderingColorScheme
QVector< QDoubleSpinBox * > _3dRenderingMaxRange
void loadWidgetState(QWidget *widget)
void changeWorkingDirectory()
int getGeneralLoggerType() const
int getSourceScanNormalsK() const
void selectSourceDatabase()
rtabmap::ParametersMap _modifiedParameters
bool isCloudsShown(int index) const
bool notifyWhenNewGlobalPathIsReceived() const
int getOdomRegistrationApproach() const
std::string UTILITE_EXP uNumber2Str(unsigned int number)
void addParameters(const QObjectList &children)
int getScanColorScheme(int index) const
bool isOctomap2dGrid() const
int getOdomQualityWarnThr() const
double projMaxGroundHeight() const
virtual QString getTmpIniFilePath() const
void selectSourceOni2Path()
static std::string createDefaultWorkingDirectory()
bool imageRejectedShown() const
void selectSourceDistortionModel()
int getOdomBufferSize() const
float getTimeLimit() const
double getGridMapOpacity() const
QVector< QCheckBox * > _3dRenderingShowClouds
double getCloudMinDepth(int index) const
void uInsert(std::map< K, V > &map, const std::pair< K, V > &pair)
void selectSourceImagesPath()
StereoCameraModel stereoCalibration(const CameraModel &left, const CameraModel &right, bool ignoreStereoRectification) const
const std::string & name() const
void makeObsoleteSourcePanel()
Transform getSourceLocalTransform() const
CreateSimpleCalibrationDialog * _createCalibrationDialog